srh_joint_velocity_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  SrhJointVelocityController::SrhJointVelocityController()
47  : velocity_deadband(0.015)
48  {
49  }
50 
51  bool SrhJointVelocityController::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 
84  (node_, "state", 1));
85 
86  ROS_DEBUG(" --------- ");
87  ROS_DEBUG_STREAM("Init: " << joint_name_);
88 
89  // joint 0s e.g. FFJ0
90  has_j2 = is_joint_0();
91  if (has_j2)
92  {
94  if (!joint_state_)
95  {
96  ROS_ERROR("SrhVelocityController could not find the first joint relevant to \"%s\"\n", joint_name_.c_str());
97  return false;
98  }
99  if (!joint_state_2)
100  {
101  ROS_ERROR("SrhVelocityController could not find the second joint relevant to \"%s\"\n", joint_name_.c_str());
102  return false;
103  }
104  if (!joint_state_2->calibrated_)
105  {
106  ROS_ERROR("Joint %s not calibrated for SrhVelocityController", joint_name_.c_str());
107  return false;
108  }
109  else
110  {
111  joint_state_->calibrated_ = true;
112  }
113  }
114  else
115  {
116  joint_state_ = robot_->getJointState(joint_name_);
117  if (!joint_state_)
118  {
119  ROS_ERROR("SrhVelocityController could not find joint named \"%s\"\n", joint_name_.c_str());
120  return false;
121  }
122  if (!joint_state_->calibrated_)
123  {
124  ROS_ERROR("Joint %s not calibrated for SrhJointVelocityController", joint_name_.c_str());
125  return false;
126  }
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 
137  after_init();
138  return true;
139  }
140 
142  {
143  resetJointState();
144  pid_controller_velocity_->reset();
145  read_parameters();
146 
147  if (has_j2)
149  "Reseting PID for joints " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
150  else
151  ROS_WARN_STREAM("Reseting PID for joint " << joint_state_->joint_->name);
152  }
153 
154  bool SrhJointVelocityController::setGains(sr_robot_msgs::SetPidGains::Request &req,
155  sr_robot_msgs::SetPidGains::Response &resp)
156  {
157  pid_controller_velocity_->setGains(req.p, req.i, req.d, req.i_clamp, -req.i_clamp);
158  max_force_demand = req.max_force;
159  friction_deadband = req.friction_deadband;
160  velocity_deadband = req.deadband;
161 
162  // Setting the new parameters in the parameter server
163  node_.setParam("pid/p", req.p);
164  node_.setParam("pid/i", req.i);
165  node_.setParam("pid/d", req.d);
166  node_.setParam("pid/i_clamp", req.i_clamp);
167 
168  node_.setParam("pid/max_force", max_force_demand);
169  node_.setParam("pid/velocity_deadband", velocity_deadband);
170  node_.setParam("pid/friction_deadband", friction_deadband);
171 
172  return true;
173  }
174 
175  bool SrhJointVelocityController::resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
176  {
177  resetJointState();
178 
179  if (!pid_controller_velocity_->init(ros::NodeHandle(node_, "velocity_pid")))
180  {
181  return false;
182  }
183 
184  read_parameters();
185 
186  if (has_j2)
188  "Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
189  else
190  ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
191 
192  return true;
193  }
194 
195  void SrhJointVelocityController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
196  {
197  pid_controller_velocity_->getGains(p, i, d, i_max, i_min);
198  }
199 
201  {
202  if (!has_j2 && !joint_state_->calibrated_)
203  {
204  return;
205  }
206 
208  ROS_ASSERT(joint_state_->joint_);
209 
210  if (!initialized_)
211  {
212  resetJointState();
213  initialized_ = true;
214  }
215  if (has_j2)
216  {
217  command_ = joint_state_->commanded_velocity_ + joint_state_2->commanded_velocity_;
218  }
219  else
220  {
221  command_ = joint_state_->commanded_velocity_;
222  }
224 
225  double error_velocity = 0.0;
226  double commanded_effort = 0.0;
227 
228  if (has_j2)
229  {
230  error_velocity = (joint_state_->velocity_ + joint_state_2->velocity_) - command_;
231  }
232  else
233  {
234  error_velocity = joint_state_->velocity_ - command_;
235  }
236 
237  bool in_deadband = hysteresis_deadband.is_in_deadband(command_, error_velocity, velocity_deadband);
238  // are we in the deadband?
239  if (in_deadband)
240  {
241  error_velocity = 0.0; // force the error to zero to not further change the pid control terms
242  // if the requested velocity is smaller than the velocity_deadband, consider no movement is wanted.
243  if (std::fabs(command_) < velocity_deadband)
244  {
245  pid_controller_velocity_->reset();
246  }
247  }
248 
249  // compute the effort demand using the velocity pid loop
250  commanded_effort = pid_controller_velocity_->computeCommand(-error_velocity, period);
251 
252  // clamp the result to max force
253  commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
254  commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
255 
256  if (has_j2)
257  {
258  commanded_effort += friction_compensator->friction_compensation(
259  (joint_state_->position_ + joint_state_2->position_),
260  (joint_state_->velocity_ + joint_state_2->velocity_),
261  static_cast<int>(commanded_effort),
263  }
264  else
265  {
266  commanded_effort += friction_compensator->friction_compensation(joint_state_->position_,
267  joint_state_->velocity_,
268  static_cast<int>(commanded_effort),
270  }
271 
272  joint_state_->commanded_effort_ = commanded_effort;
273 
274  if (loop_count_ % 10 == 0)
275  {
277  {
278  controller_state_publisher_->msg_.header.stamp = time;
279  controller_state_publisher_->msg_.set_point = command_;
280  if (has_j2)
281  {
282  controller_state_publisher_->msg_.process_value = joint_state_->velocity_ + joint_state_2->velocity_;
283  }
284  else
285  {
286  controller_state_publisher_->msg_.process_value = joint_state_->velocity_;
287  }
288  controller_state_publisher_->msg_.error = error_velocity;
289  controller_state_publisher_->msg_.time_step = period.toSec();
290  controller_state_publisher_->msg_.command = commanded_effort;
291 
292  double dummy;
296  controller_state_publisher_->msg_.i_clamp,
297  dummy);
298  controller_state_publisher_->unlockAndPublish();
299  }
300  }
301  loop_count_++;
302  }
303 
305  {
307  }
308 
310  {
311  node_.param<double>("pid/max_force", max_force_demand, 1023.0);
312  node_.param<double>("pid/velocity_deadband", velocity_deadband, 0.015);
313  node_.param<int>("pid/friction_deadband", friction_deadband, 5);
314  }
315 
316  void SrhJointVelocityController::setCommandCB(const std_msgs::Float64ConstPtr &msg)
317  {
318  joint_state_->commanded_velocity_ = msg->data;
319  if (has_j2)
320  {
321  joint_state_2->commanded_velocity_ = 0.0;
322  }
323  }
324 
326  {
327  if (has_j2)
328  {
329  joint_state_->commanded_velocity_ = joint_state_->velocity_;
330  joint_state_2->commanded_velocity_ = joint_state_2->velocity_;
331  command_ = joint_state_->velocity_ + joint_state_2->velocity_;
332  }
333  else
334  {
335  joint_state_->commanded_velocity_ = joint_state_->velocity_;
336  command_ = joint_state_->velocity_;
337  }
338  }
339 } // namespace controller
340 
341 /* For the emacs weenies in the crowd.
342 Local Variables:
343  c-basic-offset: 2
344 End:
345  */
346 
347 
void get_min_max(urdf::Model model, std::string joint_name)
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.
bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp)
double clamp_command(double cmd)
clamp the command to velocity limits
boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
double velocity_deadband
the velocity deadband value used in the hysteresis_deadband
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the velocity target from a topic
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros_ethercat_model::JointState * joint_state_2
boost::scoped_ptr< sr_friction_compensation::SrFrictionCompensator > friction_compensator
virtual void getGains(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_
Follows a position target. The position demand is converted into a force demand by a PID loop...
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)
void read_parameters()
read all the controller settings from the parameter server
#define ROS_WARN_STREAM(args)
double vel_min_
Min and max range of the velocity, used to clamp the command.
#define ROS_DEBUG_STREAM(args)
double max_force_demand
clamps the force demand to this value
boost::scoped_ptr< control_toolbox::Pid > pid_controller_velocity_
Internal PID controller for the velocity loop.
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We&#39;re using an hysteresis deadband.
bool getParam(const std::string &key, std::string &s) const
ros::ServiceServer serve_set_gains_
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#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