浏览代码

优化hector map效果

corvin 5 年之前
父节点
当前提交
e2eb40952d

+ 1 - 1
src/robot_navigation/config/costmap_common_params.yaml

@@ -13,7 +13,7 @@
 
 obstacle_range: 2.0
 raytrace_range: 3.0
-robot_radius: 0.18
+robot_radius: 0.126
 inflation_radius: 0.2
 observation_sources: scan
 scan: {data_type: LaserScan, topic: scan, marking: true, clearing: true}

+ 1 - 1
src/robot_navigation/config/local_costmap_params.yaml

@@ -17,7 +17,7 @@
 #
 
 local_costmap:
-   global_frame: /odom_combined
+   global_frame: /odom
    robot_base_frame: /base_footprint
    update_frequency: 3.0
    publish_frequency: 2.0

+ 3 - 1
src/robot_navigation/launch/hector_mapping.launch

@@ -15,10 +15,10 @@
   <arg name="scan_topic" default="/scan" />
   <arg name="map_size"   default="512" />
 
+  <!-- startup ydlidar -->
   <include file="$(find ydlidar)/launch/lidar.launch" />
 
   <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
-
     <!-- Frame names -->
     <param name="map_frame" value="$(arg map_frame)" />
     <param name="base_frame" value="$(arg base_frame)" />
@@ -54,5 +54,7 @@
     <param name="use_tf_pose_start_estimate" value="true" />
     <param name="tf_map_scanmatch_transform_frame_name" value="$(arg map_scanmatch_frame_name)" />
   </node>
+
+  <node pkg="tf" type="static_transform_publisher" name="map_to_odom" args="0.0 0.0 0.0 0 0 0.0 /map /odom 100"/>
 </launch>