Go to the documentation of this file.
34 #ifndef WRIST_CALIBRATION_CONTROLLER_H
35 #define WRIST_CALIBRATION_CONTROLLER_H
37 #include <boost/scoped_ptr.hpp>
38 #include <boost/shared_ptr.hpp>
43 #include "std_msgs/Empty.h"
44 #include "pr2_controllers_msgs/QueryCalibrationState.h"
58 bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req, pr2_controllers_msgs::QueryCalibrationState::Response&
resp);
71 boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> >
pub_calibrated_;
89 std::vector<pr2_hardware_interface::Actuator*>
fake_as;
90 std::vector<pr2_mechanism_model::JointState*>
fake_js;
WristCalibrationController()
double roll_search_velocity_
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
controller::JointVelocityController vc_roll_
pr2_mechanism_model::RobotState * robot_
pr2_hardware_interface::Actuator * actuator_r_
ros::ServiceServer is_calibrated_srv_
controller::JointVelocityController vc_flex_
std::vector< pr2_hardware_interface::Actuator * > fake_as
double flex_search_velocity_
pr2_mechanism_model::JointState * flex_joint_
pr2_mechanism_model::JointState * roll_joint_
pr2_hardware_interface::Actuator * actuator_l_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
~WristCalibrationController()
double prev_actuator_l_position_
boost::shared_ptr< pr2_mechanism_model::Transmission > transmission_
double prev_actuator_r_position_
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
bool original_switch_state_
ros::Time last_publish_time_
std::vector< pr2_mechanism_model::JointState * > fake_js