34 #ifndef CASTER_CALIBRATION_CONTROLLER_H 35 #define CASTER_CALIBRATION_CONTROLLER_H 40 #include "std_msgs/Empty.h" 41 #include "pr2_controllers_msgs/QueryCalibrationState.h" 55 bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req, pr2_controllers_msgs::QueryCalibrationState::Response&
resp);
77 std::vector<pr2_hardware_interface::Actuator*>
fake_as;
78 std::vector<pr2_mechanism_model::JointState*>
fake_js;
84 boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> >
pub_calibrated_;
pr2_mechanism_model::JointState * wheel_r_joint_
ros::Time last_publish_time_
~CasterCalibrationController()
pr2_mechanism_model::JointState * joint_
pr2_mechanism_model::JointState * wheel_l_joint_
std::vector< pr2_mechanism_model::JointState * > fake_js
CasterCalibrationController()
pr2_mechanism_model::RobotState * robot_
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
std::vector< pr2_hardware_interface::Actuator * > fake_as
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
boost::shared_ptr< pr2_mechanism_model::Transmission > transmission_
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
bool original_switch_state_
ros::ServiceServer is_calibrated_srv_
controller::CasterController cc_
double original_position_
pr2_hardware_interface::Actuator * actuator_