Browse Source

优化panda左右旋转控制

corvin_zhang 4 years ago
parent
commit
06db631187

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

@@ -37,7 +37,7 @@ wheel_track: 0.21     #L value
 encoder_resolution: 11 #12V DC motors
 gear_reduction: 19     #empty payload rpm 130 r/m
 linear_scale_correction: 1.028
-angular_scale_correction: 2.00
+angular_scale_correction: 1.00
 
 # === PID parameters
 debugPID: False

+ 1 - 1
src/ros_arduino_bridge/ros_arduino_python/nodes/arduino_node.py

@@ -45,7 +45,7 @@ class ArduinoROS():
         self.cmd_vel = Twist()
 
         # A cmd_vel publisher so we can stop the robot when shutting down
-        self.cmd_vel_pub = rospy.Publisher('cmd_vel', Twist, queue_size=20)
+        self.cmd_vel_pub = rospy.Publisher('cmd_vel', Twist, queue_size=10)
 
         # A service to turn set the direction of a digital pin (0 = input, 1 = output)
         rospy.Service('~digital_set_direction', DigitalSetDirection, self.DigitalSetDirectionHandler)

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

@@ -23,7 +23,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
@@ -35,7 +35,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)

+ 5 - 5
src/teleop_twist_keyboard/teleop_twist_keyboard.py

@@ -18,9 +18,9 @@ msg = """
 Reading from the keyboard  and Publishing to Twist!
 ---------------------------
 Moving around:
-        i    
+        i
    j    k    l
-        ,    
+        ,
 
 
 anything else : stop
@@ -68,8 +68,8 @@ if __name__=="__main__":
     pub = rospy.Publisher('cmd_vel', Twist, queue_size = 5)
     rospy.init_node('teleop_twist_keyboard')
 
-    speed = rospy.get_param("~speed", 0.2)
-    turn = rospy.get_param("~turn", 1.4)
+    speed = rospy.get_param("~speed", 0.3)
+    turn = rospy.get_param("~turn", 2.5)
 
     x = 0
     y = 0
@@ -96,7 +96,7 @@ if __name__=="__main__":
                 print(vels(speed,turn))
                 if (status == 14):
                     print(msg)
-                status = (status + 1) % 15                   
+                status = (status + 1) % 15
             else:
                 x = 0
                 y = 0