gmapping fixed

This commit is contained in:
yikestone 2019-04-02 00:45:44 +05:30
parent 2a5297cbb4
commit 3691f123ba
4 changed files with 3 additions and 5 deletions

View File

@ -1843,6 +1843,7 @@
<depthImageInfoTopicName>/camera_ir/depth/camera_info</depthImageInfoTopicName>
<pointCloudTopicName>/qt_pi/camera_ir/depth/points</pointCloudTopicName>
<frameName>camera_link</frameName>
<pointCloudCutoffMax>100</pointCloudCutoffMax>
<pointCloudCutoff>0.05</pointCloudCutoff>
<distortionK1>0</distortionK1>
<distortionK2>0</distortionK2>

View File

@ -3,9 +3,8 @@
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find qt_pi)/gazebo_sim/worlds/playground.world"/>
</include>
<include file="$(find qt_pi)/launch/gazebo_sim/static_tf_sim.launch"/>
<include file="$(find qt_pi)/launch/gazebo_sim/depth_to_laser_sim.launch"/>
<!--<include file="$(find qt_pi)/launch/gazebo_sim/gmapping.launch"/>-->
<include file="$(find qt_pi)/launch/gazebo_sim/gmapping.launch"/>
</launch>

View File

@ -1,6 +1,5 @@
<launch>
<remap from="image" to="qt_pi/camera_ir/depth/image_raw"/>
<node name="depthimage_to_laserscan" pkg="depthimage_to_laserscan" type="depthimage_to_laserscan">
<param name="scan_height" value="1"/>
<param name="range_max" value="100"/>

View File

@ -1,9 +1,8 @@
<launch>
<node name="gmapping" pkg="gmapping" type="slam_gmapping">
<param name="base_frame" value="qt_pi/base_link" type="string"/>
<param name="odom" value="qt_pi/odom" type="string"/>
<param name="odom_frame" value="qt_pi/odom" type="string"/>
<param name="maxUrange" value="90"/>
<param name="maxRange" value="100"/>
<param name="minimumScore" value="50"/>
</node>
</launch>