hysteresis_controller.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
37 #include "urdf_model/joint.h"
38 
41 
42 #define MAX_DATA_POINTS 120000
43 
44 using namespace std;
45 using namespace joint_qualification_controllers;
46 
47 HysteresisController::HysteresisController() :
48  joint_(NULL),
49  robot_(NULL),
50  data_sent_(false),
51  hyst_pub_(NULL)
52 {
53  test_data_.joint_name = "default joint";
54  test_data_.time_up.resize(MAX_DATA_POINTS);
55  test_data_.effort_up.resize(MAX_DATA_POINTS);
56  test_data_.position_up.resize(MAX_DATA_POINTS);
57  test_data_.velocity_up.resize(MAX_DATA_POINTS);
58 
59  test_data_.time_down.resize(MAX_DATA_POINTS);
60  test_data_.effort_down.resize(MAX_DATA_POINTS);
61  test_data_.position_down.resize(MAX_DATA_POINTS);
62  test_data_.velocity_down.resize(MAX_DATA_POINTS);
63 
64  test_data_.arg_name.resize(14);
65  test_data_.arg_value.resize(14);
66  test_data_.arg_name[0] = "Min. Expected Effort";
67  test_data_.arg_name[1] = "Max. Expected Effort";
68  test_data_.arg_name[2] = "Minimum Position";
69  test_data_.arg_name[3] = "Maximum Position";
70  test_data_.arg_name[4] = "Velocity";
71  test_data_.arg_name[5] = "Timeout";
72  test_data_.arg_name[6] = "Max. Allowed Effort";
73  test_data_.arg_name[7] = "Tolerance";
74  test_data_.arg_name[8] = "SD Max";
75  test_data_.arg_name[9] = "Slope";
76  test_data_.arg_name[10] = "P Gain";
77  test_data_.arg_name[11] = "I Gain";
78  test_data_.arg_name[12] = "D Gain";
79  test_data_.arg_name[13] = "I-Clamp";
80 
81  state_ = STOPPED;
82  starting_count_ = 0;
83  velocity_ = 0;
85  max_effort_ = 0;
86  complete = false;
87  up_count_ = 0;
88  down_count_ = 0;
89 }
90 
92 {
94 }
95 
97 {
98  assert(robot);
99  robot_ = robot;
100 
101  std::string name;
102  if (!n.getParam("velocity_controller/joint", name)){
103  ROS_ERROR("Hysteresis Controller: No joint name found on parameter namespace: %s)",
104  n.getNamespace().c_str());
105  return false;
106  }
107  if (!(joint_ = robot->getJointState(name)))
108  {
109  ROS_ERROR("HysteresisController could not find joint named \"%s\"\n", name.c_str());
110  return false;
111  }
112 
113  if (!n.getParam("velocity", velocity_)){
114  ROS_ERROR("Hysteresis Controller: No velocity found on parameter namespace: %s)",
115  n.getNamespace().c_str());
116  return false;
117  }
118  velocity_ = velocity_ > 0 ? velocity_ : -1.0 * velocity_;
119 
120  if (!n.getParam("max_effort", max_effort_)){
121  ROS_ERROR("Hysteresis Controller: No max effort found on parameter namespace: %s)",
122  n.getNamespace().c_str());
123  return false;
124  }
125 
126  double min_expected, max_expected, max_pos, min_pos;
127 
128  if (!n.getParam("min_expected", min_expected)){
129  ROS_ERROR("Hysteresis Controller: No min expected effort found on parameter namespace: %s)",
130  n.getNamespace().c_str());
131  return false;
132  }
133 
134  if (!n.getParam("max_expected", max_expected)){
135  ROS_ERROR("Hysteresis Controller: No max expected effort found on parameter namespace: %s)",
136  n.getNamespace().c_str());
137  return false;
138  }
139 
140  if (!n.getParam("max_position", max_pos)){
141  ROS_ERROR("Hysteresis Controller: No max position found on parameter namespace: %s)",
142  n.getNamespace().c_str());
143  return false;
144  }
145 
146  if (!n.getParam("min_position", min_pos)){
147  ROS_ERROR("Hysteresis Controller: No min position found on parameter namespace: %s)",
148  n.getNamespace().c_str());
149  return false;
150  }
151 
152  if (!n.getParam("timeout", timeout_)){
153  ROS_ERROR("Hysteresis Controller: No timeout found on parameter namespace: %s)",
154  n.getNamespace().c_str());
155  return false;
156  }
157 
158  double tolerance, sd_max;
159  if (!n.getParam("tolerance", tolerance)){
160  ROS_WARN("Parameter 'tolerance' is not set on namespace: %s. Default is 0.20.",
161  n.getNamespace().c_str());
162  // This is deprecated, so eventually "return false" will be here.
163  tolerance = 0.20;
164  }
165 
166  if (!n.getParam("sd_max", sd_max)) {
167  ROS_WARN("Parameter 'sd_max' is not set on namespace: %s. Default is 0.20.",
168  n.getNamespace().c_str());
169  // This is deprecated, so eventually "return false" will be here.
170  sd_max = 0.20;
171  }
172 
173  double slope;
174  if (!n.getParam("slope", slope))
175  slope = 0;
176 
179 
180  // Set values in test data output
181  test_data_.joint_name = name;
182  test_data_.arg_value[0] = min_expected;
183  test_data_.arg_value[1] = max_expected;
184  test_data_.arg_value[2] = min_pos;
185  test_data_.arg_value[3] = max_pos;
186  test_data_.arg_value[4] = velocity_;
187  test_data_.arg_value[5] = timeout_;
188  test_data_.arg_value[6] = max_effort_;
189  test_data_.arg_value[7] = tolerance;
190  test_data_.arg_value[8] = sd_max;
191  test_data_.arg_value[9] = slope;
192 
194  ros::NodeHandle n_vel(n, "velocity_controller");
195  if (!velocity_controller_->init(robot, n_vel)) return false;
196 
197  // Get the gains, add them to test data
198  double p, i, d, iClamp, imin;
199  velocity_controller_->getGains(p, i, d, iClamp, imin);
200 
201  test_data_.arg_value[10] = p;
202  test_data_.arg_value[11] = i;
203  test_data_.arg_value[12] = d;
204  test_data_.arg_value[13] = iClamp;
205 
207 
208  return true;
209 }
210 
212 {
214 
217 }
218 
220 {
221  if (!joint_->calibrated_)
222  return;
223 
224  ros::Time time = robot_->getTime();
226 
227  // Timeout check.
228  if ((time - initial_time_).toSec() > timeout_ && state_ != ANALYZING && state_ != DONE)
229  {
230  state_ = ANALYZING;
231  test_data_.arg_value[5] = -1;
233  }
234 
235  switch (state_)
236  {
237  case STOPPED:
239  starting_count_ = 0;
241  break;
242  case MOVING_HOME:
243  starting_count_++;
244  if (turn() and starting_count_ > 100)
245  {
247  state_ = MOVING_UP;
248  starting_count_ = 0;
249  }
250  break;
251  case MOVING_UP:
252  starting_count_++;
254  {
255  test_data_.time_up[up_count_] = time.toSec();
257  test_data_.position_up[up_count_] = joint_->position_;
258  test_data_.velocity_up[up_count_] = joint_->velocity_;
259  up_count_++;
260  }
261 
262  if ((turn() and starting_count_ > 100) or up_count_ >= MAX_DATA_POINTS)
263  {
266  starting_count_ = 0;
267  }
268  break;
269  case MOVING_DOWN:
270  starting_count_++;
272  {
273  test_data_.time_down[down_count_] = time.toSec();
275  test_data_.position_down[down_count_] = joint_->position_;
276  test_data_.velocity_down[down_count_] = joint_->velocity_;
277  down_count_++;
278  }
279  if ((turn() and starting_count_ > 100) or down_count_ >= MAX_DATA_POINTS)
280  {
282  state_ = ANALYZING;
283  starting_count_ = 0;
284  }
285  break;
286  case ANALYZING:
288  analysis();
289  state_ = DONE;
290  break;
291  case DONE:
293  if (!data_sent_)
294  data_sent_ = sendData();
295  break;
296  }
297 
298 }
299 
301 {
302  if (joint_->joint_->type!=urdf::Joint::CONTINUOUS)
303  {
304  return (fabs(joint_->velocity_) < 0.001 && fabs(joint_->commanded_effort_) > max_effort_);
305  }
306  else
307  {
308  if (fabs(joint_->position_-initial_position_) > 6.28)
309  {
311  return true;
312  }
313  return false;
314  }
315 }
316 
318 {
319  // Resize if no points
320  if (up_count_ == 0)
321  up_count_ = 1;
322  if (down_count_ == 0)
323  down_count_ = 1;
324 
325  test_data_.time_up.resize(up_count_);
326  test_data_.effort_up.resize(up_count_);
327  test_data_.position_up.resize(up_count_);
328  test_data_.velocity_up.resize(up_count_);
329 
330  test_data_.time_down.resize(down_count_);
331  test_data_.effort_down.resize(down_count_);
332  test_data_.position_down.resize(down_count_);
333  test_data_.velocity_down.resize(down_count_);
334 
335  return;
336 }
337 
339 {
340  if (hyst_pub_->trylock())
341  {
342  joint_qualification_controllers::HysteresisData *out = &hyst_pub_->msg_;
343  out->joint_name = test_data_.joint_name;
344 
345  out->time_up = test_data_.time_up;
346  out->effort_up = test_data_.effort_up;
347  out->position_up = test_data_.position_up;
348  out->velocity_up = test_data_.velocity_up;
349 
350  out->time_down = test_data_.time_down;
351  out->effort_down = test_data_.effort_down;
352  out->position_down = test_data_.position_down;
353  out->velocity_down = test_data_.velocity_down;
354 
355 
356  out->arg_name = test_data_.arg_name;
357  out->arg_value = test_data_.arg_value;
358 
359  hyst_pub_->unlockAndPublish();
360  return true;
361  }
362  return false;
363 }
364 
365 
366 
d
void update()
Issues commands to the joint to perform hysteresis test.
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::HysteresisController, pr2_controller_interface::Controller) using namespace std
boost::shared_ptr< const urdf::Joint > joint_
#define ROS_WARN(...)
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Functional way to initialize.
controller::JointVelocityController * velocity_controller_
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
joint_qualification_controllers::HysteresisData test_data_
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::HysteresisData > > hyst_pub_
bool getParam(const std::string &key, std::string &s) const
void starting()
Called when controller is started.
#define ROS_ERROR(...)
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
#define MAX_DATA_POINTS


joint_qualification_controllers
Author(s): Kevin Watts, Melonee Wise
autogenerated on Wed Jan 6 2021 03:39:12