35 #ifndef PR2_JOINT_CALIBRATION_CONTROLLER 36 #define PR2_JOINT_CALIBRATION_CONTROLLER 38 #include <boost/scoped_ptr.hpp> 39 #include <boost/shared_ptr.hpp> 45 #include "std_msgs/Empty.h" 46 #include "pr2_controllers_msgs/QueryCalibrationState.h" 62 bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req, pr2_controllers_msgs::QueryCalibrationState::Response&
resp);
70 boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> >
pub_calibrated_;
ros::ServiceServer is_calibrated_srv_
pr2_hardware_interface::Actuator * actuator_
ros::Time last_publish_time_
pr2_mechanism_model::RobotState * robot_
virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > pub_calibrated_
boost::shared_ptr< pr2_mechanism_model::Transmission > transmission_
pr2_mechanism_model::JointState * joint_
JointCalibrationController()
bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp)
virtual ~JointCalibrationController()
double original_position_
controller::JointVelocityController vc_