srh_muscle_joint_position_controller.cpp
Go to the documentation of this file.
1 
28 #include "angles/angles.h"
30 #include <algorithm>
31 #include <string>
32 #include <sstream>
33 #include <math.h>
35 
36 #include <std_msgs/Float64.h>
37 
39 
40 using std::min;
41 using std::max;
42 
43 namespace controller
44 {
45 
46  SrhMuscleJointPositionController::SrhMuscleJointPositionController()
47  : position_deadband(0.015), command_acc_(0)
48  {
49  }
50 
51  bool SrhMuscleJointPositionController::init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
52  {
53  ROS_ASSERT(robot);
54 
55  std::string robot_state_name;
56  node_.param<std::string>("robot_state_name", robot_state_name, "unique_robot_hw");
57 
58  try
59  {
60  robot_ = robot->getHandle(robot_state_name).getState();
61  }
63  {
64  ROS_ERROR_STREAM("Could not find robot state: " << robot_state_name << " Not loading the controller. " <<
65  e.what());
66  return false;
67  }
68 
69  node_ = n;
70 
71  if (!node_.getParam("joint", joint_name_))
72  {
73  ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
74  return false;
75  }
76 
79  {
80  return false;
81  }
82 
85  (node_, "state", 1));
86 
87  ROS_DEBUG(" --------- ");
88  ROS_DEBUG_STREAM("Init: " << joint_name_);
89 
90  // joint 0s e.g. FFJ0
91  has_j2 = is_joint_0();
92  if (has_j2)
93  {
95  if (!joint_state_)
96  {
97  ROS_ERROR("SrhMuscleJointPositionController could not find the first joint relevant to \"%s\"\n",
98  joint_name_.c_str());
99  return false;
100  }
101  if (!joint_state_2)
102  {
103  ROS_ERROR("SrhMuscleJointPositionController could not find the second joint relevant to \"%s\"\n",
104  joint_name_.c_str());
105  return false;
106  }
107  }
108  else
109  {
110  joint_state_ = robot_->getJointState(joint_name_);
111  if (!joint_state_)
112  {
113  ROS_ERROR("SrhMuscleJointPositionController could not find joint named \"%s\"\n", joint_name_.c_str());
114  return false;
115  }
116  }
117 
118  // get the min and max value for the current joint:
119  get_min_max(robot_->robot_model_, joint_name_);
120 
122 
125 
126  after_init();
127  return true;
128  }
129 
131  {
132  resetJointState();
133  pid_controller_position_->reset();
134  read_parameters();
135 
136  if (has_j2)
138  "Reseting PID for joints " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
139  else
140  ROS_WARN_STREAM("Reseting PID for joint " << joint_state_->joint_->name);
141  }
142 
143  bool SrhMuscleJointPositionController::setGains(sr_robot_msgs::SetPidGains::Request &req,
144  sr_robot_msgs::SetPidGains::Response &resp)
145  {
146  ROS_INFO_STREAM("Setting new PID parameters. P:" << req.p << " / I:" << req.i <<
147  " / D:" << req.d << " / IClamp:" << req.i_clamp << ", max force: " << req.max_force <<
148  ", friction deadband: " << req.friction_deadband << " pos deadband: " << req.deadband);
149  pid_controller_position_->setGains(req.p, req.i, req.d, req.i_clamp, -req.i_clamp);
150  max_force_demand = req.max_force;
151  friction_deadband = req.friction_deadband;
152  position_deadband = req.deadband;
153 
154  // Setting the new parameters in the parameter server
155  node_.setParam("pid/p", req.p);
156  node_.setParam("pid/i", req.i);
157  node_.setParam("pid/d", req.d);
158  node_.setParam("pid/i_clamp", req.i_clamp);
159  node_.setParam("pid/max_force", max_force_demand);
160  node_.setParam("pid/position_deadband", position_deadband);
161  node_.setParam("pid/friction_deadband", friction_deadband);
162 
163  return true;
164  }
165 
166  bool SrhMuscleJointPositionController::resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
167  {
168  resetJointState();
169 
170  if (!pid_controller_position_->init(ros::NodeHandle(node_, "pid")))
171  {
172  return false;
173  }
174 
175  read_parameters();
176 
177  if (has_j2)
179  "Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
180  else
181  ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
182 
183  return true;
184  }
185 
186  void SrhMuscleJointPositionController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
187  {
188  pid_controller_position_->getGains(p, i, d, i_max, i_min);
189  }
190 
192  {
193  // The valve commands can have values between -4 and 4
194  int8_t valve[2];
195 
196  ROS_ASSERT(robot_ != NULL);
197  ROS_ASSERT(joint_state_->joint_);
198 
199  if (!initialized_)
200  {
201  resetJointState();
202  initialized_ = true;
203  }
204  if (has_j2)
205  {
206  command_ = joint_state_->commanded_position_ + joint_state_2->commanded_position_;
207  }
208  else
209  {
210  command_ = joint_state_->commanded_position_;
211  }
213 
214  // IGNORE the following lines if we don't want to use the pressure sensors data
215  // We don't want to define a modified version of JointState, as that would imply using
216  // a modified version of robot_state.hpp, controller manager,
217  // ethercat_hardware and ros_etherCAT main loop
218  // So we have encoded the two uint16 that contain the data from the muscle pressure
219  // sensors into the double effort_. (We don't
220  // have any measured effort in the muscle hand anyway).
221  // Here we extract the pressure values from joint_state_->effort_ and decode that back into uint16.
222  double pressure_0_tmp = fmod(joint_state_->effort_, 0x10000);
223  double pressure_1_tmp = (fmod(joint_state_->effort_, 0x100000000) - pressure_0_tmp) / 0x10000;
224  uint16_t pressure_0 = static_cast<uint16_t> (pressure_0_tmp + 0.5);
225  uint16_t pressure_1 = static_cast<uint16_t> (pressure_1_tmp + 0.5);
226 
227  // ****************************************
228 
230 
231  // Compute position demand from position error:
232  double error_position = 0.0;
233 
234  if (has_j2)
235  {
236  error_position = (joint_state_->position_ + joint_state_2->position_) - command_;
237  }
238  else
239  {
240  error_position = joint_state_->position_ - command_;
241  }
242 
243  bool in_deadband = hysteresis_deadband.is_in_deadband(command_, error_position, position_deadband);
244 
245  // don't compute the error if we're in the deadband.
246  if (in_deadband)
247  {
248  error_position = 0.0;
249  }
250 
251  // Run the PID loop to get a new command, we don't do this at the full rate
252  // as that will drive the valves too hard with switch changes. Instead we
253  // store a longer time in the command accumulator to keep using at the full
254  // loop rate.
255  if (loop_count_ % 50 == 0)
256  {
257  double commanded_effort = pid_controller_position_->computeCommand(-error_position, period);
258 
259  // clamp the result to max force
260  commanded_effort = min(commanded_effort, max_force_demand);
261  commanded_effort = max(commanded_effort, -max_force_demand);
262 
263  if (!in_deadband)
264  {
265  if (has_j2)
266  {
267  commanded_effort += friction_compensator->friction_compensation(
268  joint_state_->position_ + joint_state_2->position_,
269  joint_state_->velocity_ + joint_state_2->velocity_, static_cast<int>(commanded_effort),
271  }
272  else
273  {
274  commanded_effort += friction_compensator->friction_compensation(joint_state_->position_,
275  joint_state_->velocity_,
276  static_cast<int>(commanded_effort),
278  }
279  }
280 
281  command_acc_ = commanded_effort;
282  }
283 
284  // Drive the joint from the accumulator. This runs at full update speed so
285  // we can keep valves open continuously (with high enough P). A value of 4 fills
286  // the valve for the whole of the next 1ms. 2 for half that time etc. Negative
287  // values empty the valve.
288  // The 2 involved muscles will act complementary for the moment, when one inflates,
289  // the other deflates at the same rate
290  double amt = abs(command_acc_) < 4 ? fabs(command_acc_) : 4;
291  if (abs(command_acc_) == 0)
292  {
293  valve[0] = 0;
294  valve[1] = 0;
295  }
296  else if (command_acc_ > 0)
297  {
298  command_acc_ -= amt;
299  valve[0] = amt;
300  valve[1] = -amt;
301  }
302  else
303  {
304  command_acc_ += amt;
305  valve[0] = -amt;
306  valve[1] = amt;
307  }
308 
309 
310  // ************************************************
311  // After doing any computation we consider, we encode the obtained valve
312  // commands into joint_state_->commanded_effort_
313  // We don't want to define a modified version of JointState, as that would
314  // imply using a modified version of robot_state.hpp, controller manager,
315  // ethercat_hardware and ros_etherCAT main loop
316  // So the controller encodes the two int8 (that are in fact int4) that contain
317  // the valve commands into the double commanded_effort_. (We don't
318  // have any real commanded_effort_ in the muscle hand anyway).
319 
320  uint16_t valve_tmp[2];
321  for (int i = 0; i < 2; ++i)
322  {
323  // Check that the limits of the valve command are not exceded
324  if (valve[i] > 4)
325  {
326  valve[i] = 4;
327  }
328  if (valve[i] < -4)
329  {
330  valve[i] = -4;
331  }
332  // encode
333  if (valve[i] < 0)
334  {
335  valve_tmp[i] = -valve[i] + 8;
336  }
337  else
338  {
339  valve_tmp[i] = valve[i];
340  }
341  }
342 
343  // We encode the valve 0 command in the lowest "half byte" i.e. the lowest 16 integer
344  // values in the double var (see decoding in simple_transmission_for_muscle.cpp)
345  // the valve 1 command is encoded in the next 4 bits
346  joint_state_->commanded_effort_ = static_cast<double> (valve_tmp[0]) + static_cast<double> (valve_tmp[1] << 4);
347 
348  // *******************************************************************************
349 
350  // Send status msg
351  if (loop_count_ % 10 == 0)
352  {
354  {
355  controller_state_publisher_->msg_.header.stamp = time;
356  controller_state_publisher_->msg_.set_point = command_;
357  if (has_j2)
358  {
359  controller_state_publisher_->msg_.process_value = joint_state_->position_ + joint_state_2->position_;
360  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_ + joint_state_2->velocity_;
361  }
362  else
363  {
364  controller_state_publisher_->msg_.process_value = joint_state_->position_;
365  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
366  }
367 
368  controller_state_publisher_->msg_.error = error_position;
369  controller_state_publisher_->msg_.time_step = period.toSec();
370  controller_state_publisher_->msg_.pseudo_command = command_acc_;
371  controller_state_publisher_->msg_.valve_muscle_0 = valve[0];
372  controller_state_publisher_->msg_.valve_muscle_1 = valve[1];
373  controller_state_publisher_->msg_.packed_valve = joint_state_->commanded_effort_;
374  controller_state_publisher_->msg_.muscle_pressure_0 = pressure_0;
375  controller_state_publisher_->msg_.muscle_pressure_1 = pressure_1;
376 
377 
378  double dummy;
382  controller_state_publisher_->msg_.i_clamp,
383  dummy);
384  controller_state_publisher_->unlockAndPublish();
385  }
386  }
387  loop_count_++;
388  }
389 
391  {
392  node_.param<double>("pid/max_force", max_force_demand, 1023.0);
393  node_.param<double>("pid/position_deadband", position_deadband, 0.015);
394  node_.param<int>("pid/friction_deadband", friction_deadband, 5);
395  }
396 
397  void SrhMuscleJointPositionController::setCommandCB(const std_msgs::Float64ConstPtr &msg)
398  {
399  joint_state_->commanded_position_ = msg->data;
400  if (has_j2)
401  {
402  joint_state_2->commanded_position_ = 0.0;
403  }
404  }
405 
407  {
408  if (has_j2)
409  {
410  joint_state_->commanded_position_ = joint_state_->position_;
411  joint_state_2->commanded_position_ = joint_state_2->position_;
412  command_ = joint_state_->position_ + joint_state_2->position_;
413  }
414  else
415  {
416  joint_state_->commanded_position_ = joint_state_->position_;
417  command_ = joint_state_->position_;
418  }
419  }
420 } // namespace controller
421 
422 /* For the emacs weenies in the crowd.
423 Local Variables:
424  c-basic-offset: 2
425 End:
426  */
427 
428 
void get_min_max(urdf::Model model, std::string joint_name)
ros_ethercat_model::JointState * joint_state_
double position_deadband
the position deadband value used in the hysteresis_deadband
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We&#39;re using an hysteresis deadband.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
ros_ethercat_model::JointState * joint_state_2
boost::scoped_ptr< sr_friction_compensation::SrFrictionCompensator > friction_compensator
double clamp_command(double cmd, double min_cmd, double max_cmd)
ros_ethercat_model::RobotState * robot_
bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp)
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
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)
boost::scoped_ptr< realtime_tools::RealtimePublisher< sr_robot_msgs::JointMusclePositionControllerState > > controller_state_publisher_
publish our joint controller state
double max_force_demand
clamps the force demand to this value
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
ros::ServiceServer serve_set_gains_
int command_acc_
Command accumulator, time to keep the valves open/shut, sign gives the direction. ...
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
void read_parameters()
read all the controller settings from the parameter server
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
#define ROS_ERROR(...)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
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