Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<arg name="base_frame" default="base_footprint"/>
<arg name="odom_frame" default="odom"/>

<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<node pkg="nodelet" type="nodelet" name="slam_gmapping" args="load SlamGMappingNodelet camera/camera_nodelet_manager" output="screen">
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

People use the turtlebot gmapping with Lidars, in which case they would not have the camera nodelet manager.
I am not entirely sure that it is a good idea to make loading the nodelet the default.

I think it would be better to make a separate laser gmapping launch, that does not use the nodelet, before merging,

<param name="base_frame" value="$(arg base_frame)"/>
<param name="odom_frame" value="$(arg odom_frame)"/>
<param name="map_update_interval" value="5.0"/>
Expand Down Expand Up @@ -44,6 +44,9 @@
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
<remap from="scan" to="$(arg scan_topic)"/>

<remap from="camera/scan" to="$(arg scan_topic)"/>
<remap from="camera/map" to="map"/>
<remap from="camera/map_metadata" to="map_metadata"/>
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<arg name="base_frame" default="base_footprint"/>
<arg name="odom_frame" default="odom"/>

<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<node pkg="nodelet" type="nodelet" name="slam_gmapping" args="load SlamGMappingNodelet camera/camera_nodelet_manager" output="screen">
<param name="base_frame" value="$(arg base_frame)"/>
<param name="odom_frame" value="$(arg odom_frame)"/>
<param name="map_update_interval" value="5.0"/>
Expand Down Expand Up @@ -39,6 +39,9 @@
<param name="llsamplestep" value="0.01"/>
<param name="lasamplerange" value="0.005"/>
<param name="lasamplestep" value="0.005"/>
<remap from="scan" to="$(arg scan_topic)"/>

<remap from="camera/scan" to="$(arg scan_topic)"/>
<remap from="camera/map" to="map"/>
<remap from="camera/map_metadata" to="map_metadata"/>
</node>
</launch>