Skip to content

Commit 8d73088

Browse files
committed
added comments to the controller #7
1 parent bf2e193 commit 8d73088

File tree

6 files changed

+125
-163
lines changed

6 files changed

+125
-163
lines changed

controller_modules/include/controller_modules/ControllerBase.h

+6
Original file line numberDiff line numberDiff line change
@@ -4,12 +4,17 @@
44
#include <Eigen/Core>
55
#include <ros/ros.h>
66

7+
/**
8+
* @brief Base class for controllers to be build
9+
*
10+
*/
711
class ControllerBase
812
{
913
public:
1014
ControllerBase(){}
1115
~ControllerBase(){}
1216

17+
//overide function to calculate the controller output
1318
virtual void update(const trajectory_msgs::JointTrajectoryPoint&, const trajectory_msgs::JointTrajectoryPoint&, std::vector<double>&)=0;
1419
virtual std::vector<double> get_error(){return error;}
1520
virtual std::vector<double> get_tau(){return tau;}
@@ -20,6 +25,7 @@ class ControllerBase
2025
std::vector<double> error;
2126
std::vector<double> tau;
2227

28+
//helper function to convert between the std vectors and Eigen vectors
2329
template<typename T, typename A>
2430
Eigen::VectorXd VectToEigen(std::vector<T,A> const& msg )
2531
{

controller_modules/include/controller_modules/ControllerManager.h

+4
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,10 @@
99
#include "controller_modules/ControllerList.h"
1010
#include <vector>
1111

12+
/**
13+
* @brief Manages the attached controllers and wrapps them to be called by ros
14+
*
15+
*/
1216
class ControllerManager
1317
{
1418
public:

controller_modules/include/controller_modules/PDController.h

-1
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@ class PDController : public ControllerBase
1818
void calculate_torque( const Eigen::VectorXd& e, const Eigen::VectorXd& ed, Eigen::VectorXd& tau);
1919
void update(const trajectory_msgs::JointTrajectoryPoint&, const trajectory_msgs::JointTrajectoryPoint&, std::vector<double>&);
2020

21-
2221
private:
2322

2423
Eigen::MatrixXd Kp;
+59-18
Original file line numberDiff line numberDiff line change
@@ -1,51 +1,92 @@
11
#include "controller_modules/ControllerManager.h"
22

33

4-
5-
ControllerManager::ControllerManager(ros::NodeHandle* n):nh(*n)
4+
/**
5+
* @brief Construct a new Controller Manager:: Controller Manager object
6+
*
7+
* @param n ros node handle
8+
*/
9+
ControllerManager::ControllerManager(ros::NodeHandle *n) : nh(*n)
610
{
7-
calc_tau_srv = nh.advertiseService("CalcTau", &ControllerManager::calcTauSrv, this);
11+
calc_tau_srv = nh.advertiseService("CalcTau", &ControllerManager::calcTauSrv, this);
812
controller_list_srv = nh.advertiseService("ControllerList", &ControllerManager::getControllersListSrv, this);
913
}
1014

1115
ControllerManager::ControllerManager() {}
1216

13-
1417
ControllerManager::~ControllerManager()
1518
{
16-
1719
}
1820

19-
bool ControllerManager::getControllersListSrv(controller_modules::ControllerListRequest& req, controller_modules::ControllerListResponse& res)
20-
{
21+
/**
22+
* @brief Ros serverice to get a list of the controllers
23+
*
24+
* @param req blank message
25+
* @param res list of controllers
26+
* @return true service was called
27+
* @return false service failed to be called
28+
*/
29+
bool ControllerManager::getControllersListSrv(controller_modules::ControllerListRequest &req, controller_modules::ControllerListResponse &res)
30+
{
2131
res.controllers = getControllerList();
32+
return true;
2233
}
2334

35+
/**
36+
* @brief get a list of the attached controllers
37+
*
38+
* @return std::vector<std::string>
39+
*/
2440
std::vector<std::string> ControllerManager::getControllerList()
2541
{
2642
std::vector<std::string> names;
27-
for( std::pair<std::string, boost::shared_ptr<ControllerBase>> node: controller_list )
43+
for (std::pair<std::string, boost::shared_ptr<ControllerBase>> node : controller_list)
2844
{
2945
names.push_back(node.first);
3046
}
3147
return names;
3248
}
3349

34-
void ControllerManager::addController(std::string name, boost::shared_ptr<ControllerBase> controller )
50+
/**
51+
* @brief add a controller to the manager that can be accessed by the server
52+
*
53+
* @param name the name of the controller to be added
54+
* @param controller the controller to be added
55+
*
56+
*/
57+
void ControllerManager::addController(std::string name, boost::shared_ptr<ControllerBase> controller)
3558
{
3659
//boost::shared_ptr<ControllerBase> cntl(*controller) ;
3760
controller_list[name] = controller;
3861
}
3962

40-
41-
bool ControllerManager::calcTauSrv(controller_modules::JointControlRequest& req, controller_modules::JointControlResponse& res )
63+
/**
64+
* @brief service to call the control manager, used the name of the controller to calculat the control input
65+
*
66+
* @param req Joint control request message
67+
* @param res Joint control responce message
68+
* @return true
69+
* @return false
70+
*/
71+
bool ControllerManager::calcTauSrv(controller_modules::JointControlRequest &req, controller_modules::JointControlResponse &res)
4272
{
73+
std::vector<double> output; // declare a var to hold the output
74+
std::string name = req.controller_name; //get the name of the controller to call
75+
// ROS_INFO( name.c_str() ) ;
76+
std::unordered_map<std::string, boost::shared_ptr<ControllerBase>>::const_iterator got = controller_list.find (name); //check is controller exists
4377

44-
std::vector<double> thing;
45-
std::string name = req.controller_name;
46-
controller_list[name.c_str()]->update(req.actual, req.desired, thing );
47-
//std::vector<double> error = controller_list[req.controller_name]->get_error();
48-
res.control_output.effort = thing;
78+
//if the controller is not found throw error
79+
if (got == controller_list.end() )
80+
{
81+
ROS_ERROR("Controller not found");
82+
return false;
83+
}
84+
else
85+
{
86+
//if the controller is found call the controller
87+
controller_list[name.c_str()]->update(req.actual, req.desired, output);
88+
res.control_output.effort = output;
89+
return true;
90+
}
4991

50-
return true;
51-
}
92+
}

controller_modules/src/PDController.cpp

+56-10
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,11 @@
11
#include "controller_modules/PDController.h"
22

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+
*/
49
PDController::PDController(const Eigen::MatrixXd& _Kp, const Eigen::MatrixXd& _Kd):
510
Kp(validateMat(_Kp, _Kd)),
611
Kd(validateMat(_Kd, _Kp)) //validate the size of the matrix
@@ -17,7 +22,13 @@ PDController::~PDController()
1722
{
1823

1924
}
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+
*/
2132
bool PDController::setKp(const Eigen::MatrixXd& mat)
2233
{
2334
int r = mat.rows();
@@ -35,6 +46,13 @@ bool PDController::setKp(const Eigen::MatrixXd& mat)
3546

3647
}
3748

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+
*/
3856
bool PDController::setKd(const Eigen::MatrixXd& mat)
3957
{
4058

@@ -53,18 +71,33 @@ bool PDController::setKd(const Eigen::MatrixXd& mat)
5371

5472
}
5573

74+
/**
75+
* @brief get the Kp matrix
76+
*
77+
* @return Eigen::MatrixXd
78+
*/
5679
Eigen::MatrixXd PDController::getKp()
5780

5881
{
5982
return Kp;
6083
}
61-
84+
/**
85+
* @brief get the Kd matrix
86+
*
87+
* @return Eigen::MatrixXd
88+
*/
6289
Eigen::MatrixXd PDController::getKd()
6390
{
6491
return Kd;
6592
}
6693

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+
*/
68101
Eigen::MatrixXd PDController::validateMat(const Eigen::MatrixXd& mat1, const Eigen::MatrixXd& mat2)
69102
{
70103
int r1 = mat1.rows();
@@ -83,17 +116,29 @@ Eigen::MatrixXd PDController::validateMat(const Eigen::MatrixXd& mat1, const Eig
83116

84117
}
85118

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+
*/
86127
void PDController::calculate_torque(const Eigen::VectorXd &e, const Eigen::VectorXd &ed, Eigen::VectorXd &torque)
87128
{
88-
torque = Kp*e+ Kd*ed;
129+
torque = Kp*e + Kd*ed;
89130
}
90131

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+
*/
92139
void PDController::update(const trajectory_msgs::JointTrajectoryPoint& actual, const trajectory_msgs::JointTrajectoryPoint& desired, std::vector<double>& torque)
93140
{
94141

95-
96-
97142
int dp_size = desired.positions.size();
98143
int ap_size = actual.positions.size();
99144
int pv_size = desired.velocities.size();
@@ -106,15 +151,16 @@ void PDController::update(const trajectory_msgs::JointTrajectoryPoint& actual, c
106151
Eigen::VectorXd ed = VectToEigen(desired.velocities) - VectToEigen(actual.velocities);
107152
Eigen::VectorXd tau_(e.rows());
108153
calculate_torque(e, ed, tau_);
109-
154+
155+
156+
// tau = qdd + Kq(q_d - q) + Kd(qd_d - q_d)
110157
if (desired.accelerations.size() == dp_size)
111158
{
112159
tau_ = tau_ + VectToEigen(desired.accelerations);
113160
}
114161

115162
std::vector<double> my_tau(&tau_[0], tau_.data()+tau_.cols()*tau_.rows());
116163
tau = my_tau;
117-
//error = std::vector<double>(&e[0], e.data()+e.cols()*e.rows());
118164
torque = tau;
119165

120166
}

0 commit comments

Comments
 (0)