Skip to content

Commit

Permalink
Work to recieve heartbeat from ODID Scanner
Browse files Browse the repository at this point in the history
  • Loading branch information
shipp02 committed Dec 20, 2023
1 parent 256d61c commit ea24a0d
Show file tree
Hide file tree
Showing 2 changed files with 33 additions and 5 deletions.
29 changes: 24 additions & 5 deletions libraries/AP_ODIDScanner/AP_ODIDScanner.cpp
Original file line number Diff line number Diff line change
@@ -1,17 +1,36 @@
#include "AP_ODIDScanner.h"

AP_ODIDScanner::AP_ODIDScanner() {
// TODO: Random default for mav_port needs fix
AP_ODIDScanner::AP_ODIDScanner() : _mav_port(7){

}
void AP_ODIDScanner::init() {

_chan = mavlink_channel_t(gcs().get_channel_from_port_number(_mav_port));
_initialised = true;
_port = AP::serialmanager().get_serial_by_id(_mav_port);
}

void AP_ODIDScanner::update_recv() {
mavlink_message_t msg;
mavlink_status_t status;
uint32_t tstart_us = AP_HAL::micros();
uint32_t now_ms = AP_HAL::millis();

status.packet_rx_drop_count = 0;

const uint16_t nbytes = _port->available();
for (uint16_t i=0; i<nbytes; i++)
{
const uint8_t c = (uint8_t)_port->read();
if (mavlink_frame_char_buffer(channel_buffer(), channel_status(), c, &msg, &status) == MAVLINK_FRAMING_OK) {
// TODO: How do I process this?
}
}
}
void AP_ODIDScanner::update() {
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - last_send_ms > 5000) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "The driver is here.");
last_send_ms =now_ms;
if (now_ms - last_dev_hb_ms > 5000 && now_ms - last_dev_hb_msg_ms > 5000) {
last_dev_hb_msg_ms = now_ms;
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Scanner: Device Not Found");
}
}
9 changes: 9 additions & 0 deletions libraries/AP_ODIDScanner/AP_ODIDScanner.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,17 @@ class AP_ODIDScanner
mavlink_channel_t _chan; // mavlink channel that communicates with the remote id transceiver
AP_Int8 _mav_port;
mavlink_uav_found_t found_msg;
AP_HaL::UARTDriver* _port;
bool _initialised;
uint32_t last_send_ms;
uint32_t last_dev_hb_ms;
uint32_t last_dev_hb_msg_ms;

mavlink_message_t _channel_buffer;
mavlink_status_t _channel_status;

mavlink_message_t *channel_buffer() { return &_channel_buffer; }
mavlink_status_t *channel_status() { return &_channel_status; }
};

#endif

0 comments on commit ea24a0d

Please sign in to comment.