srh_joint_effort_controller.cpp
Go to the documentation of this file.
1 
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  {
83  get_joints_states_1_2();
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 
105  friction_compensator.reset(new sr_friction_compensation::SrFrictionCompensator(joint_name_));
106 
107  // get the min and max value for the current joint:
108  get_min_max(robot_->robot_model_, joint_name_);
109 
110  serve_set_gains_ = node_.advertiseService("set_gains", &SrhEffortJointController::setGains, this);
111  serve_reset_gains_ = node_.advertiseService("reset_gains", &SrhEffortJointController::resetGains, this);
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 
121  void SrhEffortJointController::starting(const ros::Time &time)
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 
159  void SrhEffortJointController::update(const ros::Time &time, const ros::Duration &period)
160  {
161  if (!has_j2 && !joint_state_->calibrated_)
162  {
163  return;
164  }
165 
166  ROS_ASSERT(robot_);
167  ROS_ASSERT(joint_state_->joint_);
168 
169  if (!initialized_)
170  {
171  initialized_ = true;
172  command_ = 0.0;
173  }
174 
175  // The commanded effort is the error directly:
176  // the PID loop for the force controller is running on the
177  // motorboard.
178  double commanded_effort = command_; // clamp_command(command_) // do not use urdf effort limits;
179 
180  // Clamps the effort
181  commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
182  commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
183 
184  // Friction compensation
185  if (has_j2)
186  {
187  commanded_effort += friction_compensator->friction_compensation(
188  joint_state_->position_ + joint_state_2->position_, joint_state_->velocity_ + joint_state_2->velocity_,
189  static_cast<int>(commanded_effort), friction_deadband);
190  }
191  else
192  {
193  commanded_effort += friction_compensator->friction_compensation(joint_state_->position_, joint_state_->velocity_,
194  static_cast<int>(commanded_effort),
195  friction_deadband);
196  }
197 
198  joint_state_->commanded_effort_ = commanded_effort;
199 
200  if (loop_count_ % 10 == 0)
201  {
202  if (controller_state_publisher_ && controller_state_publisher_->trylock())
203  {
204  controller_state_publisher_->msg_.header.stamp = time;
205  controller_state_publisher_->msg_.set_point = command_;
206  controller_state_publisher_->msg_.process_value = joint_state_->effort_;
207  // @todo compute the derivative of the effort.
208  controller_state_publisher_->msg_.process_value_dot = -1.0;
209  controller_state_publisher_->msg_.error = commanded_effort - joint_state_->effort_;
210  controller_state_publisher_->msg_.time_step = period.toSec();
211  controller_state_publisher_->msg_.command = commanded_effort;
212 
213  double dummy;
214  getGains(controller_state_publisher_->msg_.p,
215  controller_state_publisher_->msg_.i,
216  controller_state_publisher_->msg_.d,
217  controller_state_publisher_->msg_.i_clamp,
218  dummy);
219  controller_state_publisher_->unlockAndPublish();
220  }
221  }
222  loop_count_++;
223  }
224 
225  double SrhEffortJointController::clamp_command(double cmd)
226  {
227  return SrController::clamp_command(cmd, eff_min_, eff_max_);
228  }
229 
230  void SrhEffortJointController::read_parameters()
231  {
232  node_.param<double>("max_force", max_force_demand, 1023.0);
233  node_.param<int>("friction_deadband", friction_deadband, 5);
234  }
235 
236  void SrhEffortJointController::setCommandCB(const std_msgs::Float64ConstPtr &msg)
237  {
238  command_ = msg->data;
239  }
240 } // namespace controller
241 
242 /* For the emacs weenies in the crowd.
243 Local Variables:
244  c-basic-offset: 2
245 End:
246  */
Compute an effort demand from the effort error. As the effort PID loop is running on the motor boards...
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
int min(int a, int b)
#define ROS_ERROR_STREAM(args)
#define ROS_ASSERT(cond)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define ROS_ERROR(...)
#define ROS_DEBUG(...)


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:58