#include <ArduinoDAQ_LowLevel.h>
Public Member Functions | |
ArduinoDAQ_LowLevel () | |
bool | CMD_ADC_START (const TFrameCMD_ADC_start_payload_t &enc_config) |
bool | CMD_ADC_STOP () |
bool | CMD_DAC (int dac_index, double dac_value_volts) |
bool | CMD_ENCODER_ABS_START (const TFrameCMD_EMS22A_start_payload_t &enc_config) |
bool | CMD_ENCODER_ABS_STOP () |
bool | CMD_ENCODERS_START (const TFrameCMD_ENCODERS_start_payload_t &enc_config) |
bool | CMD_ENCODERS_STOP () |
bool | CMD_GPIO_output (int pin, bool pinState) |
Sets the clutch. More... | |
bool | CMD_PWM (int pin_index, uint8_t pwm_value) |
std::string | getSerialPort () const |
bool | initialize () |
bool | iterate () |
void | set_ADC_readings_callback (const std::function< void(TFrame_ADC_readings_payload_t)> &f) |
void | set_ENCODER_ABS_readings_callback (const std::function< void(TFrame_ENCODER_ABS_reading_payload_t)> &f) |
void | set_ENCODERS_readings_callback (const std::function< void(TFrame_ENCODERS_readings_payload_t)> &f) |
void | setSerialPort (const std::string &sSerialName) |
virtual | ~ArduinoDAQ_LowLevel () |
Protected Member Functions | |
bool | AttemptConnection () |
Returns true if connected OK, false on error. More... | |
void | daqOnNewADCCallback (const TFrame_ADC_readings_payload_t &data) |
void | daqOnNewENCAbsCallback (const TFrame_ENCODER_ABS_reading_payload_t &data) |
void | daqOnNewENCCallback (const TFrame_ENCODERS_readings_payload_t &data) |
bool | IsConnected () const |
Returns true if the serial comms are working. More... | |
void | processIncommingFrame (const std::vector< uint8_t > &rxFrame) |
bool | ReceiveFrameFromController (std::vector< uint8_t > &rx_data) |
Tries to get a framed chunk of data from the controller. More... | |
bool | SendFrameAndWaitAnswer (const uint8_t *full_frame, const size_t full_frame_len, const int num_retries=10, const int retries_interval_ms=40, uint8_t expected_ans_opcode=0) |
Sends a binary packet, in the expected format (returns false on COMMS error) More... | |
bool | WriteBinaryFrame (const uint8_t *full_frame, const size_t full_frame_len) |
Sends a binary packet, in the expected format (returns false on COMMS error) More... | |
Protected Attributes | |
std::function< void(TFrame_ADC_readings_payload_t)> | m_adc_callback |
std::function< void(TFrame_ENCODERS_readings_payload_t)> | m_enc_callback |
std::function< void(TFrame_ENCODER_ABS_reading_payload_t)> | m_encabs_callback |
int | m_NOP_sent_counter {0} |
CSerialPort | m_serial |
The serial COMMS object. More... | |
int | m_serial_port_baudrate |
std::string | m_serial_port_name |
Definition at line 59 of file ArduinoDAQ_LowLevel.h.
ArduinoDAQ_LowLevel::ArduinoDAQ_LowLevel | ( | ) |
Definition at line 90 of file ArduinoDAQ_LowLevel.cpp.
|
virtual |
Definition at line 115 of file ArduinoDAQ_LowLevel.cpp.
|
protected |
Returns true if connected OK, false on error.
Definition at line 434 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::CMD_ADC_START | ( | const TFrameCMD_ADC_start_payload_t & | enc_config | ) |
Definition at line 670 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::CMD_ADC_STOP | ( | ) |
Definition at line 678 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::CMD_DAC | ( | int | dac_index, |
double | dac_value_volts | ||
) |
Definition at line 649 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::CMD_ENCODER_ABS_START | ( | const TFrameCMD_EMS22A_start_payload_t & | enc_config | ) |
Definition at line 702 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::CMD_ENCODER_ABS_STOP | ( | ) |
Definition at line 710 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::CMD_ENCODERS_START | ( | const TFrameCMD_ENCODERS_start_payload_t & | enc_config | ) |
Definition at line 686 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::CMD_ENCODERS_STOP | ( | ) |
Definition at line 694 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::CMD_GPIO_output | ( | int | pin, |
bool | pinState | ||
) |
Sets the clutch.
Definition at line 637 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::CMD_PWM | ( | int | pin_index, |
uint8_t | pwm_value | ||
) |
Definition at line 718 of file ArduinoDAQ_LowLevel.cpp.
|
protected |
|
protected |
|
protected |
|
inline |
Definition at line 81 of file ArduinoDAQ_LowLevel.h.
bool ArduinoDAQ_LowLevel::initialize | ( | ) |
called at startup, load params from ROS launch file and attempts to connect to the USB device
Definition at line 119 of file ArduinoDAQ_LowLevel.cpp.
|
protected |
Returns true if the serial comms are working.
Definition at line 665 of file ArduinoDAQ_LowLevel.cpp.
bool ArduinoDAQ_LowLevel::iterate | ( | ) |
called when work is to be done
Definition at line 330 of file ArduinoDAQ_LowLevel.cpp.
Definition at line 284 of file ArduinoDAQ_LowLevel.cpp.
|
protected |
Tries to get a framed chunk of data from the controller.
Definition at line 530 of file ArduinoDAQ_LowLevel.cpp.
|
protected |
Sends a binary packet, in the expected format (returns false on COMMS error)
Definition at line 488 of file ArduinoDAQ_LowLevel.cpp.
|
inline |
Definition at line 102 of file ArduinoDAQ_LowLevel.h.
|
inline |
Definition at line 108 of file ArduinoDAQ_LowLevel.h.
|
inline |
Definition at line 105 of file ArduinoDAQ_LowLevel.h.
|
inline |
Definition at line 78 of file ArduinoDAQ_LowLevel.h.
|
protected |
Sends a binary packet, in the expected format (returns false on COMMS error)
Sends a binary packet (returns false on COMMS error)
Definition at line 457 of file ArduinoDAQ_LowLevel.cpp.
|
protected |
Definition at line 133 of file ArduinoDAQ_LowLevel.h.
|
protected |
Definition at line 134 of file ArduinoDAQ_LowLevel.h.
|
protected |
Definition at line 135 of file ArduinoDAQ_LowLevel.h.
|
protected |
Definition at line 117 of file ArduinoDAQ_LowLevel.h.
|
protected |
The serial COMMS object.
Definition at line 116 of file ArduinoDAQ_LowLevel.h.
|
protected |
Definition at line 115 of file ArduinoDAQ_LowLevel.h.
|
protected |
Definition at line 114 of file ArduinoDAQ_LowLevel.h.