Public Member Functions | Protected Types | Protected Attributes | List of all members
controller::JointCalibrationController Class Reference

#include <joint_calibration_controller.h>

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

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 ()
 
- Public Member Functions inherited from pr2_controller_interface::Controller
 Controller ()
 
bool getController (const std::string &name, int sched, ControllerType *&c)
 
bool initRequest (ControllerProvider *cp, pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 
bool isRunning ()
 
void starting (const ros::Time &time)
 
bool startRequest ()
 
void stopping (const ros::Time &time)
 
virtual void stopping ()
 
bool stopRequest ()
 
void update (const ros::Time &time, const ros::Duration &period)
 
void updateRequest ()
 
virtual ~Controller ()
 

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_
 
boost::shared_ptr< pr2_mechanism_model::Transmissiontransmission_
 
controller::JointVelocityController vc_
 

Additional Inherited Members

- Public Attributes inherited from pr2_controller_interface::Controller
std::vector< std::string > after_list_
 
 AFTER_ME
 
std::vector< std::string > before_list_
 
 BEFORE_ME
 
 CONSTRUCTED
 
 INITIALIZED
 
 RUNNING
 
enum pr2_controller_interface::Controller:: { ... }  state_
 

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

controller::JointCalibrationController::JointCalibrationController ( )

Definition at line 45 of file joint_calibration_controller.cpp.

controller::JointCalibrationController::~JointCalibrationController ( )
virtual

Definition at line 51 of file joint_calibration_controller.cpp.

Member Function Documentation

bool controller::JointCalibrationController::init ( pr2_mechanism_model::RobotState robot,
ros::NodeHandle n 
)
virtual
bool controller::JointCalibrationController::isCalibrated ( pr2_controllers_msgs::QueryCalibrationState::Request &  req,
pr2_controllers_msgs::QueryCalibrationState::Response &  resp 
)

Definition at line 191 of file joint_calibration_controller.cpp.

void controller::JointCalibrationController::starting ( )
virtual

Reimplemented from pr2_controller_interface::Controller.

Definition at line 183 of file joint_calibration_controller.cpp.

void controller::JointCalibrationController::update ( void  )
virtual

Member Data Documentation

pr2_hardware_interface::Actuator* controller::JointCalibrationController::actuator_
protected

Definition at line 76 of file joint_calibration_controller.h.

int controller::JointCalibrationController::countdown_
protected

Definition at line 71 of file joint_calibration_controller.h.

ros::ServiceServer controller::JointCalibrationController::is_calibrated_srv_
protected

Definition at line 66 of file joint_calibration_controller.h.

pr2_mechanism_model::JointState* controller::JointCalibrationController::joint_
protected

Definition at line 77 of file joint_calibration_controller.h.

ros::Time controller::JointCalibrationController::last_publish_time_
protected

Definition at line 65 of file joint_calibration_controller.h.

ros::NodeHandle controller::JointCalibrationController::node_
protected

Definition at line 64 of file joint_calibration_controller.h.

double controller::JointCalibrationController::original_position_
protected

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.

pr2_mechanism_model::RobotState* controller::JointCalibrationController::robot_
protected

Definition at line 63 of file joint_calibration_controller.h.

double controller::JointCalibrationController::search_velocity_
protected

Definition at line 73 of file joint_calibration_controller.h.

int controller::JointCalibrationController::state_
protected

Definition at line 70 of file joint_calibration_controller.h.

boost::shared_ptr<pr2_mechanism_model::Transmission> controller::JointCalibrationController::transmission_
protected

Definition at line 78 of file joint_calibration_controller.h.

controller::JointVelocityController controller::JointCalibrationController::vc_
protected

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 Wed Jun 5 2019 19:34:12