srh_mixed_position_velocity_controller.cpp
Go to the documentation of this file.
1 /*
2 * Copyright 2011 Shadow Robot Company Ltd.
3 *
4 * This program is free software: you can redistribute it and/or modify it
5 * under the terms of the GNU General Public License as published by the Free
6 * Software Foundation version 2 of the License.
7 *
8 * This program is distributed in the hope that it will be useful, but WITHOUT
9 * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 * FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 * more details.
12 *
13 * You should have received a copy of the GNU General Public License along
14 * with this program. If not, see <http://www.gnu.org/licenses/>.
15 */
16 
30 #include "angles/angles.h"
32 #include <string>
33 #include <algorithm>
34 #include <sstream>
35 #include <math.h>
37 
38 #include <std_msgs/Float64.h>
39 
41 
42 using std::string;
43 using std::min;
44 using std::max;
45 
46 namespace controller
47 {
48 
50  : max_velocity_(1.0), min_velocity_(-1.0), prev_in_deadband_(false),
51  maintained_command_(0.0), override_to_current_effort_(false),
52  position_deadband(0.05), motor_min_force_threshold(0)
53  {
54  }
55 
56  bool SrhMixedPositionVelocityJointController::init(ros_ethercat_model::RobotStateInterface *robot,
57  ros::NodeHandle &n)
58  {
59  ROS_ASSERT(robot);
60 
61  std::string robot_state_name;
62  node_.param<std::string>("robot_state_name", robot_state_name, "unique_robot_hw");
63 
64  try
65  {
66  robot_ = robot->getHandle(robot_state_name).getState();
67  }
69  {
70  ROS_ERROR_STREAM("Could not find robot state: " << robot_state_name << " Not loading the controller. " <<
71  e.what());
72  return false;
73  }
74 
75  node_ = n;
76 
77  if (!node_.getParam("joint", joint_name_))
78  {
79  ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
80  return false;
81  }
82 
84  if (!pid_controller_position_->init(ros::NodeHandle(node_, "position_pid")))
85  {
86  return false;
87  }
88 
90  if (!pid_controller_velocity_->init(ros::NodeHandle(node_, "velocity_pid")))
91  {
92  return false;
93  }
94 
96  (node_, "state", 1));
97 
98  ROS_DEBUG(" --------- ");
99  ROS_DEBUG_STREAM("Init: " << joint_name_);
100 
101  // joint 0s e.g. FFJ0
102  has_j2 = is_joint_0();
103  if (has_j2)
104  {
106  if (!joint_state_)
107  {
108  ROS_ERROR("SrhMixedPositionVelocityController could not find the first joint relevant to \"%s\"\n",
109  joint_name_.c_str());
110  return false;
111  }
112  if (!joint_state_2)
113  {
114  ROS_ERROR("SrhMixedPositionVelocityController could not find the second joint relevant to \"%s\"\n",
115  joint_name_.c_str());
116  return false;
117  }
118  }
119  else // "normal" joints
120  {
121  joint_state_ = robot_->getJointState(joint_name_);
122  if (!joint_state_)
123  {
124  ROS_ERROR("SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
125  joint_name_.c_str());
126  return false;
127  }
128  }
130 
131  // get the min and max value for the current joint:
132  get_min_max(robot_->robot_model_, joint_name_);
133 
136  this);
137 
138  ROS_DEBUG_STREAM(" joint_state name: " << joint_state_->joint_->name);
139  ROS_DEBUG_STREAM(" In Init: " << getJointName() << " This: " << this
140  << " joint_state: " << joint_state_);
141 
142 #ifdef DEBUG_PUBLISHER
143  if (string("FFJ3").compare(getJointName()) == 0)
144  {
145  ROS_INFO("Publishing debug info for FFJ3 mixed position/velocity controller");
146  stringstream ss2;
147  ss2 << getJointName() << "debug_velocity";
148  debug_pub = n_tilde_.advertise<std_msgs::Float64>(ss2.str(), 2);
149  }
150 #endif
151 
152  after_init();
153  return true;
154  }
155 
157  {
158  resetJointState();
159  pid_controller_position_->reset();
160  pid_controller_velocity_->reset();
161  read_parameters();
162 
163  if (has_j2)
165  "Reseting PID for joints " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
166  else
167  ROS_WARN_STREAM("Reseting PID for joint " << joint_state_->joint_->name);
168  }
169 
170  bool SrhMixedPositionVelocityJointController::setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req,
171  sr_robot_msgs::SetMixedPositionVelocityPidGains::Response
172  &resp)
173  {
175  "New parameters: " << "PID pos: [" << req.position_p << ", " << req.position_i << ", " << req.position_d <<
176  ", " << req.position_i_clamp << "] PID vel: [" << req.velocity_p << ", " << req.velocity_i << ", " <<
177  req.velocity_d << ", " << req.velocity_i_clamp << "], max force: " << req.max_force <<
178  ", friction deadband: " << req.friction_deadband << " pos deadband: " << req.position_deadband <<
179  " min and max vel: [" << req.min_velocity << ", " << req.max_velocity << "]");
180 
181  // retrieve previous antiwindup settings for velocity
182  double p, i, d, i_max, i_min;
183  bool antiwindup;
184  pid_controller_velocity_->getGains(p, i, d, i_max, i_min, antiwindup);
185 
186  pid_controller_position_->setGains(req.position_p, req.position_i, req.position_d, req.position_i_clamp,
187  -req.position_i_clamp);
188 
189  pid_controller_velocity_->setGains(req.velocity_p, req.velocity_i, req.velocity_d, req.velocity_i_clamp,
190  -req.velocity_i_clamp, antiwindup);
191  max_force_demand = req.max_force;
192  friction_deadband = req.friction_deadband;
193  position_deadband = req.position_deadband;
194 
195  // setting the position controller parameters
196  min_velocity_ = req.min_velocity;
197  max_velocity_ = req.max_velocity;
198 
199  // Setting the new parameters in the parameter server
200  node_.setParam("position_pid/p", req.position_p);
201  node_.setParam("position_pid/i", req.position_i);
202  node_.setParam("position_pid/d", req.position_d);
203  node_.setParam("position_pid/i_clamp", req.position_i_clamp);
204 
205  node_.setParam("velocity_pid/p", req.velocity_p);
206  node_.setParam("velocity_pid/i", req.velocity_i);
207  node_.setParam("velocity_pid/d", req.velocity_d);
208  node_.setParam("velocity_pid/i_clamp", req.velocity_i_clamp);
209 
210  node_.setParam("position_pid/min_velocity", min_velocity_);
211  node_.setParam("position_pid/max_velocity", max_velocity_);
212  node_.setParam("position_pid/position_deadband", position_deadband);
213 
214  node_.setParam("velocity_pid/friction_deadband", friction_deadband);
215  node_.setParam("velocity_pid/max_force", max_force_demand);
216  node_.setParam("velocity_pid/antiwindup", antiwindup);
217  node_.setParam("motor_min_force_threshold", motor_min_force_threshold);
218 
219  return true;
220  }
221 
222  bool SrhMixedPositionVelocityJointController::resetGains(std_srvs::Empty::Request &req,
223  std_srvs::Empty::Response &resp)
224  {
225  resetJointState();
226 
227  if (!pid_controller_position_->init(ros::NodeHandle(node_, "position_pid")))
228  {
229  return false;
230  }
231 
232  if (!pid_controller_velocity_->init(ros::NodeHandle(node_, "velocity_pid")))
233  {
234  return false;
235  }
236 
237  read_parameters();
238 
239  if (has_j2)
241  "Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
242  else
243  ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
244 
245  return true;
246  }
247 
248  void SrhMixedPositionVelocityJointController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
249  {
250  pid_controller_position_->getGains(p, i, d, i_max, i_min);
251  }
252 
253  void SrhMixedPositionVelocityJointController::getGains_velocity(double &p, double &i, double &d, double &i_max,
254  double &i_min)
255  {
256  pid_controller_velocity_->getGains(p, i, d, i_max, i_min);
257  }
258 
260  {
262  ROS_ASSERT(joint_state_->joint_);
263 
264  if (!initialized_)
265  {
266  resetJointState();
267  initialized_ = true;
268  }
269  if (has_j2)
270  {
271  command_ = joint_state_->commanded_position_ + joint_state_2->commanded_position_;
272  }
273  else
274  {
275  command_ = joint_state_->commanded_position_;
276  }
278 
280  // POSITION
281 
282  // Compute velocity demand from position error:
283  double error_position = 0.0;
284  if (has_j2)
285  {
286  error_position = command_ - (joint_state_->position_ + joint_state_2->position_);
287  ROS_DEBUG_STREAM("j0: " << joint_state_->position_ + joint_state_2->position_);
288  }
289  else
290  {
291  error_position = command_ - joint_state_->position_;
292  }
293 
294  // are we in the deadband?
295  bool in_deadband = hysteresis_deadband.is_in_deadband(command_, error_position, position_deadband);
296 
297  if (in_deadband) // consider the error as 0 if we're in the deadband
298  {
299  error_position = 0.0;
300  pid_controller_position_->reset();
301  }
302 
303  double commanded_velocity = 0.0;
304  double error_velocity = 0.0;
305  double commanded_effort = 0.0;
306 
307  // compute the velocity demand using the position pid loop
308  commanded_velocity = pid_controller_position_->computeCommand(-error_position, period);
309  // saturate the velocity demand
310  commanded_velocity = max(commanded_velocity, min_velocity_);
311  commanded_velocity = min(commanded_velocity, max_velocity_);
312 
314  // VELOCITY
315 
316  // velocity loop:
317  if (!in_deadband) // don't compute the error if we're in the deadband
318  {
319  prev_in_deadband_ = false;
320  // we're not in the deadband, compute the error
321  if (has_j2)
322  {
323  error_velocity = commanded_velocity - (joint_state_->velocity_ + joint_state_2->velocity_);
324  }
325  else
326  {
327  error_velocity = commanded_velocity - joint_state_->velocity_;
328  }
329  }
330  // compute the effort demand using the velocity pid loop
331  commanded_effort = pid_controller_velocity_->computeCommand(-error_velocity, period);
332 
333  // when entering the deadband, override command
334  if (in_deadband && !prev_in_deadband_)
335  {
336  prev_in_deadband_ = true;
338  {
339  // override with current joint_effort to avoid further movements
340  commanded_effort = joint_state_->effort_;
341  }
342  // else use the current command for further loops in deadband
343  maintained_command_ = commanded_effort;
344  }
345  else
346  {
347  // when already in deadband, override command with previous command
348  if (in_deadband && prev_in_deadband_)
349  {
350  commanded_effort = maintained_command_;
351  }
352  }
353 
354  // clamp the result to max force
355  commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
356  commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
357 
358  // Friction compensation, only if we're not in the deadband.
359  int friction_offset = 0;
360  if (!in_deadband)
361  {
362  if (has_j2)
363  {
364  friction_offset = friction_compensator->friction_compensation(
365  joint_state_->position_ + joint_state_2->position_, joint_state_->velocity_ + joint_state_2->velocity_,
366  static_cast<int>(commanded_effort), friction_deadband);
367  }
368  else
369  {
370  friction_offset = friction_compensator->friction_compensation(joint_state_->position_, joint_state_->velocity_,
371  static_cast<int>(commanded_effort),
373  }
374 
375  commanded_effort += friction_offset;
376  }
377 
378  // if the demand is too small to be executed by the motor, then we ask for a force
379  // of 0
380  if (fabs(commanded_effort) <= motor_min_force_threshold)
381  {
382  commanded_effort = 0.0;
383  }
384 
385  joint_state_->commanded_effort_ = commanded_effort;
386 
387  if (loop_count_ % 10 == 0)
388  {
390  {
391  controller_state_publisher_->msg_.header.stamp = time;
392  controller_state_publisher_->msg_.set_point = command_;
393  if (has_j2)
394  {
395  controller_state_publisher_->msg_.process_value = joint_state_->position_ + joint_state_2->position_;
396  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_ + joint_state_2->velocity_;
397  }
398  else
399  {
400  controller_state_publisher_->msg_.process_value = joint_state_->position_;
401  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
402  }
403  controller_state_publisher_->msg_.commanded_velocity = commanded_velocity;
404 
405  controller_state_publisher_->msg_.error = error_position;
406  controller_state_publisher_->msg_.time_step = period.toSec();
407 
408  controller_state_publisher_->msg_.command = commanded_effort;
409  controller_state_publisher_->msg_.measured_effort = joint_state_->effort_;
410 
411  controller_state_publisher_->msg_.friction_compensation = friction_offset;
412 
413  double dummy;
414  getGains(controller_state_publisher_->msg_.position_p,
415  controller_state_publisher_->msg_.position_i,
416  controller_state_publisher_->msg_.position_d,
417  controller_state_publisher_->msg_.position_i_clamp,
418  dummy);
419 
421  controller_state_publisher_->msg_.velocity_i,
422  controller_state_publisher_->msg_.velocity_d,
423  controller_state_publisher_->msg_.velocity_i_clamp,
424  dummy);
425 
426  controller_state_publisher_->unlockAndPublish();
427  }
428  }
429  loop_count_++;
430  }
431 
433  {
434  node_.param<double>("position_pid/min_velocity", min_velocity_, -1.0);
435  node_.param<double>("position_pid/max_velocity", max_velocity_, 1.0);
436  node_.param<double>("position_pid/position_deadband", position_deadband, 0.015);
437 
438  node_.param<int>("velocity_pid/friction_deadband", friction_deadband, 5);
439  node_.param<double>("velocity_pid/max_force", max_force_demand, 1023.0);
440  node_.param<int>("motor_min_force_threshold", motor_min_force_threshold, 0);
441  node_.param<bool>("override_to_current_effort", override_to_current_effort_, false);
442  if (override_to_current_effort_)
443  ROS_WARN_STREAM("using override commanded effort to current effort for " << joint_state_->joint_->name);
444  }
445 
446  void SrhMixedPositionVelocityJointController::setCommandCB(const std_msgs::Float64ConstPtr &msg)
447  {
448  joint_state_->commanded_position_ = msg->data;
449  if (has_j2)
450  {
451  joint_state_2->commanded_position_ = 0.0;
452  }
453  }
454 
456  {
457  if (has_j2)
458  {
459  joint_state_->commanded_position_ = joint_state_->position_;
460  joint_state_2->commanded_position_ = joint_state_2->position_;
461  command_ = joint_state_->position_ + joint_state_2->position_;
462  }
463  else
464  {
465  joint_state_->commanded_position_ = joint_state_->position_;
466  command_ = joint_state_->position_;
467  }
468  }
469 } // namespace controller
470 
471 /* For the emacs weenies in the crowd.
472 Local Variables:
473  c-basic-offset: 2
474 End:
475  */
476 
477 
void get_min_max(urdf::Model model, std::string joint_name)
d
ros_ethercat_model::JointState * joint_state_
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
void read_parameters()
read all the controller settings from the parameter server
Compute a velocity demand from the position error using a PID loop. The velocity demand is then conve...
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
#define ROS_ERROR(...)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
boost::scoped_ptr< control_toolbox::Pid > pid_controller_velocity_
Internal PID controller for the velocity loop.
ros_ethercat_model::JointState * joint_state_2
boost::scoped_ptr< sr_friction_compensation::SrFrictionCompensator > friction_compensator
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual void getGains_velocity(double &p, double &i, double &d, double &i_max, double &i_min)
#define ROS_DEBUG(...)
double clamp_command(double cmd, double min_cmd, double max_cmd)
ros_ethercat_model::RobotState * robot_
bool override_to_current_effort_
Override commanded_effort to current effort when in deadband.
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const char * what() const noexcept override
#define ROS_INFO(...)
bool getParam(const std::string &key, std::string &s) const
int friction_deadband
the deadband for the friction compensation algorithm
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We&#39;re using an hysteresis deadband.
double min(double a, double b)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool is_in_deadband(T demand, T error, T deadband, double deadband_multiplicator=5.0, unsigned int nb_errors_for_avg=50)
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
double max_force_demand
clamps the force demand to this value
#define ROS_INFO_STREAM(args)
const std::string & getNamespace() const
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
int motor_min_force_threshold
smallest demand we can send to the motors
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
bool setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req, sr_robot_msgs::SetMixedPositionVelocityPidGains::Response &resp)
double max_velocity_
The values for the velocity demand saturation.
double max(double a, double b)
boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointControllerState > > controller_state_publisher_
void after_init()
call this function at the end of the init function in the inheriting classes.
ros::ServiceServer serve_reset_gains_


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:30