caster_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 CASTER_CALIBRATION_CONTROLLER_H
35 #define CASTER_CALIBRATION_CONTROLLER_H
36 
37 #include <boost/scoped_ptr.hpp>
38 #include <boost/shared_ptr.hpp>
39 
40 #include "ros/node_handle.h"
43 #include "std_msgs/Empty.h"
44 #include "pr2_controllers_msgs/QueryCalibrationState.h"
45 
46 namespace controller {
47 
49 {
50 public:
53 
54  virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
55  virtual void starting();
56  virtual void update();
57 
58  bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req, pr2_controllers_msgs::QueryCalibrationState::Response& resp);
59 
60 protected:
61 
64 
66  int state_;
67 
71 
74 
78 
79  // Preallocated, for use in update()
80  std::vector<pr2_hardware_interface::Actuator*> fake_as;
81  std::vector<pr2_mechanism_model::JointState*> fake_js;
82 
84 
87  boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
88 };
89 
90 } // namespace
91 
92 #endif
realtime_publisher.h
node_handle.h
pr2_mechanism_model::JointState
controller::CasterCalibrationController::beginning_
ros::Time beginning_
Definition: caster_calibration_controller.h:72
controller::CasterCalibrationController::starting
virtual void starting()
Definition: caster_calibration_controller.cpp:216
controller::CasterCalibrationController::fake_js
std::vector< pr2_mechanism_model::JointState * > fake_js
Definition: caster_calibration_controller.h:81
controller::CasterCalibrationController::actuator_
pr2_hardware_interface::Actuator * actuator_
Definition: caster_calibration_controller.h:75
boost::shared_ptr< pr2_mechanism_model::Transmission >
controller::CasterCalibrationController::node_
ros::NodeHandle node_
Definition: caster_calibration_controller.h:62
controller::CasterCalibrationController::robot_
pr2_mechanism_model::RobotState * robot_
Definition: caster_calibration_controller.h:63
controller::CasterCalibrationController::state_
int state_
Definition: caster_calibration_controller.h:66
controller::CasterCalibrationController::init
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: caster_calibration_controller.cpp:55
controller::CasterCalibrationController::wheel_r_joint_
pr2_mechanism_model::JointState * wheel_r_joint_
Definition: caster_calibration_controller.h:76
controller::CasterCalibrationController::fake_as
std::vector< pr2_hardware_interface::Actuator * > fake_as
Definition: caster_calibration_controller.h:80
controller::CasterCalibrationController::last_publish_time_
ros::Time last_publish_time_
Definition: caster_calibration_controller.h:85
ros::ServiceServer
controller::CasterCalibrationController::BEGINNING
@ BEGINNING
Definition: caster_calibration_controller.h:65
controller::CasterCalibrationController::unstick_iter_
int unstick_iter_
Definition: caster_calibration_controller.h:73
controller::CasterCalibrationController::~CasterCalibrationController
~CasterCalibrationController()
Definition: caster_calibration_controller.cpp:47
controller::CasterCalibrationController::search_velocity_
double search_velocity_
Definition: caster_calibration_controller.h:68
controller::CasterCalibrationController::update
virtual void update()
Definition: caster_calibration_controller.cpp:236
controller::CasterCalibrationController::CasterCalibrationController
CasterCalibrationController()
Definition: caster_calibration_controller.cpp:41
controller::CasterCalibrationController::original_switch_state_
bool original_switch_state_
Definition: caster_calibration_controller.h:69
controller::CasterCalibrationController::joint_
pr2_mechanism_model::JointState * joint_
Definition: caster_calibration_controller.h:76
controller::CasterCalibrationController::wheel_l_joint_
pr2_mechanism_model::JointState * wheel_l_joint_
Definition: caster_calibration_controller.h:76
controller
pr2_mechanism_model::RobotState
caster_controller.h
controller::CasterCalibrationController::cc_
controller::CasterController cc_
Definition: caster_calibration_controller.h:83
controller::CasterCalibrationController::original_position_
double original_position_
Definition: caster_calibration_controller.h:70
resp
resp
controller::CasterCalibrationController::CALIBRATED
@ CALIBRATED
Definition: caster_calibration_controller.h:65
controller::CasterCalibrationController::pub_calibrated_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
Definition: caster_calibration_controller.h:87
pr2_controller_interface::Controller
controller::CasterCalibrationController::MOVING
@ MOVING
Definition: caster_calibration_controller.h:65
controller::CasterCalibrationController::isCalibrated
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
Definition: caster_calibration_controller.cpp:226
ros::Time
controller::CasterCalibrationController
Definition: caster_calibration_controller.h:48
controller::CasterCalibrationController::transmission_
boost::shared_ptr< pr2_mechanism_model::Transmission > transmission_
Definition: caster_calibration_controller.h:77
controller::CasterCalibrationController::is_calibrated_srv_
ros::ServiceServer is_calibrated_srv_
Definition: caster_calibration_controller.h:86
controller::CasterController
pr2_hardware_interface::Actuator
ros::NodeHandle
controller::CasterCalibrationController::INITIALIZED
@ INITIALIZED
Definition: caster_calibration_controller.h:65


pr2_calibration_controllers
Author(s): Stuart Glaser
autogenerated on Sat Nov 12 2022 03:33:28