#include <cod_decod_std_io.hpp>
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_ |
Definition at line 67 of file cod_decod_std_io.hpp.
Definition at line 38 of file cod_decod_std_io.cpp.
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 357 of file cod_decod_std_io.cpp.
double sr_cod_decod::CodDecodStdIo::analogInputToDouble | ( | sr_cod_decod_std_io::AnalogInput | input_pin | ) | [virtual] |
returns the value read from an analog input of the ethercat module
input_pin | the physical analog input pin of the ethercat module |
Definition at line 387 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.
input_pin | the physical analog input pin of the ethercat module |
where_to_store_it | a pointer to a double variable where we want to write the read value |
Definition at line 393 of file cod_decod_std_io.cpp.
returns the value read from an analog input of the ethercat module
input_pin | the physical analog input pin of the ethercat module |
Definition at line 413 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.
input_pin | the physical analog input pin of the ethercat module |
where_to_store_it | a pointer to a int variable where we want to write the read value |
Definition at line 419 of file cod_decod_std_io.cpp.
uint16_t sr_cod_decod::CodDecodStdIo::analogInputToUint16 | ( | sr_cod_decod_std_io::AnalogInput | input_pin | ) |
returns the value read from an analog input of the ethercat module
input_pin | the physical analog input pin of the ethercat module |
Definition at line 400 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.
input_pin | the physical analog input pin of the ethercat module |
where_to_store_it | a pointer to a uint16 variable where we want to write the read value |
Definition at line 406 of file cod_decod_std_io.cpp.
void sr_cod_decod::CodDecodStdIo::analogOutputCommandCB | ( | const std_msgs::UInt16MultiArrayConstPtr & | msg | ) | [protected] |
Definition at line 296 of file cod_decod_std_io.cpp.
void sr_cod_decod::CodDecodStdIo::boolToDigitalOutput | ( | sr_cod_decod_std_io::DigitalIo | output_pin, |
bool | value | ||
) | [virtual] |
Maps the sign of a double value to a digital output of the ethercat module.
output_pin | the physical digital I/O pin of the ethercat module |
value | determines the value of the digital output |
Definition at line 431 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_.
command_buffer | a pointer to the buffer where the command will be written |
Reimplemented from sr_cod_decod::CodDecod.
Definition at line 208 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 52 of file cod_decod_std_io.cpp.
bool sr_cod_decod::CodDecodStdIo::digitalInputToBool | ( | sr_cod_decod_std_io::DigitalIo | input_pin | ) | [virtual] |
returns the value read from a digital input of the ethercat module
input_pin | the physical digital I/O pin of the ethercat module |
Definition at line 374 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.
input_pin | the physical digital I/O pin of the ethercat module |
where_to_store_it | a pointer to a bool variable where we want to write the read value |
Definition at line 380 of file cod_decod_std_io.cpp.
void sr_cod_decod::CodDecodStdIo::digitalOutputCommandCB | ( | const sr_ronex_msgs::BoolArrayConstPtr & | msg | ) | [protected] |
Definition at line 278 of file cod_decod_std_io.cpp.
void sr_cod_decod::CodDecodStdIo::doubleToAnalogOutput | ( | sr_cod_decod_std_io::AnalogOutput | output_pin, |
double | value | ||
) | [virtual] |
Sets an analog output using a value from a double variable.
output_pin | the physical analog output pin of the ethercat module |
value | the value to set the output |
Definition at line 446 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.
output_pin | the physical digital I/O pin of the ethercat module |
PWM_period | the period of the PWM signal from 0x0000 to 0xFFFE |
PWM_ON_time | the ON time of the PWM signal from 0x0000 to 0xFFFF (effectively from 0 to PWM_period+1 ) |
Definition at line 464 of file cod_decod_std_io.cpp.
void sr_cod_decod::CodDecodStdIo::PWMOutputCommandCB | ( | const std_msgs::UInt16MultiArrayConstPtr & | msg | ) | [protected] |
Definition at line 314 of file cod_decod_std_io.cpp.
void sr_cod_decod::CodDecodStdIo::setPinAsDigitalInput | ( | sr_cod_decod_std_io::DigitalIo | pin | ) | [virtual] |
Configures a digital I/O pin as digital input.
pin | the physical digital I/O pin of the ethercat module |
Definition at line 361 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.
output_pin | the physical digital I/O pin of the ethercat module |
value | a number whose sign will determine the value of the digital output |
Definition at line 426 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.
output_pin | the physical analog output pin of the ethercat module |
value | the value to set the output |
Definition at line 451 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.
output_pin | the physical digital I/O pin of the ethercat module |
PWM_period | the period of the PWM signal from 0x0000 to 0xFFFE |
PWM_ON_time | the ON time of the PWM signal from 0x0000 to 0xFFFF (effectively from 0 to PWM_period+1 ) |
Definition at line 472 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_;.
status_buffer | a pointer to the buffer containing the info to read |
Reimplemented from sr_cod_decod::CodDecod.
Definition at line 147 of file cod_decod_std_io.cpp.
std_msgs::UInt16MultiArray sr_cod_decod::CodDecodStdIo::a_in_ [protected] |
Definition at line 237 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 230 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 233 of file cod_decod_std_io.hpp.
unsigned int sr_cod_decod::CodDecodStdIo::command_size_ [protected] |
Definition at line 221 of file cod_decod_std_io.hpp.
sr_ronex_msgs::BoolArray sr_cod_decod::CodDecodStdIo::d_in_ [protected] |
Definition at line 236 of file cod_decod_std_io.hpp.
boost::scoped_ptr<realtime_tools::RealtimePublisher<sr_ronex_msgs::BoolArray> > sr_cod_decod::CodDecodStdIo::digital_input_state_publisher_ [protected] |
Definition at line 229 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 232 of file cod_decod_std_io.hpp.
unsigned sr_cod_decod::CodDecodStdIo::n_analog_inputs_ [protected] |
Definition at line 218 of file cod_decod_std_io.hpp.
unsigned sr_cod_decod::CodDecodStdIo::n_analog_outputs_ [protected] |
Definition at line 216 of file cod_decod_std_io.hpp.
unsigned sr_cod_decod::CodDecodStdIo::n_digital_inputs_ [protected] |
Definition at line 217 of file cod_decod_std_io.hpp.
unsigned sr_cod_decod::CodDecodStdIo::n_digital_outputs_ [protected] |
Definition at line 215 of file cod_decod_std_io.hpp.
unsigned sr_cod_decod::CodDecodStdIo::n_PWM_outputs_ [protected] |
Definition at line 219 of file cod_decod_std_io.hpp.
ros::NodeHandle sr_cod_decod::CodDecodStdIo::node_ [protected] |
Definition at line 243 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 234 of file cod_decod_std_io.hpp.
unsigned int sr_cod_decod::CodDecodStdIo::status_size_ [protected] |
Definition at line 222 of file cod_decod_std_io.hpp.
Definition at line 240 of file cod_decod_std_io.hpp.
Definition at line 239 of file cod_decod_std_io.hpp.
Definition at line 241 of file cod_decod_std_io.hpp.