#include <sr_ronex_simple_controller.hpp>
Public Member Functions | |
virtual bool | init (ros_ethercat_model::RobotState *robot, ros::NodeHandle &n) |
SrRoNeXSimpleController () | |
virtual void | starting (const ros::Time &) |
virtual void | stopping (const ros::Time &) |
virtual void | update (const ros::Time &, const ros::Duration &) |
virtual | ~SrRoNeXSimpleController () |
Private Attributes | |
ronex::GeneralIO * | general_io_ |
int | loop_count_ |
Definition at line 40 of file sr_ronex_simple_controller.hpp.
Definition at line 32 of file sr_ronex_simple_controller.cpp.
ronex::SrRoNeXSimpleController::~SrRoNeXSimpleController | ( | ) | [virtual] |
Definition at line 37 of file sr_ronex_simple_controller.cpp.
bool ronex::SrRoNeXSimpleController::init | ( | ros_ethercat_model::RobotState * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Reimplemented from controller_interface::Controller< ros_ethercat_model::RobotState >.
Definition at line 41 of file sr_ronex_simple_controller.cpp.
void ronex::SrRoNeXSimpleController::starting | ( | const ros::Time & | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 56 of file sr_ronex_simple_controller.cpp.
void ronex::SrRoNeXSimpleController::stopping | ( | const ros::Time & | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 71 of file sr_ronex_simple_controller.cpp.
void ronex::SrRoNeXSimpleController::update | ( | const ros::Time & | , |
const ros::Duration & | |||
) | [virtual] |
Implements controller_interface::ControllerBase.
Definition at line 61 of file sr_ronex_simple_controller.cpp.
Definition at line 58 of file sr_ronex_simple_controller.hpp.
int ronex::SrRoNeXSimpleController::loop_count_ [private] |
Definition at line 56 of file sr_ronex_simple_controller.hpp.