ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
2 years late but anyone trying this must provide, as described in the above comment, the map->odom identity transform. This can be done with tf2_ros
package:
ros2 run tf2_ros static_transform_publisher 0 0 0 0 0 0 map odom
You'll also need to modify the global_costmap
in params.yaml
to have rolling_window: True
since you are not using any map. Also provide the window size, in my case 20x20 worked well. Also don't use the static layer since it does not make sense because there is no map. Then you are ready to send any goal.
For example the global_costmap
can look like:
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
global_frame: odom
robot_base_frame: chassis
use_sim_time: True
rolling_window: True
width: 20
height: 20
robot_radius: 0.5
resolution: 0.05
track_unknown_space: true
plugins: ["obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
footprint_clearing_enabled: true
scan:
topic: /scan
max_obstacle_height: 2.0
obstacle_range: 10.0
raytrace_range: 10.0
clearing: True
marking: True
data_type: "LaserScan"
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.4
2 | No.2 Revision |
2 years late but anyone trying this must provide, as described in the above stevemacenski's comment, the map->odom identity transform. This can be done with tf2_ros
package:
ros2 run tf2_ros static_transform_publisher 0 0 0 0 0 0 map odom
You'll also need to modify the global_costmap
in params.yaml
to have rolling_window: True
since you are not using any map. Also provide the window size, in my case 20x20 worked well. Also don't use the static layer since it does not make sense because there is no map. Then you are ready to send any goal.
For example the global_costmap
can look like:
global_costmap:
global_costmap:
ros__parameters:
update_frequency: 1.0
publish_frequency: 1.0
global_frame: odom
robot_base_frame: chassis
use_sim_time: True
rolling_window: True
width: 20
height: 20
robot_radius: 0.5
resolution: 0.05
track_unknown_space: true
plugins: ["obstacle_layer", "inflation_layer"]
obstacle_layer:
plugin: "nav2_costmap_2d::ObstacleLayer"
enabled: True
observation_sources: scan
footprint_clearing_enabled: true
scan:
topic: /scan
max_obstacle_height: 2.0
obstacle_range: 10.0
raytrace_range: 10.0
clearing: True
marking: True
data_type: "LaserScan"
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
cost_scaling_factor: 3.0
inflation_radius: 0.4