diff --git a/src/autoware_practice_launch/config/autoware.rviz b/src/autoware_practice_launch/config/autoware.rviz index 32758e0..77cc6b8 100644 --- a/src/autoware_practice_launch/config/autoware.rviz +++ b/src/autoware_practice_launch/config/autoware.rviz @@ -88,7 +88,7 @@ Visualization Manager: Name: TrajectoryMarkers Namespaces: {} Topic: - Value: /trajectory_marker + Value: /debug/trajectory_marker History Policy: Keep Last Reliability Policy: Reliable Qos Overrides: @@ -104,7 +104,7 @@ Visualization Manager: Name: TrajectoryMarkers Namespaces: {} Topic: - Value: /reference_trajectory_marker + Value: /debug/reference_trajectory_marker History Policy: Keep Last Reliability Policy: Reliable Qos Overrides: @@ -120,7 +120,7 @@ Visualization Manager: Name: TrajectoryMarkers Namespaces: {} Topic: - Value: /candidate_trajectory_marker + Value: /debug/candidate_trajectory_marker History Policy: Keep Last Reliability Policy: Reliable Qos Overrides: diff --git a/src/autoware_practice_visualization/src/marker.cpp b/src/autoware_practice_visualization/src/marker.cpp index bbb4c30..68aa536 100644 --- a/src/autoware_practice_visualization/src/marker.cpp +++ b/src/autoware_practice_visualization/src/marker.cpp @@ -33,12 +33,12 @@ TrajectoryVisualizer::TrajectoryVisualizer(const rclcpp::NodeOptions & options) "/planning/scenario_planning/costmap", 10, std::bind(&TrajectoryVisualizer::costmapCallback, this, std::placeholders::_1)); - marker_pub_ = this->create_publisher("/trajectory_marker", 10); + marker_pub_ = this->create_publisher("/debug/trajectory_marker", 10); reference_marker_pub_ = - this->create_publisher("/reference_trajectory_marker", 10); + this->create_publisher("/debug/reference_trajectory_marker", 10); candidate_marker_pub_ = - this->create_publisher("/candidate_trajectory_marker", 10); - costmap_marker_pub_ = this->create_publisher("/costmap_marker", 10); + this->create_publisher("/debug/candidate_trajectory_marker", 10); + costmap_marker_pub_ = this->create_publisher("/debug/costmap_marker", 10); } void TrajectoryVisualizer::trajectoryCallback(const autoware_auto_planning_msgs::msg::Trajectory::SharedPtr msg)