#include <sr_tcat.hpp>
Public Member Functions | |
virtual void | construct (EtherCAT_SlaveHandler *sh, int &start_address) |
virtual int | initialize (hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true) |
SrTCAT () | |
virtual | ~SrTCAT () |
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_ |
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. | |
int | level_ |
ros::NodeHandle | node_ |
int | parameter_id_ |
Id of this ronex on the parameter server. | |
int16u | previous_sequence_number_ |
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::TCATState | state_msg_ |
Temporary message. | |
boost::scoped_ptr < realtime_tools::RealtimePublisher < sr_ronex_msgs::TCATState > > | state_publisher_ |
publisher for the data. | |
int | status_base_ |
Static Protected Attributes | |
static const std::string | product_alias_ = "tcat" |
Replaces the product ID with a human readable product alias. |
Definition at line 40 of file sr_tcat.hpp.
SrTCAT::SrTCAT | ( | ) |
Definition at line 38 of file sr_tcat.cpp.
SrTCAT::~SrTCAT | ( | ) | [virtual] |
Definition at line 42 of file sr_tcat.cpp.
void SrTCAT::build_topics_ | ( | ) | [protected] |
building the topics for publishing the state.
Definition at line 285 of file sr_tcat.cpp.
void SrTCAT::construct | ( | EtherCAT_SlaveHandler * | sh, |
int & | start_address | ||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 50 of file sr_tcat.cpp.
void SrTCAT::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | d, |
unsigned char * | buffer | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 276 of file sr_tcat.cpp.
int SrTCAT::initialize | ( | hardware_interface::HardwareInterface * | hw, |
bool | allow_unprogrammed = true |
||
) | [virtual] |
Reimplemented from EthercatDevice.
Definition at line 157 of file sr_tcat.cpp.
void SrTCAT::packCommand | ( | unsigned char * | buffer, |
bool | halt, | ||
bool | reset | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 176 of file sr_tcat.cpp.
bool SrTCAT::unpackState | ( | unsigned char * | this_buffer, |
unsigned char * | prev_buffer | ||
) | [protected, virtual] |
Reimplemented from EthercatDevice.
Definition at line 183 of file sr_tcat.cpp.
int SrTCAT::command_base_ [protected] |
Definition at line 59 of file sr_tcat.hpp.
std::string SrTCAT::device_name_ [protected] |
Name under which the RoNeX will appear (prefix the topics etc...)
Definition at line 71 of file sr_tcat.hpp.
int SrTCAT::device_offset_ [protected] |
Offset of device position from first device.
Definition at line 75 of file sr_tcat.hpp.
int SrTCAT::level_ [protected] |
Definition at line 57 of file sr_tcat.hpp.
ros::NodeHandle SrTCAT::node_ [protected] |
Definition at line 62 of file sr_tcat.hpp.
int SrTCAT::parameter_id_ [protected] |
Id of this ronex on the parameter server.
Definition at line 91 of file sr_tcat.hpp.
int16u SrTCAT::previous_sequence_number_ [protected] |
Stores the previous sequence number: we publish the data when this number is changed as it means we've received all the data
Definition at line 68 of file sr_tcat.hpp.
const std::string SrTCAT::product_alias_ = "tcat" [static, protected] |
Replaces the product ID with a human readable product alias.
Definition at line 51 of file sr_tcat.hpp.
string SrTCAT::reason_ [protected] |
Definition at line 56 of file sr_tcat.hpp.
std::string SrTCAT::ronex_id_ [protected] |
A unique identifier for the ronex (either serial number or alias if provided)
Definition at line 54 of file sr_tcat.hpp.
std::string SrTCAT::serial_number_ [protected] |
Definition at line 72 of file sr_tcat.hpp.
sr_ronex_msgs::TCATState SrTCAT::state_msg_ [protected] |
Temporary message.
Definition at line 85 of file sr_tcat.hpp.
boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_ronex_msgs::TCATState> > SrTCAT::state_publisher_ [protected] |
publisher for the data.
Definition at line 83 of file sr_tcat.hpp.
int SrTCAT::status_base_ [protected] |
Definition at line 60 of file sr_tcat.hpp.