AP_AHRS: move VehicleClass handling to AHRS frontend
.... and renaming the enumeration while we're at it
This commit is contained in:
parent
f5c68d54cb
commit
1cfd9f57ce
@ -1746,8 +1746,8 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const
|
||||
wing and rover
|
||||
*/
|
||||
if (ret != EKFType::NONE &&
|
||||
(_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
|
||||
_vehicle_class == AHRS_VEHICLE_GROUND) &&
|
||||
(_vehicle_class == VehicleClass::FIXED_WING ||
|
||||
_vehicle_class == VehicleClass::GROUND) &&
|
||||
(fly_forward || !hal.util->get_soft_armed())) {
|
||||
bool should_use_gps = true;
|
||||
nav_filter_status filt_state;
|
||||
@ -1881,8 +1881,8 @@ bool AP_AHRS::healthy(void) const
|
||||
if (!ret) {
|
||||
return false;
|
||||
}
|
||||
if ((_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
|
||||
_vehicle_class == AHRS_VEHICLE_GROUND) &&
|
||||
if ((_vehicle_class == VehicleClass::FIXED_WING ||
|
||||
_vehicle_class == VehicleClass::GROUND) &&
|
||||
active_EKF_type() != EKFType::TWO) {
|
||||
// on fixed wing we want to be using EKF to be considered
|
||||
// healthy if EKF is enabled
|
||||
@ -1898,8 +1898,8 @@ bool AP_AHRS::healthy(void) const
|
||||
if (!ret) {
|
||||
return false;
|
||||
}
|
||||
if ((_vehicle_class == AHRS_VEHICLE_FIXED_WING ||
|
||||
_vehicle_class == AHRS_VEHICLE_GROUND) &&
|
||||
if ((_vehicle_class == VehicleClass::FIXED_WING ||
|
||||
_vehicle_class == VehicleClass::GROUND) &&
|
||||
active_EKF_type() != EKFType::THREE) {
|
||||
// on fixed wing we want to be using EKF to be considered
|
||||
// healthy if EKF is enabled
|
||||
|
@ -414,6 +414,24 @@ public:
|
||||
return fly_forward;
|
||||
}
|
||||
|
||||
/* we modify our behaviour based on what sort of vehicle the
|
||||
* vehicle code tells us we are. This information is also pulled
|
||||
* from AP_AHRS by other libraries
|
||||
*/
|
||||
enum class VehicleClass : uint8_t {
|
||||
UNKNOWN,
|
||||
GROUND,
|
||||
COPTER,
|
||||
FIXED_WING,
|
||||
SUBMARINE,
|
||||
};
|
||||
VehicleClass get_vehicle_class(void) const {
|
||||
return _vehicle_class;
|
||||
}
|
||||
void set_vehicle_class(VehicleClass vclass) {
|
||||
_vehicle_class = vclass;
|
||||
}
|
||||
|
||||
protected:
|
||||
// optional view class
|
||||
AP_AHRS_View *_view;
|
||||
@ -421,6 +439,12 @@ protected:
|
||||
private:
|
||||
static AP_AHRS *_singleton;
|
||||
|
||||
/* we modify our behaviour based on what sort of vehicle the
|
||||
* vehicle code tells us we are. This information is also pulled
|
||||
* from AP_AHRS by other libraries
|
||||
*/
|
||||
VehicleClass _vehicle_class{VehicleClass::UNKNOWN};
|
||||
|
||||
enum class EKFType {
|
||||
NONE = 0
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
|
@ -33,15 +33,6 @@ class OpticalFlow;
|
||||
#define AP_AHRS_RP_P_MIN 0.05f // minimum value for AHRS_RP_P parameter
|
||||
#define AP_AHRS_YAW_P_MIN 0.05f // minimum value for AHRS_YAW_P parameter
|
||||
|
||||
enum AHRS_VehicleClass : uint8_t {
|
||||
AHRS_VEHICLE_UNKNOWN,
|
||||
AHRS_VEHICLE_GROUND,
|
||||
AHRS_VEHICLE_COPTER,
|
||||
AHRS_VEHICLE_FIXED_WING,
|
||||
AHRS_VEHICLE_SUBMARINE,
|
||||
};
|
||||
|
||||
|
||||
class AP_AHRS_Backend
|
||||
{
|
||||
public:
|
||||
@ -58,14 +49,6 @@ public:
|
||||
// init sets up INS board orientation
|
||||
virtual void init();
|
||||
|
||||
AHRS_VehicleClass get_vehicle_class(void) const {
|
||||
return _vehicle_class;
|
||||
}
|
||||
|
||||
void set_vehicle_class(AHRS_VehicleClass vclass) {
|
||||
_vehicle_class = vclass;
|
||||
}
|
||||
|
||||
void set_wind_estimation(bool b) {
|
||||
_flags.wind_estimation = b;
|
||||
}
|
||||
@ -483,8 +466,6 @@ protected:
|
||||
// multi-thread access support
|
||||
HAL_Semaphore _rsem;
|
||||
|
||||
AHRS_VehicleClass _vehicle_class{AHRS_VEHICLE_UNKNOWN};
|
||||
|
||||
// settable parameters
|
||||
// these are public for ArduCopter
|
||||
AP_Float _kp_yaw;
|
||||
|
Loading…
Reference in New Issue
Block a user