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

#include <joint_calibration_controller.h>

Inheritance diagram for controller::JointCalibrationController:
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)
 JointCalibrationController ()
virtual void starting ()
virtual void update ()
virtual ~JointCalibrationController ()

Protected Types

enum  {
  INITIALIZED, BEGINNING, MOVING_TO_LOW, MOVING_TO_HIGH,
  CALIBRATED
}

Protected Attributes

pr2_hardware_interface::Actuatoractuator_
int countdown_
ros::ServiceServer is_calibrated_srv_
pr2_mechanism_model::JointStatejoint_
ros::Time last_publish_time_
ros::NodeHandle node_
double original_position_
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< std_msgs::Empty > > 
pub_calibrated_
pr2_mechanism_model::RobotStaterobot_
double search_velocity_
int state_
pr2_mechanism_model::Transmissiontransmission_
controller::JointVelocityController vc_

Detailed Description

Definition at line 49 of file joint_calibration_controller.h.


Member Enumeration Documentation

anonymous enum [protected]
Enumerator:
INITIALIZED 
BEGINNING 
MOVING_TO_LOW 
MOVING_TO_HIGH 
CALIBRATED 

Definition at line 69 of file joint_calibration_controller.h.


Constructor & Destructor Documentation

Definition at line 45 of file joint_calibration_controller.cpp.

Definition at line 51 of file joint_calibration_controller.cpp.


Member Function Documentation

Definition at line 191 of file joint_calibration_controller.cpp.

Reimplemented from pr2_controller_interface::Controller.

Definition at line 183 of file joint_calibration_controller.cpp.


Member Data Documentation

Definition at line 76 of file joint_calibration_controller.h.

Definition at line 71 of file joint_calibration_controller.h.

Definition at line 66 of file joint_calibration_controller.h.

Definition at line 77 of file joint_calibration_controller.h.

Definition at line 65 of file joint_calibration_controller.h.

Definition at line 64 of file joint_calibration_controller.h.

Definition at line 74 of file joint_calibration_controller.h.

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

Definition at line 67 of file joint_calibration_controller.h.

Definition at line 63 of file joint_calibration_controller.h.

Definition at line 73 of file joint_calibration_controller.h.

Reimplemented from pr2_controller_interface::Controller.

Definition at line 70 of file joint_calibration_controller.h.

Definition at line 78 of file joint_calibration_controller.h.

Definition at line 80 of file joint_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