forked from Archive/PX4-Autopilot
mavlink update to latest and enable address-of-packed-member warning
This commit is contained in:
parent
f8ae8ba502
commit
f3533d31f8
|
@ -99,7 +99,6 @@ function(px4_add_common_flags)
|
||||||
add_compile_options(
|
add_compile_options(
|
||||||
-Qunused-arguments
|
-Qunused-arguments
|
||||||
|
|
||||||
-Wno-address-of-packed-member # TODO: fix and enable (mavlink, etc)
|
|
||||||
-Wno-unknown-warning-option
|
-Wno-unknown-warning-option
|
||||||
-Wno-unused-const-variable
|
-Wno-unused-const-variable
|
||||||
-Wno-varargs
|
-Wno-varargs
|
||||||
|
@ -113,10 +112,6 @@ function(px4_add_common_flags)
|
||||||
add_compile_options(-fdiagnostics-color=always)
|
add_compile_options(-fdiagnostics-color=always)
|
||||||
endif()
|
endif()
|
||||||
|
|
||||||
if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 9)
|
|
||||||
add_compile_options(-Wno-address-of-packed-member) # TODO: fix and enable (mavlink, etc)
|
|
||||||
endif()
|
|
||||||
|
|
||||||
add_compile_options(
|
add_compile_options(
|
||||||
-fno-builtin-printf
|
-fno-builtin-printf
|
||||||
-fno-strength-reduce
|
-fno-strength-reduce
|
||||||
|
|
|
@ -1 +1 @@
|
||||||
Subproject commit 2a47f11e73eef6d817af7934692b1223d7fb434f
|
Subproject commit b32bd3f004b971c03711617c79e5dc67e720e864
|
|
@ -450,8 +450,7 @@ MavlinkParametersManager::send_uavcan()
|
||||||
msg.param_value = value.real_value;
|
msg.param_value = value.real_value;
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
int32_t val;
|
int32_t val = (int32_t)value.int_value;
|
||||||
val = (int32_t)value.int_value;
|
|
||||||
memcpy(&msg.param_value, &val, sizeof(int32_t));
|
memcpy(&msg.param_value, &val, sizeof(int32_t));
|
||||||
msg.param_type = MAVLINK_TYPE_INT32_T;
|
msg.param_type = MAVLINK_TYPE_INT32_T;
|
||||||
}
|
}
|
||||||
|
@ -545,14 +544,19 @@ MavlinkParametersManager::send_param(param_t param, int component_id)
|
||||||
* get param value, since MAVLink encodes float and int params in the same
|
* get param value, since MAVLink encodes float and int params in the same
|
||||||
* space during transmission, copy param onto float val_buf
|
* space during transmission, copy param onto float val_buf
|
||||||
*/
|
*/
|
||||||
if (param_get(param, &msg.param_value) != OK) {
|
float param_value{};
|
||||||
|
|
||||||
|
if (param_get(param, ¶m_value) != OK) {
|
||||||
return 2;
|
return 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
msg.param_value = param_value;
|
||||||
|
|
||||||
msg.param_count = param_count_used();
|
msg.param_count = param_count_used();
|
||||||
msg.param_index = param_get_used_index(param);
|
msg.param_index = param_get_used_index(param);
|
||||||
|
|
||||||
#if defined(__GNUC__) && __GNUC__ >= 8
|
#if defined(__GNUC__) && __GNUC__ >= 8
|
||||||
|
#pragma GCC diagnostic push
|
||||||
#pragma GCC diagnostic ignored "-Wstringop-truncation"
|
#pragma GCC diagnostic ignored "-Wstringop-truncation"
|
||||||
#endif
|
#endif
|
||||||
/*
|
/*
|
||||||
|
|
Loading…
Reference in New Issue