AP_DroneCAN: rename more variables, types and defines

This commit is contained in:
Andrew Tridgell 2023-04-08 14:09:10 +10:00
parent e469ed9bd7
commit 9261f89e39
7 changed files with 19 additions and 19 deletions

View File

@ -1,7 +1,7 @@
#include "AP_Canard_iface.h"
#include <AP_HAL/AP_HAL.h>
#include <AP_CANManager/AP_CANManager.h>
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#if HAL_ENABLE_DRONECAN_DRIVERS
#include <canard/handler_list.h>
#include <canard/transfer_object.h>
extern const AP_HAL::HAL& hal;
@ -309,4 +309,4 @@ bool CanardInterface::add_interface(AP_HAL::CANIface *can_iface)
num_ifaces++;
return true;
}
#endif // #if HAL_ENABLE_LIBUAVCAN_DRIVERS
#endif // #if HAL_ENABLE_DRONECAN_DRIVERS

View File

@ -1,6 +1,6 @@
#pragma once
#include <AP_HAL/AP_HAL.h>
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#if HAL_ENABLE_DRONECAN_DRIVERS
#include <canard/interface.h>
class AP_DroneCAN;
@ -65,4 +65,4 @@ private:
bool initialized;
HAL_Semaphore _sem;
};
#endif // HAL_ENABLE_LIBUAVCAN_DRIVERS
#endif // HAL_ENABLE_DRONECAN_DRIVERS

View File

@ -18,7 +18,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#if HAL_ENABLE_DRONECAN_DRIVERS
#include "AP_DroneCAN.h"
#include <GCS_MAVLink/GCS.h>
@ -172,7 +172,7 @@ AP_DroneCAN::~AP_DroneCAN()
AP_DroneCAN *AP_DroneCAN::get_uavcan(uint8_t driver_index)
{
if (driver_index >= AP::can().get_num_drivers() ||
AP::can().get_driver_type(driver_index) != AP_CANManager::Driver_Type_UAVCAN) {
AP::can().get_driver_type(driver_index) != AP_CANManager::Driver_Type_DroneCAN) {
return nullptr;
}
return static_cast<AP_DroneCAN*>(AP::can().get_driver(driver_index));
@ -234,22 +234,22 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters)
}
// Roundup all subscribers from supported drivers
AP_GPS_UAVCAN::subscribe_msgs(this);
AP_GPS_DroneCAN::subscribe_msgs(this);
#if AP_COMPASS_DRONECAN_ENABLED
AP_Compass_UAVCAN::subscribe_msgs(this);
AP_Compass_DroneCAN::subscribe_msgs(this);
#endif
#if AP_BARO_DRONECAN_ENABLED
AP_Baro_UAVCAN::subscribe_msgs(this);
AP_Baro_DroneCAN::subscribe_msgs(this);
#endif
AP_BattMonitor_UAVCAN::subscribe_msgs(this);
AP_BattMonitor_DroneCAN::subscribe_msgs(this);
#if AP_AIRSPEED_DRONECAN_ENABLED
AP_Airspeed_UAVCAN::subscribe_msgs(this);
AP_Airspeed_DroneCAN::subscribe_msgs(this);
#endif
#if AP_OPTICALFLOW_HEREFLOW_ENABLED
AP_OpticalFlow_HereFlow::subscribe_msgs(this);
#endif
#if AP_RANGEFINDER_DRONECAN_ENABLED
AP_RangeFinder_UAVCAN::subscribe_msgs(this);
AP_RangeFinder_DroneCAN::subscribe_msgs(this);
#endif
#if AP_EFI_DRONECAN_ENABLED
AP_EFI_DroneCAN::subscribe_msgs(this);
@ -383,7 +383,7 @@ void AP_DroneCAN::loop(void)
#endif
#if AP_DRONECAN_SEND_GPS
if (option_is_set(AP_DroneCAN::Options::SEND_GNSS) && !AP_GPS_UAVCAN::instance_exists(this)) {
if (option_is_set(AP_DroneCAN::Options::SEND_GNSS) && !AP_GPS_DroneCAN::instance_exists(this)) {
// send if enabled and this interface/driver is not used by the AP_GPS driver
gnss_send_fix();
gnss_send_yaw();

View File

@ -18,7 +18,7 @@
#include <AP_HAL/AP_HAL.h>
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#if HAL_ENABLE_DRONECAN_DRIVERS
#include "AP_Canard_iface.h"
#include <AP_CANManager/AP_CANManager.h>
@ -230,7 +230,7 @@ private:
} _buzzer;
#if AP_DRONECAN_SEND_GPS
// send GNSS Fix and yaw, same thing AP_GPS_UAVCAN would receive
// send GNSS Fix and yaw, same thing AP_GPS_DroneCAN would receive
void gnss_send_fix();
void gnss_send_yaw();
@ -329,4 +329,4 @@ private:
void handle_node_info_request(const CanardRxTransfer& transfer, const uavcan_protocol_GetNodeInfoRequest& req);
};
#endif // #if HAL_ENABLE_LIBUAVCAN_DRIVERS
#endif // #if HAL_ENABLE_DRONECAN_DRIVERS

View File

@ -18,7 +18,7 @@
#include <AP_HAL/AP_HAL.h>
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#if HAL_ENABLE_DRONECAN_DRIVERS
#include "AP_DroneCAN_DNA_Server.h"
#include "AP_DroneCAN.h"

View File

@ -2,7 +2,7 @@
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_HAL/Semaphores.h>
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#if HAL_ENABLE_DRONECAN_DRIVERS
#include <AP_Common/Bitmask.h>
#include <StorageManager/StorageManager.h>
#include <AP_CANManager/AP_CANManager.h>

View File

@ -4,7 +4,7 @@
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#if HAL_ENABLE_LIBUAVCAN_DRIVERS
#if HAL_ENABLE_DRONECAN_DRIVERS
#include <AP_HAL/Semaphores.h>