counterbalance_test_controller.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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 
35 /* Author: Kevin Watts */
36 
37 
40 
43 
44 using namespace std;
45 using namespace joint_qualification_controllers;
46 
48  lift_dither_(NULL),
49  flex_dither_(NULL),
50  lift_controller_(NULL),
51  flex_controller_(NULL),
52  robot_(NULL),
53  initial_time_(0.0),
54  start_time_(0.0),
55  cb_data_pub_(NULL)
56 {
57  timeout_ = 180;
58  lift_index_ = 0;
59  flex_index_ = 0;
60  data_sent_ = false;
61 
62  cb_test_data_.arg_name.resize(25);
63  cb_test_data_.arg_value.resize(25);
64  cb_test_data_.arg_name[0] = "Settle Time";
65  cb_test_data_.arg_name[1] = "Dither Points";
66  cb_test_data_.arg_name[2] = "Timeout";
67  cb_test_data_.arg_name[3] = "Lift Min";
68  cb_test_data_.arg_name[4] = "Lift Max";
69  cb_test_data_.arg_name[5] = "Lift Delta";
70  cb_test_data_.arg_name[6] = "Flex Min";
71  cb_test_data_.arg_name[7] = "Flex Max";
72  cb_test_data_.arg_name[8] = "Flex Delta";
73 
74  // P/F params
75  cb_test_data_.arg_name[9] = "Lift MSE";
76  cb_test_data_.arg_name[10] = "Lift Avg Abs";
77  cb_test_data_.arg_name[11] = "Lift Avg Effort";
78  cb_test_data_.arg_name[12] = "Flex MSE";
79  cb_test_data_.arg_name[13] = "Flex Avg Abs";
80  cb_test_data_.arg_name[14] = "Flex Avg Effort";
81 
82  // PID's
83  cb_test_data_.arg_name[15] = "Lift P";
84  cb_test_data_.arg_name[16] = "Lift I";
85  cb_test_data_.arg_name[17] = "Lift D";
86  cb_test_data_.arg_name[18] = "Lift I Clamp";
87 
88  cb_test_data_.arg_name[19] = "Flex P";
89  cb_test_data_.arg_name[20] = "Flex I";
90  cb_test_data_.arg_name[21] = "Flex D";
91  cb_test_data_.arg_name[22] = "Flex I Clamp";
92 
93  cb_test_data_.arg_name[23] = "Screw Tolerance";
94  cb_test_data_.arg_name[24] = "Bar Tolerance";
95 
96  cb_test_data_.timeout_hit = false;
97  cb_test_data_.lift_joint = "None";
98  cb_test_data_.lift_joint = "";
99  cb_test_data_.lift_amplitude = 0;
100  cb_test_data_.flex_amplitude = 0;
101 
103 
104  state_ = STARTING;
105 
106 }
107 
108 CounterbalanceTestController::~CounterbalanceTestController()
109 {
112  if (flex_dither_) delete flex_dither_;
113  if (lift_dither_) delete lift_dither_;
114 }
115 
117 {
118  ROS_ASSERT(robot);
119  robot_ = robot;
120 
121  // Lift joint
122  string lift_joint;
123  if (!n.getParam("lift/joint", lift_joint)){
124  ROS_ERROR("CounterbalanceTestController: No lift joint name found on parameter namespace: %s)",
125  n.getNamespace().c_str());
126  return false;
127  }
128  if (!(lift_state_ = robot->getJointState(lift_joint)))
129  {
130  ROS_ERROR("CounterbalanceTestController could not find lift joint named \"%s\"\n", lift_joint.c_str());
131  return false;
132  }
133  cb_test_data_.lift_joint = lift_joint;
134 
136  ros::NodeHandle n_lift(n, "lift");
137  if (!lift_controller_->init(robot, n_lift)) return false;
138 
139  int num_flexs = 1;
140  double flex_min = 0;
141  double flex_max = 0;
142  double flex_delta = 0;
143  double flex_mse = 0;
144  double flex_avg_abs = 0;
145  double flex_avg_eff = 0;
146 
147  cb_test_data_.flex_test = false;
148 
149  // Flex joint
150  string flex_joint;
151  if (n.getParam("flex/joint", flex_joint))
152  {
153  cb_test_data_.flex_test = true;
154 
155  if (!(flex_state_ = robot->getJointState(flex_joint)))
156  {
157  ROS_ERROR("CounterbalanceTestController could not find flex joint named \"%s\"\n", flex_joint.c_str());
158  return false;
159  }
160  cb_test_data_.flex_joint = flex_joint;
161 
162  // Flex range
163  if (!n.getParam("flex/min", flex_min))
164  {
165  ROS_ERROR("CounterbalanceTestController: No min flex position found on parameter namespace: %s)",
166  n.getNamespace().c_str());
167  return false;
168  }
169  if (!n.getParam("flex/max", flex_max))
170  {
171  ROS_ERROR("CounterbalanceTestController: No max flex position found on parameter namespace: %s)",
172  n.getNamespace().c_str());
173  return false;
174  }
175  if (!n.getParam("flex/delta", flex_delta))
176  {
177  ROS_ERROR("CounterbalanceTestController: No flex delta found on parameter namespace: %s)",
178  n.getNamespace().c_str());
179  return false;
180  }
181 
182  if (flex_max < flex_min)
183  {
184  ROS_ERROR("CounterbalanceTestController: Flex max position must be >= flex min position");
185  return false;
186  }
187  if (flex_delta < 0)
188  {
189  ROS_ERROR("CounterbalanceTestController: \"flex_delta\" parameter must be >=0");
190  return false;
191  }
192 
193  num_flexs = (int)(((flex_max - flex_min) / flex_delta) + 1);
194 
195  // MSE, Avg. Abs. Effort
196  if (!n.getParam("flex/mse", flex_mse))
197  {
198  ROS_ERROR("CounterbalanceTestController: No flex/mse (mean square effort) found on parameter namespace: %s)",
199  n.getNamespace().c_str());
200  return false;
201  }
202 
203  if (!n.getParam("flex/avg_abs", flex_avg_abs))
204  {
205  ROS_ERROR("CounterbalanceTestController: No flex/avg_abs (average absolute effort) found on parameter namespace: %s)",
206  n.getNamespace().c_str());
207  return false;
208  }
209 
210  if (!n.getParam("flex/avg_eff", flex_avg_eff))
211  {
212  ROS_ERROR("CounterbalanceTestController: No flex/avg_eff (average absolute effort) found on parameter namespace: %s)",
213  n.getNamespace().c_str());
214  return false;
215  }
216 
217  double flex_amplitude;
218  if (!n.getParam("flex/dither", flex_amplitude))
219  {
220  ROS_ERROR("CounterbalanceTestController: No flex amplitude found on parameter namespace: %s)",
221  n.getNamespace().c_str());
222  return false;
223  }
225  if (!flex_dither_->init(flex_amplitude, 100)) return false;
226 
227  cb_test_data_.flex_amplitude = flex_amplitude;
228 
230  ros::NodeHandle n_flex(n, "flex");
231  if (!flex_controller_->init(robot, n_flex)) return false;
232 
233  ROS_INFO("Initializing CounterbalanceTestController as a lift and flex test. Namespace: %s",
234  n.getNamespace().c_str());
235  }
236  else
237  {
238  ROS_INFO("Initializing CounterbalanceTestController as a shoulder lift test only. Namespace: %s",
239  n.getNamespace().c_str());
240  }
241 
242  double lift_amplitude;
243  if (!n.getParam("lift/dither", lift_amplitude))
244  {
245  ROS_ERROR("CounterbalanceTestController: No lift amplitude found on parameter namespace: %s)",
246  n.getNamespace().c_str());
247  return false;
248  }
250  if (!lift_dither_->init(lift_amplitude, 100)) return false;
251 
252  cb_test_data_.lift_amplitude = lift_amplitude;
253 
254  // Lift range
255  double lift_min, lift_max, lift_delta;
256  if (!n.getParam("lift/min", lift_min))
257  {
258  ROS_ERROR("CounterbalanceTestController: No min lift position found on parameter namespace: %s)",
259  n.getNamespace().c_str());
260  return false;
261  }
262  if (!n.getParam("lift/max", lift_max))
263  {
264  ROS_ERROR("CounterbalanceTestController: No max lift position found on parameter namespace: %s)",
265  n.getNamespace().c_str());
266  return false;
267  }
268  if (lift_max < lift_min)
269  {
270  ROS_ERROR("CounterbalanceTestController was given a shoulder lift maximum with values less than its minimum. Max: %f, Min %f", lift_max, lift_min);
271  return false;
272  }
273 
274  if (!n.getParam("lift/delta", lift_delta))
275  {
276  ROS_ERROR("CounterbalanceTestController: No lift delta found on parameter namespace: %s)",
277  n.getNamespace().c_str());
278  return false;
279  }
280  if (lift_delta < 0)
281  {
282  ROS_ERROR("CounterbalanceTestController was given a shoulder lift position delta <0. Delta given: %f", lift_delta);
283  return false;
284  }
285 
286  // Setting controller defaults
287  if (!n.getParam("settle_time", settle_time_))
288  {
289  ROS_ERROR("CounterbalanceTestController: No settle time found on parameter namespace: %s)",
290  n.getNamespace().c_str());
291  return false;
292  }
293 
294  if (!n.getParam("dither_points", dither_points_))
295  {
296  ROS_ERROR("CounterbalanceTestController: No dither points param found on parameter namespace: %s)",
297  n.getNamespace().c_str());
298  return false;
299  }
300 
301  if (!n.getParam("timeout", timeout_))
302  {
303  ROS_ERROR("CounterbalanceTestController: No timeout found on parameter namespace: %s)",
304  n.getNamespace().c_str());
305  return false;
306  }
307 
308  double lift_mse, lift_avg_abs, lift_avg_eff;
309  if (!n.getParam("lift/mse", lift_mse))
310  {
311  ROS_ERROR("CounterbalanceTestController: No lift/mse (mean square effort) found on parameter namespace: %s)",
312  n.getNamespace().c_str());
313  return false;
314  }
315 
316  if (!n.getParam("lift/avg_abs", lift_avg_abs))
317  {
318  ROS_ERROR("CounterbalanceTestController: No lift/avg_abs (average absolute effort) found on parameter namespace: %s)",
319  n.getNamespace().c_str());
320  return false;
321  }
322 
323  if (!n.getParam("lift/avg_eff", lift_avg_eff))
324  {
325  ROS_ERROR("CounterbalanceTestController: No lift/avg_eff (average absolute effort) found on parameter namespace: %s)",
326  n.getNamespace().c_str());
327  return false;
328  }
329 
330  // Set up array of lift, flex commands
331  int num_lifts = 1;
332  if (lift_delta > 0)
333  num_lifts = (int)((lift_max - lift_min)/lift_delta + 1);
334  ROS_ASSERT(num_lifts > 0);
335 
336  cb_test_data_.lift_data.resize(num_lifts);
337  for (int i = 0; i < num_lifts; ++i)
338  {
339  cb_test_data_.lift_data[i].lift_position = (double)lift_min + lift_delta * i;
340  cb_test_data_.lift_data[i].flex_data.resize(num_flexs);
341  for (int j = 0; j < num_flexs; ++j)
342  {
343  cb_test_data_.lift_data[i].flex_data[j].flex_position = (double)flex_min + flex_delta * ((double)j);
344 
345  cb_test_data_.lift_data[i].flex_data[j].lift_hold.time.resize(dither_points_);
346  cb_test_data_.lift_data[i].flex_data[j].lift_hold.position.resize(dither_points_);
347  cb_test_data_.lift_data[i].flex_data[j].lift_hold.velocity.resize(dither_points_);
348  cb_test_data_.lift_data[i].flex_data[j].lift_hold.effort.resize(dither_points_);
349 
350  cb_test_data_.lift_data[i].flex_data[j].flex_hold.time.resize(dither_points_);
351  cb_test_data_.lift_data[i].flex_data[j].flex_hold.position.resize(dither_points_);
352  cb_test_data_.lift_data[i].flex_data[j].flex_hold.velocity.resize(dither_points_);
353  cb_test_data_.lift_data[i].flex_data[j].flex_hold.effort.resize(dither_points_);
354  }
355  }
356 
357  cb_test_data_.arg_value[0] = settle_time_;
358  cb_test_data_.arg_value[1] = dither_points_;
359  cb_test_data_.arg_value[2] = timeout_;
360  cb_test_data_.arg_value[3] = lift_min;
361  cb_test_data_.arg_value[4] = lift_max;
362  cb_test_data_.arg_value[5] = lift_delta;
363  cb_test_data_.arg_value[6] = flex_min;
364  cb_test_data_.arg_value[7] = flex_max;
365  cb_test_data_.arg_value[8] = flex_delta;
366 
367  // Mean square efforts, avg abs efforts
368  cb_test_data_.arg_value[9] = lift_mse;
369  cb_test_data_.arg_value[10] = lift_avg_abs;
370  cb_test_data_.arg_value[11] = lift_avg_eff;
371 
372  if (cb_test_data_.flex_test)
373  {
374  cb_test_data_.arg_value[12] = flex_mse;
375  cb_test_data_.arg_value[13] = flex_avg_abs;
376  cb_test_data_.arg_value[14] = flex_avg_eff;
377  }
378  else
379  {
380  cb_test_data_.arg_value[12] = 0;
381  cb_test_data_.arg_value[13] = 0;
382  cb_test_data_.arg_value[14] = 0;
383  }
384 
385  double p, i, d, i_clamp, dummy;
386  lift_controller_->getGains(p, i, d, i_clamp, dummy);
387  cb_test_data_.arg_value[15] = p;
388  cb_test_data_.arg_value[16] = i;
389  cb_test_data_.arg_value[17] = d;
390  cb_test_data_.arg_value[18] = i_clamp;
391 
392  if (cb_test_data_.flex_test)
393  {
394  flex_controller_->getGains(p, i, d, i_clamp, dummy);
395  cb_test_data_.arg_value[19] = p;
396  cb_test_data_.arg_value[20] = i;
397  cb_test_data_.arg_value[21] = d;
398  cb_test_data_.arg_value[22] = i_clamp;
399  }
400  else
401  {
402  cb_test_data_.arg_value[19] = 0;
403  cb_test_data_.arg_value[20] = 0;
404  cb_test_data_.arg_value[21] = 0;
405  cb_test_data_.arg_value[22] = 0;
406  }
407 
408  // Record screw, bar tolerances
409  double screw_tol, bar_tol;
410  if (!n.getParam("screw_tol", screw_tol))
411  {
412  ROS_INFO("CounterbalanceTestController was not given parameter 'screw_tol' on namespace %s. Using default 2.0",
413  n.getNamespace().c_str());
414  screw_tol = 2.0;
415  }
416 
417  if (!n.getParam("bar_tol", bar_tol))
418  {
419  ROS_INFO("CounterbalanceTestController was not given parameter 'bar_tol' on namespace %s. Using default 0.8",
420  n.getNamespace().c_str());
421  bar_tol = 0.8;
422  }
423  cb_test_data_.arg_value[23] = screw_tol;
424  cb_test_data_.arg_value[24] = bar_tol;
425 
426 
428  joint_qualification_controllers::CounterbalanceTestData>(n, "/cb_test_data", 1, true));
429 
430  //ROS_INFO("Initialized CB controller successfully!");
431 
432  return true;
433 }
434 
436 {
438 }
439 
441 {
442  // wait until the joints are calibrated to start
443  if (!lift_state_->calibrated_)
444  return;
445  if (cb_test_data_.flex_test and !flex_state_->calibrated_)
446  return;
447 
448  ros::Time time = robot_->getTime();
449 
450  if ((time - initial_time_).toSec() > timeout_ && state_ != DONE)
451  {
452  ROS_WARN("CounterbalanceTestController timed out during test. Timeout: %f.", timeout_);
453  state_ = DONE;
454  cb_test_data_.timeout_hit = true;
455  }
456 
458  if (cb_test_data_.flex_test)
460 
461  switch (state_)
462  {
463  case STARTING:
464  {
465  double lift_cmd = cb_test_data_.lift_data[lift_index_].lift_position;
466  double flex_cmd = cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_position;
467 
468  // Set controllers
469  lift_controller_->setCommand(lift_cmd);
470  if (cb_test_data_.flex_test) flex_controller_->setCommand(flex_cmd);
471 
472  dither_count_ = 0;
473  start_time_ = time;
474 
475  state_ = SETTLING;
476 
477  //ROS_INFO("Moving to position lift %f, flex %f", lift_cmd, flex_cmd);
478  break;
479  }
480  case SETTLING:
481  {
482  if ((time - start_time_).toSec() > settle_time_)
483  {
484  state_ = DITHERING;
485  start_time_ = time;
486  }
487 
488  break;
489  }
490  case DITHERING:
491  {
492  // Add dither
495 
496  // Lift
497  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].lift_hold.time[dither_count_] = (time - start_time_).toSec();
498  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].lift_hold.position[dither_count_] = lift_state_->position_;
499  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].lift_hold.velocity[dither_count_] = lift_state_->velocity_;
500  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].lift_hold.effort[dither_count_] = lift_state_->measured_effort_;
501 
502  // Flex
503  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.time[dither_count_] = (time - start_time_).toSec();
504  if (cb_test_data_.flex_test)
505  {
506  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.position[dither_count_] = flex_state_->position_;
507  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.velocity[dither_count_] = flex_state_->velocity_;
508  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.effort[dither_count_] = flex_state_->measured_effort_;
509  }
510  else
511  {
512  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.position[dither_count_] = 0;
513  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.velocity[dither_count_] = 0;
514  cb_test_data_.lift_data[lift_index_].flex_data[flex_index_].flex_hold.effort[dither_count_] = 0;
515  }
516 
517  ++dither_count_;
518 
520  {
521  state_ = NEXT;
522  }
523  break;
524  }
525  case NEXT:
526  {
527  // Increment flex, lift indices
528  ++flex_index_;
529  if (flex_index_ >= cb_test_data_.lift_data[0].flex_data.size())
530  {
531  flex_index_ = 0;
532  lift_index_++;
533  }
534  if (lift_index_ >= cb_test_data_.lift_data.size())
535  {
536  state_ = DONE;
537  break;
538  }
539 
540  state_ = STARTING;
541  break;
542  }
543  case DONE:
544  {
545  if (!data_sent_)
546  data_sent_ = sendData();
547 
548  break;
549  }
550  }
551 }
552 
554 {
555  if (cb_data_pub_->trylock())
556  {
557  // Copy data and send
558  joint_qualification_controllers::CounterbalanceTestData *out = &cb_data_pub_->msg_;
559 
560  out->lift_joint = cb_test_data_.lift_joint;
561  out->flex_joint = cb_test_data_.flex_joint;
562  out->lift_amplitude = cb_test_data_.lift_amplitude;
563  out->flex_amplitude = cb_test_data_.flex_amplitude;
564  out->timeout_hit = cb_test_data_.timeout_hit;
565  out->flex_test = cb_test_data_.flex_test;
566  out->arg_name = cb_test_data_.arg_name;
567  out->arg_value = cb_test_data_.arg_value;
568 
569  out->lift_data = cb_test_data_.lift_data;
570  cb_data_pub_->unlockAndPublish();
571  return true;
572  }
573  return false;
574 }
575 
d
#define ROS_WARN(...)
bool init(const double &amplitude, const double &seed)
#define ROS_INFO(...)
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
void update()
Issues commands to the joint. Should be called at regular intervals.
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
joint_qualification_controllers::CounterbalanceTestData cb_test_data_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Functional way to initialize.
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::CounterbalanceTestController, pr2_controller_interface::Controller) using namespace std
bool getParam(const std::string &key, std::string &s) const
#define ROS_ASSERT(cond)
#define ROS_ERROR(...)
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::CounterbalanceTestData > > cb_data_pub_


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