diff --git a/nav2_bringup/launch/nav2_params.yaml b/nav2_bringup/launch/nav2_params.yaml index c0ee0be53a614884eaa5169345c867956a7e9c87..fce7d0c15e8b6374b3647053d34b3bb34a5301ec 100644 --- a/nav2_bringup/launch/nav2_params.yaml +++ b/nav2_bringup/launch/nav2_params.yaml @@ -100,7 +100,7 @@ local_costmap: width: 3 height: 3 resolution: 0.05 - robot_radius: 0.17 + robot_radius: 0.22 inflation_layer.cost_scaling_factor: 3.0 obstacle_layer: enabled: True @@ -122,7 +122,7 @@ global_costmap: global_costmap: ros__parameters: use_sim_time: True - robot_radius: 0.17 + robot_radius: 0.22 obstacle_layer: enabled: True always_send_full_costmap: True diff --git a/nav2_motion_primitives/src/main.cpp b/nav2_motion_primitives/src/main.cpp index 86b269325b5b831a1bd671660c3bd5e7d9edff62..006b8e600c581b7d7934dbca882f6d1cf20588dd 100644 --- a/nav2_motion_primitives/src/main.cpp +++ b/nav2_motion_primitives/src/main.cpp @@ -26,9 +26,9 @@ int main(int argc, char ** argv) auto motion_primitives_node = rclcpp::Node::make_shared("motion_primitives"); motion_primitives_node->declare_parameter( - "costmap_topic", rclcpp::ParameterValue(std::string("local_costmap/costmap_raw"))); + "costmap_topic", rclcpp::ParameterValue(std::string("global_costmap/costmap_raw"))); motion_primitives_node->declare_parameter( - "footprint_topic", rclcpp::ParameterValue(std::string("local_costmap/published_footprint"))); + "footprint_topic", rclcpp::ParameterValue(std::string("global_costmap/published_footprint"))); auto spin = std::make_shared<nav2_motion_primitives::Spin>( motion_primitives_node);