1
1
#include " controller_modules/PDController.h"
2
2
3
-
3
+ /* *
4
+ * @brief Construct a new PDController::PDController object
5
+ *
6
+ * @param _Kp matrix for the Kp gains
7
+ * @param _Kd matrix forthe Kd gains
8
+ */
4
9
PDController::PDController (const Eigen::MatrixXd& _Kp, const Eigen::MatrixXd& _Kd):
5
10
Kp(validateMat(_Kp, _Kd)),
6
11
Kd(validateMat(_Kd, _Kp)) // validate the size of the matrix
@@ -17,7 +22,13 @@ PDController::~PDController()
17
22
{
18
23
19
24
}
20
-
25
+ /* *
26
+ * @brief initlize the Kp matrix
27
+ *
28
+ * @param mat matrix to set the gains
29
+ * @return true matrix is valid
30
+ * @return false matix is not valid
31
+ */
21
32
bool PDController::setKp (const Eigen::MatrixXd& mat)
22
33
{
23
34
int r = mat.rows ();
@@ -35,6 +46,13 @@ bool PDController::setKp(const Eigen::MatrixXd& mat)
35
46
36
47
}
37
48
49
+ /* *
50
+ * @brief initlize the Kd matrix
51
+ *
52
+ * @param mat matrix to set the gains
53
+ * @return true matrix is valid
54
+ * @return false matix is not valid
55
+ */
38
56
bool PDController::setKd (const Eigen::MatrixXd& mat)
39
57
{
40
58
@@ -53,18 +71,33 @@ bool PDController::setKd(const Eigen::MatrixXd& mat)
53
71
54
72
}
55
73
74
+ /* *
75
+ * @brief get the Kp matrix
76
+ *
77
+ * @return Eigen::MatrixXd
78
+ */
56
79
Eigen::MatrixXd PDController::getKp ()
57
80
58
81
{
59
82
return Kp;
60
83
}
61
-
84
+ /* *
85
+ * @brief get the Kd matrix
86
+ *
87
+ * @return Eigen::MatrixXd
88
+ */
62
89
Eigen::MatrixXd PDController::getKd ()
63
90
{
64
91
return Kd;
65
92
}
66
93
67
-
94
+ /* *
95
+ * @brief The matrix need to be the same shape
96
+ *
97
+ * @param mat1 matrix 1 to compare
98
+ * @param mat2 matrix 2 to compare
99
+ * @return Eigen::MatrixXd
100
+ */
68
101
Eigen::MatrixXd PDController::validateMat (const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2)
69
102
{
70
103
int r1 = mat1.rows ();
@@ -83,17 +116,29 @@ Eigen::MatrixXd PDController::validateMat(const Eigen::MatrixXd& mat1, const Eig
83
116
84
117
}
85
118
119
+
120
+ /* *
121
+ * @brief calculate the torque for the cotnroller
122
+ * tau = Kq(q_d - q) + Kd(qd_d - q_d)
123
+ * @param e vector of the position error
124
+ * @param ed vector of the velocity error
125
+ * @param torque output vector of the torque
126
+ */
86
127
void PDController::calculate_torque (const Eigen::VectorXd &e, const Eigen::VectorXd &ed, Eigen::VectorXd &torque)
87
128
{
88
- torque = Kp*e+ Kd*ed;
129
+ torque = Kp*e + Kd*ed;
89
130
}
90
131
91
-
132
+ /* *
133
+ * @brief calls the main controller calculation function and puts the data into the required form
134
+ *
135
+ * @param actual message with the current joint states
136
+ * @param desired message with the desired jotni states
137
+ * @param torque output of the torque requried
138
+ */
92
139
void PDController::update (const trajectory_msgs::JointTrajectoryPoint& actual, const trajectory_msgs::JointTrajectoryPoint& desired, std::vector<double >& torque)
93
140
{
94
141
95
-
96
-
97
142
int dp_size = desired.positions .size ();
98
143
int ap_size = actual.positions .size ();
99
144
int pv_size = desired.velocities .size ();
@@ -106,15 +151,16 @@ void PDController::update(const trajectory_msgs::JointTrajectoryPoint& actual, c
106
151
Eigen::VectorXd ed = VectToEigen (desired.velocities ) - VectToEigen (actual.velocities );
107
152
Eigen::VectorXd tau_ (e.rows ());
108
153
calculate_torque (e, ed, tau_);
109
-
154
+
155
+
156
+ // tau = qdd + Kq(q_d - q) + Kd(qd_d - q_d)
110
157
if (desired.accelerations .size () == dp_size)
111
158
{
112
159
tau_ = tau_ + VectToEigen (desired.accelerations );
113
160
}
114
161
115
162
std::vector<double > my_tau (&tau_[0 ], tau_.data ()+tau_.cols ()*tau_.rows ());
116
163
tau = my_tau;
117
- // error = std::vector<double>(&e[0], e.data()+e.cols()*e.rows());
118
164
torque = tau;
119
165
120
166
}
0 commit comments