#include <sr_spi.hpp>
Public Member Functions | |
virtual void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
virtual int | initialize (hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true) |
SrSPI () | |
virtual | ~SrSPI () |
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) | |
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. | |
std::string | reason_ |
std::string | ronex_id_ |
A unique identifier for the ronex (either serial number or alias if provided) | |
std::string | serial_number_ |
ronex::SPI * | spi_ |
The SPI module which is added as a CustomHW to the hardware interface. | |
sr_ronex_msgs::SPIState | state_msg_ |
Temporary message. | |
boost::scoped_ptr < realtime_tools::RealtimePublisher < sr_ronex_msgs::SPIState > > | state_publisher_ |
publisher for the data. | |
int | status_base_ |
Static Protected Attributes | |
static const char | product_alias_ [] = PRODUCT_NAME |
Replaces the product ID with a human readable product alias. |
Definition at line 39 of file sr_spi.hpp.
SrSPI::SrSPI | ( | ) |
Definition at line 42 of file sr_spi.cpp.
SrSPI::~SrSPI | ( | ) | [virtual] |
Definition at line 46 of file sr_spi.cpp.
void SrSPI::build_topics_ | ( | ) | [protected] |
building the topics for publishing the state.
Definition at line 320 of file sr_spi.cpp.
void SrSPI::construct | ( | EtherCAT_SlaveHandler * | sh, |
int & | start_address | ||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 59 of file sr_spi.cpp.
void SrSPI::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | d, |
unsigned char * | buffer | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 309 of file sr_spi.cpp.
int SrSPI::initialize | ( | hardware_interface::HardwareInterface * | hw, |
bool | allow_unprogrammed = true |
||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 164 of file sr_spi.cpp.
void SrSPI::packCommand | ( | unsigned char * | buffer, |
bool | halt, | ||
bool | reset | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 189 of file sr_spi.cpp.
bool SrSPI::unpackState | ( | unsigned char * | this_buffer, |
unsigned char * | prev_buffer | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 222 of file sr_spi.cpp.
int SrSPI::command_base_ [protected] |
Definition at line 58 of file sr_spi.hpp.
int16_t SrSPI::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 70 of file sr_spi.hpp.
std::string SrSPI::device_name_ [protected] |
Name under which the RoNeX will appear (prefix the topics etc...)
Definition at line 76 of file sr_spi.hpp.
int SrSPI::device_offset_ [protected] |
Offset of device position from first device.
Definition at line 80 of file sr_spi.hpp.
int32u SrSPI::digital_commands_ [protected] |
the digital commands sent at each cycle (updated when we call the topic)
Definition at line 73 of file sr_spi.hpp.
std::vector<bool> SrSPI::input_mode_ [protected] |
False to run digital pins as output, True to run as input.
Definition at line 83 of file sr_spi.hpp.
int SrSPI::level_ [protected] |
Definition at line 56 of file sr_spi.hpp.
ros::NodeHandle SrSPI::node_ [protected] |
Definition at line 61 of file sr_spi.hpp.
int SrSPI::parameter_id_ [protected] |
Id of this ronex on the parameter server.
Definition at line 99 of file sr_spi.hpp.
const char SrSPI::product_alias_ = PRODUCT_NAME [static, protected] |
Replaces the product ID with a human readable product alias.
Definition at line 50 of file sr_spi.hpp.
std::string SrSPI::reason_ [protected] |
Definition at line 55 of file sr_spi.hpp.
std::string SrSPI::ronex_id_ [protected] |
A unique identifier for the ronex (either serial number or alias if provided)
Definition at line 53 of file sr_spi.hpp.
std::string SrSPI::serial_number_ [protected] |
Definition at line 77 of file sr_spi.hpp.
ronex::SPI* SrSPI::spi_ [protected] |
The SPI module which is added as a CustomHW to the hardware interface.
Definition at line 64 of file sr_spi.hpp.
sr_ronex_msgs::SPIState SrSPI::state_msg_ [protected] |
Temporary message.
Definition at line 93 of file sr_spi.hpp.
boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_ronex_msgs::SPIState> > SrSPI::state_publisher_ [protected] |
publisher for the data.
Definition at line 91 of file sr_spi.hpp.
int SrSPI::status_base_ [protected] |
Definition at line 59 of file sr_spi.hpp.