srh_joint_position_controller.cpp
Go to the documentation of this file.
1 
28 #include "angles/angles.h"
30 #include <string>
31 #include <sstream>
32 #include <algorithm>
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  SrhJointPositionController::SrhJointPositionController()
47  : position_deadband(0.015)
48  {
49  }
50 
51  bool SrhJointPositionController::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("SrhJointPositionController could not find the first joint relevant to \"%s\"\n",
97  joint_name_.c_str());
98  return false;
99  }
100  if (!joint_state_2)
101  {
102  ROS_ERROR("SrhJointPositionController could not find the second joint relevant to \"%s\"\n",
103  joint_name_.c_str());
104  return false;
105  }
106  if (!joint_state_2->calibrated_)
107  {
108  ROS_ERROR("Joint %s not calibrated for SrhJointPositionController", joint_name_.c_str());
109  return false;
110  }
111  else
112  {
113  joint_state_->calibrated_ = true;
114  }
115  }
116  else
117  {
118  joint_state_ = robot_->getJointState(joint_name_);
119  if (!joint_state_)
120  {
121  ROS_ERROR("SrhJointPositionController could not find joint named \"%s\"\n", joint_name_.c_str());
122  return false;
123  }
124  if (!joint_state_->calibrated_)
125  {
126  ROS_ERROR("Joint %s not calibrated for SrhJointPositionController", joint_name_.c_str());
127  return false;
128  }
129  }
130 
131  // get the min and max value for the current joint:
132  get_min_max(robot_->robot_model_, joint_name_);
133 
135 
138 
139  after_init();
140  return true;
141  }
142 
144  {
145  resetJointState();
146  pid_controller_position_->reset();
147  read_parameters();
148 
149  if (has_j2)
151  "Reseting PID for joints " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
152  else
153  ROS_WARN_STREAM("Reseting PID for joint " << joint_state_->joint_->name);
154  }
155 
156  bool SrhJointPositionController::setGains(sr_robot_msgs::SetPidGains::Request &req,
157  sr_robot_msgs::SetPidGains::Response &resp)
158  {
159  ROS_INFO_STREAM("Setting new PID parameters. P:" << req.p << " / I:" << req.i <<
160  " / D:" << req.d << " / IClamp:" << req.i_clamp << ", max force: " <<
161  req.max_force << ", friction deadband: " << req.friction_deadband <<
162  " pos deadband: " << req.deadband);
163 
164  pid_controller_position_->setGains(req.p, req.i, req.d, req.i_clamp, -req.i_clamp);
165  max_force_demand = req.max_force;
166  friction_deadband = req.friction_deadband;
167  position_deadband = req.deadband;
168 
169  // Setting the new parameters in the parameter server
170  node_.setParam("pid/p", req.p);
171  node_.setParam("pid/i", req.i);
172  node_.setParam("pid/d", req.d);
173  node_.setParam("pid/i_clamp", req.i_clamp);
174  node_.setParam("pid/max_force", max_force_demand);
175  node_.setParam("pid/position_deadband", position_deadband);
176  node_.setParam("pid/friction_deadband", friction_deadband);
177 
178  return true;
179  }
180 
181  bool SrhJointPositionController::resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
182  {
183  resetJointState();
184 
185  if (!pid_controller_position_->init(ros::NodeHandle(node_, "pid")))
186  {
187  return false;
188  }
189 
190  read_parameters();
191 
192  if (has_j2)
194  "Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
195  else
196  ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
197 
198  return true;
199  }
200 
201  void SrhJointPositionController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
202  {
203  pid_controller_position_->getGains(p, i, d, i_max, i_min);
204  }
205 
207  {
208  if (!has_j2 && !joint_state_->calibrated_)
209  {
210  return;
211  }
212 
214  ROS_ASSERT(joint_state_->joint_);
215 
216  if (!initialized_)
217  {
218  resetJointState();
219  initialized_ = true;
220  }
221  if (has_j2)
222  {
223  command_ = joint_state_->commanded_position_ + joint_state_2->commanded_position_;
224  }
225  else
226  {
227  command_ = joint_state_->commanded_position_;
228  }
230 
231  // Compute position demand from position error:
232  double error_position = 0.0;
233  double commanded_effort = 0.0;
234 
235  if (has_j2)
236  {
237  error_position = (joint_state_->position_ + joint_state_2->position_) - command_;
238  }
239  else
240  {
241  error_position = joint_state_->position_ - command_;
242  }
243 
244  bool in_deadband = hysteresis_deadband.is_in_deadband(command_, error_position, position_deadband);
245 
246  // don't compute the error if we're in the deadband.
247  if (in_deadband)
248  {
249  error_position = 0.0;
250  }
251 
252  commanded_effort = pid_controller_position_->computeCommand(-error_position, period);
253 
254  // clamp the result to max force
255  commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
256  commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
257 
258  if (!in_deadband)
259  {
260  if (has_j2)
261  {
262  commanded_effort += friction_compensator->friction_compensation(
263  joint_state_->position_ + joint_state_2->position_,
264  joint_state_->velocity_ + joint_state_2->velocity_,
265  static_cast<int>(commanded_effort),
267  }
268  else
269  {
270  commanded_effort += friction_compensator->friction_compensation(joint_state_->position_,
271  joint_state_->velocity_,
272  static_cast<int>(commanded_effort),
274  }
275  }
276 
277  joint_state_->commanded_effort_ = commanded_effort;
278 
279  if (loop_count_ % 10 == 0)
280  {
282  {
283  controller_state_publisher_->msg_.header.stamp = time;
284  controller_state_publisher_->msg_.set_point = command_;
285  if (has_j2)
286  {
287  controller_state_publisher_->msg_.process_value = joint_state_->position_ + joint_state_2->position_;
288  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_ + joint_state_2->velocity_;
289  }
290  else
291  {
292  controller_state_publisher_->msg_.process_value = joint_state_->position_;
293  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
294  }
295 
296  controller_state_publisher_->msg_.error = error_position;
297  controller_state_publisher_->msg_.time_step = period.toSec();
298  controller_state_publisher_->msg_.command = commanded_effort;
299 
300  double dummy;
304  controller_state_publisher_->msg_.i_clamp,
305  dummy);
306  controller_state_publisher_->unlockAndPublish();
307  }
308  }
309  loop_count_++;
310  }
311 
313  {
314  node_.param<double>("pid/max_force", max_force_demand, 1023.0);
315  node_.param<double>("pid/position_deadband", position_deadband, 0.015);
316  node_.param<int>("pid/friction_deadband", friction_deadband, 5);
317  }
318 
319  void SrhJointPositionController::setCommandCB(const std_msgs::Float64ConstPtr &msg)
320  {
321  joint_state_->commanded_position_ = msg->data;
322  if (has_j2)
323  {
324  joint_state_2->commanded_position_ = 0.0;
325  }
326  }
327 
329  {
330  if (has_j2)
331  {
332  joint_state_->commanded_position_ = joint_state_->position_;
333  joint_state_2->commanded_position_ = joint_state_2->position_;
334  command_ = joint_state_->position_ + joint_state_2->position_;
335  }
336  else
337  {
338  joint_state_->commanded_position_ = joint_state_->position_;
339  command_ = joint_state_->position_;
340  }
341  }
342 } // namespace controller
343 
344 /* For the emacs weenies in the crowd.
345 Local Variables:
346  c-basic-offset: 2
347 End:
348  */
349 
350 
void get_min_max(urdf::Model model, std::string joint_name)
ros_ethercat_model::JointState * joint_state_
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We&#39;re using an hysteresis deadband.
boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
double position_deadband
the position deadband value used in the hysteresis_deadband
void read_parameters()
read all the controller settings from the parameter server
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros_ethercat_model::JointState * joint_state_2
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
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_
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::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
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
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)
double max_force_demand
clamps the force demand to this value
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
ros::ServiceServer serve_set_gains_
boost::scoped_ptr< control_toolbox::Pid > pid_controller_position_
Internal PID controller for the position loop.
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool setGains(sr_robot_msgs::SetPidGains::Request &req, sr_robot_msgs::SetPidGains::Response &resp)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
#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