|
@@ -2,17 +2,15 @@
|
|
|
#-*- coding:utf-8 -*-
|
|
|
|
|
|
"""
|
|
|
- Copyright: 2016-2021 www.corvin.cn ROS小课堂
|
|
|
+ Copyright: 2016-2022 www.corvin.cn ROS小课堂
|
|
|
Description: A base controller class for the Arduino DUE microcontroller
|
|
|
Author: corvin
|
|
|
History:
|
|
|
20200704:当超过给下位机发送控制移动命令时间后,不需要再发送pwm控制0的命令.
|
|
|
因为在arduino代码会根据超时自己会执行pwm清零停止电机移动的命令.
|
|
|
- 20210913:为增加两轮平衡车模式优化代码.
|
|
|
+ 20210913:为增加两轮平衡车模式优化代码.
|
|
|
"""
|
|
|
-import os
|
|
|
-import rospy
|
|
|
-import roslib; roslib.load_manifest('ros_arduino_python')
|
|
|
+import os,rospy,roslib
|
|
|
import dynamic_reconfigure.client
|
|
|
|
|
|
from math import sin, cos, pi
|
|
@@ -32,10 +30,10 @@ class BaseController:
|
|
|
self.cmd_topic = cmd_topic
|
|
|
self.PID_rate = 100 #下位机中pid固定频率100hz
|
|
|
self.target_speed = 0
|
|
|
-
|
|
|
+
|
|
|
self.odom_name = rospy.get_param("~odom_name", "odom")
|
|
|
self.debugPID = rospy.get_param('/dynamic_tutorials/debugPID', False)
|
|
|
-
|
|
|
+
|
|
|
pid_params = dict()
|
|
|
pid_params['wheel_diameter'] = rospy.get_param("~wheel_diameter", 0.067)
|
|
|
pid_params['wheel_track'] = rospy.get_param("~wheel_track", 0.126)
|
|
@@ -103,12 +101,12 @@ class BaseController:
|
|
|
|
|
|
#增加用于调试PID参数的发布者
|
|
|
if self.debugPID:
|
|
|
- self.AEncoderPub = rospy.Publisher('Aencoder', Int32, queue_size=10)
|
|
|
- self.BEncoderPub = rospy.Publisher('Bencoder', Int32, queue_size=10)
|
|
|
- self.APidoutPub = rospy.Publisher('Apidout', Int32, queue_size=10)
|
|
|
- self.BPidoutPub = rospy.Publisher('Bpidout', Int32, queue_size=10)
|
|
|
- self.AVelPub = rospy.Publisher('Avel', Int32, queue_size=10)
|
|
|
- self.BVelPub = rospy.Publisher('Bvel', Int32, queue_size=10)
|
|
|
+ self.AEncoderPub = rospy.Publisher('Aencoder', Int32, queue_size=5)
|
|
|
+ self.BEncoderPub = rospy.Publisher('Bencoder', Int32, queue_size=5)
|
|
|
+ self.APidoutPub = rospy.Publisher('Apidout', Int32, queue_size=5)
|
|
|
+ self.BPidoutPub = rospy.Publisher('Bpidout', Int32, queue_size=5)
|
|
|
+ self.AVelPub = rospy.Publisher('Avel', Int32, queue_size=5)
|
|
|
+ self.BVelPub = rospy.Publisher('Bvel', Int32, queue_size=5)
|
|
|
|
|
|
rospy.loginfo("Started base controller of " + str(self.wheel_track) + "m with " + str(self.encoder_resolution) + " ticks per rev")
|
|
|
|
|
@@ -207,7 +205,7 @@ class BaseController:
|
|
|
#启动直立环控制,PD控制器,控制pitch角度和角速度
|
|
|
stand_pwm = self.balanceControl.keepBalance(pitch_err)
|
|
|
#stand_pwm = 0
|
|
|
-
|
|
|
+
|
|
|
#启动速度环控制,PI控制器
|
|
|
#speed_pwm = self.balanceControl.keepVelocity(encoder_diff_A, encoder_diff_B, self.target_speed)
|
|
|
speed_pwm = 0
|
|
@@ -218,11 +216,11 @@ class BaseController:
|
|
|
#计算最终发送给电机的pwm
|
|
|
pwm_A_tmp = stand_pwm + speed_pwm - turn_pwm
|
|
|
pwm_B_tmp = stand_pwm + speed_pwm + turn_pwm
|
|
|
-
|
|
|
+
|
|
|
#将计算得到的pwm值进行限幅,最大pwm值为255,保持正负号
|
|
|
pwm_A, pwm_B = self.pwm_ctrl(pwm_A_tmp, pwm_B_tmp)
|
|
|
pwm_A, pwm_B = self.balanceControl.checkIfDown(pitch_err, pwm_A, pwm_B)
|
|
|
-
|
|
|
+
|
|
|
if self.use_serial:
|
|
|
self.arduino.pwm_drive(pwm_A, pwm_B)
|
|
|
else:
|
|
@@ -287,7 +285,7 @@ class BaseController:
|
|
|
if time_now < (self.last_cmd_time + rospy.Duration(0.1)):
|
|
|
self.send_motor_speed()
|
|
|
#rospy.loginfo("send motor speed")
|
|
|
-
|
|
|
+
|
|
|
# normalize motor dest encode value and send
|
|
|
def send_motor_speed(self):
|
|
|
if self.v_A < self.v_des_AWheel:
|