hysteresis_controller2.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 HysteresisController2::HysteresisController2() :
48  joint_(NULL),
49  robot_(NULL),
50  data_sent_(false),
51  hyst_pub_(NULL)
52 {
53  test_data_.joint_name = "default joint";
54 
55  /* TODO: figure out if I need to update this or just remove it
56  I _think_ I can just remove this; it's done in init() instead
57  test_data_.time_up.resize(MAX_DATA_POINTS);
58  test_data_.effort_up.resize(MAX_DATA_POINTS);
59  test_data_.position_up.resize(MAX_DATA_POINTS);
60  test_data_.velocity_up.resize(MAX_DATA_POINTS);
61 
62  test_data_.time_down.resize(MAX_DATA_POINTS);
63  test_data_.effort_down.resize(MAX_DATA_POINTS);
64  test_data_.position_down.resize(MAX_DATA_POINTS);
65  test_data_.velocity_down.resize(MAX_DATA_POINTS);
66  */
67 
68  test_data_.arg_name.resize(14);
69  test_data_.arg_value.resize(14);
70  test_data_.arg_name[0] = "Min. Expected Effort";
71  test_data_.arg_name[1] = "Max. Expected Effort";
72  test_data_.arg_name[2] = "Minimum Position";
73  test_data_.arg_name[3] = "Maximum Position";
74  test_data_.arg_name[4] = "Velocity";
75  test_data_.arg_name[5] = "Timeout";
76  test_data_.arg_name[6] = "Max. Allowed Effort";
77  test_data_.arg_name[7] = "Tolerance";
78  test_data_.arg_name[8] = "SD Max";
79  test_data_.arg_name[9] = "Slope";
80  test_data_.arg_name[10] = "P Gain";
81  test_data_.arg_name[11] = "I Gain";
82  test_data_.arg_name[12] = "D Gain";
83  test_data_.arg_name[13] = "I-Clamp";
84 
85  state_ = STOPPED;
86  starting_count_ = 0;
87  velocity_ = 0;
89  max_effort_ = 0;
90  complete = false;
91  up_count_ = 0;
92  down_count_ = 0;
93  repeat_count_ = 0;
94  repeat_ = 0;
95 }
96 
98 {
100 }
101 
103 {
104  assert(robot);
105  robot_ = robot;
106 
107  std::string name;
108  if (!n.getParam("velocity_controller/joint", name)){
109  ROS_ERROR("Hysteresis Controller: No joint name found on parameter namespace: %s)",
110  n.getNamespace().c_str());
111  return false;
112  }
113  if (!(joint_ = robot->getJointState(name)))
114  {
115  ROS_ERROR("HysteresisController2 could not find joint named \"%s\"\n", name.c_str());
116  return false;
117  }
118 
119  if (!n.getParam("velocity", velocity_)){
120  ROS_ERROR("Hysteresis Controller: No velocity found on parameter namespace: %s)",
121  n.getNamespace().c_str());
122  return false;
123  }
124  velocity_ = velocity_ > 0 ? velocity_ : -1.0 * velocity_;
125 
126  if (!n.getParam("max_effort", max_effort_)){
127  ROS_ERROR("Hysteresis Controller: No max effort found on parameter namespace: %s)",
128  n.getNamespace().c_str());
129  return false;
130  }
131 
132  double min_expected, max_expected, max_pos, min_pos;
133 
134  if (!n.getParam("min_expected", min_expected)){
135  ROS_ERROR("Hysteresis Controller: No min expected effort found on parameter namespace: %s)",
136  n.getNamespace().c_str());
137  return false;
138  }
139 
140  if (!n.getParam("max_expected", max_expected)){
141  ROS_ERROR("Hysteresis Controller: No max expected effort found on parameter namespace: %s)",
142  n.getNamespace().c_str());
143  return false;
144  }
145 
146  if (!n.getParam("max_position", max_pos)){
147  ROS_ERROR("Hysteresis Controller: No max position found on parameter namespace: %s)",
148  n.getNamespace().c_str());
149  return false;
150  }
151 
152  if (!n.getParam("min_position", min_pos)){
153  ROS_ERROR("Hysteresis Controller: No min position found on parameter namespace: %s)",
154  n.getNamespace().c_str());
155  return false;
156  }
157 
158  if (!n.getParam("timeout", timeout_)){
159  ROS_ERROR("Hysteresis Controller: No timeout found on parameter namespace: %s)",
160  n.getNamespace().c_str());
161  return false;
162  }
163 
164  if (!n.getParam("repeat_count", repeat_count_)){
165  repeat_count_ = 1;
166  }
167 
168  double tolerance, sd_max;
169  if (!n.getParam("tolerance", tolerance)){
170  ROS_WARN("Parameter 'tolerance' is not set on namespace: %s. Default is 0.20.",
171  n.getNamespace().c_str());
172  // This is deprecated, so eventually "return false" will be here.
173  tolerance = 0.20;
174  }
175 
176  if (!n.getParam("sd_max", sd_max)) {
177  ROS_WARN("Parameter 'sd_max' is not set on namespace: %s. Default is 0.20.",
178  n.getNamespace().c_str());
179  // This is deprecated, so eventually "return false" will be here.
180  sd_max = 0.20;
181  }
182 
183  double slope;
184  if (!n.getParam("slope", slope))
185  slope = 0;
186 
189 
190  // Set values in test data output
191  test_data_.joint_name = name;
192  test_data_.arg_value[0] = min_expected;
193  test_data_.arg_value[1] = max_expected;
194  test_data_.arg_value[2] = min_pos;
195  test_data_.arg_value[3] = max_pos;
196  test_data_.arg_value[4] = velocity_;
197  test_data_.arg_value[5] = timeout_;
198  test_data_.arg_value[6] = max_effort_;
199  test_data_.arg_value[7] = tolerance;
200  test_data_.arg_value[8] = sd_max;
201  test_data_.arg_value[9] = slope;
202 
204  ros::NodeHandle n_vel(n, "velocity_controller");
205  if (!velocity_controller_->init(robot, n_vel)) return false;
206 
207  // Get the gains, add them to test data
208  double p, i, d, iClamp, imin;
209  velocity_controller_->getGains(p, i, d, iClamp, imin);
210 
211  test_data_.arg_value[10] = p;
212  test_data_.arg_value[11] = i;
213  test_data_.arg_value[12] = d;
214  test_data_.arg_value[13] = iClamp;
215 
216  // repeat count is the number of up+down movements. we have one run for each
217  // direction
218  test_data_.runs.resize(repeat_count_ * 2);
219  move_count_.resize(repeat_count_ * 2);
220  for( int i=0; i < 2*repeat_count_; ++i ) {
221  test_data_.runs[i].time.resize(MAX_DATA_POINTS);
222  test_data_.runs[i].effort.resize(MAX_DATA_POINTS);
223  test_data_.runs[i].position.resize(MAX_DATA_POINTS);
224  test_data_.runs[i].velocity.resize(MAX_DATA_POINTS);
225  if( i % 2 ) {
226  // odd-numbered runs are down
227  test_data_.runs[i].dir = HysteresisRun::DOWN;
228  } else {
229  test_data_.runs[i].dir = HysteresisRun::UP;
230  }
231  move_count_[i] = 0;
232  }
233 
235 
236  return true;
237 }
238 
240 {
242 
245 }
246 
248 {
249  if (!joint_->calibrated_)
250  return;
251 
252  ros::Time time = robot_->getTime();
254 
255  // Timeout check.
256  if ((time - initial_time_).toSec() > timeout_ && state_ != ANALYZING && state_ != DONE)
257  {
258  state_ = ANALYZING;
259  test_data_.arg_value[5] = -1;
261  }
262 
263  switch (state_)
264  {
265  case STOPPED:
267  starting_count_ = 0;
269  break;
270  case MOVING_HOME:
271  starting_count_++;
272  if (turn() and starting_count_ > 100)
273  {
275  state_ = MOVING_UP;
276  starting_count_ = 0;
277  }
278  break;
279  case MOVING_UP:
280  starting_count_++;
282  {
283  test_data_.runs[repeat_*2].time[up_count_] = time.toSec();
285  test_data_.runs[repeat_*2].position[up_count_] = joint_->position_;
286  test_data_.runs[repeat_*2].velocity[up_count_] = joint_->velocity_;
287  up_count_++;
288  }
289 
290  if ((turn() and starting_count_ > 100) or up_count_ >= MAX_DATA_POINTS)
291  {
293  up_count_ = 0;
296  starting_count_ = 0;
297  }
298  break;
299  case MOVING_DOWN:
300  starting_count_++;
302  {
303  test_data_.runs[repeat_*2 + 1].time[down_count_] = time.toSec();
304  test_data_.runs[repeat_*2 + 1].effort[down_count_] = joint_->measured_effort_;
305  test_data_.runs[repeat_*2 + 1].position[down_count_] = joint_->position_;
306  test_data_.runs[repeat_*2 + 1].velocity[down_count_] = joint_->velocity_;
307  down_count_++;
308  }
309  if ((turn() and starting_count_ > 100) or down_count_ >= MAX_DATA_POINTS)
310  {
312  down_count_ = 0;
313  starting_count_ = 0;
314  ++repeat_;
315 
316  // if we still have more repeats
317  if(repeat_ < repeat_count_ ) {
319  state_ = MOVING_UP;
320  } else {
321  // done. Analyze data
323  state_ = ANALYZING;
324  }
325  }
326  break;
327  case ANALYZING:
329  analysis();
330  state_ = DONE;
331  break;
332  case DONE:
334  if (!data_sent_)
335  data_sent_ = sendData();
336  break;
337  }
338 
339 }
340 
342 {
343  if (joint_->joint_->type!=urdf::Joint::CONTINUOUS)
344  {
345  return (fabs(joint_->velocity_) < 0.001 && fabs(joint_->commanded_effort_) > max_effort_);
346  }
347  else
348  {
349  if (fabs(joint_->position_-initial_position_) > 6.28)
350  {
352  return true;
353  }
354  return false;
355  }
356 }
357 
359 {
360  // Resize if no points
361  for( int i=0; i < repeat_count_ * 2; ++i ) {
362  int count = move_count_[i];
363  if( count < 1 ) count = 1;
364  test_data_.runs[i].time.resize(count);
365  test_data_.runs[i].effort.resize(count);
366  test_data_.runs[i].position.resize(count);
367  test_data_.runs[i].velocity.resize(count);
368  }
369 
370  return;
371 }
372 
374 {
375  if (hyst_pub_->trylock())
376  {
377  joint_qualification_controllers::HysteresisData2 *out = &hyst_pub_->msg_;
378  out->joint_name = test_data_.joint_name;
379 
380  out->runs = test_data_.runs;
381 
382  out->arg_name = test_data_.arg_name;
383  out->arg_value = test_data_.arg_value;
384 
385  hyst_pub_->unlockAndPublish();
386  return true;
387  }
388  return false;
389 }
390 
391 
392 
d
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::HysteresisData2 > > hyst_pub_
void update()
Issues commands to the joint to perform hysteresis test.
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Functional way to initialize.
boost::shared_ptr< const urdf::Joint > joint_
#define ROS_WARN(...)
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
controller::JointVelocityController * velocity_controller_
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::HysteresisController2, pr2_controller_interface::Controller) using namespace std
const std::string & getNamespace() const
joint_qualification_controllers::HysteresisData2 test_data_
JointState * getJointState(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR(...)
#define MAX_DATA_POINTS
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)


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