Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 #ifndef WRIST_CALIBRATION_CONTROLLER_H
00035 #define WRIST_CALIBRATION_CONTROLLER_H
00036
00037 #include "robot_mechanism_controllers/joint_velocity_controller.h"
00038 #include "realtime_tools/realtime_publisher.h"
00039 #include "pr2_mechanism_model/wrist_transmission.h"
00040 #include "std_msgs/Empty.h"
00041 #include "pr2_controllers_msgs/QueryCalibrationState.h"
00042
00043 namespace controller {
00044
00045 class WristCalibrationController : public pr2_controller_interface::Controller
00046 {
00047 public:
00048 WristCalibrationController();
00049 ~WristCalibrationController();
00050
00051 virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00052 virtual void starting();
00053 virtual void update();
00054
00055 bool isCalibrated(pr2_controllers_msgs::QueryCalibrationState::Request& req, pr2_controllers_msgs::QueryCalibrationState::Response& resp);
00056
00057 protected:
00058
00059 enum { INITIALIZED, BEGINNING,
00060 MOVING_FLEX_TO_HIGH, MOVING_FLEX,
00061 MOVING_ROLL_TO_LOW, MOVING_ROLL, CALIBRATED };
00062 int state_;
00063
00064 pr2_mechanism_model::RobotState *robot_;
00065 ros::NodeHandle node_;
00066 ros::Time last_publish_time_;
00067 ros::ServiceServer is_calibrated_srv_;
00068 boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
00069
00070 double roll_search_velocity_;
00071 double flex_search_velocity_;
00072 bool original_switch_state_;
00073 int countdown_;
00074
00075
00076 double flex_switch_l_, flex_switch_r_;
00077 double roll_switch_l_, roll_switch_r_;
00078
00079 double prev_actuator_l_position_, prev_actuator_r_position_;
00080
00081 pr2_hardware_interface::Actuator *actuator_l_, *actuator_r_;
00082 pr2_mechanism_model::JointState *flex_joint_, *roll_joint_;
00083 pr2_mechanism_model::Transmission *transmission_;
00084
00085
00086 std::vector<pr2_hardware_interface::Actuator*> fake_as;
00087 std::vector<pr2_mechanism_model::JointState*> fake_js;
00088
00089 controller::JointVelocityController vc_flex_, vc_roll_;
00090 };
00091
00092
00093 }
00094
00095 #endif