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 
37 #include <boost/scoped_ptr.hpp>
38 #include <boost/shared_ptr.hpp>
39 
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 
65  int state_;
66 
71  boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
72 
77 
78  // Tracks the actuator positions for when the optical switch occurred.
81 
83 
87 
88  // Preallocated, for use in update()
89  std::vector<pr2_hardware_interface::Actuator*> fake_as;
90  std::vector<pr2_mechanism_model::JointState*> fake_js;
91 
93 };
94 
95 
96 }
97 
98 #endif
realtime_publisher.h
controller::WristCalibrationController::roll_switch_l_
double roll_switch_l_
Definition: wrist_calibration_controller.h:80
pr2_mechanism_model::JointState
controller::WristCalibrationController::WristCalibrationController
WristCalibrationController()
Definition: wrist_calibration_controller.cpp:42
boost::shared_ptr< pr2_mechanism_model::Transmission >
controller::WristCalibrationController::roll_search_velocity_
double roll_search_velocity_
Definition: wrist_calibration_controller.h:73
controller::WristCalibrationController::init
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
Definition: wrist_calibration_controller.cpp:55
controller::WristCalibrationController::vc_roll_
controller::JointVelocityController vc_roll_
Definition: wrist_calibration_controller.h:92
joint_velocity_controller.h
controller::WristCalibrationController::countdown_
int countdown_
Definition: wrist_calibration_controller.h:76
controller::WristCalibrationController::robot_
pr2_mechanism_model::RobotState * robot_
Definition: wrist_calibration_controller.h:67
controller::WristCalibrationController::actuator_r_
pr2_hardware_interface::Actuator * actuator_r_
Definition: wrist_calibration_controller.h:84
controller::WristCalibrationController::MOVING_FLEX
@ MOVING_FLEX
Definition: wrist_calibration_controller.h:63
controller::WristCalibrationController::MOVING_ROLL
@ MOVING_ROLL
Definition: wrist_calibration_controller.h:64
controller::WristCalibrationController::is_calibrated_srv_
ros::ServiceServer is_calibrated_srv_
Definition: wrist_calibration_controller.h:70
controller::WristCalibrationController::flex_switch_l_
double flex_switch_l_
Definition: wrist_calibration_controller.h:79
controller::WristCalibrationController::INITIALIZED
@ INITIALIZED
Definition: wrist_calibration_controller.h:62
ros::ServiceServer
controller::WristCalibrationController::state_
int state_
Definition: wrist_calibration_controller.h:65
controller::WristCalibrationController::vc_flex_
controller::JointVelocityController vc_flex_
Definition: wrist_calibration_controller.h:92
controller::WristCalibrationController::BEGINNING
@ BEGINNING
Definition: wrist_calibration_controller.h:62
controller
pr2_mechanism_model::RobotState
controller::WristCalibrationController::fake_as
std::vector< pr2_hardware_interface::Actuator * > fake_as
Definition: wrist_calibration_controller.h:89
controller::WristCalibrationController::flex_search_velocity_
double flex_search_velocity_
Definition: wrist_calibration_controller.h:74
resp
resp
controller::WristCalibrationController::flex_joint_
pr2_mechanism_model::JointState * flex_joint_
Definition: wrist_calibration_controller.h:85
controller::WristCalibrationController
Definition: wrist_calibration_controller.h:48
controller::WristCalibrationController::MOVING_FLEX_TO_HIGH
@ MOVING_FLEX_TO_HIGH
Definition: wrist_calibration_controller.h:63
controller::WristCalibrationController::roll_joint_
pr2_mechanism_model::JointState * roll_joint_
Definition: wrist_calibration_controller.h:85
controller::WristCalibrationController::actuator_l_
pr2_hardware_interface::Actuator * actuator_l_
Definition: wrist_calibration_controller.h:84
controller::WristCalibrationController::node_
ros::NodeHandle node_
Definition: wrist_calibration_controller.h:68
pr2_controller_interface::Controller
controller::WristCalibrationController::pub_calibrated_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
Definition: wrist_calibration_controller.h:71
controller::WristCalibrationController::update
virtual void update()
Definition: wrist_calibration_controller.cpp:297
controller::JointVelocityController
controller::WristCalibrationController::starting
virtual void starting()
Definition: wrist_calibration_controller.cpp:278
controller::WristCalibrationController::~WristCalibrationController
~WristCalibrationController()
Definition: wrist_calibration_controller.cpp:47
ros::Time
controller::WristCalibrationController::prev_actuator_l_position_
double prev_actuator_l_position_
Definition: wrist_calibration_controller.h:82
controller::WristCalibrationController::transmission_
boost::shared_ptr< pr2_mechanism_model::Transmission > transmission_
Definition: wrist_calibration_controller.h:86
controller::WristCalibrationController::MOVING_ROLL_TO_LOW
@ MOVING_ROLL_TO_LOW
Definition: wrist_calibration_controller.h:64
controller::WristCalibrationController::roll_switch_r_
double roll_switch_r_
Definition: wrist_calibration_controller.h:80
controller::WristCalibrationController::prev_actuator_r_position_
double prev_actuator_r_position_
Definition: wrist_calibration_controller.h:82
controller::WristCalibrationController::isCalibrated
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
Definition: wrist_calibration_controller.cpp:288
wrist_transmission.h
controller::WristCalibrationController::original_switch_state_
bool original_switch_state_
Definition: wrist_calibration_controller.h:75
controller::WristCalibrationController::last_publish_time_
ros::Time last_publish_time_
Definition: wrist_calibration_controller.h:69
pr2_hardware_interface::Actuator
controller::WristCalibrationController::flex_switch_r_
double flex_switch_r_
Definition: wrist_calibration_controller.h:79
ros::NodeHandle
controller::WristCalibrationController::CALIBRATED
@ CALIBRATED
Definition: wrist_calibration_controller.h:64
controller::WristCalibrationController::fake_js
std::vector< pr2_mechanism_model::JointState * > fake_js
Definition: wrist_calibration_controller.h:90


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