瀏覽代碼

将robot_pose_ekf发布融合后数据话题的频率从10hz提高到20hz

corvin rasp melodic 2 年之前
父節點
當前提交
da911a7700

+ 1 - 1
src/robot_bringup/launch/odom_ekf.py

@@ -14,7 +14,7 @@ class OdomEKF():
         rospy.init_node('odom_ekf_node', anonymous=False)
 
         # Publisher of type nav_msgs/Odometry
-        self.ekf_pub = rospy.Publisher('output', Odometry, queue_size=10)
+        self.ekf_pub = rospy.Publisher('output', Odometry, queue_size=20)
 
         # Wait for the /odom_combined topic to become available
         rospy.wait_for_message('input', PoseWithCovarianceStamped)

+ 9 - 8
src/robot_bringup/launch/robot_bringup.launch

@@ -10,6 +10,7 @@
     20200716:init this file.
     20210602:使用串口获取imu模块的数据.
     20220902:增加启动oled显示屏的launch.
+    20220928:将robot_pose_ekf的数据融合发布频率从10hz提高为20hz.
 -->
 <launch>
     <!-- (1) startup panda robot urdf description -->
@@ -25,20 +26,20 @@
     <include file="$(find rasp_camera)/launch/rasp_camera.launch" />
 
     <!-- (5) startup robot_pose_ekf node -->
-    <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf">
+    <node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
         <param name="output_frame" value="odom_combined"/>
-        <param name="freq" value="10.0"/>
+        <param name="freq" value="20.0"/>
         <param name="sensor_timeout" value="1.2"/>
         <param name="odom_used" value="true"/>
-        <param name="imu_used" value="true"/>
-        <param name="vo_used" value="false"/>
-        <param name="debug" value="false"/>
+        <param name="imu_used"  value="true"/>
+        <param name="vo_used"   value="false"/>
+        <param name="debug"     value="false"/>
         <param name="self_diagnose" value="false"/>
     </node>
 
-    <!-- (6) /odom_combined view in rviz -->
-    <node pkg="robot_bringup" type="odom_ekf.py" name="odom_ekf" output="screen">
-        <remap from="input" to="/robot_pose_ekf/odom_combined" />
+    <!-- (6) /odom_combined view in rviz,dwa_local_planner subscribe /odom_ekf topic -->
+    <node pkg="robot_bringup" type="odom_ekf.py" name="odom_ekf_node" output="screen">
+        <remap from="input"  to="/robot_pose_ekf/odom_combined" />
         <remap from="output" to="/odom_ekf" />
     </node>
 

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

@@ -46,8 +46,8 @@ DWAPlannerROS:
   vth_samples: 20
 
 # Trajectory Scoring Parameters
-  path_distance_bias: 48.0
-  goal_distance_bias: 20.0
+  path_distance_bias: 32.0
+  goal_distance_bias: 24.0
   occdist_scale: 0.02
   forward_point_distance: 0.2
   stop_time_buffer: 0.6
@@ -60,6 +60,6 @@ DWAPlannerROS:
 # Global plan parameters
   prune_plan: true
 
-# Debugging
+# Debugging parameters
   publish_traj_pc : true
   publish_cost_grid_pc: true

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

@@ -2,7 +2,7 @@
 #   global_frame: 全局代价地图参考系
 #   robot_base_frame: 指定机器人的基础参考系
 #   update_frequency: 指定地图更新频率,数值太大造成CPU负担重
-#   publish_frequency: 对于静态全局地图来说,不需不断发布
+#   publish_frequency: 对于全局地图发布频率
 #   rolling_window:全局地图不会在机器人移动时候更新
 #   transform_tolerance:指定在tf树中frame直接的转换最大延时,单位秒
 # Author: corvin

+ 11 - 6
src/robot_navigation/launch/move_base.launch

@@ -5,8 +5,12 @@
   History:
     20190728:init this file.
     20220922:设置planner_frequency参数为1,为1hz生成全局规划的路径.
+    20220928:配置dwa_local_planner订阅的odom话题信息参数odom_topic为odom_ekf,
+      使用robot_pose_ekf融合后的,不使用原始的odom话题,提高里程计精度.
 -->
 <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"/>
@@ -24,14 +28,15 @@
 
     <param name="max_planning_retries" value="10"/>
 
-    <rosparam file="$(find robot_navigation)/config/costmap_common_params.yaml" command="load" ns="global_costmap" />
-    <rosparam file="$(find robot_navigation)/config/costmap_common_params.yaml" command="load" ns="local_costmap" />
-    <rosparam file="$(find robot_navigation)/config/local_costmap_params.yaml"  command="load" />
-    <rosparam file="$(find robot_navigation)/config/global_costmap_params.yaml" command="load" />
+    <rosparam file="$(find robot_navigation)/config/costmap_common_params.yaml" command="load" ns="global_costmap"/>
+    <rosparam file="$(find robot_navigation)/config/costmap_common_params.yaml" command="load" ns="local_costmap"/>
+    <rosparam file="$(find robot_navigation)/config/local_costmap_params.yaml"  command="load"/>
+    <rosparam file="$(find robot_navigation)/config/global_costmap_params.yaml" command="load"/>
 
     <!-- 加载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" />
+    <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>