mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: add terrain pre-arm check
This commit is contained in:
parent
91f6c7b503
commit
ddffbe27aa
@ -900,6 +900,7 @@ private:
|
|||||||
void pre_arm_rc_checks();
|
void pre_arm_rc_checks();
|
||||||
bool pre_arm_gps_checks(bool display_failure);
|
bool pre_arm_gps_checks(bool display_failure);
|
||||||
bool pre_arm_ekf_attitude_check();
|
bool pre_arm_ekf_attitude_check();
|
||||||
|
bool pre_arm_terrain_check();
|
||||||
bool arm_checks(bool display_failure, bool arming_from_gcs);
|
bool arm_checks(bool display_failure, bool arming_from_gcs);
|
||||||
void init_disarm_motors();
|
void init_disarm_motors();
|
||||||
void motors_output();
|
void motors_output();
|
||||||
|
@ -332,6 +332,12 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
#endif // HELI_FRAME
|
#endif // HELI_FRAME
|
||||||
|
|
||||||
|
// check for missing terrain data
|
||||||
|
if (!pre_arm_terrain_check()) {
|
||||||
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: Waiting for Terrain data");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// check throttle is above failsafe throttle
|
// check throttle is above failsafe throttle
|
||||||
@ -486,6 +492,20 @@ bool Copter::pre_arm_ekf_attitude_check()
|
|||||||
return filt_status.flags.attitude;
|
return filt_status.flags.attitude;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check we have required terrain data
|
||||||
|
bool Copter::pre_arm_terrain_check()
|
||||||
|
{
|
||||||
|
// succeed if not using terrain data
|
||||||
|
if (!terrain_use()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// show terrain statistics
|
||||||
|
uint16_t terr_pending, terr_loaded;
|
||||||
|
terrain.get_statistics(terr_pending, terr_loaded);
|
||||||
|
return (terr_pending <= 0);
|
||||||
|
}
|
||||||
|
|
||||||
// arm_checks - perform final checks before arming
|
// arm_checks - perform final checks before arming
|
||||||
// always called just before arming. Return true if ok to arm
|
// always called just before arming. Return true if ok to arm
|
||||||
// has side-effect that logging is started
|
// has side-effect that logging is started
|
||||||
@ -636,6 +656,14 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check for missing terrain data
|
||||||
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_PARAMETERS)) {
|
||||||
|
if (!pre_arm_terrain_check()) {
|
||||||
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: Waiting for Terrain data");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// check throttle
|
// check throttle
|
||||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
|
||||||
// check throttle is not too low - must be above failsafe throttle
|
// check throttle is not too low - must be above failsafe throttle
|
||||||
|
Loading…
Reference in New Issue
Block a user