Contents
Experimental Package
This package contains unreleased code related to navigation as used in the CWRU mobile robots.
Nodes
map_as_sensor
map_as_sensor converts a map to a point cloud to be used with costmap_2dSubscribed Topics
input_map (nav_msgs/OccupancyGrid)- The input occupancy grid to be turned into a point cloud. The metadata is used to determine the coordinates of the output XY points. Only points with a value of 100 (fatal obstacle cost) will be in the output PointCloud. You will likely want to manually mark up a map generated by gmapping or being input to the map_server to reflect forbidden zones that are not detected by a laser rangefinder.
Published Topics
map_cloud (sensor_msgs/PointCloud)- The output point cloud. You will need to add this topic to the observation_sources of your costmap_2d in order for the obstacles to be respected.
Parameters
~channel_name (string, default: intensity)- The name to set for the channel that accompanies the XYZ points in the output sensor_msgs/PointCloud
- The value of the entry in the output PointCloud's channel corresponding to each obstacle point.
- The rate in Hz that the node should publish an updated PointCloud. This could become CPU-intensive at very high rates and dense maps as each time map_cloud is generated it must be transformed into the target frame.
- The height in meters to set for each point in the output PointCloud
- The reference frame that map_cloud should be transformed into before being output. This should correspond to the robot_base_frame parameter of the costmap_2d you intend on receiving the map_cloud. This ensures that the origin of the map_cloud is always on the costmap; if it is not, raytracing will fail and the costmap will be unable to use the map_cloud.
Required tf Transforms
(value of input_map.header.frame_id) → (value of robot_base_frame parameter)- Usually provided by a node responsible for odometry or localization such as amcl.