srh_fake_joint_calibration_controller.h
Go to the documentation of this file.
00001 
00027 #ifndef _SRH_FAKE_JOINT_CALIBRATION_CONTROLLER_
00028 #define _SRH_FAKE_JOINT_CALIBRATION_CONTROLLER_
00029 
00030 #include "ros/node_handle.h"
00031 #include "pr2_mechanism_model/robot.h"
00032 #include "robot_mechanism_controllers/joint_velocity_controller.h"
00033 #include "realtime_tools/realtime_publisher.h"
00034 #include "std_msgs/Empty.h"
00035 
00036 
00037 namespace controller
00038 {
00039 
00040   class SrhFakeJointCalibrationController : public pr2_controller_interface::Controller
00041   {
00042   public:
00043     SrhFakeJointCalibrationController();
00044     virtual ~SrhFakeJointCalibrationController();
00045 
00046     virtual bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00047 
00048     virtual void update();
00049 
00050     bool calibrated() { return state_ == CALIBRATED; }
00051     void beginCalibration()
00052     {
00053       if (state_ == INITIALIZED)
00054         state_ = BEGINNING;
00055     }
00056 
00057   protected:
00058 
00059     pr2_mechanism_model::RobotState* robot_;
00060     ros::NodeHandle node_;
00061     boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > pub_calibrated_;
00062     ros::Time last_publish_time_;
00063 
00064     enum { INITIALIZED, BEGINNING, MOVING_TO_LOW, MOVING_TO_HIGH, CALIBRATED };
00065     int state_;
00066     int countdown_;
00067 
00068     double search_velocity_, reference_position_;
00069     bool original_switch_state_;
00070 
00071     pr2_hardware_interface::Actuator *actuator_;
00072     pr2_mechanism_model::JointState *joint_;
00073     pr2_mechanism_model::Transmission *transmission_;
00074 
00075     std::string joint_name_, actuator_name_;
00076 
00081     void initialize_pids();
00082   };
00083 
00084 }
00085 
00086 /* For the emacs weenies in the crowd.
00087 Local Variables:
00088    c-basic-offset: 2
00089 End:
00090 */
00091 
00092 
00093 #endif


sr_mechanism_controllers
Author(s): Ugo Cupcic / ugo@shadowrobot.com , contact@shadowrobot.com
autogenerated on Mon Oct 6 2014 07:54:39