motor_joint_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 
40 
41 using namespace std;
42 using namespace joint_qualification_controllers;
43 
44 
46 : robot_(NULL), last_publish_time_(0), joint_(NULL)
47 {
48 }
49 
50 MotorJointCalibrationController::~MotorJointCalibrationController()
51 {
52 }
53 
55 {
56  robot_ = robot;
57  node_ = n;
58 
59  // Joint
60 
61  std::string joint_name;
62  if (!node_.getParam("joint", joint_name))
63  {
64  ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
65  return false;
66  }
67  if (!(joint_ = robot->getJointState(joint_name)))
68  {
69  ROS_ERROR("Could not find joint %s (namespace: %s)",
70  joint_name.c_str(), node_.getNamespace().c_str());
71  return false;
72  }
73 
74  // "Calibrated" topic
75  pub_calibrated_.reset(
77 
78  // Calibrate at zero, basically
79  joint_->calibrated_ = true;
80 
81  return true;
82 }
83 
84 
86 {
87  assert(joint_);
88 
89  if (pub_calibrated_)
90  {
92  {
93  assert(pub_calibrated_);
94  if (pub_calibrated_->trylock())
95  {
97  pub_calibrated_->unlockAndPublish();
98  }
99  }
100  }
101 
102 }
103 
PLUGINLIB_EXPORT_CLASS(joint_qualification_controllers::CheckoutController, pr2_controller_interface::Controller) using namespace std
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
bool getParam(const std::string &key, std::string &s) const
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
#define ROS_ERROR(...)


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