/
gravity_comp_controller.cpp
344 lines (287 loc) · 9.87 KB
/
gravity_comp_controller.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
#include <controller_interface/controller.h>
#include <hardware_interface/joint_command_interface.h>
#include <control_toolbox/pid.h>
#include <realtime_tools/realtime_buffer.h>
#include <pluginlib/class_list_macros.h>
#include <std_msgs/Float64MultiArray.h>
#include <angles/angles.h>
#include <urdf/model.h>
#include <kdl/tree.hpp>
#include <kdl/kdl.hpp>
#include <kdl/chain.hpp>
#include <kdl/chaindynparam.hpp>
#include <kdl_parser/kdl_parser.hpp>
#include <boost/scoped_ptr.hpp>
#include "arm_controllers/ControllerJointState.h"
#define PI 3.141592
#define D2R PI/180.0
#define R2D 180.0/PI
namespace arm_controllers{
class GravityCompController: public controller_interface::Controller<hardware_interface::EffortJointInterface>
{
public:
~GravityCompController()
{
command_sub_.shutdown();
}
bool init(hardware_interface::EffortJointInterface* hw, ros::NodeHandle &n)
{
loop_count_ = 0;
// List of controlled joints
if (!n.getParam("joints", joint_names_))
{
ROS_ERROR("Could not find joint name");
return false;
}
n_joints_ = joint_names_.size();
if(n_joints_ == 0)
{
ROS_ERROR("List of joint names is empty.");
return false;
}
// urdf
urdf::Model urdf;
if (!urdf.initParam("robot_description"))
{
ROS_ERROR("Failed to parse urdf file");
return false;
}
// joint handle
for(int i=0; i<n_joints_; i++)
{
try
{
joints_.push_back(hw->getHandle(joint_names_[i]));
}
catch (const hardware_interface::HardwareInterfaceException& e)
{
ROS_ERROR_STREAM("Exception thrown: " << e.what());
return false;
}
urdf::JointConstSharedPtr joint_urdf = urdf.getJoint(joint_names_[i]);
if (!joint_urdf)
{
ROS_ERROR("Could not find joint '%s' in urdf", joint_names_[i].c_str());
return false;
}
joint_urdfs_.push_back(joint_urdf);
}
// kdl parser
if (!kdl_parser::treeFromUrdfModel(urdf, kdl_tree_)){
ROS_ERROR("Failed to construct kdl tree");
return false;
}
// kdl chain
std::string root_name, tip_name;
if (!n.getParam("root_link", root_name))
{
ROS_ERROR("Could not find root link name");
return false;
}
if (!n.getParam("tip_link", tip_name))
{
ROS_ERROR("Could not find tip link name");
return false;
}
if(!kdl_tree_.getChain(root_name, tip_name, kdl_chain_))
{
ROS_ERROR_STREAM("Failed to get KDL chain from tree: ");
ROS_ERROR_STREAM(" "<<root_name<<" --> "<<tip_name);
ROS_ERROR_STREAM(" Tree has "<<kdl_tree_.getNrOfJoints()<<" joints");
ROS_ERROR_STREAM(" Tree has "<<kdl_tree_.getNrOfSegments()<<" segments");
ROS_ERROR_STREAM(" The segments are:");
KDL::SegmentMap segment_map = kdl_tree_.getSegments();
KDL::SegmentMap::iterator it;
for( it=segment_map.begin(); it != segment_map.end(); it++ )
ROS_ERROR_STREAM( " "<<(*it).first);
return false;
}
gravity_ = KDL::Vector::Zero();
gravity_(2) = -9.81;
G_.resize(n_joints_);
// inverse dynamics solver
id_solver_.reset( new KDL::ChainDynParam(kdl_chain_, gravity_) );
// command and state
tau_cmd_ = Eigen::VectorXd::Zero(n_joints_);
tau_fric_ = Eigen::VectorXd::Zero(n_joints_);
q_cmd_.data = Eigen::VectorXd::Zero(n_joints_);
qdot_cmd_.data = Eigen::VectorXd::Zero(n_joints_);
qddot_cmd_.data = Eigen::VectorXd::Zero(n_joints_);
q_.data = Eigen::VectorXd::Zero(n_joints_);
qdot_.data = Eigen::VectorXd::Zero(n_joints_);
q_error_ = Eigen::VectorXd::Zero(n_joints_);
q_error_dot_ = Eigen::VectorXd::Zero(n_joints_);
// pids
pids_.resize(n_joints_);
for (size_t i=0; i<n_joints_; i++)
{
// Load PID Controller using gains set on parameter server
if (!pids_[i].init(ros::NodeHandle(n, "gains/" + joint_names_[i] + "/pid")))
{
ROS_ERROR_STREAM("Failed to load PID parameters from " << joint_names_[i] + "/pid");
return false;
}
}
// command subscriber
commands_buffer_.writeFromNonRT(std::vector<double>(n_joints_, 0.0));
command_sub_ = n.subscribe<std_msgs::Float64MultiArray>("command", 1, &GravityCompController::commandCB, this);
// Start realtime state publisher
controller_state_pub_.reset(
new realtime_tools::RealtimePublisher<arm_controllers::ControllerJointState>(n, "state", 1));
controller_state_pub_->msg_.header.stamp = ros::Time::now();
for (size_t i=0; i<n_joints_; i++)
{
controller_state_pub_->msg_.name.push_back(joint_names_[i]);
controller_state_pub_->msg_.command.push_back(0.0);
controller_state_pub_->msg_.command_dot.push_back(0.0);
controller_state_pub_->msg_.state.push_back(0.0);
controller_state_pub_->msg_.state_dot.push_back(0.0);
controller_state_pub_->msg_.error.push_back(0.0);
controller_state_pub_->msg_.error_dot.push_back(0.0);
controller_state_pub_->msg_.effort_command.push_back(0.0);
controller_state_pub_->msg_.effort_feedforward.push_back(0.0);
controller_state_pub_->msg_.effort_feedback.push_back(0.0);
}
return true;
}
void starting(const ros::Time& time)
{
// get joint positions
for(size_t i=0; i<n_joints_; i++)
{
q_(i) = joints_[i].getPosition();
qdot_(i) = joints_[i].getVelocity();
}
ROS_INFO("Starting Gravity Compensation Controller");
}
void commandCB(const std_msgs::Float64MultiArrayConstPtr& msg)
{
if(msg->data.size()!=n_joints_)
{
ROS_ERROR_STREAM("Dimension of command (" << msg->data.size() << ") does not match number of joints (" << n_joints_ << ")! Not executing!");
return;
}
commands_buffer_.writeFromNonRT(msg->data);
}
void update(const ros::Time& time, const ros::Duration& period)
{
std::vector<double> & commands = *commands_buffer_.readFromRT();
double dt = period.toSec();
double q_cmd_old;
// get joint states
static double t = 0;
for (size_t i=0; i<n_joints_; i++)
{
q_cmd_old = q_cmd_(i);
//q_cmd_(i) = commands[i];
q_cmd_(i) = 45*D2R*sin(PI/2*t);
enforceJointLimits(q_cmd_(i), i);
// qdot_cmd_(i) = ( q_cmd_(i) - q_cmd_old )/dt;
qdot_cmd_(i) = 45*D2R*PI/2*cos(PI/2*t);
q_(i) = joints_[i].getPosition();
qdot_(i) = joints_[i].getVelocity();
// Compute position error
if (joint_urdfs_[i]->type == urdf::Joint::REVOLUTE)
{
angles::shortest_angular_distance_with_limits(
q_(i),
q_cmd_(i),
joint_urdfs_[i]->limits->lower,
joint_urdfs_[i]->limits->upper,
q_error_(i));
}
else if (joint_urdfs_[i]->type == urdf::Joint::CONTINUOUS)
{
q_error_(i) = angles::shortest_angular_distance(q_(i), q_cmd_(i));
}
else // prismatic
{
q_error_(i) = q_cmd_(i) - q_(i);
}
q_error_dot_(i) = qdot_cmd_(i) - qdot_(i);
// friction compensation, to do: implement friction observer
tau_fric_(i) = 1*qdot_(i) + 1*KDL::sign(qdot_(i));
}
t += dt;
// compute gravity torque
id_solver_->JntToGravity(q_, G_);
// torque command
for(int i=0; i<n_joints_; i++)
{
//
tau_cmd_(i) = G_(i) + tau_fric_(i);
controller_state_pub_->msg_.effort_feedforward[i] = tau_cmd_(i);
tau_cmd_(i) += pids_[i].computeCommand(q_error_(i), q_error_dot_(i), period);
// effort saturation
if (tau_cmd_(i) >= joint_urdfs_[i]->limits->effort)
tau_cmd_(i) = joint_urdfs_[i]->limits->effort;
if (tau_cmd_(i) <= -joint_urdfs_[i]->limits->effort)
tau_cmd_(i) = -joint_urdfs_[i]->limits->effort;
joints_[i].setCommand( tau_cmd_(i) );
}
// publish
if (loop_count_ % 10 == 0)
{
if (controller_state_pub_->trylock())
{
controller_state_pub_->msg_.header.stamp = time;
for(int i=0; i<n_joints_; i++)
{
controller_state_pub_->msg_.command[i] = R2D*q_cmd_(i);
controller_state_pub_->msg_.command_dot[i] = R2D*qdot_cmd_(i);
controller_state_pub_->msg_.state[i] = R2D*q_(i);
controller_state_pub_->msg_.state_dot[i] = R2D*qdot_(i);
controller_state_pub_->msg_.error[i] = R2D*q_error_(i);
controller_state_pub_->msg_.error_dot[i] = R2D*q_error_dot_(i);
controller_state_pub_->msg_.effort_command[i] = tau_cmd_(i);
controller_state_pub_->msg_.effort_feedback[i] = tau_cmd_(i) - G_(i);
}
controller_state_pub_->unlockAndPublish();
}
}
}
void stopping(const ros::Time& time) { }
void enforceJointLimits(double &command, unsigned int index)
{
// Check that this joint has applicable limits
if (joint_urdfs_[index]->type == urdf::Joint::REVOLUTE || joint_urdfs_[index]->type == urdf::Joint::PRISMATIC)
{
if( command > joint_urdfs_[index]->limits->upper ) // above upper limnit
{
command = joint_urdfs_[index]->limits->upper;
}
else if( command < joint_urdfs_[index]->limits->lower ) // below lower limit
{
command = joint_urdfs_[index]->limits->lower;
}
}
}
private:
int loop_count_;
// joint handles
unsigned int n_joints_;
std::vector<std::string> joint_names_;
std::vector<hardware_interface::JointHandle> joints_;
std::vector<urdf::JointConstSharedPtr> joint_urdfs_;
// kdl
KDL::Tree kdl_tree_;
KDL::Chain kdl_chain_;
boost::scoped_ptr<KDL::ChainDynParam> id_solver_; // inverse dynamics solver
KDL::JntArray G_; // gravity torque vector
KDL::Vector gravity_;
// cmd, state
realtime_tools::RealtimeBuffer<std::vector<double> > commands_buffer_;
KDL::JntArray q_cmd_, qdot_cmd_, qddot_cmd_;
KDL::JntArray q_, qdot_;
Eigen::VectorXd tau_cmd_, tau_fric_;
Eigen::VectorXd q_error_, q_error_dot_;
// gain
std::vector<control_toolbox::Pid> pids_; /**< Internal PID controllers. */
// topic
ros::Subscriber command_sub_;
boost::scoped_ptr<
realtime_tools::RealtimePublisher<
arm_controllers::ControllerJointState> > controller_state_pub_;
};
}
PLUGINLIB_EXPORT_CLASS(arm_controllers::GravityCompController, controller_interface::ControllerBase)