Browse Source

更新ros_arduino_python代码,不用再根据超时后向arduino发送stop命令,因为arduino代码会自己根据超时来执行

corvin 4 years ago
parent
commit
ce386165b7

+ 2 - 2
src/ros_arduino_bridge/ros_arduino_python/config/my_arduino_params.yaml

@@ -16,7 +16,7 @@ serial_port: /dev/ttyACM0
 serial_baud: 57600
 
 #raspberryPi:1, huawei altals 200DK: 2
-i2c_smbus_num: 1   
+i2c_smbus_num: 1
 i2c_slave_addr: 0x08  #Get arduino due i2c slave addr
 
 timeout: 0.5
@@ -36,7 +36,7 @@ odom_name: odom
 wheel_diameter: 0.058
 wheel_track: 0.109     #L value
 encoder_resolution: 11 #12V DC motors
-gear_reduction: 103     #empty payload rpm 130 r/m
+gear_reduction: 103     #empty payload rpm 60 r/m
 linear_scale_correction: 1.028
 angular_scale_correction: 1.00
 

+ 14 - 8
src/ros_arduino_bridge/ros_arduino_python/src/ros_arduino_python/base_controller.py

@@ -1,7 +1,13 @@
 #!/usr/bin/env python
+#-*- coding:utf-8 -*-
 
 """
-    A base controller class for the Arduino microcontroller
+  Copyright: 2016-2020 www.corvin.cn ROS小课堂
+  Description:  A base controller class for the Arduino DUE microcontroller
+  Author: corvin
+  History:
+      20200704:当超过给下位机发送控制移动命令时间后,不需要再发送pwm控制0的命令.
+        因为在arduino代码会根据超时自己会执行pwm清零停止电机移动的命令.
 """
 import os
 import rospy
@@ -16,7 +22,7 @@ from std_msgs.msg import Int32
 
 """ Class to receive Twist commands and publish wheel Odometry data """
 class BaseController:
-    
+
     def __init__(self, is_use_serial, arduino, base_frame, name="base_controllers_node"):
         self.use_serial = is_use_serial
         self.arduino    = arduino
@@ -28,7 +34,7 @@ class BaseController:
         self.timeout    = rospy.get_param("~base_controller_timeout", 0.7)
 
         self.debugPID   = rospy.get_param('/dynamic_tutorials/debugPID', False)
-	
+
         pid_params = dict()
         pid_params['wheel_diameter']     = rospy.get_param("~wheel_diameter", 0.058)
         pid_params['wheel_track']        = rospy.get_param("~wheel_track", 0.126)
@@ -324,7 +330,7 @@ class BaseController:
             self.CVelPub.publish(self.v_C)
 
 
-    # stop move mobile base
+    # stop move mobileBase
     def stop(self):
         self.v_A = 0
         self.v_B = 0
@@ -332,10 +338,10 @@ class BaseController:
         self.v_des_AWheel = 0
         self.v_des_BWheel = 0
         self.v_des_CWheel = 0
-        if self.use_serial:
-            self.arduino.drive(0, 0, 0)
-        else:
-            self.arduino.i2c_drive(0, 0, 0)
+        #if self.use_serial:
+        #    self.arduino.drive(0, 0, 0)
+        #else:
+        #    self.arduino.i2c_drive(0, 0, 0)
         #rospy.logwarn("stop mobilebase move!!!!")
 
     def cmdVelCallback(self, req):