diff --git a/cmake/px4_add_common_flags.cmake b/cmake/px4_add_common_flags.cmake index a486089d8fa7ac43de051b0417cdbaecff579cc0..feeaa7bdae5da16937787e87f7d91e8944f18c3f 100644 --- a/cmake/px4_add_common_flags.cmake +++ b/cmake/px4_add_common_flags.cmake @@ -99,7 +99,6 @@ function(px4_add_common_flags) add_compile_options( -Qunused-arguments - -Wno-address-of-packed-member # TODO: fix and enable (mavlink, etc) -Wno-unknown-warning-option -Wno-unused-const-variable -Wno-varargs @@ -113,10 +112,6 @@ function(px4_add_common_flags) add_compile_options(-fdiagnostics-color=always) 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( -fno-builtin-printf -fno-strength-reduce diff --git a/mavlink/include/mavlink/v2.0 b/mavlink/include/mavlink/v2.0 index 2a47f11e73eef6d817af7934692b1223d7fb434f..b32bd3f004b971c03711617c79e5dc67e720e864 160000 --- a/mavlink/include/mavlink/v2.0 +++ b/mavlink/include/mavlink/v2.0 @@ -1 +1 @@ -Subproject commit 2a47f11e73eef6d817af7934692b1223d7fb434f +Subproject commit b32bd3f004b971c03711617c79e5dc67e720e864 diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index cbfdf75f2d5fee48629bbd375db08ba1301c9181..0f1afcb77f0e6a458beaf5197dc86f7d1dbdaa06 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -450,8 +450,7 @@ MavlinkParametersManager::send_uavcan() msg.param_value = value.real_value; } else { - int32_t val; - val = (int32_t)value.int_value; + int32_t val = (int32_t)value.int_value; memcpy(&msg.param_value, &val, sizeof(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 * 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; } + msg.param_value = param_value; + msg.param_count = param_count_used(); msg.param_index = param_get_used_index(param); #if defined(__GNUC__) && __GNUC__ >= 8 +#pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wstringop-truncation" #endif /*