mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Copter: remove AP_AHRS_NAVEKF_AVAILABLE checks
Copter requires an EKF
This commit is contained in:
parent
e3183babde
commit
ce1031a5bd
@ -665,10 +665,8 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||||||
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
||||||
copter.send_simstate(chan);
|
copter.send_simstate(chan);
|
||||||
#endif
|
#endif
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
||||||
CHECK_PAYLOAD_SIZE(AHRS2);
|
CHECK_PAYLOAD_SIZE(AHRS2);
|
||||||
copter.gcs[chan-MAVLINK_COMM_0].send_ahrs2(copter.ahrs);
|
copter.gcs[chan-MAVLINK_COMM_0].send_ahrs2(copter.ahrs);
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_HWSTATUS:
|
case MSG_HWSTATUS:
|
||||||
@ -703,10 +701,8 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_EKF_STATUS_REPORT:
|
case MSG_EKF_STATUS_REPORT:
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
||||||
CHECK_PAYLOAD_SIZE(EKF_STATUS_REPORT);
|
CHECK_PAYLOAD_SIZE(EKF_STATUS_REPORT);
|
||||||
copter.ahrs.get_NavEKF().send_status_report(chan);
|
copter.ahrs.get_NavEKF().send_status_report(chan);
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_FENCE_STATUS:
|
case MSG_FENCE_STATUS:
|
||||||
|
@ -365,14 +365,12 @@ void Copter::Log_Write_Attitude()
|
|||||||
Vector3f targets = attitude_control.angle_ef_targets();
|
Vector3f targets = attitude_control.angle_ef_targets();
|
||||||
DataFlash.Log_Write_Attitude(ahrs, targets);
|
DataFlash.Log_Write_Attitude(ahrs, targets);
|
||||||
|
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
||||||
#if OPTFLOW == ENABLED
|
#if OPTFLOW == ENABLED
|
||||||
DataFlash.Log_Write_EKF(ahrs,optflow.enabled());
|
DataFlash.Log_Write_EKF(ahrs,optflow.enabled());
|
||||||
#else
|
#else
|
||||||
DataFlash.Log_Write_EKF(ahrs,false);
|
DataFlash.Log_Write_EKF(ahrs,false);
|
||||||
#endif
|
#endif
|
||||||
DataFlash.Log_Write_AHRS2(ahrs);
|
DataFlash.Log_Write_AHRS2(ahrs);
|
||||||
#endif
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
sitl.Log_Write_SIMSTATE(DataFlash);
|
sitl.Log_Write_SIMSTATE(DataFlash);
|
||||||
#endif
|
#endif
|
||||||
|
@ -1010,11 +1010,9 @@ const AP_Param::Info Copter::var_info[] PROGMEM = {
|
|||||||
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
|
// @Path: ../libraries/AP_RCMapper/AP_RCMapper.cpp
|
||||||
GOBJECT(rcmap, "RCMAP_", RCMapper),
|
GOBJECT(rcmap, "RCMAP_", RCMapper),
|
||||||
|
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
||||||
// @Group: EKF_
|
// @Group: EKF_
|
||||||
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
|
// @Path: ../libraries/AP_NavEKF/AP_NavEKF.cpp
|
||||||
GOBJECTN(EKF, NavEKF, "EKF_", NavEKF),
|
GOBJECTN(EKF, NavEKF, "EKF_", NavEKF),
|
||||||
#endif
|
|
||||||
|
|
||||||
// @Group: MIS_
|
// @Group: MIS_
|
||||||
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
||||||
|
@ -311,11 +311,7 @@
|
|||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// OPTICAL_FLOW
|
// OPTICAL_FLOW
|
||||||
#ifndef OPTFLOW
|
#ifndef OPTFLOW
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
||||||
# define OPTFLOW ENABLED
|
# define OPTFLOW ENABLED
|
||||||
#else
|
|
||||||
# define OPTFLOW DISABLED
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -85,7 +85,6 @@ void Copter::ekf_check()
|
|||||||
// ekf_over_threshold - returns true if the ekf's variance are over the tolerance
|
// ekf_over_threshold - returns true if the ekf's variance are over the tolerance
|
||||||
bool Copter::ekf_over_threshold()
|
bool Copter::ekf_over_threshold()
|
||||||
{
|
{
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
||||||
// return false immediately if disabled
|
// return false immediately if disabled
|
||||||
if (g.fs_ekf_thresh <= 0.0f) {
|
if (g.fs_ekf_thresh <= 0.0f) {
|
||||||
return false;
|
return false;
|
||||||
@ -107,9 +106,6 @@ bool Copter::ekf_over_threshold()
|
|||||||
|
|
||||||
// return true if compass and velocity variance over the threshold
|
// return true if compass and velocity variance over the threshold
|
||||||
return (compass_variance >= g.fs_ekf_thresh && vel_variance >= g.fs_ekf_thresh);
|
return (compass_variance >= g.fs_ekf_thresh && vel_variance >= g.fs_ekf_thresh);
|
||||||
#else
|
|
||||||
return false;
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -131,10 +131,9 @@ bool Copter::set_mode(uint8_t mode)
|
|||||||
// called at 100hz or more
|
// called at 100hz or more
|
||||||
void Copter::update_flight_mode()
|
void Copter::update_flight_mode()
|
||||||
{
|
{
|
||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
||||||
// Update EKF speed limit - used to limit speed when we are using optical flow
|
// Update EKF speed limit - used to limit speed when we are using optical flow
|
||||||
ahrs.getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
|
ahrs.getEkfControlLimits(ekfGndSpdLimit, ekfNavVelGainScaler);
|
||||||
#endif
|
|
||||||
switch (control_mode) {
|
switch (control_mode) {
|
||||||
case ACRO:
|
case ACRO:
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
Loading…
Reference in New Issue
Block a user