|
@@ -9,6 +9,8 @@
|
|
|
20200704:当超过给下位机发送控制移动命令时间后,不需要再发送pwm控制0的命令.
|
|
|
因为在arduino代码会根据超时自己会执行pwm清零停止电机移动的命令.
|
|
|
20210913:为增加两轮平衡车模式优化代码.
|
|
|
+ 20220927:将电机编码器计数的参数获取改为一个参数motor_encoder_cnt,直接为
|
|
|
+ CHANGE模式四倍频的总计数1320个,不使用减速比和编码器分辨率参数.
|
|
|
"""
|
|
|
import os,rospy,roslib
|
|
|
import dynamic_reconfigure.client
|
|
@@ -35,10 +37,6 @@ class BaseController:
|
|
|
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)
|
|
|
- pid_params['encoder_resolution'] = rospy.get_param("~encoder_resolution", 11)
|
|
|
- pid_params['gear_reduction'] = rospy.get_param("~gear_reduction", 30)
|
|
|
pid_params['AWheel_Kp'] = rospy.get_param("~AWheel_Kp", 18)
|
|
|
pid_params['AWheel_Kd'] = rospy.get_param("~AWheel_Kd", 18)
|
|
|
pid_params['AWheel_Ki'] = rospy.get_param("~AWheel_Ki", 0)
|
|
@@ -49,19 +47,25 @@ class BaseController:
|
|
|
pid_params['BWheel_Ki'] = rospy.get_param("~BWheel_Ki", 0)
|
|
|
pid_params['BWheel_Ko'] = rospy.get_param("~BWheel_Ko", 10)
|
|
|
|
|
|
- self.accel_limit = rospy.get_param('~accel_limit', 0.1)
|
|
|
self.linear_scale_correction = rospy.get_param("~linear_scale_correction", 1.0)
|
|
|
self.angular_scale_correction = rospy.get_param("~angular_scale_correction", 1.0)
|
|
|
|
|
|
+ #获取两轮子之间距离的配置参数,影响小车的转动角速度大小
|
|
|
+ self.wheel_track = rospy.get_param("~wheel_track", 0.126)
|
|
|
+ self.wheel_track = self.wheel_track/self.angular_scale_correction
|
|
|
+
|
|
|
#配置电机pid参数
|
|
|
- self.setup_pid(pid_params)
|
|
|
+ self.setup_motor_pid(pid_params)
|
|
|
|
|
|
#配置电机每米有多少个脉冲数
|
|
|
- self.ticks_per_meter = self.encoder_resolution*self.gear_reduction*2/(self.wheel_diameter*pi)
|
|
|
- self.ticks_per_meter = self.ticks_per_meter/self.linear_scale_correction
|
|
|
+ self.motor_encoder_cnt = rospy.get_param("~motor_encoder_cnt", 1320)
|
|
|
+ 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
|
|
|
|
|
|
#设置电机的加速度最大值
|
|
|
- self.max_accel = self.accel_limit*self.ticks_per_meter
|
|
|
+ self.accel_limit = rospy.get_param('~motor_accel_limit', 0.1)
|
|
|
+ self.max_accel = self.accel_limit*self.ticks_per_meter
|
|
|
|
|
|
now = rospy.Time.now()
|
|
|
self.old_time = now # time for determining dx/dy
|
|
@@ -108,9 +112,7 @@ class BaseController:
|
|
|
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")
|
|
|
-
|
|
|
- def setup_pid(self, pid_params):
|
|
|
+ def setup_motor_pid(self, pid_params):
|
|
|
# Check to see if any PID parameters are missing
|
|
|
missing_params = False
|
|
|
for param in pid_params:
|
|
@@ -121,12 +123,6 @@ class BaseController:
|
|
|
if missing_params:
|
|
|
os._exit(1)
|
|
|
|
|
|
- self.encoder_resolution = pid_params['encoder_resolution']
|
|
|
- self.gear_reduction = pid_params['gear_reduction']
|
|
|
- self.wheel_diameter = pid_params['wheel_diameter']
|
|
|
- self.wheel_track = pid_params['wheel_track']
|
|
|
- self.wheel_track = self.wheel_track/self.angular_scale_correction
|
|
|
-
|
|
|
self.AWheel_Kp = pid_params['AWheel_Kp']
|
|
|
self.AWheel_Kd = pid_params['AWheel_Kd']
|
|
|
self.AWheel_Ki = pid_params['AWheel_Ki']
|
|
@@ -238,7 +234,6 @@ class BaseController:
|
|
|
va = dist_A/dt
|
|
|
vb = dist_B/dt
|
|
|
|
|
|
-
|
|
|
#正向运动学模型,计算里程计模型
|
|
|
vx = (va + vb)/2.0
|
|
|
vth = (va - vb)/(self.wheel_track)
|