srh_joint_effort_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 
30 #include "angles/angles.h"
32 #include <string>
33 #include <sstream>
34 #include <math.h>
35 #include <algorithm>
37 
38 #include <std_msgs/Float64.h>
39 
40 using std::min;
41 using std::max;
42 
44 
45 namespace controller
46 {
47  bool SrhEffortJointController::init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
48  {
49  ROS_ASSERT(robot);
50 
51  std::string robot_state_name;
52  node_.param<std::string>("robot_state_name", robot_state_name, "unique_robot_hw");
53 
54  try
55  {
56  robot_ = robot->getHandle(robot_state_name).getState();
57  }
59  {
60  ROS_ERROR_STREAM("Could not find robot state: " << robot_state_name << " Not loading the controller. " <<
61  e.what());
62  return false;
63  }
64 
65  node_ = n;
66 
67  if (!node_.getParam("joint", joint_name_))
68  {
69  ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
70  return false;
71  }
72 
74  (node_, "state", 1));
75 
76  ROS_DEBUG(" --------- ");
77  ROS_DEBUG_STREAM("Init: " << joint_name_);
78 
79  // joint 0s e.g. FFJ0
80  has_j2 = is_joint_0();
81  if (has_j2)
82  {
84  if (!joint_state_)
85  {
86  ROS_ERROR("SrhEffortJointController could not find the first joint relevant to \"%s\"\n", joint_name_.c_str());
87  return false;
88  }
89  if (!joint_state_2)
90  {
91  ROS_ERROR("SrhEffortJointController could not find the second joint relevant to \"%s\"\n", joint_name_.c_str());
92  return false;
93  }
94  }
95  else
96  {
97  joint_state_ = robot_->getJointState(joint_name_);
98  if (!joint_state_)
99  {
100  ROS_ERROR("SrhEffortJointController could not find joint named \"%s\"\n", joint_name_.c_str());
101  return false;
102  }
103  }
104 
106 
107  // get the min and max value for the current joint:
108  get_min_max(robot_->robot_model_, joint_name_);
109 
112 
113  ROS_DEBUG_STREAM(" joint_state name: " << joint_state_->joint_->name);
114  ROS_DEBUG_STREAM(" In Init: " << getJointName() << " This: " << this
115  << " joint_state: " << joint_state_);
116 
117  after_init();
118  return true;
119  }
120 
122  {
123  command_ = 0.0;
124  read_parameters();
125  }
126 
127  bool SrhEffortJointController::setGains(sr_robot_msgs::SetEffortControllerGains::Request &req,
128  sr_robot_msgs::SetEffortControllerGains::Response &resp)
129  {
130  max_force_demand = req.max_force;
131  friction_deadband = req.friction_deadband;
132 
133  // Setting the new parameters in the parameter server
134  node_.setParam("max_force", max_force_demand);
135  node_.setParam("friction_deadband", friction_deadband);
136 
137  return true;
138  }
139 
140  bool SrhEffortJointController::resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
141  {
142  command_ = 0.0;
143 
144  read_parameters();
145 
146  if (has_j2)
148  "Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
149  else
150  ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
151 
152  return true;
153  }
154 
155  void SrhEffortJointController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
156  {
157  }
158 
160  {
162  ROS_ASSERT(joint_state_->joint_);
163 
164  if (!initialized_)
165  {
166  initialized_ = true;
167  command_ = 0.0;
168  }
169 
170  // The commanded effort is the error directly:
171  // the PID loop for the force controller is running on the
172  // motorboard.
173  double commanded_effort = command_; // clamp_command(command_) // do not use urdf effort limits;
174 
175  // Clamps the effort
176  commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
177  commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
178 
179  // Friction compensation
180  if (has_j2)
181  {
182  commanded_effort += friction_compensator->friction_compensation(
183  joint_state_->position_ + joint_state_2->position_, joint_state_->velocity_ + joint_state_2->velocity_,
184  static_cast<int>(commanded_effort), friction_deadband);
185  }
186  else
187  {
188  commanded_effort += friction_compensator->friction_compensation(joint_state_->position_, joint_state_->velocity_,
189  static_cast<int>(commanded_effort),
191  }
192 
193  joint_state_->commanded_effort_ = commanded_effort;
194 
195  if (loop_count_ % 10 == 0)
196  {
198  {
199  controller_state_publisher_->msg_.header.stamp = time;
200  controller_state_publisher_->msg_.set_point = command_;
201  controller_state_publisher_->msg_.process_value = joint_state_->effort_;
202  // @todo compute the derivative of the effort.
203  controller_state_publisher_->msg_.process_value_dot = -1.0;
204  controller_state_publisher_->msg_.error = commanded_effort - joint_state_->effort_;
205  controller_state_publisher_->msg_.time_step = period.toSec();
206  controller_state_publisher_->msg_.command = commanded_effort;
207 
208  double dummy;
212  controller_state_publisher_->msg_.i_clamp,
213  dummy);
214  controller_state_publisher_->unlockAndPublish();
215  }
216  }
217  loop_count_++;
218  }
219 
221  {
223  }
224 
226  {
227  node_.param<double>("max_force", max_force_demand, 1023.0);
228  node_.param<int>("friction_deadband", friction_deadband, 5);
229  }
230 
231  void SrhEffortJointController::setCommandCB(const std_msgs::Float64ConstPtr &msg)
232  {
233  command_ = msg->data;
234  }
235 } // namespace controller
236 
237 /* For the emacs weenies in the crowd.
238 Local Variables:
239  c-basic-offset: 2
240 End:
241  */
void get_min_max(urdf::Model model, std::string joint_name)
ros_ethercat_model::JointState * joint_state_
bool setGains(sr_robot_msgs::SetEffortControllerGains::Request &req, sr_robot_msgs::SetEffortControllerGains::Response &resp)
double eff_min_
Min and max range of the effort, used to clamp the command.
void read_parameters()
read all the controller settings from the parameter server
boost::scoped_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
Compute an effort demand from the effort error. As the effort PID loop is running on the motor boards...
#define ROS_ERROR(...)
double clamp_command(double cmd)
clamp the command to effort limits
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
virtual void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
ros_ethercat_model::JointState * joint_state_2
boost::scoped_ptr< sr_friction_compensation::SrFrictionCompensator > friction_compensator
#define ROS_DEBUG(...)
double clamp_command(double cmd, double min_cmd, double max_cmd)
bool init(ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n)
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
bool getParam(const std::string &key, std::string &s) const
int friction_deadband
the deadband for the friction compensation algorithm
virtual void starting(const ros::Time &time)
double min(double a, double b)
virtual void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
double max_force_demand
clamps the force demand to this value
const std::string & getNamespace() const
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
virtual bool resetGains(std_srvs::Empty::Request &req, std_srvs::Empty::Response &resp)
ros::ServiceServer serve_set_gains_
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
set the effort target from a topic
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