#include <general_io_passthrough_controller.hpp>

Public Member Functions | |
| void | digital_commands_cb (const std_msgs::BoolConstPtr &msg, int index) |
| GeneralIOPassthroughController () | |
| virtual bool | init (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n) |
| void | pwm_commands_cb (const sr_ronex_msgs::PWMConstPtr &msg, int index) |
| virtual void | update (const ros::Time &, const ros::Duration &) |
| Issues commands to the joint. Should be called at regular intervals. | |
Private Attributes | |
| std::vector< ros::Subscriber > | digital_subscribers_ |
| send commands to the RoNeX's digital I/O | |
| ronex::GeneralIO * | general_io_ |
| int | loop_count_ |
| ros::NodeHandle | node_ |
| std::vector< ros::Subscriber > | pwm_subscribers_ |
| send PWM commands to the RoNeX's | |
Definition at line 42 of file general_io_passthrough_controller.hpp.
Definition at line 33 of file general_io_passthrough_controller.cpp.
| void ronex::GeneralIOPassthroughController::digital_commands_cb | ( | const std_msgs::BoolConstPtr & | msg, |
| int | index | ||
| ) |
Definition at line 116 of file general_io_passthrough_controller.cpp.
| bool ronex::GeneralIOPassthroughController::init | ( | ros_ethercat_model::RobotStateInterface * | robot, |
| ros::NodeHandle & | n | ||
| ) | [virtual] |
Reimplemented from controller_interface::Controller< ros_ethercat_model::RobotStateInterface >.
Definition at line 37 of file general_io_passthrough_controller.cpp.
| void ronex::GeneralIOPassthroughController::pwm_commands_cb | ( | const sr_ronex_msgs::PWMConstPtr & | msg, |
| int | index | ||
| ) |
Definition at line 121 of file general_io_passthrough_controller.cpp.
| virtual void ronex::GeneralIOPassthroughController::update | ( | const ros::Time & | , |
| const ros::Duration & | |||
| ) | [inline, virtual] |
Issues commands to the joint. Should be called at regular intervals.
Implements controller_interface::ControllerBase.
Definition at line 53 of file general_io_passthrough_controller.hpp.
std::vector<ros::Subscriber> ronex::GeneralIOPassthroughController::digital_subscribers_ [private] |
send commands to the RoNeX's digital I/O
Definition at line 67 of file general_io_passthrough_controller.hpp.
Definition at line 64 of file general_io_passthrough_controller.hpp.
int ronex::GeneralIOPassthroughController::loop_count_ [private] |
Definition at line 62 of file general_io_passthrough_controller.hpp.
Definition at line 60 of file general_io_passthrough_controller.hpp.
std::vector<ros::Subscriber> ronex::GeneralIOPassthroughController::pwm_subscribers_ [private] |
send PWM commands to the RoNeX's
Definition at line 69 of file general_io_passthrough_controller.hpp.