Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes
SrSPI Class Reference

#include <sr_spi.hpp>

Inheritance diagram for SrSPI:
Inheritance graph
[legend]

List of all members.

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_
short 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::SPIspi_
 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 std::string product_alias_ = PRODUCT_NAME
 Replaces the product ID with a human readable product alias.

Detailed Description

Definition at line 38 of file sr_spi.hpp.


Constructor & Destructor Documentation

Definition at line 42 of file sr_spi.cpp.

SrSPI::~SrSPI ( ) [virtual]

Definition at line 46 of file sr_spi.cpp.


Member Function Documentation

void SrSPI::build_topics_ ( ) [protected]

building the topics for publishing the state.

Definition at line 300 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 289 of file sr_spi.cpp.

int SrSPI::initialize ( hardware_interface::HardwareInterface hw,
bool  allow_unprogrammed = true 
) [virtual]

Reimplemented from EthercatDevice.

Definition at line 163 of file sr_spi.cpp.

void SrSPI::packCommand ( unsigned char *  buffer,
bool  halt,
bool  reset 
) [protected, virtual]

Reimplemented from EthercatDevice.

Definition at line 188 of file sr_spi.cpp.

bool SrSPI::unpackState ( unsigned char *  this_buffer,
unsigned char *  prev_buffer 
) [protected, virtual]

Reimplemented from EthercatDevice.

Definition at line 220 of file sr_spi.cpp.


Member Data Documentation

int SrSPI::command_base_ [protected]

Definition at line 57 of file sr_spi.hpp.

short 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 69 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 75 of file sr_spi.hpp.

int SrSPI::device_offset_ [protected]

Offset of device position from first device.

Definition at line 79 of file sr_spi.hpp.

the digital commands sent at each cycle (updated when we call the topic)

Definition at line 72 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 82 of file sr_spi.hpp.

int SrSPI::level_ [protected]

Definition at line 55 of file sr_spi.hpp.

Definition at line 60 of file sr_spi.hpp.

int SrSPI::parameter_id_ [protected]

Id of this ronex on the parameter server.

Definition at line 98 of file sr_spi.hpp.

const string SrSPI::product_alias_ = PRODUCT_NAME [static, protected]

Replaces the product ID with a human readable product alias.

Definition at line 49 of file sr_spi.hpp.

std::string SrSPI::reason_ [protected]

Definition at line 54 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 52 of file sr_spi.hpp.

std::string SrSPI::serial_number_ [protected]

Definition at line 76 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 63 of file sr_spi.hpp.

sr_ronex_msgs::SPIState SrSPI::state_msg_ [protected]

Temporary message.

Definition at line 92 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 90 of file sr_spi.hpp.

int SrSPI::status_base_ [protected]

Definition at line 58 of file sr_spi.hpp.


The documentation for this class was generated from the following files:


sr_ronex_drivers
Author(s): Ugo Cupcic, Toni Oliver, Mark Pitchless
autogenerated on Fri Aug 28 2015 13:12:23