joint_calibration_controller.h
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 
35 #ifndef PR2_JOINT_CALIBRATION_CONTROLLER
36 #define PR2_JOINT_CALIBRATION_CONTROLLER
37 
38 #include "ros/node_handle.h"
42 #include "std_msgs/Empty.h"
43 #include "pr2_controllers_msgs/QueryCalibrationState.h"
44 
45 
46 namespace controller
47 {
48 
50 {
51 public:
54 
55  virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
56  virtual void starting();
57  virtual void update();
58 
59  bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req, pr2_controllers_msgs::QueryCalibrationState::Response& resp);
60 
61 
62 protected:
67  boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
68 
70  int state_;
72 
75 
79 
81 };
82 
83 }
84 
85 
86 #endif
pr2_hardware_interface::Actuator * actuator_
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
boost::shared_ptr< pr2_mechanism_model::Transmission > transmission_
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
resp
controller::JointVelocityController vc_


pr2_calibration_controllers
Author(s): Stuart Glaser
autogenerated on Wed Jun 5 2019 19:34:11