AP_AHRS: use typename SIM instead of SITL as it conflicts with namespace name

This commit is contained in:
bugobliterator 2021-07-30 16:11:13 +05:30 committed by Andrew Tridgell
parent 3033589fca
commit 62b6350af1
2 changed files with 52 additions and 52 deletions

View File

@ -339,7 +339,7 @@ void AP_AHRS::update(bool skip_ins_update)
shortname = "DCM";
break;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
shortname = "SITL";
break;
#endif
@ -555,7 +555,7 @@ void AP_AHRS::update_SITL(void)
const struct SITL::sitl_fdm &fdm = _sitl->state;
const AP_InertialSensor &_ins = AP::ins();
if (active_EKF_type() == EKFType::SITL) {
if (active_EKF_type() == EKFType::SIM) {
fdm.quaternion.rotation_matrix(_dcm_matrix);
_dcm_matrix = _dcm_matrix * get_rotation_vehicle_body_to_autopilot_body();
@ -693,7 +693,7 @@ bool AP_AHRS::get_position(struct Location &loc) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL: {
case EKFType::SIM: {
if (_sitl) {
const struct SITL::sitl_fdm &fdm = _sitl->state;
loc = {};
@ -741,7 +741,7 @@ Vector3f AP_AHRS::wind_estimate(void) const
break;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
wind.zero();
break;
#endif
@ -791,7 +791,7 @@ bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const
return AP_AHRS_DCM::airspeed_estimate(get_active_airspeed_index(), airspeed_ret);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
#if HAL_NAVEKF3_AVAILABLE
if (EKF3.getWind(-1,wind_vel)) {
ret = true;
@ -862,7 +862,7 @@ bool AP_AHRS::airspeed_vector_true(Vector3f &vec) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
break;
#endif
@ -891,7 +891,7 @@ bool AP_AHRS::use_compass(void)
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return true;
#endif
@ -932,7 +932,7 @@ bool AP_AHRS::get_quaternion(Quaternion &quat) const
break;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL: {
case EKFType::SIM: {
if (!_sitl) {
return false;
}
@ -983,7 +983,7 @@ bool AP_AHRS::get_secondary_attitude(Vector3f &eulers) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
// SITL is secondary (should never happen)
return false;
#endif
@ -1044,7 +1044,7 @@ bool AP_AHRS::get_secondary_quaternion(Quaternion &quat) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
// SITL is secondary (should never happen)
return false;
#endif
@ -1091,7 +1091,7 @@ bool AP_AHRS::get_secondary_position(struct Location &loc) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
// SITL is secondary (should never happen)
return false;
#endif
@ -1129,7 +1129,7 @@ Vector2f AP_AHRS::groundspeed_vector(void)
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL: {
case EKFType::SIM: {
if (_sitl) {
const struct SITL::sitl_fdm &fdm = _sitl->state;
return Vector2f(fdm.speedN, fdm.speedE);
@ -1175,7 +1175,7 @@ bool AP_AHRS::set_origin(const Location &loc)
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
// never allow origin set in SITL. The origin is set by the
// simulation backend
return false;
@ -1217,7 +1217,7 @@ bool AP_AHRS::get_velocity_NED(Vector3f &vec) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL: {
case EKFType::SIM: {
if (!_sitl) {
return false;
}
@ -1254,7 +1254,7 @@ bool AP_AHRS::get_mag_field_NED(Vector3f &vec) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return false;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -1285,7 +1285,7 @@ bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return false;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -1318,7 +1318,7 @@ bool AP_AHRS::get_vert_pos_rate(float &velocity) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
if (_sitl) {
const struct SITL::sitl_fdm &fdm = _sitl->state;
velocity = fdm.speedD;
@ -1354,7 +1354,7 @@ bool AP_AHRS::get_hagl(float &height) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL: {
case EKFType::SIM: {
if (!_sitl) {
return false;
}
@ -1412,7 +1412,7 @@ bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL: {
case EKFType::SIM: {
if (!_sitl) {
return false;
}
@ -1489,7 +1489,7 @@ bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL: {
case EKFType::SIM: {
Location loc, orgn;
if (!get_position(loc) ||
!get_origin(orgn)) {
@ -1559,7 +1559,7 @@ bool AP_AHRS::get_relative_position_D_origin(float &posD) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL: {
case EKFType::SIM: {
if (!_sitl) {
return false;
}
@ -1612,7 +1612,7 @@ AP_AHRS::EKFType AP_AHRS::ekf_type(void) const
EKFType type = (EKFType)_ekf_type.get();
switch (type) {
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return type;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -1696,8 +1696,8 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
ret = EKFType::SITL;
case EKFType::SIM:
ret = EKFType::SIM;
break;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -1734,7 +1734,7 @@ AP_AHRS::EKFType AP_AHRS::active_EKF_type(void) const
}
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (ret == EKFType::SITL) {
if (ret == EKFType::SIM) {
get_filter_status(filt_state);
}
#endif
@ -1819,7 +1819,7 @@ bool AP_AHRS::get_secondary_EKF_type(EKFType &secondary_ekf_type) const
case EKFType::THREE:
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
case EKFType::EXTERNAL:
@ -1880,7 +1880,7 @@ bool AP_AHRS::healthy(void) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return true;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -1906,7 +1906,7 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f
switch (ekf_type()) {
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
#endif
case EKFType::NONE:
return ret;
@ -1960,7 +1960,7 @@ bool AP_AHRS::initialised(void) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return true;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -1991,7 +1991,7 @@ bool AP_AHRS::get_filter_status(nav_filter_status &status) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
memset(&status, 0, sizeof(status));
status.flags.attitude = 1;
status.flags.horiz_vel = 1;
@ -2086,7 +2086,7 @@ void AP_AHRS::getEkfControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainSca
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
// same as EKF2 for no optical flow
ekfGndSpdLimit = 400.0f;
ekfNavVelGainScaler = 1.0f;
@ -2119,7 +2119,7 @@ bool AP_AHRS::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
magOffsets.zero();
return true;
#endif
@ -2153,7 +2153,7 @@ void AP_AHRS::getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const
break;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
break;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -2284,7 +2284,7 @@ uint32_t AP_AHRS::getLastYawResetAngle(float &yawAng)
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return 0;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -2315,7 +2315,7 @@ uint32_t AP_AHRS::getLastPosNorthEastReset(Vector2f &pos)
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return 0;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -2346,7 +2346,7 @@ uint32_t AP_AHRS::getLastVelNorthEastReset(Vector2f &vel) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return 0;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -2377,7 +2377,7 @@ uint32_t AP_AHRS::getLastPosDownReset(float &posDelta)
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return 0;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -2426,7 +2426,7 @@ bool AP_AHRS::resetHeightDatum(void)
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return false;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -2447,7 +2447,7 @@ void AP_AHRS::send_ekf_status_report(mavlink_channel_t chan) const
break;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
{
// send status report with everything looking good
const uint16_t flags =
@ -2512,7 +2512,7 @@ bool AP_AHRS::get_origin(Location &ret) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL: {
case EKFType::SIM: {
if (!_sitl) {
return false;
}
@ -2551,7 +2551,7 @@ bool AP_AHRS::get_hgt_ctrl_limit(float& limit) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return false;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -2613,7 +2613,7 @@ bool AP_AHRS::get_location(struct Location &loc) const
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
return get_position(loc);
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -2647,7 +2647,7 @@ bool AP_AHRS::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
velInnov.zero();
posInnov.zero();
magInnov.zero();
@ -2678,7 +2678,7 @@ bool AP_AHRS::is_vibration_affected() const
case EKFType::TWO:
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
case EKFType::EXTERNAL:
@ -2716,7 +2716,7 @@ bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
velVar = 0;
posVar = 0;
hgtVar = 0;
@ -2756,7 +2756,7 @@ bool AP_AHRS::get_vel_innovations_and_variances_for_source(uint8_t source, Vecto
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
// SITL does not support source level variances
return false;
#endif
@ -2816,7 +2816,7 @@ uint8_t AP_AHRS::get_primary_IMU_index() const
break;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
break;
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
@ -2842,7 +2842,7 @@ int8_t AP_AHRS::get_primary_core_index() const
switch (active_EKF_type()) {
case EKFType::NONE:
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
case EKFType::EXTERNAL:
@ -2892,7 +2892,7 @@ void AP_AHRS::check_lane_switch(void)
break;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
break;
#endif
@ -2923,7 +2923,7 @@ void AP_AHRS::request_yaw_reset(void)
break;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
break;
#endif
@ -2978,7 +2978,7 @@ bool AP_AHRS::is_ext_nav_used_for_yaw(void) const
return EKF3.using_external_yaw();
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
case EKFType::SITL:
case EKFType::SIM:
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
case EKFType::EXTERNAL:

View File

@ -353,7 +353,7 @@ private:
,TWO = 2
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
,SITL = 10
,SIM = 10
#endif
#if HAL_EXTERNAL_AHRS_ENABLED
,EXTERNAL = 11