GCS_MAVLink: exclude deadlock-creation based on FAILURE_CREATION_ENABLED
This commit is contained in:
parent
f9c9a09327
commit
6d172a1b22
@ -581,11 +581,13 @@ protected:
|
||||
void handle_set_gps_global_origin(const mavlink_message_t &msg);
|
||||
void handle_setup_signing(const mavlink_message_t &msg) const;
|
||||
virtual MAV_RESULT handle_preflight_reboot(const mavlink_command_int_t &packet, const mavlink_message_t &msg);
|
||||
#if AP_MAVLINK_FAILURE_CREATION_ENABLED
|
||||
struct {
|
||||
HAL_Semaphore sem;
|
||||
bool taken;
|
||||
} _deadlock_sem;
|
||||
void deadlock_sem(void);
|
||||
#endif
|
||||
|
||||
// reset a message interval via mavlink:
|
||||
MAV_RESULT handle_command_set_message_interval(const mavlink_command_int_t &packet);
|
||||
|
@ -3203,6 +3203,16 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
if (is_equal(packet.param4, 100.0f)) {
|
||||
send_text(MAV_SEVERITY_WARNING,"Creating mutex deadlock");
|
||||
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::deadlock_sem, void));
|
||||
while (!_deadlock_sem.taken) {
|
||||
hal.scheduler->delay(1);
|
||||
}
|
||||
WITH_SEMAPHORE(_deadlock_sem.sem);
|
||||
send_text(MAV_SEVERITY_WARNING,"deadlock passed");
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
#endif // AP_MAVLINK_FAILURE_CREATION_ENABLED
|
||||
|
||||
#if HAL_ENABLE_DFU_BOOT
|
||||
@ -3217,16 +3227,6 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
if (is_equal(packet.param4, 100.0f)) {
|
||||
send_text(MAV_SEVERITY_WARNING,"Creating mutex deadlock");
|
||||
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&GCS_MAVLINK::deadlock_sem, void));
|
||||
while (!_deadlock_sem.taken) {
|
||||
hal.scheduler->delay(1);
|
||||
}
|
||||
WITH_SEMAPHORE(_deadlock_sem.sem);
|
||||
send_text(MAV_SEVERITY_WARNING,"deadlock passed");
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
}
|
||||
|
||||
// refuse reboot when armed:
|
||||
@ -3270,6 +3270,7 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
|
||||
#if AP_MAVLINK_FAILURE_CREATION_ENABLED
|
||||
/*
|
||||
take a semaphore and do not release it, triggering a deadlock
|
||||
*/
|
||||
@ -3280,6 +3281,7 @@ void GCS_MAVLINK::deadlock_sem(void)
|
||||
_deadlock_sem.sem.take_blocking();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/*
|
||||
handle a flight termination request
|
||||
|
Loading…
Reference in New Issue
Block a user