From 4e349450a74b8abfbf691cc8f78cc3245e7174bf Mon Sep 17 00:00:00 2001 From: Aashay Shah Date: Thu, 21 Dec 2023 06:15:11 +0800 Subject: [PATCH] Changes to compile --- libraries/AP_ODIDScanner/AP_ODIDScanner.cpp | 3 +-- libraries/AP_ODIDScanner/AP_ODIDScanner.h | 6 ++++-- libraries/AP_Vehicle/AP_Vehicle.cpp | 1 + 3 files changed, 6 insertions(+), 4 deletions(-) diff --git a/libraries/AP_ODIDScanner/AP_ODIDScanner.cpp b/libraries/AP_ODIDScanner/AP_ODIDScanner.cpp index f6cfe11857f7c..3d4ee93dbc18d 100644 --- a/libraries/AP_ODIDScanner/AP_ODIDScanner.cpp +++ b/libraries/AP_ODIDScanner/AP_ODIDScanner.cpp @@ -13,8 +13,7 @@ void AP_ODIDScanner::init() { 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(); + // uint32_t now_ms = AP_HAL::millis(); status.packet_rx_drop_count = 0; diff --git a/libraries/AP_ODIDScanner/AP_ODIDScanner.h b/libraries/AP_ODIDScanner/AP_ODIDScanner.h index 21967f5151355..b8662eec28757 100644 --- a/libraries/AP_ODIDScanner/AP_ODIDScanner.h +++ b/libraries/AP_ODIDScanner/AP_ODIDScanner.h @@ -1,6 +1,7 @@ #pragma once +#include #define ODID_SCANNER_ENABLED 1 #ifdef ODID_SCANNER_ENABLED @@ -20,10 +21,11 @@ class AP_ODIDScanner CLASS_NO_COPY(AP_ODIDScanner); void init(); void update(); + void update_recv(); mavlink_channel_t _chan; // mavlink channel that communicates with the remote id transceiver - AP_Int8 _mav_port; + uint8_t _mav_port; mavlink_uav_found_t found_msg; - AP_HaL::UARTDriver* _port; + AP_HAL::UARTDriver* _port; bool _initialised; uint32_t last_send_ms; uint32_t last_dev_hb_ms; diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 74b36a10a511d..ccc85a3269f8e 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -511,6 +511,7 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Airspeed, &vehicle.airspeed, update, 10, 100, 41), // NOTE: the priority number here should be right before Plane's calc_airspeed_errors #endif SCHED_TASK_CLASS(AP_ODIDScanner,&vehicle.odidscanner, update, 10, 50, 237), + SCHED_TASK_CLASS(AP_ODIDScanner,&vehicle.odidscanner, update_recv, 10, 50, 237), #if COMPASS_CAL_ENABLED SCHED_TASK_CLASS(Compass, &vehicle.compass, cal_update, 100, 200, 75), #endif