#include <gripper_calibration_controller.h>

Public Member Functions | |
| GripperCalibrationController () | |
| 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 () |
| ~GripperCalibrationController () | |
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, STARTING, CLOSING, BACK_OFF, CLOSING_SLOWLY, CALIBRATED } |
Protected Attributes | |
| pr2_hardware_interface::Actuator * | actuator_ |
| int | count_ |
| double | init_time |
| ros::ServiceServer | is_calibrated_srv_ |
| pr2_mechanism_model::JointState * | joint_ |
| ros::Time | last_publish_time_ |
| ros::NodeHandle | node_ |
| std::vector< pr2_mechanism_model::JointState * > | other_joints_ |
| boost::scoped_ptr< realtime_tools::RealtimePublisher< std_msgs::Empty > > | pub_calibrated_ |
| pr2_mechanism_model::RobotState * | robot_ |
| double | search_velocity_ |
| int | state_ |
| int | stop_count_ |
| double | stopped_velocity_tolerance_ |
| 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_ |
Definition at line 48 of file gripper_calibration_controller.h.
|
protected |
| Enumerator | |
|---|---|
| INITIALIZED | |
| BEGINNING | |
| STARTING | |
| CLOSING | |
| BACK_OFF | |
| CLOSING_SLOWLY | |
| CALIBRATED | |
Definition at line 63 of file gripper_calibration_controller.h.
| controller::GripperCalibrationController::GripperCalibrationController | ( | ) |
Definition at line 47 of file gripper_calibration_controller.cpp.
| controller::GripperCalibrationController::~GripperCalibrationController | ( | ) |
Definition at line 52 of file gripper_calibration_controller.cpp.
|
virtual |
Implements pr2_controller_interface::Controller.
Definition at line 56 of file gripper_calibration_controller.cpp.
| bool controller::GripperCalibrationController::isCalibrated | ( | pr2_controllers_msgs::QueryCalibrationState::Request & | req, |
| pr2_controllers_msgs::QueryCalibrationState::Response & | resp | ||
| ) |
Definition at line 168 of file gripper_calibration_controller.cpp.
|
virtual |
Reimplemented from pr2_controller_interface::Controller.
Definition at line 160 of file gripper_calibration_controller.cpp.
|
virtual |
Implements pr2_controller_interface::Controller.
Definition at line 176 of file gripper_calibration_controller.cpp.
|
protected |
Definition at line 75 of file gripper_calibration_controller.h.
|
protected |
Definition at line 65 of file gripper_calibration_controller.h.
|
protected |
Definition at line 79 of file gripper_calibration_controller.h.
|
protected |
Definition at line 71 of file gripper_calibration_controller.h.
|
protected |
Definition at line 76 of file gripper_calibration_controller.h.
|
protected |
Definition at line 70 of file gripper_calibration_controller.h.
|
protected |
Definition at line 68 of file gripper_calibration_controller.h.
|
protected |
Definition at line 77 of file gripper_calibration_controller.h.
|
protected |
Definition at line 72 of file gripper_calibration_controller.h.
|
protected |
Definition at line 69 of file gripper_calibration_controller.h.
|
protected |
Definition at line 74 of file gripper_calibration_controller.h.
|
protected |
Definition at line 64 of file gripper_calibration_controller.h.
|
protected |
Definition at line 66 of file gripper_calibration_controller.h.
|
protected |
Definition at line 80 of file gripper_calibration_controller.h.
|
protected |
Definition at line 82 of file gripper_calibration_controller.h.