Jelajahi Sumber

在进行导航是dwa_local_planner订阅的odom话题只能是ros_arduino_python发布的原始odom话题,因为其包含有twist信息,而odom_ekf只包含有融合后的pose信息,没有速度信息,会导致导航时一直以最低速度移动

corvin rasp melodic 2 tahun lalu
induk
melakukan
501c91079d

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

@@ -46,7 +46,7 @@ DWAPlannerROS:
   vth_samples: 20
 
 # Trajectory Scoring Parameters
-  path_distance_bias: 32.0
+  path_distance_bias: 42.0
   goal_distance_bias: 18.0
   occdist_scale: 0.02
   forward_point_distance: 0.2

+ 3 - 5
src/robot_navigation/launch/move_base.launch

@@ -5,12 +5,11 @@
   History:
     20190728:init this file.
     20220922:设置planner_frequency参数为1,为1hz生成全局规划的路径.
-    20220928:配置dwa_local_planner订阅的odom话题信息参数odom_topic为odom_ekf,
-      使用robot_pose_ekf融合后的,不使用原始的odom话题,提高里程计精度.
+    20220928:配置dwa_local_planner订阅的odom话题信息参数为默认的odom,直接是轮式里程计话题.
+      不能使用robot_pose_ekf融合后的odom_ekf,因为该话题只包含pose信息,没有twist速度信息.
+      会导致小车在导航时由于无法感知到小车速度,就会一直以最低速度在移动.
 -->
 <launch>
-  <arg name="odom_topic" default="odom" />
-
   <node pkg="move_base" type="move_base" name="move_base" respawn="true" output="screen" clear_params="true">
     <param name="controller_frequency" value="7"/>
     <param name="controller_patiente"  value="3.0"/>
@@ -36,7 +35,6 @@
     <!-- 加载move_base使用的全局路径规划和局部路径规划算法及对应的参数  -->
     <rosparam file="$(find robot_navigation)/config/base_global_planner_params.yaml" command="load"/>
     <rosparam file="$(find robot_navigation)/config/dwa_local_planner_params.yaml"   command="load"/>
-    <remap from="odom" to="$(arg odom_topic)"/>
   </node>
 </launch>