srh_joint_velocity_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 <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 
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  }
105  else
106  {
107  joint_state_ = robot_->getJointState(joint_name_);
108  if (!joint_state_)
109  {
110  ROS_ERROR("SrhVelocityController could not find joint named \"%s\"\n", joint_name_.c_str());
111  return false;
112  }
113  }
114 
116 
117  // get the min and max value for the current joint:
118  get_min_max(robot_->robot_model_, joint_name_);
119 
122 
123  after_init();
124  return true;
125  }
126 
128  {
129  resetJointState();
130  pid_controller_velocity_->reset();
131  read_parameters();
132 
133  if (has_j2)
135  "Reseting PID for joints " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
136  else
137  ROS_WARN_STREAM("Reseting PID for joint " << joint_state_->joint_->name);
138  }
139 
140  bool SrhJointVelocityController::setGains(sr_robot_msgs::SetPidGains::Request &req,
141  sr_robot_msgs::SetPidGains::Response &resp)
142  {
143  pid_controller_velocity_->setGains(req.p, req.i, req.d, req.i_clamp, -req.i_clamp);
144  max_force_demand = req.max_force;
145  friction_deadband = req.friction_deadband;
146  velocity_deadband = req.deadband;
147 
148  // Setting the new parameters in the parameter server
149  node_.setParam("pid/p", req.p);
150  node_.setParam("pid/i", req.i);
151  node_.setParam("pid/d", req.d);
152  node_.setParam("pid/i_clamp", req.i_clamp);
153 
154  node_.setParam("pid/max_force", max_force_demand);
155  node_.setParam("pid/velocity_deadband", velocity_deadband);
156  node_.setParam("pid/friction_deadband", friction_deadband);
157 
158  return true;
159  }
160 
161  bool SrhJointVelocityController::resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
162  {
163  resetJointState();
164 
165  if (!pid_controller_velocity_->init(ros::NodeHandle(node_, "velocity_pid")))
166  {
167  return false;
168  }
169 
170  read_parameters();
171 
172  if (has_j2)
174  "Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
175  else
176  ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
177 
178  return true;
179  }
180 
181  void SrhJointVelocityController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
182  {
183  pid_controller_velocity_->getGains(p, i, d, i_max, i_min);
184  }
185 
187  {
189  ROS_ASSERT(joint_state_->joint_);
190 
191  if (!initialized_)
192  {
193  resetJointState();
194  initialized_ = true;
195  }
196  if (has_j2)
197  {
198  command_ = joint_state_->commanded_velocity_ + joint_state_2->commanded_velocity_;
199  }
200  else
201  {
202  command_ = joint_state_->commanded_velocity_;
203  }
205 
206  double error_velocity = 0.0;
207  double commanded_effort = 0.0;
208 
209  if (has_j2)
210  {
211  error_velocity = (joint_state_->velocity_ + joint_state_2->velocity_) - command_;
212  }
213  else
214  {
215  error_velocity = joint_state_->velocity_ - command_;
216  }
217 
218  bool in_deadband = hysteresis_deadband.is_in_deadband(command_, error_velocity, velocity_deadband);
219  // are we in the deadband?
220  if (in_deadband)
221  {
222  error_velocity = 0.0; // force the error to zero to not further change the pid control terms
223  // if the requested velocity is smaller than the velocity_deadband, consider no movement is wanted.
224  if (std::fabs(command_) < velocity_deadband)
225  {
226  pid_controller_velocity_->reset();
227  }
228  }
229 
230  // compute the effort demand using the velocity pid loop
231  commanded_effort = pid_controller_velocity_->computeCommand(-error_velocity, period);
232 
233  // clamp the result to max force
234  commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
235  commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
236 
237  if (has_j2)
238  {
239  commanded_effort += friction_compensator->friction_compensation(
240  (joint_state_->position_ + joint_state_2->position_),
241  (joint_state_->velocity_ + joint_state_2->velocity_),
242  static_cast<int>(commanded_effort),
244  }
245  else
246  {
247  commanded_effort += friction_compensator->friction_compensation(joint_state_->position_,
248  joint_state_->velocity_,
249  static_cast<int>(commanded_effort),
251  }
252 
253  joint_state_->commanded_effort_ = commanded_effort;
254 
255  if (loop_count_ % 10 == 0)
256  {
258  {
259  controller_state_publisher_->msg_.header.stamp = time;
260  controller_state_publisher_->msg_.set_point = command_;
261  if (has_j2)
262  {
263  controller_state_publisher_->msg_.process_value = joint_state_->velocity_ + joint_state_2->velocity_;
264  }
265  else
266  {
267  controller_state_publisher_->msg_.process_value = joint_state_->velocity_;
268  }
269  controller_state_publisher_->msg_.error = error_velocity;
270  controller_state_publisher_->msg_.time_step = period.toSec();
271  controller_state_publisher_->msg_.command = commanded_effort;
272 
273  double dummy;
277  controller_state_publisher_->msg_.i_clamp,
278  dummy);
279  controller_state_publisher_->unlockAndPublish();
280  }
281  }
282  loop_count_++;
283  }
284 
286  {
288  }
289 
291  {
292  node_.param<double>("pid/max_force", max_force_demand, 1023.0);
293  node_.param<double>("pid/velocity_deadband", velocity_deadband, 0.015);
294  node_.param<int>("pid/friction_deadband", friction_deadband, 5);
295  }
296 
297  void SrhJointVelocityController::setCommandCB(const std_msgs::Float64ConstPtr &msg)
298  {
299  joint_state_->commanded_velocity_ = msg->data;
300  if (has_j2)
301  {
302  joint_state_2->commanded_velocity_ = 0.0;
303  }
304  }
305 
307  {
308  if (has_j2)
309  {
310  joint_state_->commanded_velocity_ = joint_state_->velocity_;
311  joint_state_2->commanded_velocity_ = joint_state_2->velocity_;
312  command_ = joint_state_->velocity_ + joint_state_2->velocity_;
313  }
314  else
315  {
316  joint_state_->commanded_velocity_ = joint_state_->velocity_;
317  command_ = joint_state_->velocity_;
318  }
319  }
320 } // namespace controller
321 
322 /* For the emacs weenies in the crowd.
323 Local Variables:
324  c-basic-offset: 2
325 End:
326  */
327 
328 
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)
#define ROS_ERROR(...)
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)
#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)
Follows a position target. The position demand is converted into a force demand by a PID loop...
bool param(const std::string &param_name, T &param_val, const T &default_val) const
const char * what() const noexcept override
bool getParam(const std::string &key, std::string &s) const
int friction_deadband
the deadband for the friction compensation algorithm
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)
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.
const std::string & getNamespace() const
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
sr_deadband::HysteresisDeadband< double > hysteresis_deadband
We&#39;re using an hysteresis deadband.
ros::ServiceServer serve_set_gains_
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
double max(double a, double b)
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