#include <srh_fake_joint_calibration_controller.h>
Public Member Functions | |
void | beginCalibration () |
bool | calibrated () |
virtual bool | init (ros_ethercat_model::RobotState *robot, ros::NodeHandle &n) |
SrhFakeJointCalibrationController () | |
virtual void | update (const ros::Time &time, const ros::Duration &period) |
Protected Types | |
enum | { IS_INITIALIZED, BEGINNING, MOVING_TO_LOW, MOVING_TO_HIGH, CALIBRATED } |
Protected Member Functions | |
void | initialize_pids () |
Protected Attributes | |
ros_ethercat_model::Actuator * | actuator_ |
std::string | actuator_name_ |
int | calibration_state_ |
ros_ethercat_model::JointState * | joint_ |
std::string | joint_name_ |
std::string | joint_prefix_ |
ros::Time | last_publish_time_ |
ros::NodeHandle | node_ |
std::string | ns_ |
boost::scoped_ptr < realtime_tools::RealtimePublisher < std_msgs::Empty > > | pub_calibrated_ |
ros_ethercat_model::RobotState * | robot_ |
std::string | robot_id_ |
Definition at line 42 of file srh_fake_joint_calibration_controller.h.
anonymous enum [protected] |
Definition at line 65 of file srh_fake_joint_calibration_controller.h.
Definition at line 40 of file srh_fake_joint_calibration_controller.cpp.
void controller::SrhFakeJointCalibrationController::beginCalibration | ( | ) | [inline] |
Definition at line 52 of file srh_fake_joint_calibration_controller.h.
bool controller::SrhFakeJointCalibrationController::calibrated | ( | ) | [inline] |
Definition at line 51 of file srh_fake_joint_calibration_controller.h.
bool controller::SrhFakeJointCalibrationController::init | ( | ros_ethercat_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Reimplemented from controller_interface::Controller< ros_ethercat_model::RobotState >.
Definition at line 49 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 140 of file srh_fake_joint_calibration_controller.cpp.
void controller::SrhFakeJointCalibrationController::update | ( | const ros::Time & | time, |
const ros::Duration & | period | ||
) | [virtual] |
Implements controller_interface::ControllerBase.
Definition at line 106 of file srh_fake_joint_calibration_controller.cpp.
Definition at line 68 of file srh_fake_joint_calibration_controller.h.
Definition at line 71 of file srh_fake_joint_calibration_controller.h.
Definition at line 66 of file srh_fake_joint_calibration_controller.h.
Definition at line 69 of file srh_fake_joint_calibration_controller.h.
Definition at line 71 of file srh_fake_joint_calibration_controller.h.
Definition at line 71 of file srh_fake_joint_calibration_controller.h.
Definition at line 63 of file srh_fake_joint_calibration_controller.h.
Definition at line 61 of file srh_fake_joint_calibration_controller.h.
Definition at line 71 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 62 of file srh_fake_joint_calibration_controller.h.
Definition at line 60 of file srh_fake_joint_calibration_controller.h.
Definition at line 71 of file srh_fake_joint_calibration_controller.h.