mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Mission: limit memcpy to constant 12 bytes
... essentially to make static analyzers happy
This commit is contained in:
parent
556e836a66
commit
c594e51922
@ -611,7 +611,9 @@ bool AP_Mission::write_cmd_to_storage(uint16_t index, const Mission_Command& cmd
|
||||
packed.location.lng = cmd.content.location.lng;
|
||||
} else {
|
||||
// all other options in Content are assumed to be packed:
|
||||
memcpy(packed.bytes, &cmd.content.jump, sizeof(packed.bytes));
|
||||
static_assert(sizeof(packed.bytes) >= 12,
|
||||
"packed.bytes is big enough to take content");
|
||||
memcpy(packed.bytes, &cmd.content, 12);
|
||||
}
|
||||
|
||||
// calculate where in storage the command should be placed
|
||||
|
Loading…
Reference in New Issue
Block a user