#include <fake_calibration_controller.hpp>

Public Member Functions | |
| FakeCalibrationController () | |
| virtual bool | init (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n) |
| virtual void | update (const ros::Time &, const ros::Duration &) |
| Issues commands to the joint. Should be called at regular intervals. | |
Private Types | |
| enum | { INITIALIZED, BEGINNING, MOVING_TO_LOW, MOVING_TO_HIGH, CALIBRATED } |
Private Attributes | |
| std_msgs::Bool | calib_msg_ |
| ros_ethercat_model::JointState * | joint_ |
| std::string | joint_name_ |
| ros::Time | last_publish_time_ |
| ros::NodeHandle | node_ |
| boost::shared_ptr < realtime_tools::RealtimePublisher < std_msgs::Bool > > | pub_calibrated_ |
| ros_ethercat_model::RobotStateInterface * | robot_ |
| int | state_ |
Definition at line 40 of file fake_calibration_controller.hpp.
anonymous enum [private] |
Definition at line 59 of file fake_calibration_controller.hpp.
Definition at line 33 of file fake_calibration_controller.cpp.
| bool ronex::FakeCalibrationController::init | ( | ros_ethercat_model::RobotStateInterface * | robot, |
| ros::NodeHandle & | n | ||
| ) | [virtual] |
Reimplemented from controller_interface::Controller< ros_ethercat_model::RobotStateInterface >.
Definition at line 39 of file fake_calibration_controller.cpp.
| void ronex::FakeCalibrationController::update | ( | const ros::Time & | time, |
| const ros::Duration & | |||
| ) | [virtual] |
Issues commands to the joint. Should be called at regular intervals.
Sets the joint to calibrated = true; Also publishes true to the calibrated topic.
Implements controller_interface::ControllerBase.
Definition at line 83 of file fake_calibration_controller.cpp.
std_msgs::Bool ronex::FakeCalibrationController::calib_msg_ [private] |
Definition at line 65 of file fake_calibration_controller.hpp.
Definition at line 62 of file fake_calibration_controller.hpp.
std::string ronex::FakeCalibrationController::joint_name_ [private] |
Definition at line 63 of file fake_calibration_controller.hpp.
Definition at line 57 of file fake_calibration_controller.hpp.
Definition at line 55 of file fake_calibration_controller.hpp.
boost::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Bool> > ronex::FakeCalibrationController::pub_calibrated_ [private] |
Definition at line 56 of file fake_calibration_controller.hpp.
Definition at line 54 of file fake_calibration_controller.hpp.
int ronex::FakeCalibrationController::state_ [private] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 60 of file fake_calibration_controller.hpp.