dp_pid_controller_base.py
Go to the documentation of this file.
1 # Copyright (c) 2016-2019 The UUV Simulator Authors.
2 # All rights reserved.
3 #
4 # Licensed under the Apache License, Version 2.0 (the "License");
5 # you may not use this file except in compliance with the License.
6 # You may obtain a copy of the License at
7 #
8 # http://www.apache.org/licenses/LICENSE-2.0
9 #
10 # Unless required by applicable law or agreed to in writing, software
11 # distributed under the License is distributed on an "AS IS" BASIS,
12 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 # See the License for the specific language governing permissions and
14 # limitations under the License.
15 import numpy as np
16 import rospy
17 from uuv_control_msgs.srv import *
18 from .dp_controller_base import DPControllerBase
19 
20 
21 class DPPIDControllerBase(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.
25  """
26 
27  def __init__(self, *args):
28  # Start the super class
29  DPControllerBase.__init__(self, *args)
30  self._logger.info('Initializing: PID controller')
31  # Proportional gains
32  self._Kp = np.zeros(shape=(6, 6))
33  # Derivative gains
34  self._Kd = np.zeros(shape=(6, 6))
35  # Integral gains
36  self._Ki = np.zeros(shape=(6, 6))
37  # Integrator component
38  self._int = np.zeros(6)
39  # Error for the vehicle pose
40  self._error_pose = np.zeros(6)
41 
42  if rospy.has_param('~Kp'):
43  Kp_diag = rospy.get_param('~Kp')
44  if len(Kp_diag) == 6:
45  self._Kp = np.diag(Kp_diag)
46  else:
47  raise rospy.ROSException('Kp matrix error: 6 coefficients '
48  'needed')
49 
50  self._logger.info('Kp=' + str([self._Kp[i, i] for i in range(6)]))
51 
52  if rospy.has_param('~Kd'):
53  Kd_diag = rospy.get_param('~Kd')
54  if len(Kd_diag) == 6:
55  self._Kd = np.diag(Kd_diag)
56  else:
57  raise rospy.ROSException('Kd matrix error: 6 coefficients '
58  'needed')
59 
60  self._logger.info('Kd=' + str([self._Kd[i, i] for i in range(6)]))
61 
62  if rospy.has_param('~Ki'):
63  Ki_diag = rospy.get_param('~Ki')
64  if len(Ki_diag) == 6:
65  self._Ki = np.diag(Ki_diag)
66  else:
67  raise rospy.ROSException('Ki matrix error: 6 coefficients '
68  'needed')
69 
70  self._logger.info('Ki=' + str([self._Ki[i, i] for i in range(6)]))
71 
72  self._services['set_pid_params'] = rospy.Service(
73  'set_pid_params',
74  SetPIDParams,
76  self._services['get_pid_params'] = rospy.Service(
77  'get_pid_params',
78  GetPIDParams,
80 
81  self._logger.info('PID controller ready!')
82 
83  def _reset_controller(self):
84  """Reset reference and and error vectors."""
85  super(DPPIDControllerBase, self)._reset_controller()
86  self._error_pose = np.zeros(6)
87  self._int = np.zeros(6)
88 
89  def set_pid_params_callback(self, request):
90  """Service callback function to set the
91  PID's parameters
92  """
93  kp = request.Kp
94  kd = request.Kd
95  ki = request.Ki
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)
102 
103  def get_pid_params_callback(self, request):
104  """Service callback function to return
105  the PID's parameters
106  """
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)])
111 
112  def update_pid(self):
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
117  vector.
118 
119  > *Returns*
120 
121  `numpy.array`: Control signal
122  """
123  if not self.odom_is_init:
124  return
125  # Update integrator
126  self._int += 0.5 * (self.error_pose_euler + self._error_pose) * self._dt
127  # Store current pose error
128  self._error_pose = self.error_pose_euler
129  return np.dot(self._Kp, self.error_pose_euler) \
130  + np.dot(self._Kd, self._errors['vel']) \
131  + np.dot(self._Ki, self._int)


uuv_trajectory_control
Author(s):
autogenerated on Thu Jun 18 2020 03:28:42