#include <sr_board_adc16.hpp>
Public Member Functions | |
virtual void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
void | dynamic_reconfigure_cb (sr_ronex_drivers::ADC16Config &config, uint32_t level) |
virtual int | initialize (hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true) |
SrBoardADC16 () | |
virtual | ~SrBoardADC16 () |
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 | |
ronex::ADC16 * | adc16_ |
The ADC16 module which is added as a CustomHW to the hardware interface. | |
int | command_base_ |
std::queue < RONEX_COMMAND_02000008 > | command_queue_ |
bool | config_received_ |
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::ADC16Config > > | dynamic_reconfigure_server_ |
Dynamic reconfigure server for setting the parameters of the driver. | |
std::vector< uint16_t > | fake_values_s0_ |
std::vector< uint16_t > | fake_values_s1_ |
int | feedback_flag_ |
dynamic_reconfigure::Server < sr_ronex_drivers::ADC16Config > ::CallbackType | function_cb_ |
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_ |
std::vector< uint16_t > | padded_s0_ |
std::vector< uint16_t > | padded_s1_ |
int | parameter_id_ |
Id of this ronex on the parameter server. | |
std::vector< int > | pin_mode_ |
std::queue < RONEX_COMMAND_02000008 > | queue_backup_ |
string | reason_ |
bool | reg_flag_ |
int | reg_state_ |
std::string | ronex_id_ |
A unique identifier for the ronex (either serial number or alias if provided) | |
std::string | serial_number_ |
int | stack |
sr_ronex_msgs::ADC16State | state_msg_ |
Temporary message. | |
boost::scoped_ptr < realtime_tools::RealtimePublisher < sr_ronex_msgs::ADC16State > > | state_publisher_ |
publisher for the data. | |
int | status_base_ |
std::vector< uint16_t > | values_d_ |
std::vector< uint16_t > | values_s0_ |
std::vector< uint16_t > | values_s1_ |
Static Protected Attributes | |
static const std::string | product_alias_ = "adc16" |
Replaces the product ID with a human readable product alias. |
Definition at line 44 of file sr_board_adc16.hpp.
Definition at line 42 of file sr_board_adc16.cpp.
SrBoardADC16::~SrBoardADC16 | ( | ) | [virtual] |
Definition at line 46 of file sr_board_adc16.cpp.
void SrBoardADC16::build_topics_ | ( | ) | [protected] |
building the topics for publishing the state.
Definition at line 593 of file sr_board_adc16.cpp.
void SrBoardADC16::construct | ( | EtherCAT_SlaveHandler * | sh, |
int & | start_address | ||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 58 of file sr_board_adc16.cpp.
void SrBoardADC16::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | d, |
unsigned char * | buffer | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 409 of file sr_board_adc16.cpp.
void SrBoardADC16::dynamic_reconfigure_cb | ( | sr_ronex_drivers::ADC16Config & | config, |
uint32_t | level | ||
) |
Definition at line 422 of file sr_board_adc16.cpp.
int SrBoardADC16::initialize | ( | hardware_interface::HardwareInterface * | hw, |
bool | allow_unprogrammed = true |
||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 163 of file sr_board_adc16.cpp.
void SrBoardADC16::packCommand | ( | unsigned char * | buffer, |
bool | halt, | ||
bool | reset | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 189 of file sr_board_adc16.cpp.
bool SrBoardADC16::unpackState | ( | unsigned char * | this_buffer, |
unsigned char * | prev_buffer | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 249 of file sr_board_adc16.cpp.
ronex::ADC16* SrBoardADC16::adc16_ [protected] |
The ADC16 module which is added as a CustomHW to the hardware interface.
Definition at line 71 of file sr_board_adc16.hpp.
int SrBoardADC16::command_base_ [protected] |
Definition at line 65 of file sr_board_adc16.hpp.
std::queue<RONEX_COMMAND_02000008> SrBoardADC16::command_queue_ [protected] |
Definition at line 105 of file sr_board_adc16.hpp.
bool SrBoardADC16::config_received_ [protected] |
Definition at line 90 of file sr_board_adc16.hpp.
int16_t SrBoardADC16::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 77 of file sr_board_adc16.hpp.
std::string SrBoardADC16::device_name_ [protected] |
Name under which the RoNeX will appear (prefix the topics etc...)
Definition at line 83 of file sr_board_adc16.hpp.
int SrBoardADC16::device_offset_ [protected] |
Offset of device position from first device.
Definition at line 87 of file sr_board_adc16.hpp.
int32u SrBoardADC16::digital_commands_ [protected] |
the digital commands sent at each cycle (updated when we call the topic)
Definition at line 80 of file sr_board_adc16.hpp.
boost::scoped_ptr<dynamic_reconfigure::Server<sr_ronex_drivers::ADC16Config> > SrBoardADC16::dynamic_reconfigure_server_ [protected] |
Dynamic reconfigure server for setting the parameters of the driver.
Definition at line 139 of file sr_board_adc16.hpp.
std::vector<uint16_t> SrBoardADC16::fake_values_s0_ [protected] |
Definition at line 122 of file sr_board_adc16.hpp.
std::vector<uint16_t> SrBoardADC16::fake_values_s1_ [protected] |
Definition at line 123 of file sr_board_adc16.hpp.
int SrBoardADC16::feedback_flag_ [protected] |
Definition at line 96 of file sr_board_adc16.hpp.
dynamic_reconfigure::Server<sr_ronex_drivers::ADC16Config>::CallbackType SrBoardADC16::function_cb_ [protected] |
Definition at line 141 of file sr_board_adc16.hpp.
bool SrBoardADC16::has_stacker_ [protected] |
True if a stacker board is plugged in the RoNeX.
Definition at line 99 of file sr_board_adc16.hpp.
std::vector<bool> SrBoardADC16::input_mode_ [protected] |
False to run digital pins as output, True to run as input.
Definition at line 102 of file sr_board_adc16.hpp.
int SrBoardADC16::level_ [protected] |
Definition at line 63 of file sr_board_adc16.hpp.
ros::NodeHandle SrBoardADC16::node_ [protected] |
Definition at line 68 of file sr_board_adc16.hpp.
std::vector<uint16_t> SrBoardADC16::padded_s0_ [protected] |
Definition at line 124 of file sr_board_adc16.hpp.
std::vector<uint16_t> SrBoardADC16::padded_s1_ [protected] |
Definition at line 125 of file sr_board_adc16.hpp.
int SrBoardADC16::parameter_id_ [protected] |
Id of this ronex on the parameter server.
Definition at line 147 of file sr_board_adc16.hpp.
std::vector<int> SrBoardADC16::pin_mode_ [protected] |
Definition at line 109 of file sr_board_adc16.hpp.
const std::string SrBoardADC16::product_alias_ = "adc16" [static, protected] |
Replaces the product ID with a human readable product alias.
Definition at line 57 of file sr_board_adc16.hpp.
std::queue<RONEX_COMMAND_02000008> SrBoardADC16::queue_backup_ [protected] |
Definition at line 106 of file sr_board_adc16.hpp.
string SrBoardADC16::reason_ [protected] |
Definition at line 62 of file sr_board_adc16.hpp.
bool SrBoardADC16::reg_flag_ [protected] |
Definition at line 92 of file sr_board_adc16.hpp.
int SrBoardADC16::reg_state_ [protected] |
Definition at line 94 of file sr_board_adc16.hpp.
std::string SrBoardADC16::ronex_id_ [protected] |
A unique identifier for the ronex (either serial number or alias if provided)
Definition at line 60 of file sr_board_adc16.hpp.
std::string SrBoardADC16::serial_number_ [protected] |
Definition at line 84 of file sr_board_adc16.hpp.
int SrBoardADC16::stack [protected] |
Definition at line 112 of file sr_board_adc16.hpp.
sr_ronex_msgs::ADC16State SrBoardADC16::state_msg_ [protected] |
Temporary message.
Definition at line 136 of file sr_board_adc16.hpp.
boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_ronex_msgs::ADC16State> > SrBoardADC16::state_publisher_ [protected] |
publisher for the data.
Definition at line 134 of file sr_board_adc16.hpp.
int SrBoardADC16::status_base_ [protected] |
Definition at line 66 of file sr_board_adc16.hpp.
std::vector<uint16_t> SrBoardADC16::values_d_ [protected] |
Definition at line 121 of file sr_board_adc16.hpp.
std::vector<uint16_t> SrBoardADC16::values_s0_ [protected] |
Definition at line 119 of file sr_board_adc16.hpp.
std::vector<uint16_t> SrBoardADC16::values_s1_ [protected] |
Definition at line 120 of file sr_board_adc16.hpp.