#include <sr_board_mk2_gio.hpp>
Public Member Functions | |
virtual void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
void | dynamic_reconfigure_cb (sr_ronex_drivers::GeneralIOConfig &config, uint32_t level) |
virtual int | initialize (hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true) |
SrBoardMk2GIO () | |
virtual | ~SrBoardMk2GIO () |
Protected Member Functions | |
void | build_topics_ () |
building the topics for publishing the state. | |
void | diagnostics (diagnostic_updater::DiagnosticStatusWrapper &d, unsigned char *buffer) |
void | packCommand (unsigned char *buffer, bool halt, bool reset) |
bool | unpackState (unsigned char *this_buffer, unsigned char *prev_buffer) |
Protected Attributes | |
int | command_base_ |
int16_t | cycle_count_ |
std::string | device_name_ |
Name under which the RoNeX will appear (prefix the topics etc...) | |
int | device_offset_ |
Offset of device position from first device. | |
int32u | digital_commands_ |
the digital commands sent at each cycle (updated when we call the topic) | |
boost::scoped_ptr < dynamic_reconfigure::Server < sr_ronex_drivers::GeneralIOConfig > > | dynamic_reconfigure_server_ |
Dynamic reconfigure server for setting the parameters of the driver. | |
dynamic_reconfigure::Server < sr_ronex_drivers::GeneralIOConfig > ::CallbackType | function_cb_ |
ronex::GeneralIO * | general_io_ |
The GeneralIO module which is added as a CustomHW to the hardware interface. | |
bool | has_stacker_ |
True if a stacker board is plugged in the RoNeX. | |
std::vector< bool > | input_mode_ |
False to run digital pins as output, True to run as input. | |
int | level_ |
ros::NodeHandle | node_ |
int | parameter_id_ |
Id of this ronex on the parameter server. | |
string | reason_ |
std::string | ronex_id_ |
A unique identifier for the ronex (either serial number or alias if provided) | |
std::string | serial_number_ |
sr_ronex_msgs::GeneralIOState | state_msg_ |
Temporary message. | |
boost::scoped_ptr < realtime_tools::RealtimePublisher < sr_ronex_msgs::GeneralIOState > > | state_publisher_ |
publisher for the data. | |
int | status_base_ |
Static Protected Attributes | |
static const std::string | product_alias_ = "general_io" |
Replaces the product ID with a human readable product alias. |
Definition at line 42 of file sr_board_mk2_gio.hpp.
Definition at line 42 of file sr_board_mk2_gio.cpp.
SrBoardMk2GIO::~SrBoardMk2GIO | ( | ) | [virtual] |
Definition at line 46 of file sr_board_mk2_gio.cpp.
void SrBoardMk2GIO::build_topics_ | ( | ) | [protected] |
building the topics for publishing the state.
Definition at line 379 of file sr_board_mk2_gio.cpp.
void SrBoardMk2GIO::construct | ( | EtherCAT_SlaveHandler * | sh, |
int & | start_address | ||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 58 of file sr_board_mk2_gio.cpp.
void SrBoardMk2GIO::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | d, |
unsigned char * | buffer | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 320 of file sr_board_mk2_gio.cpp.
void SrBoardMk2GIO::dynamic_reconfigure_cb | ( | sr_ronex_drivers::GeneralIOConfig & | config, |
uint32_t | level | ||
) |
Definition at line 334 of file sr_board_mk2_gio.cpp.
int SrBoardMk2GIO::initialize | ( | hardware_interface::HardwareInterface * | hw, |
bool | allow_unprogrammed = true |
||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 163 of file sr_board_mk2_gio.cpp.
void SrBoardMk2GIO::packCommand | ( | unsigned char * | buffer, |
bool | halt, | ||
bool | reset | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 188 of file sr_board_mk2_gio.cpp.
bool SrBoardMk2GIO::unpackState | ( | unsigned char * | this_buffer, |
unsigned char * | prev_buffer | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 222 of file sr_board_mk2_gio.cpp.
int SrBoardMk2GIO::command_base_ [protected] |
Definition at line 63 of file sr_board_mk2_gio.hpp.
int16_t SrBoardMk2GIO::cycle_count_ [protected] |
A counter used to publish the data at 100Hz: count 10 cycles, then reset the cycle_count to 0.
Definition at line 75 of file sr_board_mk2_gio.hpp.
std::string SrBoardMk2GIO::device_name_ [protected] |
Name under which the RoNeX will appear (prefix the topics etc...)
Definition at line 81 of file sr_board_mk2_gio.hpp.
int SrBoardMk2GIO::device_offset_ [protected] |
Offset of device position from first device.
Definition at line 85 of file sr_board_mk2_gio.hpp.
int32u SrBoardMk2GIO::digital_commands_ [protected] |
the digital commands sent at each cycle (updated when we call the topic)
Definition at line 78 of file sr_board_mk2_gio.hpp.
boost::scoped_ptr<dynamic_reconfigure::Server<sr_ronex_drivers::GeneralIOConfig> > SrBoardMk2GIO::dynamic_reconfigure_server_ [protected] |
Dynamic reconfigure server for setting the parameters of the driver.
Definition at line 104 of file sr_board_mk2_gio.hpp.
dynamic_reconfigure::Server<sr_ronex_drivers::GeneralIOConfig>::CallbackType SrBoardMk2GIO::function_cb_ [protected] |
Definition at line 106 of file sr_board_mk2_gio.hpp.
ronex::GeneralIO* SrBoardMk2GIO::general_io_ [protected] |
The GeneralIO module which is added as a CustomHW to the hardware interface.
Definition at line 69 of file sr_board_mk2_gio.hpp.
bool SrBoardMk2GIO::has_stacker_ [protected] |
True if a stacker board is plugged in the RoNeX.
Definition at line 88 of file sr_board_mk2_gio.hpp.
std::vector<bool> SrBoardMk2GIO::input_mode_ [protected] |
False to run digital pins as output, True to run as input.
Definition at line 91 of file sr_board_mk2_gio.hpp.
int SrBoardMk2GIO::level_ [protected] |
Definition at line 61 of file sr_board_mk2_gio.hpp.
ros::NodeHandle SrBoardMk2GIO::node_ [protected] |
Definition at line 66 of file sr_board_mk2_gio.hpp.
int SrBoardMk2GIO::parameter_id_ [protected] |
Id of this ronex on the parameter server.
Definition at line 112 of file sr_board_mk2_gio.hpp.
const std::string SrBoardMk2GIO::product_alias_ = "general_io" [static, protected] |
Replaces the product ID with a human readable product alias.
Definition at line 55 of file sr_board_mk2_gio.hpp.
string SrBoardMk2GIO::reason_ [protected] |
Definition at line 60 of file sr_board_mk2_gio.hpp.
std::string SrBoardMk2GIO::ronex_id_ [protected] |
A unique identifier for the ronex (either serial number or alias if provided)
Definition at line 58 of file sr_board_mk2_gio.hpp.
std::string SrBoardMk2GIO::serial_number_ [protected] |
Definition at line 82 of file sr_board_mk2_gio.hpp.
sr_ronex_msgs::GeneralIOState SrBoardMk2GIO::state_msg_ [protected] |
Temporary message.
Definition at line 101 of file sr_board_mk2_gio.hpp.
boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_ronex_msgs::GeneralIOState> > SrBoardMk2GIO::state_publisher_ [protected] |
publisher for the data.
Definition at line 99 of file sr_board_mk2_gio.hpp.
int SrBoardMk2GIO::status_base_ [protected] |
Definition at line 64 of file sr_board_mk2_gio.hpp.