Skip to content

Commit

Permalink
update turtlebot3 waffle default radius, use global costmap/footprint…
Browse files Browse the repository at this point in the history
… for collision checker
  • Loading branch information
bpwilcox committed Jun 26, 2019
1 parent 6bcac32 commit 8ab347d
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
4 changes: 2 additions & 2 deletions nav2_bringup/launch/nav2_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
4 changes: 2 additions & 2 deletions nav2_motion_primitives/src/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down

0 comments on commit 8ab347d

Please sign in to comment.