18 from .dp_controller_base
import DPControllerBase
22 """Abstract class for PID-based controllers. The base 23 class method `update_controller` must be overridden 24 in other for a controller to work. 29 DPControllerBase.__init__(self, *args)
30 self._logger.info(
'Initializing: PID controller')
32 self.
_Kp = np.zeros(shape=(6, 6))
34 self.
_Kd = np.zeros(shape=(6, 6))
36 self.
_Ki = np.zeros(shape=(6, 6))
42 if rospy.has_param(
'~Kp'):
43 Kp_diag = rospy.get_param(
'~Kp')
45 self.
_Kp = np.diag(Kp_diag)
47 raise rospy.ROSException(
'Kp matrix error: 6 coefficients ' 50 self._logger.info(
'Kp=' + str([self.
_Kp[i, i]
for i
in range(6)]))
52 if rospy.has_param(
'~Kd'):
53 Kd_diag = rospy.get_param(
'~Kd')
55 self.
_Kd = np.diag(Kd_diag)
57 raise rospy.ROSException(
'Kd matrix error: 6 coefficients ' 60 self._logger.info(
'Kd=' + str([self.
_Kd[i, i]
for i
in range(6)]))
62 if rospy.has_param(
'~Ki'):
63 Ki_diag = rospy.get_param(
'~Ki')
65 self.
_Ki = np.diag(Ki_diag)
67 raise rospy.ROSException(
'Ki matrix error: 6 coefficients ' 70 self._logger.info(
'Ki=' + str([self.
_Ki[i, i]
for i
in range(6)]))
72 self._services[
'set_pid_params'] = rospy.Service(
76 self._services[
'get_pid_params'] = rospy.Service(
81 self._logger.info(
'PID controller ready!')
84 """Reset reference and and error vectors.""" 87 self.
_int = np.zeros(6)
90 """Service callback function to set the 96 if len(kp) != 6
or len(kd) != 6
or len(ki) != 6:
97 return SetPIDParamsResponse(
False)
98 self.
_Kp = np.diag(kp)
99 self.
_Ki = np.diag(ki)
100 self.
_Kd = np.diag(kd)
101 return SetPIDParamsResponse(
True)
104 """Service callback function to return 107 return GetPIDParamsResponse(
108 [self.
_Kp[i, i]
for i
in range(6)],
109 [self.
_Kd[i, i]
for i
in range(6)],
110 [self.
_Ki[i, i]
for i
in range(6)])
113 """Return the control signal computed from the PID 114 algorithm. To implement a PID-based controller that 115 inherits this class, call this function in the 116 derived class' `update` method to obtain the control 121 `numpy.array`: Control signal 123 if not self.odom_is_init:
126 self.
_int += 0.5 * (self.error_pose_euler + self.
_error_pose) * self._dt
129 return np.dot(self.
_Kp, self.error_pose_euler) \
130 + np.dot(self.
_Kd, self._errors[
'vel']) \
def _reset_controller(self)
def set_pid_params_callback(self, request)
def get_pid_params_callback(self, request)