diff --git a/nav2_collision_monitor/params/collision_monitor_params.yaml b/nav2_collision_monitor/params/collision_monitor_params.yaml index 239960e5934..e518ef680e6 100644 --- a/nav2_collision_monitor/params/collision_monitor_params.yaml +++ b/nav2_collision_monitor/params/collision_monitor_params.yaml @@ -2,7 +2,7 @@ collision_monitor: ros__parameters: base_frame_id: "base_footprint" odom_frame_id: "odom" - cmd_vel_in_topic: "cmd_vel_raw" + cmd_vel_in_topic: "cmd_vel_smoothed" cmd_vel_out_topic: "cmd_vel" state_topic: "collision_monitor_state" transform_tolerance: 0.5 diff --git a/nav2_collision_monitor/src/collision_monitor_node.cpp b/nav2_collision_monitor/src/collision_monitor_node.cpp index 6b678c9c768..8b7984a9c7d 100644 --- a/nav2_collision_monitor/src/collision_monitor_node.cpp +++ b/nav2_collision_monitor/src/collision_monitor_node.cpp @@ -205,7 +205,7 @@ bool CollisionMonitor::getParameters( auto node = shared_from_this(); nav2_util::declare_parameter_if_not_declared( - node, "cmd_vel_in_topic", rclcpp::ParameterValue("cmd_vel_raw")); + node, "cmd_vel_in_topic", rclcpp::ParameterValue("cmd_vel_smoothed")); cmd_vel_in_topic = get_parameter("cmd_vel_in_topic").as_string(); nav2_util::declare_parameter_if_not_declared( node, "cmd_vel_out_topic", rclcpp::ParameterValue("cmd_vel"));