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

#include <sr_board_dc_motor_small.hpp>

Inheritance diagram for SrBoardDCMOTORSMALL:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void construct (EtherCAT_SlaveHandler *sh, int &start_address)
void dynamic_reconfigure_cb (sr_ronex_drivers::DCMotorConfig &config, uint32_t level)
virtual int initialize (hardware_interface::HardwareInterface *hw, bool allow_unprogrammed=true)
 SrBoardDCMOTORSMALL ()
virtual ~SrBoardDCMOTORSMALL ()

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_
ronex::DCMotordc_motor_small_
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::DCMotorConfig > > 
dynamic_reconfigure_server_
 Dynamic reconfigure server for setting the parameters of the driver.
dynamic_reconfigure::Server
< sr_ronex_drivers::DCMotorConfig >
::CallbackType 
function_cb_
bool has_stacker_
 True if a stacker board is plugged in the RoNeX.
std::vector< bool > input_mode_
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_
int stack
sr_ronex_msgs::DCMotorState state_msg_
 Temporary message.
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< sr_ronex_msgs::DCMotorState > > 
state_publisher_
 publisher for the data.
int status_base_

Static Protected Attributes

static const std::string product_alias_ = "DC_MOTOR_SMALL"
 Replaces the product ID with a human readable product alias.

Detailed Description

Definition at line 43 of file sr_board_dc_motor_small.hpp.


Constructor & Destructor Documentation

Definition at line 43 of file sr_board_dc_motor_small.cpp.

Definition at line 47 of file sr_board_dc_motor_small.cpp.


Member Function Documentation

void SrBoardDCMOTORSMALL::build_topics_ ( ) [protected]

building the topics for publishing the state.

Definition at line 345 of file sr_board_dc_motor_small.cpp.

void SrBoardDCMOTORSMALL::construct ( EtherCAT_SlaveHandler sh,
int &  start_address 
) [virtual]

Reimplemented from EthercatDevice.

Definition at line 59 of file sr_board_dc_motor_small.cpp.

void SrBoardDCMOTORSMALL::diagnostics ( diagnostic_updater::DiagnosticStatusWrapper d,
unsigned char *  buffer 
) [protected, virtual]

Reimplemented from EthercatDevice.

Definition at line 316 of file sr_board_dc_motor_small.cpp.

void SrBoardDCMOTORSMALL::dynamic_reconfigure_cb ( sr_ronex_drivers::DCMotorConfig &  config,
uint32_t  level 
)

Definition at line 329 of file sr_board_dc_motor_small.cpp.

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

Reimplemented from EthercatDevice.

Definition at line 164 of file sr_board_dc_motor_small.cpp.

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

Reimplemented from EthercatDevice.

Definition at line 189 of file sr_board_dc_motor_small.cpp.

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

Reimplemented from EthercatDevice.

Definition at line 218 of file sr_board_dc_motor_small.cpp.


Member Data Documentation

Definition at line 64 of file sr_board_dc_motor_small.hpp.

int16_t SrBoardDCMOTORSMALL::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 74 of file sr_board_dc_motor_small.hpp.

Definition at line 69 of file sr_board_dc_motor_small.hpp.

std::string SrBoardDCMOTORSMALL::device_name_ [protected]

Name under which the RoNeX will appear (prefix the topics etc...)

Definition at line 79 of file sr_board_dc_motor_small.hpp.

Offset of device position from first device.

Definition at line 83 of file sr_board_dc_motor_small.hpp.

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

Definition at line 77 of file sr_board_dc_motor_small.hpp.

boost::scoped_ptr<dynamic_reconfigure::Server<sr_ronex_drivers::DCMotorConfig> > SrBoardDCMOTORSMALL::dynamic_reconfigure_server_ [protected]

Dynamic reconfigure server for setting the parameters of the driver.

Definition at line 104 of file sr_board_dc_motor_small.hpp.

dynamic_reconfigure::Server<sr_ronex_drivers::DCMotorConfig>::CallbackType SrBoardDCMOTORSMALL::function_cb_ [protected]

Definition at line 106 of file sr_board_dc_motor_small.hpp.

True if a stacker board is plugged in the RoNeX.

Definition at line 86 of file sr_board_dc_motor_small.hpp.

std::vector<bool> SrBoardDCMOTORSMALL::input_mode_ [protected]

Definition at line 91 of file sr_board_dc_motor_small.hpp.

int SrBoardDCMOTORSMALL::level_ [protected]

Definition at line 62 of file sr_board_dc_motor_small.hpp.

Definition at line 67 of file sr_board_dc_motor_small.hpp.

Id of this ronex on the parameter server.

Definition at line 113 of file sr_board_dc_motor_small.hpp.

const std::string SrBoardDCMOTORSMALL::product_alias_ = "DC_MOTOR_SMALL" [static, protected]

Replaces the product ID with a human readable product alias.

Definition at line 56 of file sr_board_dc_motor_small.hpp.

string SrBoardDCMOTORSMALL::reason_ [protected]

Definition at line 61 of file sr_board_dc_motor_small.hpp.

std::string SrBoardDCMOTORSMALL::ronex_id_ [protected]

A unique identifier for the ronex (either serial number or alias if provided)

Definition at line 59 of file sr_board_dc_motor_small.hpp.

std::string SrBoardDCMOTORSMALL::serial_number_ [protected]

Definition at line 80 of file sr_board_dc_motor_small.hpp.

int SrBoardDCMOTORSMALL::stack [protected]

Definition at line 89 of file sr_board_dc_motor_small.hpp.

sr_ronex_msgs::DCMotorState SrBoardDCMOTORSMALL::state_msg_ [protected]

Temporary message.

Definition at line 101 of file sr_board_dc_motor_small.hpp.

boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_ronex_msgs::DCMotorState> > SrBoardDCMOTORSMALL::state_publisher_ [protected]

publisher for the data.

Definition at line 99 of file sr_board_dc_motor_small.hpp.

Definition at line 65 of file sr_board_dc_motor_small.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 Thu Jun 6 2019 21:22:00