#include <cod_decod_manager.hpp>
Public Member Functions | |
void | build_command (unsigned char *command_buffer) |
CodDecodManager (hardware_interface::HardwareInterface *hw, EtherCAT_SlaveHandler *sh, int n_digital_outputs, int n_analog_outputs, int n_digital_inputs, int n_analog_inputs, int n_PWM_outputs) | |
void | update (unsigned char *status_buffer) |
Private Attributes | |
boost::shared_ptr< CodDecod > | cod_decod_ |
pluginlib::ClassLoader< CodDecod > | cod_decod_loader_ |
ros::NodeHandle | node_ |
Definition at line 39 of file cod_decod_manager.hpp.
sr_cod_decod::CodDecodManager::CodDecodManager | ( | hardware_interface::HardwareInterface * | hw, |
EtherCAT_SlaveHandler * | sh, | ||
int | n_digital_outputs, | ||
int | n_analog_outputs, | ||
int | n_digital_inputs, | ||
int | n_analog_inputs, | ||
int | n_PWM_outputs | ||
) |
Definition at line 36 of file cod_decod_manager.cpp.
void sr_cod_decod::CodDecodManager::build_command | ( | unsigned char * | command_buffer | ) |
Definition at line 131 of file cod_decod_manager.cpp.
void sr_cod_decod::CodDecodManager::update | ( | unsigned char * | status_buffer | ) |
Definition at line 123 of file cod_decod_manager.cpp.
boost::shared_ptr<CodDecod> sr_cod_decod::CodDecodManager::cod_decod_ [private] |
This points to an object of a CodDecod child class. The actual type is decided in the construct function based on the declared plugins, and on the product code and serial number read from the ethercat slave
Definition at line 50 of file cod_decod_manager.hpp.
this ClassLoader allows us to get the list of the declared CodDecod classes and load the one that matches the product code and serial number read from the ethercat slave
Definition at line 55 of file cod_decod_manager.hpp.
Definition at line 52 of file cod_decod_manager.hpp.