mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_ExternalAHRS: create and use backend defines for AP_ExternalAHRS
This commit is contained in:
parent
eca456e521
commit
b471f9bfac
@ -16,12 +16,15 @@
|
|||||||
suppport for serial connected AHRS systems
|
suppport for serial connected AHRS systems
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "AP_ExternalAHRS.h"
|
#include "AP_ExternalAHRS_config.h"
|
||||||
#include "AP_ExternalAHRS_VectorNav.h"
|
|
||||||
#include "AP_ExternalAHRS_LORD.h"
|
|
||||||
|
|
||||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
#if HAL_EXTERNAL_AHRS_ENABLED
|
||||||
|
|
||||||
|
#include "AP_ExternalAHRS.h"
|
||||||
|
#include "AP_ExternalAHRS_backend.h"
|
||||||
|
#include "AP_ExternalAHRS_VectorNav.h"
|
||||||
|
#include "AP_ExternalAHRS_LORD.h"
|
||||||
|
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
@ -90,13 +93,17 @@ void AP_ExternalAHRS::init(void)
|
|||||||
case DevType::None:
|
case DevType::None:
|
||||||
// nothing to do
|
// nothing to do
|
||||||
break;
|
break;
|
||||||
|
#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
|
||||||
case DevType::VecNav:
|
case DevType::VecNav:
|
||||||
backend = new AP_ExternalAHRS_VectorNav(this, state);
|
backend = new AP_ExternalAHRS_VectorNav(this, state);
|
||||||
break;
|
break;
|
||||||
|
#endif
|
||||||
|
#if AP_EXTERNAL_AHRS_LORD_ENABLED
|
||||||
case DevType::LORD:
|
case DevType::LORD:
|
||||||
backend = new AP_ExternalAHRS_LORD(this, state);
|
backend = new AP_ExternalAHRS_LORD(this, state);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
|
#endif
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unsupported ExternalAHRS type %u", unsigned(devtype));
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unsupported ExternalAHRS type %u", unsigned(devtype));
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -43,8 +43,12 @@ public:
|
|||||||
|
|
||||||
enum class DevType : uint8_t {
|
enum class DevType : uint8_t {
|
||||||
None = 0,
|
None = 0,
|
||||||
|
#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
|
||||||
VecNav = 1,
|
VecNav = 1,
|
||||||
|
#endif
|
||||||
|
#if AP_EXTERNAL_AHRS_LORD_ENABLED
|
||||||
LORD = 2,
|
LORD = 2,
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
static AP_ExternalAHRS *get_singleton(void) {
|
static AP_ExternalAHRS *get_singleton(void) {
|
||||||
|
@ -16,8 +16,11 @@
|
|||||||
|
|
||||||
#define ALLOW_DOUBLE_MATH_FUNCTIONS
|
#define ALLOW_DOUBLE_MATH_FUNCTIONS
|
||||||
|
|
||||||
|
#include "AP_ExternalAHRS_config.h"
|
||||||
|
|
||||||
|
#if AP_EXTERNAL_AHRS_LORD_ENABLED
|
||||||
|
|
||||||
#include "AP_ExternalAHRS_LORD.h"
|
#include "AP_ExternalAHRS_LORD.h"
|
||||||
#if HAL_EXTERNAL_AHRS_LORD_ENABLED
|
|
||||||
#include <AP_Baro/AP_Baro.h>
|
#include <AP_Baro/AP_Baro.h>
|
||||||
#include <AP_Compass/AP_Compass.h>
|
#include <AP_Compass/AP_Compass.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
@ -582,5 +585,4 @@ double AP_ExternalAHRS_LORD::extract_double(const uint8_t *data, uint8_t offset)
|
|||||||
return *reinterpret_cast<double*>(&tmp);
|
return *reinterpret_cast<double*>(&tmp);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAL_EXTERNAL_AHRS_ENABLED
|
#endif // AP_EXTERNAL_AHRS_LORD_ENABLE
|
||||||
|
|
||||||
|
@ -16,15 +16,12 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "AP_ExternalAHRS_config.h"
|
||||||
|
|
||||||
|
#if AP_EXTERNAL_AHRS_LORD_ENABLED
|
||||||
|
|
||||||
#include "AP_ExternalAHRS_backend.h"
|
#include "AP_ExternalAHRS_backend.h"
|
||||||
|
#include <AP_GPS/AP_GPS.h>
|
||||||
#ifndef HAL_EXTERNAL_AHRS_LORD_ENABLED
|
|
||||||
#define HAL_EXTERNAL_AHRS_LORD_ENABLED HAL_EXTERNAL_AHRS_ENABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if HAL_EXTERNAL_AHRS_LORD_ENABLED
|
|
||||||
|
|
||||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
|
||||||
|
|
||||||
class AP_ExternalAHRS_LORD: public AP_ExternalAHRS_backend
|
class AP_ExternalAHRS_LORD: public AP_ExternalAHRS_backend
|
||||||
{
|
{
|
||||||
@ -153,5 +150,4 @@ private:
|
|||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // HAL_EXTERNAL_AHRS_ENABLED
|
#endif // AP_EXTERNAL_AHRS_LORD_ENABLED
|
||||||
|
|
||||||
|
@ -18,6 +18,10 @@
|
|||||||
|
|
||||||
#define ALLOW_DOUBLE_MATH_FUNCTIONS
|
#define ALLOW_DOUBLE_MATH_FUNCTIONS
|
||||||
|
|
||||||
|
#include "AP_ExternalAHRS_config.h"
|
||||||
|
|
||||||
|
#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
|
||||||
|
|
||||||
#include "AP_ExternalAHRS_VectorNav.h"
|
#include "AP_ExternalAHRS_VectorNav.h"
|
||||||
#include <AP_Math/AP_Math.h>
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_Math/crc.h>
|
#include <AP_Math/crc.h>
|
||||||
@ -31,8 +35,6 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
|
||||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL &hal;
|
extern const AP_HAL::HAL &hal;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -819,5 +821,4 @@ void AP_ExternalAHRS_VectorNav::send_status_report(GCS_MAVLINK &link) const
|
|||||||
mag_var, 0, 0);
|
mag_var, 0, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAL_EXTERNAL_AHRS_ENABLED
|
#endif // AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
|
||||||
|
|
||||||
|
@ -18,9 +18,11 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "AP_ExternalAHRS_backend.h"
|
#include "AP_ExternalAHRS_config.h"
|
||||||
|
|
||||||
#if HAL_EXTERNAL_AHRS_ENABLED
|
#if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
|
||||||
|
|
||||||
|
#include "AP_ExternalAHRS_backend.h"
|
||||||
|
|
||||||
class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend {
|
class AP_ExternalAHRS_VectorNav : public AP_ExternalAHRS_backend {
|
||||||
|
|
||||||
@ -92,5 +94,4 @@ private:
|
|||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // HAL_EXTERNAL_AHRS_ENABLED
|
#endif // AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
|
||||||
|
|
||||||
|
@ -5,3 +5,15 @@
|
|||||||
#ifndef HAL_EXTERNAL_AHRS_ENABLED
|
#ifndef HAL_EXTERNAL_AHRS_ENABLED
|
||||||
#define HAL_EXTERNAL_AHRS_ENABLED BOARD_FLASH_SIZE > 1024
|
#define HAL_EXTERNAL_AHRS_ENABLED BOARD_FLASH_SIZE > 1024
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED
|
||||||
|
#define AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED HAL_EXTERNAL_AHRS_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_EXTERNAL_AHRS_LORD_ENABLED
|
||||||
|
#define AP_EXTERNAL_AHRS_LORD_ENABLED AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_EXTERNAL_AHRS_VECTORNAV_ENABLED
|
||||||
|
#define AP_EXTERNAL_AHRS_VECTORNAV_ENABLED AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user