ソースを参照

一些小更新

corvin rasp melodic 2 年 前
コミット
00c9168814

+ 2 - 3
src/ros_arduino_bridge/ros_arduino_python/nodes/arduino_node.py

@@ -158,7 +158,6 @@ if __name__ == '__main__':
     except SerialException:
         rospy.logerr("ERROR trying to open serial port.")
         os._exit(1)
-    except Exception:
-        rospy.logerr("Get other unknown error !")
+    except Exception as err:
+        rospy.logerr("Unknown Error: %s", err)
         os._exit(2)
-

+ 4 - 4
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/base_controller.py

@@ -60,7 +60,7 @@ class BaseController:
 
         #配置电机每米有多少个脉冲数
         self.motor_encoder_cnt = rospy.get_param("~motor_encoder_cnt", 1320)
-        self.wheel_diameter    = rospy.get_param("~wheel_diameter", 0.067)
+        self.wheel_diameter    = rospy.get_param("~wheel_diameter",    0.067)
         self.ticks_per_meter   = self.motor_encoder_cnt/(self.wheel_diameter*pi)
         self.ticks_per_meter   = self.ticks_per_meter/self.linear_scale_correction
 
@@ -81,7 +81,7 @@ class BaseController:
 
         self.v_des_AWheel = 0  #计算出来应该发送的脉冲数
         self.v_des_BWheel = 0
-        
+
         now = rospy.Time.now()
         self.old_time = now
         self.last_cmd_time = now
@@ -93,8 +93,8 @@ class BaseController:
         if self.isBalance:
             self.balanceControl = BalanceMode()
 
-        #配置用于里程计信息发布和里程计坐标变换
-        self.odomPub = rospy.Publisher(self.odom_name, Odometry, queue_size=5)
+        #配置用于里程计信息发布
+        self.odomPub = rospy.Publisher(self.odom_name, Odometry, queue_size=10)
 
         #增加用于调试PID参数的发布者
         if self.debugPID: