Parcourir la source

更新base_controller.py,删除发布odom到base_link的tf转换,因为使用了传感器融合可以发布更准确的tf转换

corvin il y a 5 ans
Parent
commit
b8c97012bd

+ 11 - 7
src/robot_bringup/launch/robot_bringup.launch

@@ -1,6 +1,10 @@
 <!--
-  Copyright: 2016-2019 ROS小课堂 www.corvin.cn
+  Copyright: 2016-2020 ROS小课堂 www.corvin.cn
   Description:robot启动时最先需要启动的launch文件,主要加载各基础功能模块启动。
+    首先就需要启动机器人的urdf文件,这样就可以在rviz中可视化显示机器人模型.然后
+    启动下位机arduino的程序,上下位机建立连接,这样上位机就可以发送控制命令.接下来
+    启动IMU模块,开始发布姿态信息.接下来就开始进行信息融合,使用imu信息和轮式里程计
+    这样得出的里程计更为准确.
   Author: corvin
   History:
     20190722:init this file.
@@ -26,12 +30,12 @@
         <param name="vo_used" value="false"/>
         <param name="debug" value="false"/>
         <param name="self_diagnose" value="false"/>
-  </node>
+    </node>
 
-  <!-- (5) /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" />
-      <remap from="output" to="/odom_ekf" />
-  </node>
+    <!-- (5) /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" />
+        <remap from="output" to="/odom_ekf" />
+    </node>
 </launch>
 

+ 1 - 17
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/base_controller.py

@@ -30,7 +30,7 @@ class BaseController:
         pid_params['wheel_diameter']     = rospy.get_param("~wheel_diameter", 0.058)
         pid_params['wheel_track']        = rospy.get_param("~wheel_track", 0.126)
         pid_params['encoder_resolution'] = rospy.get_param("~encoder_resolution", 11)
-        pid_params['gear_reduction']     = rospy.get_param("~gear_reduction", 103)
+        pid_params['gear_reduction']     = rospy.get_param("~gear_reduction", 46)
         pid_params['AWheel_Kp'] = rospy.get_param("~AWheel_Kp", 15)
         pid_params['AWheel_Kd'] = rospy.get_param("~AWheel_Kd", 15)
         pid_params['AWheel_Ki'] = rospy.get_param("~AWheel_Ki", 0)
@@ -116,7 +116,6 @@ class BaseController:
         rospy.loginfo("Started base controller for a base of " + str(self.wheel_track) + "m with " + str(self.encoder_resolution) + " ticks per rev")
         rospy.loginfo("Publishing odometry data at: " + str(self.rate) + " Hz using " + str(self.base_frame) + " as base frame")
 
-
     def setup_pid(self, pid_params):
         # Check to see if any PID parameters are missing
         missing_params = False
@@ -164,10 +163,6 @@ class BaseController:
 
         time_now = rospy.Time.now()
         if time_now > self.t_next:
-            #rospy.logwarn("Voltage: %f, Current: %f", float(vol), float(current))
-            #vol = self.arduino.detect_voltage()
-            #current = self.arduino.detect_current()
-            #rospy.logwarn("Voltage: %f, Current: %f", vol, current)
             # Read the encoders
             try:
                 if self.use_serial:
@@ -217,17 +212,6 @@ class BaseController:
             quaternion.z = sin(self.th/2.0)
             quaternion.w = cos(self.th/2.0)
 
-            # create the odometry transform frame broadcaster.
-            # when startup robot_pose_ekf, should disable this broadcaster
-            #
-            #self.odomBroadcaster.sendTransform(
-            #    (self.x, self.y, 0),
-            #    (quaternion.x, quaternion.y, quaternion.z, quaternion.w),
-            #    rospy.Time.now(),
-            #    self.base_frame,
-            #    self.odom_name
-            #)
-
             odom = Odometry()
             odom.header.frame_id = self.odom_name
             odom.child_frame_id  = self.base_frame