joint_limit_calibration_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 "ros/time.h"
38 
39 using namespace std;
40 using namespace joint_qualification_controllers;
41 
44 
46 : robot_(NULL), last_publish_time_(0), state_(INITIALIZED),
47  count_(0), stop_count_(0), search_velocity_(0),
48  actuator_(NULL), joint_(NULL), transmission_(NULL)
49 {
50 }
51 
52 JointLimitCalibrationController::~JointLimitCalibrationController()
53 {
54 }
55 
56 bool JointLimitCalibrationController::init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
57 {
58  assert(robot);
59  node_ = n;
60  robot_ = robot;
61 
62  // Joint
63  std::string joint_name;
64  if (!node_.getParam("joint", joint_name))
65  {
66  ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
67  return false;
68  }
69  if (!(joint_ = robot->getJointState(joint_name)))
70  {
71  ROS_ERROR("Could not find joint %s (namespace: %s)",
72  joint_name.c_str(), node_.getNamespace().c_str());
73  return false;
74  }
75 
76  // Actuator
77  std::string actuator_name;
78  if (!node_.getParam("actuator", actuator_name))
79  {
80  ROS_ERROR("No actuator given (namespace: %s)", node_.getNamespace().c_str());
81  return false;
82  }
83  if (!(actuator_ = robot->model_->getActuator(actuator_name)))
84  {
85  ROS_ERROR("Could not find actuator %s (namespace: %s)",
86  actuator_name.c_str(), node_.getNamespace().c_str());
87  return false;
88  }
89 
90  // Transmission
91  std::string transmission_name;
92  if (!node_.getParam("transmission", transmission_name))
93  {
94  ROS_ERROR("No transmission given (namespace: %s)", node_.getNamespace().c_str());
95  return false;
96  }
97  if (!(transmission_ = robot->model_->getTransmission(transmission_name).get()))
98  {
99  ROS_ERROR("Could not find transmission %s (namespace: %s)",
100  transmission_name.c_str(), node_.getNamespace().c_str());
101  return false;
102  }
103 
104  if (!node_.getParam("velocity", search_velocity_))
105  {
106  ROS_ERROR("Velocity value was not specified (namespace: %s)", node_.getNamespace().c_str());
107  return false;
108  }
109 
110  // Contained velocity controller
111  if (!vc_.init(robot, node_))
112  return false;
113 
114  // "Calibrated" topic
115  pub_calibrated_.reset(
116  new realtime_tools::RealtimePublisher<std_msgs::Empty>(node_, "calibrated", 1));
117 
118  return true;
119 }
120 
121 void JointLimitCalibrationController::update()
122 {
123  assert(joint_);
124  assert(actuator_);
125 
126  switch (state_)
127  {
128  case INITIALIZED:
129  state_ = BEGINNING;
130  return;
131  case BEGINNING:
132  count_ = 0;
133  joint_->calibrated_ = false;
134  actuator_->state_.zero_offset_ = 0.0;
135  vc_.setCommand(search_velocity_);
136  state_ = STARTING;
137  break;
138  case STARTING:
139  // Makes sure we start moving for a bit before checking if we've stopped.
140  if (++count_ > 500)
141  {
142  count_ = 0;
143  state_ = STOPPING;
144  }
145  break;
146  case STOPPING:
147  if (fabs(joint_->velocity_) < 0.001)
148  stop_count_++;
149  else
150  stop_count_ = 0;
151 
152  if (stop_count_ > 250)
153  {
154  // Need to set zero offset correctly
157  std::vector<pr2_hardware_interface::Actuator*> fake_a;
158  std::vector<pr2_mechanism_model::JointState*> fake_j;
159  fake_a.push_back(&a);
160  fake_j.push_back(&j);
161 
162  fake_a[0]->state_.position_ = actuator_->state_.position_;
163 
164  transmission_->propagatePosition(fake_a, fake_j);
165 
166  // What is the actuator position at the joint's max or min?
167  double ref_position = 0;
168  if (search_velocity_ < 0)
169  ref_position = joint_->joint_->limits->lower;
170  else
171  ref_position = joint_->joint_->limits->upper;
172 
173 
174  fake_j[0]->position_ = fake_j[0]->position_ - ref_position;
175 
176  transmission_->propagatePositionBackwards(fake_j, fake_a);
177 
178  actuator_->state_.zero_offset_ = fake_a[0]->state_.position_;
179  state_ = CALIBRATED;
180  joint_->calibrated_ = true;
181  vc_.setCommand(0);
182  }
183  break;
184  case CALIBRATED:
185  if (pub_calibrated_)
186  {
187  if (last_publish_time_ + ros::Duration(0.5) < robot_->getTime())
188  {
189  if (pub_calibrated_->trylock())
190  {
191  last_publish_time_ = robot_->getTime();
192  pub_calibrated_->unlockAndPublish();
193  }
194  }
195  }
196  break;
197  }
198 
199  if (state_ != CALIBRATED)
200  vc_.update();
201 }
202 
boost::shared_ptr< pr2_mechanism_model::Transmission > getTransmission(const std::string &name) const
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::JointLimitCalibrationController, pr2_controller_interface::Controller) JointLimitCalibrationController
JointState * getJointState(const std::string &name)
pr2_hardware_interface::Actuator * getActuator(const std::string &name) const
#define ROS_ERROR(...)


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