#include <srh_fake_joint_calibration_controller.h>
Public Member Functions | |
void | beginCalibration () |
bool | calibrated () |
virtual bool | init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n) |
SrhFakeJointCalibrationController () | |
virtual void | update () |
virtual | ~SrhFakeJointCalibrationController () |
Protected Types | |
enum | { INITIALIZED, BEGINNING, MOVING_TO_LOW, MOVING_TO_HIGH, CALIBRATED } |
Protected Member Functions | |
void | initialize_pids () |
Protected Attributes | |
pr2_hardware_interface::Actuator * | actuator_ |
std::string | actuator_name_ |
int | countdown_ |
pr2_mechanism_model::JointState * | joint_ |
std::string | joint_name_ |
ros::Time | last_publish_time_ |
ros::NodeHandle | node_ |
bool | original_switch_state_ |
boost::scoped_ptr < realtime_tools::RealtimePublisher < std_msgs::Empty > > | pub_calibrated_ |
double | reference_position_ |
pr2_mechanism_model::RobotState * | robot_ |
double | search_velocity_ |
int | state_ |
pr2_mechanism_model::Transmission * | transmission_ |
Definition at line 40 of file srh_fake_joint_calibration_controller.h.
anonymous enum [protected] |
Definition at line 64 of file srh_fake_joint_calibration_controller.h.
Definition at line 40 of file srh_fake_joint_calibration_controller.cpp.
Definition at line 46 of file srh_fake_joint_calibration_controller.cpp.
void controller::SrhFakeJointCalibrationController::beginCalibration | ( | ) | [inline] |
Definition at line 51 of file srh_fake_joint_calibration_controller.h.
bool controller::SrhFakeJointCalibrationController::calibrated | ( | ) | [inline] |
Definition at line 50 of file srh_fake_joint_calibration_controller.h.
bool controller::SrhFakeJointCalibrationController::init | ( | pr2_mechanism_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Implements pr2_controller_interface::Controller.
Definition at line 50 of file srh_fake_joint_calibration_controller.cpp.
void controller::SrhFakeJointCalibrationController::initialize_pids | ( | ) | [protected] |
Read the pids values from the parameter server and calls the service to set them on the hand.
Reset the motor to make sure we have the proper 0 + correct PID settings
Definition at line 141 of file srh_fake_joint_calibration_controller.cpp.
void controller::SrhFakeJointCalibrationController::update | ( | void | ) | [virtual] |
Implements pr2_controller_interface::Controller.
Definition at line 107 of file srh_fake_joint_calibration_controller.cpp.
pr2_hardware_interface::Actuator* controller::SrhFakeJointCalibrationController::actuator_ [protected] |
Definition at line 71 of file srh_fake_joint_calibration_controller.h.
std::string controller::SrhFakeJointCalibrationController::actuator_name_ [protected] |
Definition at line 75 of file srh_fake_joint_calibration_controller.h.
int controller::SrhFakeJointCalibrationController::countdown_ [protected] |
Definition at line 66 of file srh_fake_joint_calibration_controller.h.
Definition at line 72 of file srh_fake_joint_calibration_controller.h.
std::string controller::SrhFakeJointCalibrationController::joint_name_ [protected] |
Definition at line 75 of file srh_fake_joint_calibration_controller.h.
Definition at line 62 of file srh_fake_joint_calibration_controller.h.
Definition at line 60 of file srh_fake_joint_calibration_controller.h.
Definition at line 69 of file srh_fake_joint_calibration_controller.h.
boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::Empty> > controller::SrhFakeJointCalibrationController::pub_calibrated_ [protected] |
Definition at line 61 of file srh_fake_joint_calibration_controller.h.
double controller::SrhFakeJointCalibrationController::reference_position_ [protected] |
Definition at line 68 of file srh_fake_joint_calibration_controller.h.
Definition at line 59 of file srh_fake_joint_calibration_controller.h.
double controller::SrhFakeJointCalibrationController::search_velocity_ [protected] |
Definition at line 68 of file srh_fake_joint_calibration_controller.h.
int controller::SrhFakeJointCalibrationController::state_ [protected] |
Reimplemented from pr2_controller_interface::Controller.
Definition at line 65 of file srh_fake_joint_calibration_controller.h.
pr2_mechanism_model::Transmission* controller::SrhFakeJointCalibrationController::transmission_ [protected] |
Definition at line 73 of file srh_fake_joint_calibration_controller.h.