|
@@ -30,24 +30,24 @@ class BaseController:
|
|
|
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)
|
|
|
- pid_params['encoder_resolution'] = rospy.get_param("~encoder_resolution", 11)
|
|
|
- pid_params['gear_reduction'] = rospy.get_param("~gear_reduction", 46)
|
|
|
- pid_params['AWheel_Kp'] = rospy.get_param("~AWheel_Kp", 15)
|
|
|
- pid_params['AWheel_Kd'] = rospy.get_param("~AWheel_Kd", 15)
|
|
|
- pid_params['AWheel_Ki'] = rospy.get_param("~AWheel_Ki", 0)
|
|
|
- pid_params['AWheel_Ko'] = rospy.get_param("~AWheel_Ko", 50)
|
|
|
-
|
|
|
- pid_params['BWheel_Kp'] = rospy.get_param("~BWheel_Kp", 15)
|
|
|
- pid_params['BWheel_Kd'] = rospy.get_param("~BWheel_Kd", 15)
|
|
|
- pid_params['BWheel_Ki'] = rospy.get_param("~BWheel_Ki", 0)
|
|
|
- pid_params['BWheel_Ko'] = rospy.get_param("~BWheel_Ko", 50)
|
|
|
-
|
|
|
- pid_params['CWheel_Kp'] = rospy.get_param("~CWheel_Kp", 15)
|
|
|
- pid_params['CWheel_Kd'] = rospy.get_param("~CWheel_Kd", 15)
|
|
|
- pid_params['CWheel_Ki'] = rospy.get_param("~CWheel_Ki", 0)
|
|
|
- pid_params['CWheel_Ko'] = rospy.get_param("~CWheel_Ko", 50)
|
|
|
+ pid_params['wheel_diameter'] = rospy.get_param("~wheel_diameter", 0.058)
|
|
|
+ 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", 46)
|
|
|
+ pid_params['AWheel_Kp'] = rospy.get_param("~AWheel_Kp", 15)
|
|
|
+ pid_params['AWheel_Kd'] = rospy.get_param("~AWheel_Kd", 15)
|
|
|
+ pid_params['AWheel_Ki'] = rospy.get_param("~AWheel_Ki", 0)
|
|
|
+ pid_params['AWheel_Ko'] = rospy.get_param("~AWheel_Ko", 50)
|
|
|
+
|
|
|
+ pid_params['BWheel_Kp'] = rospy.get_param("~BWheel_Kp", 15)
|
|
|
+ pid_params['BWheel_Kd'] = rospy.get_param("~BWheel_Kd", 15)
|
|
|
+ pid_params['BWheel_Ki'] = rospy.get_param("~BWheel_Ki", 0)
|
|
|
+ pid_params['BWheel_Ko'] = rospy.get_param("~BWheel_Ko", 50)
|
|
|
+
|
|
|
+ pid_params['CWheel_Kp'] = rospy.get_param("~CWheel_Kp", 15)
|
|
|
+ pid_params['CWheel_Kd'] = rospy.get_param("~CWheel_Kd", 15)
|
|
|
+ pid_params['CWheel_Ki'] = rospy.get_param("~CWheel_Ki", 0)
|
|
|
+ pid_params['CWheel_Ko'] = rospy.get_param("~CWheel_Ko", 50)
|
|
|
|
|
|
self.accel_limit = rospy.get_param('~accel_limit', 0.05)
|
|
|
self.linear_scale_correction = rospy.get_param("~linear_scale_correction", 1.0)
|