checkout_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 
40 
41 using namespace std;
42 using namespace joint_qualification_controllers;
43 
45  robot_(NULL),
46  data_sent_(false),
47  robot_data_pub_(NULL)
48 {
49  robot_data_.test_time = -1;
50  robot_data_.num_joints = 0;
51  robot_data_.num_actuators = 0;
52 
53  state_ = STARTING;
54  joint_count_ = 0;
55  actuator_count_ = 0;
56 
57  timeout_ = 30.0;
58 }
59 
60 bool CheckoutController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
61 {
62  assert(robot);
63  robot_ = robot;
64 
66  robot_data_.num_joints = joint_count_;
67  robot_data_.timeout = false;
68 
69  robot_data_.joint_data.resize(joint_count_);
70 
71  for (int i = 0; i < joint_count_; i++)
72  {
74 
75  robot_data_.joint_data[i].index = i;
76  robot_data_.joint_data[i].name = js->joint_->name;
77  robot_data_.joint_data[i].is_cal = 0;
78  robot_data_.joint_data[i].has_safety = js->joint_->safety && js->joint_->limits;
79 
80  // Assign type strings based on type
81  switch (js->joint_->type)
82  {
83  case (urdf::Joint::FIXED):
84  robot_data_.joint_data[i].type = "Fixed";
85  break;
86  case (urdf::Joint::REVOLUTE):
87  robot_data_.joint_data[i].type = "Rotary";
88  break;
89  case (urdf::Joint::CONTINUOUS):
90  robot_data_.joint_data[i].type = "Continuous";
91  break;
92  case (urdf::Joint::PRISMATIC):
93  robot_data_.joint_data[i].type = "Prismatic";
94  break;
95  case (urdf::Joint::PLANAR):
96  robot_data_.joint_data[i].type = "Planar";
97  break;
98  default:
99  robot_data_.joint_data[i].type = "No type given!";
100  break;
101  }
102  }
103 
104  // Assign actuators
106  robot_data_.num_actuators = actuator_count_;
107  robot_data_.actuator_data.resize(actuator_count_);
108 
109  pr2_hardware_interface::ActuatorMap::const_iterator it;
110  int i = 0;
111  for (it = robot_->model_->hw_->actuators_.begin();
112  it != robot_->model_->hw_->actuators_.end();
113  ++it, ++i)
114  {
115  pr2_hardware_interface::Actuator *actuator = it->second;
116 
117  robot_data_.actuator_data[i].index = i;
118  robot_data_.actuator_data[i].name = actuator->name_;
119  robot_data_.actuator_data[i].id = actuator->state_.device_id_;
120  }
121 
122  n.param("timeout", timeout_, 30.0);
123 
125 
127 
128  return true;
129 }
130 
132 {
134 
135  data_sent_ = false;
136 }
137 
139 {
140  ros::Time time = robot_->getTime();
141  bool cal = false;
142  //bool enabled = false;
143 
144  // Timeout check.
145  if ((time - initial_time_).toSec() > timeout_ && state_ != ANALYZING && state_ != DONE)
146  {
147  analysis((time - initial_time_).toSec(), true);
148  state_ = DONE;
149  }
150 
151  switch (state_)
152  {
153  case STARTING:
155  state_ = LISTENING;
156  break;
157  case LISTENING:
158  {
159  cal = true;
160  for (int i = 0; i < joint_count_; ++i)
161  {
162  // Check for caster wheel joints and fingers
163  // Wheel joints and fingers don't calibrate, so don't wait for them
164  if (robot_->joint_states_[i].joint_->name.find("wheel_joint") != string::npos)
165  continue;
166 
167  if (robot_->joint_states_[i].joint_->type == urdf::Joint::FIXED)
168  continue;
169 
170  if (robot_->joint_states_[i].joint_->name.find("finger") != string::npos)
171  continue;
172  if (robot_->joint_states_[i].joint_->name.find("gripper_float_joint") != string::npos)
173  continue;
174  if (robot_->joint_states_[i].joint_->name.find("accelerometer_joint") != string::npos)
175  continue;
176  if (robot_->joint_states_[i].joint_->name.find("gripper_palm_joint") != string::npos)
177  continue;
178  if (robot_->joint_states_[i].joint_->name.find("gripper_tool_joint") != string::npos)
179  continue;
180 
181 
182  // Base joint is a dummy joint used to set up visualization
183  if (robot_->joint_states_[i].joint_->name == "base_joint")
184  continue;
185 
186  if (!robot_->joint_states_[i].calibrated_)
187  {
188  cal = false;
189  break;
190  }
191  }
192 
193  // enabled = true;
194 
195  /*
196  pr2_hardware_interface::ActuatorMap::const_iterator it;
197  for (it = robot_->model_->hw_->actuators_.begin();
198  it != robot_->model_->hw_->actuators_.end();
199  ++it)
200  {
201  if (it->second->name_ == "led_projector")
202  continue;
203 
204  if (!it->second->state_.is_enabled_)
205  {
206  enabled = false;
207  break;
208  }
209  }
210  */
211 
212  if (cal)
213  state_ = ANALYZING;
214 
215  break;
216  }
217  case ANALYZING:
218  analysis((time - initial_time_).toSec());
219  state_ = DONE;
220  break;
221  case DONE:
222  if (!data_sent_)
223  data_sent_ = sendData();
224 
225 
226  break;
227  }
228 
229 }
230 
232 {
233  if (robot_data_pub_->trylock())
234  {
235  joint_qualification_controllers::RobotData *out = &robot_data_pub_->msg_;
236  out->test_time = robot_data_.test_time;
237  out->num_joints = robot_data_.num_joints;
238  out->num_actuators = robot_data_.num_actuators;
239 
240  out->joint_data.resize(robot_data_.num_joints);
241  out->actuator_data.resize(robot_data_.num_actuators);
242 
243  for (int i = 0; i < joint_count_; i++)
244  {
245  out->joint_data[i].index = robot_data_.joint_data[i].index;
246  out->joint_data[i].name = robot_data_.joint_data[i].name;
247  out->joint_data[i].is_cal = robot_data_.joint_data[i].is_cal;
248  out->joint_data[i].has_safety = robot_data_.joint_data[i].has_safety;
249  out->joint_data[i].type = robot_data_.joint_data[i].type;
250  }
251 
252  for (int i = 0; i < actuator_count_; i++)
253  {
254  out->actuator_data[i].index = robot_data_.actuator_data[i].index;
255  out->actuator_data[i].name = robot_data_.actuator_data[i].name;
256  out->actuator_data[i].id = robot_data_.actuator_data[i].id;
257  }
258 
259  robot_data_pub_->unlockAndPublish();
260 
261  return true;
262  }
263  return false;
264 }
265 
266 void CheckoutController::analysis(double time, bool timeout)
267 {
268  robot_data_.test_time = time;
269  robot_data_.timeout = timeout;
270 
271  for (int i = 0; i < joint_count_; i++)
272  {
273  robot_data_.joint_data[i].is_cal = robot_->joint_states_[i].calibrated_;
274 
275  if (robot_->joint_states_[i].joint_->type == urdf::Joint::FIXED)
276  robot_data_.joint_data[i].is_cal = true;
277  }
278 
279  /*
280  pr2_hardware_interface::ActuatorMap::const_iterator it;
281  int i = 0;
282  for (it = robot_->model_->hw_->actuators_.begin();
283  it != robot_->model_->hw_->actuators_.end();
284  ++it, ++i)
285  {
286 
287  if (it->second->name_ == "led_projector")
288  robot_data_.actuator_data[i].enabled = true;
289  else
290  robot_data_.actuator_data[i].enabled = it->second->state_.is_enabled_;
291 
292  }
293  */
294 }
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::CheckoutController, pr2_controller_interface::Controller) using namespace std
bool sendData()
Sends data, returns true if sent.
Checkout Controller checks state of PR2 mechanism.
pr2_hardware_interface::HardwareInterface * hw_
boost::shared_ptr< const urdf::Joint > joint_
void analysis(double time, bool timeout=false)
Perform the test analysis.
void update()
Checks joint, actuator status for calibrated and enabled.
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void starting()
Called when controller is started or restarted.
std::vector< JointState > joint_states_
joint_qualification_controllers::RobotData robot_data_
boost::scoped_ptr< realtime_tools::RealtimePublisher< joint_qualification_controllers::RobotData > > robot_data_pub_


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