srh_mixed_position_velocity_controller.cpp
Go to the documentation of this file.
1 
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 
49  SrhMixedPositionVelocityJointController::SrhMixedPositionVelocityJointController()
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  if (!joint_state_2->calibrated_)
119  {
120  ROS_ERROR("Joint %s not calibrated for SrhMixedPositionVelocityController", joint_name_.c_str());
121  return false;
122  }
123  else
124  {
125  joint_state_->calibrated_ = true;
126  }
127  }
128  else // "normal" joints
129  {
130  joint_state_ = robot_->getJointState(joint_name_);
131  if (!joint_state_)
132  {
133  ROS_ERROR("SrhMixedPositionVelocityController could not find joint named \"%s\"\n",
134  joint_name_.c_str());
135  return false;
136  }
137  if (!joint_state_->calibrated_)
138  {
139  ROS_ERROR("Joint %s not calibrated for SrhMixedPositionVelocityJointController", joint_name_.c_str());
140  return false;
141  }
142  }
144 
145  // get the min and max value for the current joint:
146  get_min_max(robot_->robot_model_, joint_name_);
147 
150  this);
151 
152  ROS_DEBUG_STREAM(" joint_state name: " << joint_state_->joint_->name);
153  ROS_DEBUG_STREAM(" In Init: " << getJointName() << " This: " << this
154  << " joint_state: " << joint_state_);
155 
156 #ifdef DEBUG_PUBLISHER
157  if (string("FFJ3").compare(getJointName()) == 0)
158  {
159  ROS_INFO("Publishing debug info for FFJ3 mixed position/velocity controller");
160  stringstream ss2;
161  ss2 << getJointName() << "debug_velocity";
162  debug_pub = n_tilde_.advertise<std_msgs::Float64>(ss2.str(), 2);
163  }
164 #endif
165 
166  after_init();
167  return true;
168  }
169 
171  {
172  resetJointState();
173  pid_controller_position_->reset();
174  pid_controller_velocity_->reset();
175  read_parameters();
176 
177  if (has_j2)
179  "Reseting PID for joints " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
180  else
181  ROS_WARN_STREAM("Reseting PID for joint " << joint_state_->joint_->name);
182  }
183 
184  bool SrhMixedPositionVelocityJointController::setGains(sr_robot_msgs::SetMixedPositionVelocityPidGains::Request &req,
185  sr_robot_msgs::SetMixedPositionVelocityPidGains::Response
186  &resp)
187  {
189  "New parameters: " << "PID pos: [" << req.position_p << ", " << req.position_i << ", " << req.position_d <<
190  ", " << req.position_i_clamp << "] PID vel: [" << req.velocity_p << ", " << req.velocity_i << ", " <<
191  req.velocity_d << ", " << req.velocity_i_clamp << "], max force: " << req.max_force <<
192  ", friction deadband: " << req.friction_deadband << " pos deadband: " << req.position_deadband <<
193  " min and max vel: [" << req.min_velocity << ", " << req.max_velocity << "]");
194 
195  // retrieve previous antiwindup settings for velocity
196  double p, i, d, i_max, i_min;
197  bool antiwindup;
198  pid_controller_velocity_->getGains(p, i, d, i_max, i_min, antiwindup);
199 
200  pid_controller_position_->setGains(req.position_p, req.position_i, req.position_d, req.position_i_clamp,
201  -req.position_i_clamp);
202 
203  pid_controller_velocity_->setGains(req.velocity_p, req.velocity_i, req.velocity_d, req.velocity_i_clamp,
204  -req.velocity_i_clamp, antiwindup);
205  max_force_demand = req.max_force;
206  friction_deadband = req.friction_deadband;
207  position_deadband = req.position_deadband;
208 
209  // setting the position controller parameters
210  min_velocity_ = req.min_velocity;
211  max_velocity_ = req.max_velocity;
212 
213  // Setting the new parameters in the parameter server
214  node_.setParam("position_pid/p", req.position_p);
215  node_.setParam("position_pid/i", req.position_i);
216  node_.setParam("position_pid/d", req.position_d);
217  node_.setParam("position_pid/i_clamp", req.position_i_clamp);
218 
219  node_.setParam("velocity_pid/p", req.velocity_p);
220  node_.setParam("velocity_pid/i", req.velocity_i);
221  node_.setParam("velocity_pid/d", req.velocity_d);
222  node_.setParam("velocity_pid/i_clamp", req.velocity_i_clamp);
223 
224  node_.setParam("position_pid/min_velocity", min_velocity_);
225  node_.setParam("position_pid/max_velocity", max_velocity_);
226  node_.setParam("position_pid/position_deadband", position_deadband);
227 
228  node_.setParam("velocity_pid/friction_deadband", friction_deadband);
229  node_.setParam("velocity_pid/max_force", max_force_demand);
230  node_.setParam("velocity_pid/antiwindup", antiwindup);
231  node_.setParam("motor_min_force_threshold", motor_min_force_threshold);
232 
233  return true;
234  }
235 
236  bool SrhMixedPositionVelocityJointController::resetGains(std_srvs::Empty::Request &req,
237  std_srvs::Empty::Response &resp)
238  {
239  resetJointState();
240 
241  if (!pid_controller_position_->init(ros::NodeHandle(node_, "position_pid")))
242  {
243  return false;
244  }
245 
246  if (!pid_controller_velocity_->init(ros::NodeHandle(node_, "velocity_pid")))
247  {
248  return false;
249  }
250 
251  read_parameters();
252 
253  if (has_j2)
255  "Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
256  else
257  ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
258 
259  return true;
260  }
261 
262  void SrhMixedPositionVelocityJointController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
263  {
264  pid_controller_position_->getGains(p, i, d, i_max, i_min);
265  }
266 
267  void SrhMixedPositionVelocityJointController::getGains_velocity(double &p, double &i, double &d, double &i_max,
268  double &i_min)
269  {
270  pid_controller_velocity_->getGains(p, i, d, i_max, i_min);
271  }
272 
274  {
275  if (!has_j2 && !joint_state_->calibrated_)
276  {
277  return;
278  }
279 
281  ROS_ASSERT(joint_state_->joint_);
282 
283  if (!initialized_)
284  {
285  resetJointState();
286  initialized_ = true;
287  }
288  if (has_j2)
289  {
290  command_ = joint_state_->commanded_position_ + joint_state_2->commanded_position_;
291  }
292  else
293  {
294  command_ = joint_state_->commanded_position_;
295  }
297 
299  // POSITION
300 
301  // Compute velocity demand from position error:
302  double error_position = 0.0;
303  if (has_j2)
304  {
305  error_position = command_ - (joint_state_->position_ + joint_state_2->position_);
306  ROS_DEBUG_STREAM("j0: " << joint_state_->position_ + joint_state_2->position_);
307  }
308  else
309  {
310  error_position = command_ - joint_state_->position_;
311  }
312 
313  // are we in the deadband?
314  bool in_deadband = hysteresis_deadband.is_in_deadband(command_, error_position, position_deadband);
315 
316  if (in_deadband) // consider the error as 0 if we're in the deadband
317  {
318  error_position = 0.0;
319  pid_controller_position_->reset();
320  }
321 
322  double commanded_velocity = 0.0;
323  double error_velocity = 0.0;
324  double commanded_effort = 0.0;
325 
326  // compute the velocity demand using the position pid loop
327  commanded_velocity = pid_controller_position_->computeCommand(-error_position, period);
328  // saturate the velocity demand
329  commanded_velocity = max(commanded_velocity, min_velocity_);
330  commanded_velocity = min(commanded_velocity, max_velocity_);
331 
333  // VELOCITY
334 
335  // velocity loop:
336  if (!in_deadband) // don't compute the error if we're in the deadband
337  {
338  prev_in_deadband_ = false;
339  // we're not in the deadband, compute the error
340  if (has_j2)
341  {
342  error_velocity = commanded_velocity - (joint_state_->velocity_ + joint_state_2->velocity_);
343  }
344  else
345  {
346  error_velocity = commanded_velocity - joint_state_->velocity_;
347  }
348  }
349  // compute the effort demand using the velocity pid loop
350  commanded_effort = pid_controller_velocity_->computeCommand(-error_velocity, period);
351 
352  // when entering the deadband, override command
353  if (in_deadband && !prev_in_deadband_)
354  {
355  prev_in_deadband_ = true;
357  {
358  // override with current joint_effort to avoid further movements
359  commanded_effort = joint_state_->effort_;
360  }
361  // else use the current command for further loops in deadband
362  maintained_command_ = commanded_effort;
363  }
364  else
365  {
366  // when already in deadband, override command with previous command
367  if (in_deadband && prev_in_deadband_)
368  {
369  commanded_effort = maintained_command_;
370  }
371  }
372 
373  // clamp the result to max force
374  commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
375  commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
376 
377  // Friction compensation, only if we're not in the deadband.
378  int friction_offset = 0;
379  if (!in_deadband)
380  {
381  if (has_j2)
382  {
383  friction_offset = friction_compensator->friction_compensation(
384  joint_state_->position_ + joint_state_2->position_, joint_state_->velocity_ + joint_state_2->velocity_,
385  static_cast<int>(commanded_effort), friction_deadband);
386  }
387  else
388  {
389  friction_offset = friction_compensator->friction_compensation(joint_state_->position_, joint_state_->velocity_,
390  static_cast<int>(commanded_effort),
392  }
393 
394  commanded_effort += friction_offset;
395  }
396 
397  // if the demand is too small to be executed by the motor, then we ask for a force
398  // of 0
399  if (fabs(commanded_effort) <= motor_min_force_threshold)
400  {
401  commanded_effort = 0.0;
402  }
403 
404  joint_state_->commanded_effort_ = commanded_effort;
405 
406  if (loop_count_ % 10 == 0)
407  {
409  {
410  controller_state_publisher_->msg_.header.stamp = time;
411  controller_state_publisher_->msg_.set_point = command_;
412  if (has_j2)
413  {
414  controller_state_publisher_->msg_.process_value = joint_state_->position_ + joint_state_2->position_;
415  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_ + joint_state_2->velocity_;
416  }
417  else
418  {
419  controller_state_publisher_->msg_.process_value = joint_state_->position_;
420  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
421  }
422  controller_state_publisher_->msg_.commanded_velocity = commanded_velocity;
423 
424  controller_state_publisher_->msg_.error = error_position;
425  controller_state_publisher_->msg_.time_step = period.toSec();
426 
427  controller_state_publisher_->msg_.command = commanded_effort;
428  controller_state_publisher_->msg_.measured_effort = joint_state_->effort_;
429 
430  controller_state_publisher_->msg_.friction_compensation = friction_offset;
431 
432  double dummy;
433  getGains(controller_state_publisher_->msg_.position_p,
434  controller_state_publisher_->msg_.position_i,
435  controller_state_publisher_->msg_.position_d,
436  controller_state_publisher_->msg_.position_i_clamp,
437  dummy);
438 
440  controller_state_publisher_->msg_.velocity_i,
441  controller_state_publisher_->msg_.velocity_d,
442  controller_state_publisher_->msg_.velocity_i_clamp,
443  dummy);
444 
445  controller_state_publisher_->unlockAndPublish();
446  }
447  }
448  loop_count_++;
449  }
450 
452  {
453  node_.param<double>("position_pid/min_velocity", min_velocity_, -1.0);
454  node_.param<double>("position_pid/max_velocity", max_velocity_, 1.0);
455  node_.param<double>("position_pid/position_deadband", position_deadband, 0.015);
456 
457  node_.param<int>("velocity_pid/friction_deadband", friction_deadband, 5);
458  node_.param<double>("velocity_pid/max_force", max_force_demand, 1023.0);
459  node_.param<int>("motor_min_force_threshold", motor_min_force_threshold, 0);
460  node_.param<bool>("override_to_current_effort", override_to_current_effort_, false);
461  if (override_to_current_effort_)
462  ROS_WARN_STREAM("using override commanded effort to current effort for " << joint_state_->joint_->name);
463  }
464 
465  void SrhMixedPositionVelocityJointController::setCommandCB(const std_msgs::Float64ConstPtr &msg)
466  {
467  joint_state_->commanded_position_ = msg->data;
468  if (has_j2)
469  {
470  joint_state_2->commanded_position_ = 0.0;
471  }
472  }
473 
475  {
476  if (has_j2)
477  {
478  joint_state_->commanded_position_ = joint_state_->position_;
479  joint_state_2->commanded_position_ = joint_state_2->position_;
480  command_ = joint_state_->position_ + joint_state_2->position_;
481  }
482  else
483  {
484  joint_state_->commanded_position_ = joint_state_->position_;
485  command_ = joint_state_->position_;
486  }
487  }
488 } // namespace controller
489 
490 /* For the emacs weenies in the crowd.
491 Local Variables:
492  c-basic-offset: 2
493 End:
494  */
495 
496 
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)
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)
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.
#define ROS_INFO(...)
int friction_deadband
the deadband for the friction compensation algorithm
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const std::string & getNamespace() const
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We&#39;re using an hysteresis deadband.
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)
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
bool getParam(const std::string &key, std::string &s) 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.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
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_
#define ROS_DEBUG(...)


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:58