#include <wrist_calibration_controller.h>
Public Member Functions | |
virtual bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
bool | isCalibrated (pr2_controllers_msgs::QueryCalibrationState::Request &req, pr2_controllers_msgs::QueryCalibrationState::Response &resp) |
virtual void | starting () |
virtual void | update () |
WristCalibrationController () | |
~WristCalibrationController () | |
Protected Types | |
enum | { INITIALIZED, BEGINNING, MOVING_FLEX_TO_HIGH, MOVING_FLEX, MOVING_ROLL_TO_LOW, MOVING_ROLL, CALIBRATED } |
Protected Attributes | |
pr2_hardware_interface::Actuator * | actuator_l_ |
pr2_hardware_interface::Actuator * | actuator_r_ |
int | countdown_ |
std::vector < pr2_hardware_interface::Actuator * > | fake_as |
std::vector < pr2_mechanism_model::JointState * > | fake_js |
pr2_mechanism_model::JointState * | flex_joint_ |
double | flex_search_velocity_ |
double | flex_switch_l_ |
double | flex_switch_r_ |
ros::ServiceServer | is_calibrated_srv_ |
ros::Time | last_publish_time_ |
ros::NodeHandle | node_ |
bool | original_switch_state_ |
double | prev_actuator_l_position_ |
double | prev_actuator_r_position_ |
boost::scoped_ptr < realtime_tools::RealtimePublisher < std_msgs::Empty > > | pub_calibrated_ |
pr2_mechanism_model::RobotState * | robot_ |
pr2_mechanism_model::JointState * | roll_joint_ |
double | roll_search_velocity_ |
double | roll_switch_l_ |
double | roll_switch_r_ |
int | state_ |
pr2_mechanism_model::Transmission * | transmission_ |
controller::JointVelocityController | vc_flex_ |
controller::JointVelocityController | vc_roll_ |
Definition at line 42 of file wrist_calibration_controller.h.
anonymous enum [protected] |
INITIALIZED | |
BEGINNING | |
MOVING_FLEX_TO_HIGH | |
MOVING_FLEX | |
MOVING_ROLL_TO_LOW | |
MOVING_ROLL | |
CALIBRATED |
Definition at line 53 of file wrist_calibration_controller.h.
controller::WristCalibrationController::WristCalibrationController | ( | ) |
controller::WristCalibrationController::~WristCalibrationController | ( | ) |
virtual bool controller::WristCalibrationController::init | ( | pr2_mechanism_model::RobotState * | robot, | |
ros::NodeHandle & | n | |||
) | [virtual] |
bool controller::WristCalibrationController::isCalibrated | ( | pr2_controllers_msgs::QueryCalibrationState::Request & | req, | |
pr2_controllers_msgs::QueryCalibrationState::Response & | resp | |||
) |
virtual void controller::WristCalibrationController::starting | ( | ) | [virtual] |
virtual void controller::WristCalibrationController::update | ( | ) | [virtual] |
pr2_hardware_interface::Actuator* controller::WristCalibrationController::actuator_l_ [protected] |
Definition at line 75 of file wrist_calibration_controller.h.
pr2_hardware_interface::Actuator * controller::WristCalibrationController::actuator_r_ [protected] |
Definition at line 75 of file wrist_calibration_controller.h.
int controller::WristCalibrationController::countdown_ [protected] |
Definition at line 67 of file wrist_calibration_controller.h.
std::vector<pr2_hardware_interface::Actuator*> controller::WristCalibrationController::fake_as [protected] |
Definition at line 80 of file wrist_calibration_controller.h.
std::vector<pr2_mechanism_model::JointState*> controller::WristCalibrationController::fake_js [protected] |
Definition at line 81 of file wrist_calibration_controller.h.
pr2_mechanism_model::JointState* controller::WristCalibrationController::flex_joint_ [protected] |
Definition at line 76 of file wrist_calibration_controller.h.
double controller::WristCalibrationController::flex_search_velocity_ [protected] |
Definition at line 65 of file wrist_calibration_controller.h.
double controller::WristCalibrationController::flex_switch_l_ [protected] |
Definition at line 70 of file wrist_calibration_controller.h.
double controller::WristCalibrationController::flex_switch_r_ [protected] |
Definition at line 70 of file wrist_calibration_controller.h.
ros::ServiceServer controller::WristCalibrationController::is_calibrated_srv_ [protected] |
Definition at line 61 of file wrist_calibration_controller.h.
ros::Time controller::WristCalibrationController::last_publish_time_ [protected] |
Definition at line 60 of file wrist_calibration_controller.h.
ros::NodeHandle controller::WristCalibrationController::node_ [protected] |
Definition at line 59 of file wrist_calibration_controller.h.
bool controller::WristCalibrationController::original_switch_state_ [protected] |
Definition at line 66 of file wrist_calibration_controller.h.
double controller::WristCalibrationController::prev_actuator_l_position_ [protected] |
Definition at line 73 of file wrist_calibration_controller.h.
double controller::WristCalibrationController::prev_actuator_r_position_ [protected] |
Definition at line 73 of file wrist_calibration_controller.h.
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > controller::WristCalibrationController::pub_calibrated_ [protected] |
Definition at line 62 of file wrist_calibration_controller.h.
pr2_mechanism_model::RobotState* controller::WristCalibrationController::robot_ [protected] |
Definition at line 58 of file wrist_calibration_controller.h.
pr2_mechanism_model::JointState * controller::WristCalibrationController::roll_joint_ [protected] |
Definition at line 76 of file wrist_calibration_controller.h.
double controller::WristCalibrationController::roll_search_velocity_ [protected] |
Definition at line 64 of file wrist_calibration_controller.h.
double controller::WristCalibrationController::roll_switch_l_ [protected] |
Definition at line 71 of file wrist_calibration_controller.h.
double controller::WristCalibrationController::roll_switch_r_ [protected] |
Definition at line 71 of file wrist_calibration_controller.h.
int controller::WristCalibrationController::state_ [protected] |
Definition at line 56 of file wrist_calibration_controller.h.
pr2_mechanism_model::Transmission* controller::WristCalibrationController::transmission_ [protected] |
Definition at line 77 of file wrist_calibration_controller.h.
controller::JointVelocityController controller::WristCalibrationController::vc_flex_ [protected] |
Definition at line 83 of file wrist_calibration_controller.h.
controller::JointVelocityController controller::WristCalibrationController::vc_roll_ [protected] |
Definition at line 83 of file wrist_calibration_controller.h.