mirror of https://github.com/ArduPilot/ardupilot
AP_Param: Switch from type punning to defined behavior
* This was undefined behavior in the C++ standard * Use the safer options in AP_Common * Removes a compiler warning Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
parent
d0b8e672c0
commit
c382eb192a
|
@ -3019,7 +3019,7 @@ bool AP_Param::add_param(uint8_t _key, uint8_t param_num, const char *pname, flo
|
|||
|
||||
// check CRC
|
||||
auto &hinfo = const_cast<GroupInfo*>(info.group_info)[0];
|
||||
const int32_t crc = *(const int32_t *)(&hinfo.def_value);
|
||||
const auto crc = to_int32(hinfo.def_value);
|
||||
|
||||
int32_t current_crc;
|
||||
if (load_int32(key, 0, current_crc) && current_crc != crc) {
|
||||
|
|
Loading…
Reference in New Issue