#include <DC_motor_small_passthrough_controller.h>
Public Member Functions | |
DCMotorSmallPassthroughController () | |
void | digital_commands_cb (const std_msgs::BoolConstPtr &msg, int index) |
virtual bool | init (ros_ethercat_model::RobotStateInterface *robot, ros::NodeHandle &n) |
void | motor_packet_cb (const sr_ronex_msgs::MotorPacketCommandConstPtr &msg, int index) |
virtual void | stopping (const ros::Time &time) |
virtual void | update (const ros::Time &, const ros::Duration &) |
Issues commands to the joint. Should be called at regular intervals. | |
Private Attributes | |
ronex::DCMotor * | dc_motor_small_ |
std::vector< ros::Subscriber > | digital_subscribers_ |
send commands to the RoNeX's digital I/O | |
int | loop_count_ |
std::vector< ros::Subscriber > | motor_command_subscribers_ |
send commands to the RoNeX's Motor controllers | |
ros::NodeHandle | node_ |
Definition at line 42 of file DC_motor_small_passthrough_controller.h.
Definition at line 33 of file DC_motor_small_passthrough_controller.cpp.
void ronex::DCMotorSmallPassthroughController::digital_commands_cb | ( | const std_msgs::BoolConstPtr & | msg, |
int | index | ||
) |
Definition at line 117 of file DC_motor_small_passthrough_controller.cpp.
bool ronex::DCMotorSmallPassthroughController::init | ( | ros_ethercat_model::RobotStateInterface * | robot, |
ros::NodeHandle & | n | ||
) | [virtual] |
Reimplemented from controller_interface::Controller< ros_ethercat_model::RobotStateInterface >.
Definition at line 38 of file DC_motor_small_passthrough_controller.cpp.
void ronex::DCMotorSmallPassthroughController::motor_packet_cb | ( | const sr_ronex_msgs::MotorPacketCommandConstPtr & | msg, |
int | index | ||
) |
Definition at line 122 of file DC_motor_small_passthrough_controller.cpp.
void ronex::DCMotorSmallPassthroughController::stopping | ( | const ros::Time & | time | ) | [virtual] |
Reimplemented from controller_interface::ControllerBase.
Definition at line 128 of file DC_motor_small_passthrough_controller.cpp.
virtual void ronex::DCMotorSmallPassthroughController::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 DC_motor_small_passthrough_controller.h.
Definition at line 66 of file DC_motor_small_passthrough_controller.h.
std::vector<ros::Subscriber> ronex::DCMotorSmallPassthroughController::digital_subscribers_ [private] |
send commands to the RoNeX's digital I/O
Definition at line 69 of file DC_motor_small_passthrough_controller.h.
int ronex::DCMotorSmallPassthroughController::loop_count_ [private] |
Definition at line 64 of file DC_motor_small_passthrough_controller.h.
std::vector<ros::Subscriber> ronex::DCMotorSmallPassthroughController::motor_command_subscribers_ [private] |
send commands to the RoNeX's Motor controllers
Definition at line 72 of file DC_motor_small_passthrough_controller.h.
Definition at line 62 of file DC_motor_small_passthrough_controller.h.