srh_joint_position_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 
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 
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  }
107  else
108  {
109  joint_state_ = robot_->getJointState(joint_name_);
110  if (!joint_state_)
111  {
112  ROS_ERROR("SrhJointPositionController could not find joint named \"%s\"\n", joint_name_.c_str());
113  return false;
114  }
115  }
116 
117  // get the min and max value for the current joint:
118  get_min_max(robot_->robot_model_, joint_name_);
119 
121 
124 
125  read_parameters();
126 
127  after_init();
128  return true;
129  }
130 
132  {
133  resetJointState();
134  pid_controller_position_->reset();
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 SrhJointPositionController::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: " <<
148  req.max_force << ", friction deadband: " << req.friction_deadband <<
149  " pos deadband: " << req.deadband);
150 
151  pid_controller_position_->setGains(req.p, req.i, req.d, req.i_clamp, -req.i_clamp);
152  max_force_demand = req.max_force;
153  friction_deadband = req.friction_deadband;
154  position_deadband = req.deadband;
155 
156  // Setting the new parameters in the parameter server
157  node_.setParam("pid/p", req.p);
158  node_.setParam("pid/i", req.i);
159  node_.setParam("pid/d", req.d);
160  node_.setParam("pid/i_clamp", req.i_clamp);
161  node_.setParam("pid/max_force", max_force_demand);
162  node_.setParam("pid/position_deadband", position_deadband);
163  node_.setParam("pid/friction_deadband", friction_deadband);
164 
165  return true;
166  }
167 
168  bool SrhJointPositionController::resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
169  {
170  resetJointState();
171 
172  if (!pid_controller_position_->init(ros::NodeHandle(node_, "pid")))
173  {
174  return false;
175  }
176 
177  read_parameters();
178 
179  if (has_j2)
181  "Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
182  else
183  ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
184 
185  return true;
186  }
187 
188  void SrhJointPositionController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
189  {
190  pid_controller_position_->getGains(p, i, d, i_max, i_min);
191  }
192 
194  {
196  ROS_ASSERT(joint_state_->joint_);
197 
198  if (!initialized_)
199  {
200  resetJointState();
201  initialized_ = true;
202  }
203  if (has_j2)
204  {
205  command_ = joint_state_->commanded_position_ + joint_state_2->commanded_position_;
206  }
207  else
208  {
209  command_ = joint_state_->commanded_position_;
210  }
212 
213  // Compute position demand from position error:
214  double error_position = 0.0;
215  double commanded_effort = 0.0;
216 
217  if (has_j2)
218  {
219  error_position = (joint_state_->position_ + joint_state_2->position_) - command_;
220  }
221  else
222  {
223  error_position = joint_state_->position_ - command_;
224  }
225 
226  bool in_deadband = hysteresis_deadband.is_in_deadband(command_, error_position, position_deadband);
227 
228  // don't compute the error if we're in the deadband.
229  if (in_deadband)
230  {
231  error_position = 0.0;
232  }
233 
234  commanded_effort = pid_controller_position_->computeCommand(-error_position, period);
235 
236  // clamp the result to max force
237  commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
238  commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
239 
240  if (!in_deadband)
241  {
242  if (has_j2)
243  {
244  commanded_effort += friction_compensator->friction_compensation(
245  joint_state_->position_ + joint_state_2->position_,
246  joint_state_->velocity_ + joint_state_2->velocity_,
247  static_cast<int>(commanded_effort),
249  }
250  else
251  {
252  commanded_effort += friction_compensator->friction_compensation(joint_state_->position_,
253  joint_state_->velocity_,
254  static_cast<int>(commanded_effort),
256  }
257  }
258 
259  joint_state_->commanded_effort_ = commanded_effort;
260 
261  if (loop_count_ % 10 == 0)
262  {
264  {
265  controller_state_publisher_->msg_.header.stamp = time;
266  controller_state_publisher_->msg_.set_point = command_;
267  if (has_j2)
268  {
269  controller_state_publisher_->msg_.process_value = joint_state_->position_ + joint_state_2->position_;
270  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_ + joint_state_2->velocity_;
271  }
272  else
273  {
274  controller_state_publisher_->msg_.process_value = joint_state_->position_;
275  controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
276  }
277 
278  controller_state_publisher_->msg_.error = error_position;
279  controller_state_publisher_->msg_.time_step = period.toSec();
280  controller_state_publisher_->msg_.command = commanded_effort;
281 
282  double dummy;
286  controller_state_publisher_->msg_.i_clamp,
287  dummy);
288  controller_state_publisher_->unlockAndPublish();
289  }
290  }
291  loop_count_++;
292  }
293 
295  {
296  node_.param<double>("pid/max_force", max_force_demand, 1023.0);
297  node_.param<double>("pid/position_deadband", position_deadband, 0.015);
298  node_.param<int>("pid/friction_deadband", friction_deadband, 5);
299  }
300 
301  void SrhJointPositionController::setCommandCB(const std_msgs::Float64ConstPtr &msg)
302  {
303  joint_state_->commanded_position_ = msg->data;
304  if (has_j2)
305  {
306  joint_state_2->commanded_position_ = 0.0;
307  }
308  }
309 
311  {
312  if (has_j2)
313  {
314  joint_state_->commanded_position_ = joint_state_->position_;
315  joint_state_2->commanded_position_ = joint_state_2->position_;
316  command_ = joint_state_->position_ + joint_state_2->position_;
317  }
318  else
319  {
320  joint_state_->commanded_position_ = joint_state_->position_;
321  command_ = joint_state_->position_;
322  }
323  }
324 } // namespace controller
325 
326 /* For the emacs weenies in the crowd.
327 Local Variables:
328  c-basic-offset: 2
329 End:
330  */
331 
332 
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
#define ROS_ERROR(...)
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
#define ROS_DEBUG(...)
double clamp_command(double cmd, double min_cmd, double max_cmd)
ros_ethercat_model::RobotState * robot_
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
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
bool getParam(const std::string &key, std::string &s) const
int friction_deadband
the deadband for the friction compensation algorithm
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the position target from a topic
double min(double a, double b)
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
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) 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)
double max(double a, double b)
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
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