wrist_calibration_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 /*
31  * Author: Stuart Glaser
32  */
33 
34 #ifndef WRIST_CALIBRATION_CONTROLLER_H
35 #define WRIST_CALIBRATION_CONTROLLER_H
36 
40 #include "std_msgs/Empty.h"
41 #include "pr2_controllers_msgs/QueryCalibrationState.h"
42 
43 namespace controller {
44 
46 {
47 public:
50 
51  virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
52  virtual void starting();
53  virtual void update();
54 
55  bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req, pr2_controllers_msgs::QueryCalibrationState::Response& resp);
56 
57 protected:
58 
62  int state_;
63 
68  boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
69 
74 
75  // Tracks the actuator positions for when the optical switch occurred.
78 
80 
84 
85  // Preallocated, for use in update()
86  std::vector<pr2_hardware_interface::Actuator*> fake_as;
87  std::vector<pr2_mechanism_model::JointState*> fake_js;
88 
90 };
91 
92 
93 }
94 
95 #endif
std::vector< pr2_hardware_interface::Actuator * > fake_as
controller::JointVelocityController vc_flex_
pr2_mechanism_model::JointState * roll_joint_
pr2_hardware_interface::Actuator * actuator_r_
controller::JointVelocityController vc_roll_
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
std::vector< pr2_mechanism_model::JointState * > fake_js
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
boost::shared_ptr< pr2_mechanism_model::Transmission > transmission_
pr2_hardware_interface::Actuator * actuator_l_
resp
pr2_mechanism_model::JointState * flex_joint_


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