Public Member Functions | Protected Types | Protected Attributes
controller::WristCalibrationController Class Reference

#include <wrist_calibration_controller.h>

Inheritance diagram for controller::WristCalibrationController:
Inheritance graph
[legend]

List of all members.

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::Actuatoractuator_l_
pr2_hardware_interface::Actuatoractuator_r_
int countdown_
std::vector
< pr2_hardware_interface::Actuator * > 
fake_as
std::vector
< pr2_mechanism_model::JointState * > 
fake_js
pr2_mechanism_model::JointStateflex_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::RobotStaterobot_
pr2_mechanism_model::JointStateroll_joint_
double roll_search_velocity_
double roll_switch_l_
double roll_switch_r_
int state_
pr2_mechanism_model::Transmissiontransmission_
controller::JointVelocityController vc_flex_
controller::JointVelocityController vc_roll_

Detailed Description

Definition at line 45 of file wrist_calibration_controller.h.


Member Enumeration Documentation

anonymous enum [protected]
Enumerator:
INITIALIZED 
BEGINNING 
MOVING_FLEX_TO_HIGH 
MOVING_FLEX 
MOVING_ROLL_TO_LOW 
MOVING_ROLL 
CALIBRATED 

Definition at line 59 of file wrist_calibration_controller.h.


Constructor & Destructor Documentation

Definition at line 42 of file wrist_calibration_controller.cpp.

Definition at line 47 of file wrist_calibration_controller.cpp.


Member Function Documentation

Definition at line 288 of file wrist_calibration_controller.cpp.

Reimplemented from pr2_controller_interface::Controller.

Definition at line 278 of file wrist_calibration_controller.cpp.


Member Data Documentation

Definition at line 81 of file wrist_calibration_controller.h.

Definition at line 81 of file wrist_calibration_controller.h.

Definition at line 73 of file wrist_calibration_controller.h.

Definition at line 86 of file wrist_calibration_controller.h.

Definition at line 87 of file wrist_calibration_controller.h.

Definition at line 82 of file wrist_calibration_controller.h.

Definition at line 71 of file wrist_calibration_controller.h.

Definition at line 76 of file wrist_calibration_controller.h.

Definition at line 76 of file wrist_calibration_controller.h.

Definition at line 67 of file wrist_calibration_controller.h.

Definition at line 66 of file wrist_calibration_controller.h.

Definition at line 65 of file wrist_calibration_controller.h.

Definition at line 72 of file wrist_calibration_controller.h.

Definition at line 79 of file wrist_calibration_controller.h.

Definition at line 79 of file wrist_calibration_controller.h.

boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > controller::WristCalibrationController::pub_calibrated_ [protected]

Definition at line 68 of file wrist_calibration_controller.h.

Definition at line 64 of file wrist_calibration_controller.h.

Definition at line 82 of file wrist_calibration_controller.h.

Definition at line 70 of file wrist_calibration_controller.h.

Definition at line 77 of file wrist_calibration_controller.h.

Definition at line 77 of file wrist_calibration_controller.h.

Reimplemented from pr2_controller_interface::Controller.

Definition at line 62 of file wrist_calibration_controller.h.

Definition at line 83 of file wrist_calibration_controller.h.

Definition at line 89 of file wrist_calibration_controller.h.

Definition at line 89 of file wrist_calibration_controller.h.


The documentation for this class was generated from the following files:


pr2_calibration_controllers
Author(s): Stuart Glaser
autogenerated on Thu Apr 24 2014 15:45:00