38 #include <mrpt/version.h> 39 #if MRPT_VERSION>=0x199 40 # include <mrpt/comms/CSerialPort.h> 41 using mrpt::comms::CSerialPort;
49 #include <std_msgs/UInt8.h> 50 #include <std_msgs/Bool.h> 51 #include <std_msgs/Float64.h> 74 std::vector<ros::Subscriber> m_sub_GPIO_outputs, m_sub_dac, m_sub_PWM_outputs;
93 bool CMD_DAC(
int dac_index,
double dac_value_volts);
124 bool WriteBinaryFrame(
const uint8_t *full_frame,
const size_t full_frame_len);
126 const uint8_t *full_frame,
127 const size_t full_frame_len,
128 const int num_retries = 10,
129 const int retries_interval_ms = 40,
130 uint8_t expected_ans_opcode = 0
138 void daqSetDigitalPinCallback(
int index,
const std_msgs::Bool::ConstPtr& msg);
139 void daqSetDACCallback(
int dac_index,
const std_msgs::Float64::ConstPtr& msg);
140 void daqSetPWMCallback(
int pwm_pin_index,
const std_msgs::UInt8::ConstPtr& msg);
void daqOnNewADCCallback(const TFrame_ADC_readings_payload_t &data)
bool CMD_GPIO_output(int pin, bool pinState)
Sets the clutch.
virtual ~ArduinoDAQ_LowLevel()
bool AttemptConnection()
Returns true if connected OK, false on error.
bool CMD_ADC_START(const TFrameCMD_ADC_start_payload_t &enc_config)
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)
bool IsConnected() const
Returns true if the serial comms are working.
void daqOnNewENCCallback(const TFrame_ENCODERS_readings_payload_t &data)
bool CMD_DAC(int dac_index, double dac_value_volts)
void set_ENCODERS_readings_callback(const std::function< void(TFrame_ENCODERS_readings_payload_t)> &f)
int m_serial_port_baudrate
void daqOnNewENCAbsCallback(const TFrame_ENCODER_ABS_reading_payload_t &data)
GLint GLenum GLsizei GLint GLsizei const GLvoid * data
bool CMD_ENCODER_ABS_STOP()
std::function< void(TFrame_ADC_readings_payload_t)> m_adc_callback
std::function< void(TFrame_ENCODER_ABS_reading_payload_t)> m_encabs_callback
bool CMD_ENCODER_ABS_START(const TFrameCMD_EMS22A_start_payload_t &enc_config)
CSerialPort m_serial
The serial COMMS object.
std::string getSerialPort() const
bool CMD_ENCODERS_START(const TFrameCMD_ENCODERS_start_payload_t &enc_config)
std::function< void(TFrame_ENCODERS_readings_payload_t)> m_enc_callback
std::string m_serial_port_name
bool CMD_PWM(int pin_index, uint8_t pwm_value)
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)
void set_ADC_readings_callback(const std::function< void(TFrame_ADC_readings_payload_t)> &f)
void setSerialPort(const std::string &sSerialName)
void set_ENCODER_ABS_readings_callback(const std::function< void(TFrame_ENCODER_ABS_reading_payload_t)> &f)
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.
GLdouble GLdouble GLdouble GLdouble GLdouble GLdouble f