Public Member Functions | Protected Member Functions | Protected Attributes
sr_cod_decod::CodDecodStdIo Class Reference

#include <cod_decod_std_io.hpp>

Inheritance diagram for sr_cod_decod::CodDecodStdIo:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual void add_diagnostics (std::vector< diagnostic_msgs::DiagnosticStatus > &vec, diagnostic_updater::DiagnosticStatusWrapper &d)
virtual double analogInputToDouble (sr_cod_decod_std_io::AnalogInput input_pin)
 returns the value read from an analog input of the ethercat module
virtual void analogInputToDouble (sr_cod_decod_std_io::AnalogInput input_pin, double *where_to_store_it)
 Maps the value read from an analog input of the ethercat module to a double variable.
int analogInputToInt (sr_cod_decod_std_io::AnalogInput input_pin)
 returns the value read from an analog input of the ethercat module
virtual void analogInputToInt (sr_cod_decod_std_io::AnalogInput input_pin, int *where_to_store_it)
 Maps the value read from an analog input of the ethercat module to a double variable.
uint16_t analogInputToUint16 (sr_cod_decod_std_io::AnalogInput input_pin)
 returns the value read from an analog input of the ethercat module
virtual void analogInputToUint16 (sr_cod_decod_std_io::AnalogInput input_pin, uint16_t *where_to_store_it)
 Maps the value read from an analog input of the ethercat module to a double variable.
virtual void boolToDigitalOutput (sr_cod_decod_std_io::DigitalIo output_pin, bool value)
 Maps the sign of a double value to a digital output of the ethercat module.
virtual void build_command (unsigned char *command_buffer)
 Builds the command for an ethercat device. It contains the output values currently contained in digital_output_ , analog_output_ and PWM_output_.
 CodDecodStdIo ()
virtual void construct (hardware_interface::HardwareInterface *hw, EtherCAT_SlaveHandler *sh, int n_digital_outputs, int n_analog_outputs, int n_digital_inputs, int n_analog_inputs, int n_PWM_outputs)
virtual bool digitalInputToBool (sr_cod_decod_std_io::DigitalIo input_pin)
 returns the value read from a digital input of the ethercat module
virtual void digitalInputToBool (sr_cod_decod_std_io::DigitalIo input_pin, bool *where_to_store_it)
 Maps the value read from a digital input of the ethercat module to a bool variable.
virtual void doubleToAnalogOutput (sr_cod_decod_std_io::AnalogOutput output_pin, double value)
 Sets an analog output using a value from a double variable.
virtual void doubleToPWMOutput (sr_cod_decod_std_io::DigitalIo output_pin, uint16_t PWM_period, double PWM_ON_time)
 Sets a PWM output using PWM_ON_time and PWM_period to determine the PWM signal form.
virtual void setPinAsDigitalInput (sr_cod_decod_std_io::DigitalIo pin)
 Configures a digital I/O pin as digital input.
virtual void signToDigitalOutput (sr_cod_decod_std_io::DigitalIo output_pin, double value)
 Maps the sign of a double value to a digital output of the ethercat module.
virtual void uint16ToAnalogOutput (sr_cod_decod_std_io::AnalogOutput output_pin, uint16_t value)
 Sets an analog output using a value from a uint16 variable.
virtual void uint16ToPWMOutput (sr_cod_decod_std_io::DigitalIo output_pin, uint16_t PWM_period, uint16_t PWM_ON_time)
 Sets a PWM output using PWM_ON_time and PWM_period to determine the PWM signal form.
virtual void update (unsigned char *status_buffer)
 Reads the information from the ethercat device and decodes it. It's stored in d_in_ and a_in_;.

Protected Member Functions

void analogOutputCommandCB (const std_msgs::UInt16MultiArrayConstPtr &msg)
void digitalOutputCommandCB (const sr_ronex_msgs::BoolArrayConstPtr &msg)
void PWMOutputCommandCB (const std_msgs::UInt16MultiArrayConstPtr &msg)

Protected Attributes

std_msgs::UInt16MultiArray a_in_
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< std_msgs::UInt16MultiArray > > 
analog_input_state_publisher_
realtime_tools::RealtimeBox
< boost::shared_ptr
< std_msgs::UInt16MultiArray > > 
analog_output_
unsigned int command_size_
sr_ronex_msgs::BoolArray d_in_
boost::scoped_ptr
< realtime_tools::RealtimePublisher
< sr_ronex_msgs::BoolArray > > 
digital_input_state_publisher_
realtime_tools::RealtimeBox
< boost::shared_ptr
< sr_ronex_msgs::BoolArray > > 
digital_output_
unsigned n_analog_inputs_
unsigned n_analog_outputs_
unsigned n_digital_inputs_
unsigned n_digital_outputs_
unsigned n_PWM_outputs_
ros::NodeHandle node_
realtime_tools::RealtimeBox
< boost::shared_ptr
< std_msgs::UInt16MultiArray > > 
PWM_output_
unsigned int status_size_
ros::Subscriber sub_analog_output_command_
ros::Subscriber sub_digital_output_command_
ros::Subscriber sub_PWM_output_command_

Detailed Description

Definition at line 68 of file cod_decod_std_io.hpp.


Constructor & Destructor Documentation

Definition at line 36 of file cod_decod_std_io.cpp.


Member Function Documentation

void sr_cod_decod::CodDecodStdIo::add_diagnostics ( std::vector< diagnostic_msgs::DiagnosticStatus > &  vec,
diagnostic_updater::DiagnosticStatusWrapper d 
) [virtual]

Reimplemented from sr_cod_decod::CodDecod.

Definition at line 352 of file cod_decod_std_io.cpp.

returns the value read from an analog input of the ethercat module

Parameters:
input_pinthe physical analog input pin of the ethercat module
Returns:
the value read from the analog input

Definition at line 382 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::analogInputToDouble ( sr_cod_decod_std_io::AnalogInput  input_pin,
double *  where_to_store_it 
) [virtual]

Maps the value read from an analog input of the ethercat module to a double variable.

Parameters:
input_pinthe physical analog input pin of the ethercat module
where_to_store_ita pointer to a double variable where we want to write the read value

Definition at line 388 of file cod_decod_std_io.cpp.

returns the value read from an analog input of the ethercat module

Parameters:
input_pinthe physical analog input pin of the ethercat module
Returns:
the value read from the analog input

Definition at line 406 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::analogInputToInt ( sr_cod_decod_std_io::AnalogInput  input_pin,
int *  where_to_store_it 
) [virtual]

Maps the value read from an analog input of the ethercat module to a double variable.

Parameters:
input_pinthe physical analog input pin of the ethercat module
where_to_store_ita pointer to a int variable where we want to write the read value

Definition at line 412 of file cod_decod_std_io.cpp.

returns the value read from an analog input of the ethercat module

Parameters:
input_pinthe physical analog input pin of the ethercat module
Returns:
the value read from the analog input

Definition at line 394 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::analogInputToUint16 ( sr_cod_decod_std_io::AnalogInput  input_pin,
uint16_t *  where_to_store_it 
) [virtual]

Maps the value read from an analog input of the ethercat module to a double variable.

Parameters:
input_pinthe physical analog input pin of the ethercat module
where_to_store_ita pointer to a uint16 variable where we want to write the read value

Definition at line 400 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::analogOutputCommandCB ( const std_msgs::UInt16MultiArrayConstPtr &  msg) [protected]

Definition at line 291 of file cod_decod_std_io.cpp.

Maps the sign of a double value to a digital output of the ethercat module.

Parameters:
output_pinthe physical digital I/O pin of the ethercat module
valuedetermines the value of the digital output

Definition at line 423 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::build_command ( unsigned char *  command_buffer) [virtual]

Builds the command for an ethercat device. It contains the output values currently contained in digital_output_ , analog_output_ and PWM_output_.

Parameters:
command_buffera pointer to the buffer where the command will be written

Reimplemented from sr_cod_decod::CodDecod.

Definition at line 201 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::construct ( hardware_interface::HardwareInterface hw,
EtherCAT_SlaveHandler sh,
int  n_digital_outputs,
int  n_analog_outputs,
int  n_digital_inputs,
int  n_analog_inputs,
int  n_PWM_outputs 
) [virtual]

Reimplemented from sr_cod_decod::CodDecod.

Definition at line 50 of file cod_decod_std_io.cpp.

returns the value read from a digital input of the ethercat module

Parameters:
input_pinthe physical digital I/O pin of the ethercat module
Returns:
the value read from the digital input

Definition at line 370 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::digitalInputToBool ( sr_cod_decod_std_io::DigitalIo  input_pin,
bool *  where_to_store_it 
) [virtual]

Maps the value read from a digital input of the ethercat module to a bool variable.

Parameters:
input_pinthe physical digital I/O pin of the ethercat module
where_to_store_ita pointer to a bool variable where we want to write the read value

Definition at line 376 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::digitalOutputCommandCB ( const sr_ronex_msgs::BoolArrayConstPtr &  msg) [protected]

Definition at line 273 of file cod_decod_std_io.cpp.

Sets an analog output using a value from a double variable.

Parameters:
output_pinthe physical analog output pin of the ethercat module
valuethe value to set the output

Definition at line 437 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::doubleToPWMOutput ( sr_cod_decod_std_io::DigitalIo  output_pin,
uint16_t  PWM_period,
double  PWM_ON_time 
) [virtual]

Sets a PWM output using PWM_ON_time and PWM_period to determine the PWM signal form.

Parameters:
output_pinthe physical digital I/O pin of the ethercat module
PWM_periodthe period of the PWM signal from 0x0000 to 0xFFFE
PWM_ON_timethe ON time of the PWM signal from 0x0000 to 0xFFFF (effectively from 0 to PWM_period+1 )

Definition at line 454 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::PWMOutputCommandCB ( const std_msgs::UInt16MultiArrayConstPtr &  msg) [protected]

Definition at line 309 of file cod_decod_std_io.cpp.

Configures a digital I/O pin as digital input.

Parameters:
pinthe physical digital I/O pin of the ethercat module

Definition at line 358 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::signToDigitalOutput ( sr_cod_decod_std_io::DigitalIo  output_pin,
double  value 
) [virtual]

Maps the sign of a double value to a digital output of the ethercat module.

Parameters:
output_pinthe physical digital I/O pin of the ethercat module
valuea number whose sign will determine the value of the digital output

Definition at line 418 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::uint16ToAnalogOutput ( sr_cod_decod_std_io::AnalogOutput  output_pin,
uint16_t  value 
) [virtual]

Sets an analog output using a value from a uint16 variable.

Parameters:
output_pinthe physical analog output pin of the ethercat module
valuethe value to set the output

Definition at line 442 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::uint16ToPWMOutput ( sr_cod_decod_std_io::DigitalIo  output_pin,
uint16_t  PWM_period,
uint16_t  PWM_ON_time 
) [virtual]

Sets a PWM output using PWM_ON_time and PWM_period to determine the PWM signal form.

Parameters:
output_pinthe physical digital I/O pin of the ethercat module
PWM_periodthe period of the PWM signal from 0x0000 to 0xFFFE
PWM_ON_timethe ON time of the PWM signal from 0x0000 to 0xFFFF (effectively from 0 to PWM_period+1 )

Definition at line 459 of file cod_decod_std_io.cpp.

void sr_cod_decod::CodDecodStdIo::update ( unsigned char *  status_buffer) [virtual]

Reads the information from the ethercat device and decodes it. It's stored in d_in_ and a_in_;.

Parameters:
status_buffera pointer to the buffer containing the info to read

Reimplemented from sr_cod_decod::CodDecod.

Definition at line 140 of file cod_decod_std_io.cpp.


Member Data Documentation

std_msgs::UInt16MultiArray sr_cod_decod::CodDecodStdIo::a_in_ [protected]

Definition at line 236 of file cod_decod_std_io.hpp.

boost::scoped_ptr<realtime_tools::RealtimePublisher<std_msgs::UInt16MultiArray> > sr_cod_decod::CodDecodStdIo::analog_input_state_publisher_ [protected]

Definition at line 229 of file cod_decod_std_io.hpp.

realtime_tools::RealtimeBox<boost::shared_ptr<std_msgs::UInt16MultiArray> > sr_cod_decod::CodDecodStdIo::analog_output_ [protected]

Definition at line 232 of file cod_decod_std_io.hpp.

Definition at line 220 of file cod_decod_std_io.hpp.

sr_ronex_msgs::BoolArray sr_cod_decod::CodDecodStdIo::d_in_ [protected]

Definition at line 235 of file cod_decod_std_io.hpp.

Definition at line 228 of file cod_decod_std_io.hpp.

realtime_tools::RealtimeBox<boost::shared_ptr<sr_ronex_msgs::BoolArray> > sr_cod_decod::CodDecodStdIo::digital_output_ [protected]

Definition at line 231 of file cod_decod_std_io.hpp.

Definition at line 217 of file cod_decod_std_io.hpp.

Definition at line 215 of file cod_decod_std_io.hpp.

Definition at line 216 of file cod_decod_std_io.hpp.

Definition at line 214 of file cod_decod_std_io.hpp.

Definition at line 218 of file cod_decod_std_io.hpp.

Definition at line 242 of file cod_decod_std_io.hpp.

realtime_tools::RealtimeBox<boost::shared_ptr<std_msgs::UInt16MultiArray> > sr_cod_decod::CodDecodStdIo::PWM_output_ [protected]

Definition at line 233 of file cod_decod_std_io.hpp.

Definition at line 221 of file cod_decod_std_io.hpp.

Definition at line 239 of file cod_decod_std_io.hpp.

Definition at line 238 of file cod_decod_std_io.hpp.

Definition at line 240 of file cod_decod_std_io.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