mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mission: add sanity check that 16-bit commands aren't stored_in_location
This is a rather confusing problem when it happens during development, so a sanity check is good. What you see in dev is that your latitude gets corrupted between when you store and retrieve it, with no warnings that you're doing something wrong.
This commit is contained in:
parent
7b0da89708
commit
aae524b9d5
@ -538,6 +538,14 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con
|
||||
}
|
||||
|
||||
if (stored_in_location(cmd.id)) {
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
// NOTE! no 16-bit command may be stored_in_location as only
|
||||
// 10 bytes are available for storage and lat/lon/alt required
|
||||
// 4*sizeof(float) == 12 bytes of storage.
|
||||
if (b1 == 0) {
|
||||
AP_HAL::panic("May not store location for 16-bit commands");
|
||||
}
|
||||
#endif
|
||||
// Location is not PACKED; field-wise copy it:
|
||||
cmd.content.location.relative_alt = packed_content.location.flags.relative_alt;
|
||||
cmd.content.location.loiter_ccw = packed_content.location.flags.loiter_ccw;
|
||||
|
Loading…
Reference in New Issue
Block a user