wrist_difference_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 
36 #include "urdf_model/joint.h"
37 
40 
41 #define MAX_DATA_POINTS 120000
42 
43 using namespace std;
44 using namespace joint_qualification_controllers;
45 
46 WristDifferenceController::WristDifferenceController()
47 : flex_joint_(NULL),
48  roll_joint_(NULL),
49  robot_(NULL),
50  data_sent_(false),
51  wrist_data_pub_(NULL)
52 {
53  wrist_test_data_.left_turn.time.resize(MAX_DATA_POINTS);
54  wrist_test_data_.left_turn.flex_position.resize(MAX_DATA_POINTS);
55  wrist_test_data_.left_turn.flex_effort.resize(MAX_DATA_POINTS);
56  wrist_test_data_.left_turn.flex_cmd.resize(MAX_DATA_POINTS);
57  wrist_test_data_.left_turn.roll_position.resize(MAX_DATA_POINTS);
58  wrist_test_data_.left_turn.roll_effort.resize(MAX_DATA_POINTS);
59  wrist_test_data_.left_turn.roll_cmd.resize(MAX_DATA_POINTS);
60  wrist_test_data_.left_turn.roll_velocity.resize(MAX_DATA_POINTS);
61 
62  wrist_test_data_.right_turn.time.resize(MAX_DATA_POINTS);
63  wrist_test_data_.right_turn.flex_position.resize(MAX_DATA_POINTS);
64  wrist_test_data_.right_turn.flex_effort.resize(MAX_DATA_POINTS);
65  wrist_test_data_.right_turn.flex_cmd.resize(MAX_DATA_POINTS);
66  wrist_test_data_.right_turn.roll_position.resize(MAX_DATA_POINTS);
67  wrist_test_data_.right_turn.roll_effort.resize(MAX_DATA_POINTS);
68  wrist_test_data_.right_turn.roll_cmd.resize(MAX_DATA_POINTS);
69  wrist_test_data_.right_turn.roll_velocity.resize(MAX_DATA_POINTS);
70 
71  wrist_test_data_.flex_pid.resize(4);
72  wrist_test_data_.roll_pid.resize(4);
73 
74  wrist_test_data_.arg_name.resize(10);
75  wrist_test_data_.arg_value.resize(10);
76  wrist_test_data_.arg_name[0] = "Flex Position";
77  wrist_test_data_.arg_name[1] = "Roll Velocity";
78  wrist_test_data_.arg_name[2] = "Roll Tolerance (%)";
79  wrist_test_data_.arg_name[3] = "Roll SD Max (%)";
80  wrist_test_data_.arg_name[4] = "Timeout";
81  wrist_test_data_.arg_name[5] = "Left Effort";
82  wrist_test_data_.arg_name[6] = "Right Effort";
83  wrist_test_data_.arg_name[7] = "Flex Tolerance";
84  wrist_test_data_.arg_name[8] = "Flex Max Value";
85  wrist_test_data_.arg_name[9] = "Flex SD";
86 
87  wrist_test_data_.timeout = false;
88 
89  state_ = STARTING;
90  starting_count = 0;
91  roll_velocity_ = 0;
92  flex_position_ = 0;
94  left_count_ = 0;
95  right_count_ = 0;
96  start_count_ = 0;
97  // Assume 1KHz update rate
98  timeout_ = MAX_DATA_POINTS / 1000;
99 }
100 
102 {
103  delete flex_controller_;
104  delete roll_controller_;
105 }
106 
108 {
109  ROS_ASSERT(robot);
110  robot_ = robot;
111 
112  std::string roll_name;
113  if (!n.getParam("roll_velocity_controller/joint", roll_name)){
114  ROS_ERROR("Hysteresis Controller: No joint name found on parameter namespace: %s)",
115  n.getNamespace().c_str());
116  return false;
117  }
118  if (!(roll_joint_ = robot->getJointState(roll_name)))
119  {
120  ROS_ERROR("WristDifferenceController could not find joint named \"%s\"\n", roll_name.c_str());
121  return false;
122  }
123  ROS_DEBUG("Roll joint: %s", roll_name.c_str());
124  if (roll_joint_->joint_->type != urdf::Joint::CONTINUOUS)
125  {
126  ROS_ERROR("Wrist roll joint must be continuous. Unable to check wrist symmetry. Roll joint: %s", roll_name.c_str());
127  return false;
128  }
129 
130  if (!n.getParam("roll_velocity", roll_velocity_)){
131  ROS_ERROR("Hysteresis Controller: No velocity found on parameter namespace: %s)",
132  n.getNamespace().c_str());
133  return false;
134  }
136 
137  std::string flex_name;
138  if (!n.getParam("flex_position_controller/joint", flex_name)){
139  ROS_ERROR("Hysteresis Controller: No joint name found on parameter namespace: %s)",
140  n.getNamespace().c_str());
141  return false;
142  }
143  if (!(flex_joint_ = robot->getJointState(flex_name)))
144  {
145  ROS_ERROR("WristDifferenceController could not find joint named \"%s\"\n", flex_name.c_str());
146  return false;
147  }
148 
149  if (!n.getParam("flex_position", flex_position_)) {
150  ROS_ERROR("Hysteresis Controller: No velocity found on parameter namespace: %s)",
151  n.getNamespace().c_str());
152  return false;
153  }
154 
155  if (!n.getParam("timeout", timeout_)){
156  ROS_ERROR("Hysteresis Controller: No timeout found on parameter namespace: %s)",
157  n.getNamespace().c_str());
158  return false;
159  }
160 
161  if (!n.getParam("tolerance", tolerance_)){
162  ROS_WARN("Parameter 'tolerance' is not set on namespace: %s.",
163  n.getNamespace().c_str());
164  return false;
165  }
166 
167  if (!n.getParam("sd_max", sd_max_)) {
168  ROS_WARN("Parameter 'sd_max' is not set on namespace: %s.",
169  n.getNamespace().c_str());
170  return false;
171  }
172 
173  double left_effort, right_effort, flex_tolerance, flex_max, flex_sd;
174  if (!n.getParam("left_effort", left_effort)) {
175  ROS_WARN("Parameter 'left_effort' is not set on namespace: %s.",
176  n.getNamespace().c_str());
177  return false;
178  }
179 
180  if (!n.getParam("right_effort", right_effort)) {
181  ROS_WARN("Parameter 'right_effort' is not set on namespace: %s.",
182  n.getNamespace().c_str());
183  return false;
184  }
185 
186  if (!n.getParam("flex_tolerance", flex_tolerance)) {
187  ROS_WARN("Parameter 'flex_tolerance' is not set on namespace: %s.",
188  n.getNamespace().c_str());
189  return false;
190  }
191 
192 
193  if (!n.getParam("flex_max", flex_max)) {
194  ROS_WARN("Parameter 'flex_max' is not set on namespace: %s.",
195  n.getNamespace().c_str());
196  return false;
197  }
198 
199  if (!n.getParam("flex_sd", flex_sd)) {
200  ROS_WARN("Parameter 'flex_sd' is not set on namespace: %s.",
201  n.getNamespace().c_str());
202  return false;
203  }
204 
206 
207  // Set values in test data output
208  wrist_test_data_.flex_joint = flex_name;
209  wrist_test_data_.roll_joint = roll_name;
210  wrist_test_data_.arg_value[0] = flex_position_;
211  wrist_test_data_.arg_value[1] = roll_velocity_;
212  wrist_test_data_.arg_value[2] = tolerance_;
213  wrist_test_data_.arg_value[3] = sd_max_;
214  wrist_test_data_.arg_value[4] = timeout_;
215  wrist_test_data_.arg_value[5] = left_effort;
216  wrist_test_data_.arg_value[6] = right_effort;
217  wrist_test_data_.arg_value[7] = flex_tolerance;
218  wrist_test_data_.arg_value[8] = flex_max;
219  wrist_test_data_.arg_value[9] = flex_sd;
220 
222  ros::NodeHandle n_flex(n, "flex_position_controller");
223  if (!flex_controller_->init(robot, n_flex)) return false;
224 
226  ros::NodeHandle n_roll(n, "roll_velocity_controller");
227  if (!roll_controller_->init(robot, n_roll)) return false;
228 
229  // Get the gains, add them to test data
230  double p, i, d, iClamp, imin;
231  roll_controller_->getGains(p, i, d, iClamp, imin);
232  wrist_test_data_.roll_pid[0] = p;
233  wrist_test_data_.roll_pid[1] = i;
234  wrist_test_data_.roll_pid[2] = d;
235  wrist_test_data_.roll_pid[3] = iClamp;
236 
237  flex_controller_->getGains(p, i, d, iClamp, imin);
238  wrist_test_data_.flex_pid[0] = p;
239  wrist_test_data_.flex_pid[1] = i;
240  wrist_test_data_.flex_pid[2] = d;
241  wrist_test_data_.flex_pid[3] = iClamp;
242 
244 
245  return true;
246 }
247 
249 {
252 
254 }
255 
257 {
258  // wait until the all joints calibrated
260  {
261  return;
262  }
263 
264  ros::Time time = robot_->getTime();
267 
268  // Timeout check
269  if ((time - initial_time_).toSec() > timeout_ && state_ != ANALYZING && state_ != DONE)
270  {
271  state_ = ANALYZING;
272  wrist_test_data_.timeout = true;
274  }
275 
276  switch (state_)
277  {
278  case STARTING:
281  start_count_++;
282  // Let it settle for 3sec before recording data
283  if (start_count_++ > 3000)
284  {
286  state_ = LEFT;
287  }
288  break;
289  case LEFT:
291  {
292  wrist_test_data_.left_turn.time [left_count_] = time.toSec();
293  wrist_test_data_.left_turn.flex_position[left_count_] = flex_joint_->position_;
294  wrist_test_data_.left_turn.flex_effort [left_count_] = flex_joint_->measured_effort_;
296 
297  wrist_test_data_.left_turn.roll_position[left_count_] = roll_joint_->position_;
298  wrist_test_data_.left_turn.roll_effort [left_count_] = roll_joint_->measured_effort_;
300  wrist_test_data_.left_turn.roll_velocity[left_count_] = roll_joint_->velocity_;
301  left_count_++;
302  }
303 
305  {
306  double right_vel = -1 * roll_velocity_;
307  roll_controller_->setCommand(right_vel);
309  state_ = RIGHT;
310  }
311  break;
312  case RIGHT:
314  {
315  wrist_test_data_.right_turn.time [right_count_] = time.toSec();
316  wrist_test_data_.right_turn.flex_position[right_count_] = flex_joint_->position_;
317  wrist_test_data_.right_turn.flex_effort [right_count_] = flex_joint_->measured_effort_;
319 
320  wrist_test_data_.right_turn.roll_position[right_count_] = roll_joint_->position_;
321  wrist_test_data_.right_turn.roll_effort [right_count_] = roll_joint_->measured_effort_;
323  wrist_test_data_.right_turn.roll_velocity[right_count_] = roll_joint_->velocity_;
324  right_count_++;
325  }
326 
328  {
330  state_ = ANALYZING;
331  }
332  break;
333  case ANALYZING:
335  analysis();
336  state_ = DONE;
337  break;
338  case DONE:
340  if (!data_sent_)
341  data_sent_ = sendData();
342  break;
343  }
344 }
345 
347 {
348  // Resize if no points
349  if (left_count_ == 0)
350  left_count_ = 1;
351 
352  if (right_count_ == 0)
353  right_count_ = 1;
354 
355  wrist_test_data_.left_turn.time.resize(left_count_);
356  wrist_test_data_.left_turn.flex_position.resize(left_count_);
357  wrist_test_data_.left_turn.flex_effort.resize(left_count_);
358  wrist_test_data_.left_turn.roll_cmd.resize(left_count_);
359  wrist_test_data_.left_turn.roll_position.resize(left_count_);
360  wrist_test_data_.left_turn.roll_effort.resize(left_count_);
361  wrist_test_data_.left_turn.roll_cmd.resize(left_count_);
362  wrist_test_data_.left_turn.roll_velocity.resize(left_count_);
363 
364  wrist_test_data_.right_turn.time.resize(right_count_);
365  wrist_test_data_.right_turn.flex_position.resize(right_count_);
366  wrist_test_data_.right_turn.flex_effort.resize(right_count_);
367  wrist_test_data_.right_turn.roll_cmd.resize(right_count_);
368  wrist_test_data_.right_turn.roll_position.resize(right_count_);
369  wrist_test_data_.right_turn.roll_effort.resize(right_count_);
370  wrist_test_data_.right_turn.roll_cmd.resize(right_count_);
371  wrist_test_data_.right_turn.roll_velocity.resize(right_count_);
372 
373  return;
374 }
375 
377 {
378  if (wrist_data_pub_->trylock())
379  {
380  joint_qualification_controllers::WristDiffData *out = &wrist_data_pub_->msg_;
381  out->flex_joint = wrist_test_data_.flex_joint;
382  out->roll_joint = wrist_test_data_.roll_joint;
383  out->flex_pid = wrist_test_data_.flex_pid;
384  out->roll_pid = wrist_test_data_.roll_pid;
385  out->arg_name = wrist_test_data_.arg_name;
386  out->arg_value = wrist_test_data_.arg_value;
387  out->left_turn = wrist_test_data_.left_turn;
388  out->right_turn = wrist_test_data_.right_turn;
389  out->timeout = wrist_test_data_.timeout;
390 
391  wrist_data_pub_->unlockAndPublish();
392  return true;
393  }
394  return false;
395 }
396 
397 
398 
d
boost::shared_ptr< const urdf::Joint > joint_
#define ROS_WARN(...)
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::WristDiffData > > wrist_data_pub_
joint_qualification_controllers::WristDiffData wrist_test_data_
bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Functional way to initialize.
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 to perform hysteresis test.
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool getParam(const std::string &key, std::string &s) const
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::WristDifferenceController, pr2_controller_interface::Controller) using namespace std
#define ROS_ASSERT(cond)
#define ROS_ERROR(...)
#define MAX_DATA_POINTS
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
#define ROS_DEBUG(...)


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