mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Rover: set the ahrs.set_armed() flag
This commit is contained in:
parent
a45d77f893
commit
532f06073a
@ -649,6 +649,8 @@ void loop()
|
|||||||
// update AHRS system
|
// update AHRS system
|
||||||
static void ahrs_update()
|
static void ahrs_update()
|
||||||
{
|
{
|
||||||
|
ahrs.set_armed(hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
|
||||||
|
|
||||||
#if HIL_MODE != HIL_MODE_DISABLED
|
#if HIL_MODE != HIL_MODE_DISABLED
|
||||||
// update hil before AHRS update
|
// update hil before AHRS update
|
||||||
gcs_update();
|
gcs_update();
|
||||||
|
@ -78,7 +78,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// we are armed if we are not initialising
|
// we are armed if we are not initialising
|
||||||
if (control_mode != INITIALISING) {
|
if (control_mode != INITIALISING && ahrs.get_armed()) {
|
||||||
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
|
base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -516,10 +516,7 @@ static bool should_log(uint32_t mask)
|
|||||||
if (!(mask & g.log_bitmask) || in_mavlink_delay) {
|
if (!(mask & g.log_bitmask) || in_mavlink_delay) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
bool armed;
|
bool ret = ahrs.get_armed() || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0;
|
||||||
armed = (hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
|
|
||||||
|
|
||||||
bool ret = armed || (g.log_bitmask & MASK_LOG_WHEN_DISARMED) != 0;
|
|
||||||
if (ret && !DataFlash.logging_started() && !in_log_download) {
|
if (ret && !DataFlash.logging_started() && !in_log_download) {
|
||||||
// we have to set in_mavlink_delay to prevent logging while
|
// we have to set in_mavlink_delay to prevent logging while
|
||||||
// writing headers
|
// writing headers
|
||||||
|
Loading…
Reference in New Issue
Block a user