diff --git a/src/drivers/ins/sbgecom/CMakeLists.txt b/src/drivers/ins/sbgecom/CMakeLists.txt index e4c8362da3..b9778b59b3 100644 --- a/src/drivers/ins/sbgecom/CMakeLists.txt +++ b/src/drivers/ins/sbgecom/CMakeLists.txt @@ -40,6 +40,17 @@ add_subdirectory(sbgECom) add_dependencies(sbgECom prebuild_targets) +# Vendor tree warning relaxations. +# +# sbgECom is a third-party submodule (PX4/sbgECom) we do not own. +# These -Wno-* flags are scoped PRIVATE to the sbgECom target so they +# apply only when compiling vendor .c files, not to the PX4 wrapper +# (sbgecom.cpp/.hpp) which is built as a separate target via +# px4_add_module() below and must remain under PX4's standard -Wall -Werror. +# +# If you add a flag here, it should address a warning emitted by vendor +# code only. Warnings triggered in PX4-authored code must be fixed at +# the source, not silenced here. target_compile_options(sbgECom PRIVATE -Wno-format @@ -49,8 +60,15 @@ target_compile_options(sbgECom -Wno-type-limits -Wno-maybe-uninitialized -Wno-float-equal + -Wno-logical-op ) +# -Wno-typedef-redefinition is Clang-only. GCC rejects unrecognized +# warning flags under -Werror, so guard this by compiler. +if(CMAKE_C_COMPILER_ID MATCHES "Clang") + target_compile_options(sbgECom PRIVATE -Wno-typedef-redefinition) +endif() + if("${PX4_PLATFORM}" MATCHES "nuttx") target_compile_definitions(sbgECom PUBLIC __NUTTX__) endif() diff --git a/src/drivers/ins/sbgecom/sbgecom.cpp b/src/drivers/ins/sbgecom/sbgecom.cpp index 2739e73963..48d1646d5e 100644 --- a/src/drivers/ins/sbgecom/sbgecom.cpp +++ b/src/drivers/ins/sbgecom/sbgecom.cpp @@ -43,6 +43,7 @@ #include #include +#include #include #include #include @@ -323,9 +324,9 @@ void SbgEcom::handleLogEkfNav(const SbgEComLogUnion *ref_sbg_data, void *user_ar const double longitude = ref_sbg_data->ekfNavData.position[1]; const double altitude = ref_sbg_data->ekfNavData.position[2]; - const double north_velocity = ref_sbg_data->ekfNavData.velocity[0]; - const double east_velocity = ref_sbg_data->ekfNavData.velocity[1]; - const double down_velocity = ref_sbg_data->ekfNavData.velocity[2]; + const double north_velocity = static_cast(ref_sbg_data->ekfNavData.velocity[0]); + const double east_velocity = static_cast(ref_sbg_data->ekfNavData.velocity[1]); + const double down_velocity = static_cast(ref_sbg_data->ekfNavData.velocity[2]); if (!instance->_pos_ref.isInitialized()) { instance->_pos_ref.initReference(latitude, longitude, time_now_us); @@ -457,7 +458,7 @@ void SbgEcom::handleLogGnssPosVelHdt(SbgEComMsgId msg, const SbgEComLogUnion *re sensor_gps.latitude_deg = gnss_data->gps_pos.latitude; sensor_gps.longitude_deg = gnss_data->gps_pos.longitude; sensor_gps.altitude_msl_m = gnss_data->gps_pos.altitude; - sensor_gps.altitude_ellipsoid_m = gnss_data->gps_pos.undulation; + sensor_gps.altitude_ellipsoid_m = static_cast(gnss_data->gps_pos.undulation); sensor_gps.s_variance_m_s = sqrt(pow(gnss_data->gps_vel.velocityAcc[0], 2) + pow(gnss_data->gps_vel.velocityAcc[1], 2) + @@ -831,18 +832,18 @@ void SbgEcom::send_config(SbgEComHandle *pHandle, const char *config) sbgEComCmdApiReplyConstruct(&reply); - sbgEComCmdApiPost(pHandle, "/api/v1/settings", NULL, config, &reply); + sbgEComCmdApiPost(pHandle, "/api/v1/settings", nullptr, config, &reply); if (!sbgEComCmdApiReplySuccessful(&reply)) { PX4_ERR("Fail to apply SBG configuration: %s", reply.pContent); } else { - bool need_reboot = (strstr(reply.pContent, NEED_REBOOT_STR) != NULL); - sbgEComCmdApiPost(pHandle, "/api/v1/settings/save", NULL, NULL, &reply); + bool need_reboot = (strstr(reply.pContent, NEED_REBOOT_STR) != nullptr); + sbgEComCmdApiPost(pHandle, "/api/v1/settings/save", nullptr, nullptr, &reply); if (need_reboot) { PX4_INFO("Reboot SBG device"); - sbgEComCmdApiPost(pHandle, "/api/v1/system/reboot", NULL, NULL, &reply); + sbgEComCmdApiPost(pHandle, "/api/v1/system/reboot", nullptr, nullptr, &reply); } } @@ -852,7 +853,7 @@ void SbgEcom::send_config(SbgEComHandle *pHandle, const char *config) void SbgEcom::send_config_file(SbgEComHandle *pHandle, const char *file_path) { int fd; - char *body = NULL; + char *body = nullptr; struct stat s; assert(pHandle); @@ -869,12 +870,21 @@ void SbgEcom::send_config_file(SbgEComHandle *pHandle, const char *file_path) body = (char *)malloc(s.st_size + 1); if (!body) { - PX4_ERR("Failed to allocate memory (%ld) - %s", s.st_size + 1, strerror(get_errno())); + PX4_ERR("Failed to allocate memory (%lld) - %s", + static_cast(s.st_size + 1), + strerror(errno)); + close(fd); + return; + } + + ssize_t ret = read(fd, body, s.st_size); + + if (ret < 0) { + PX4_ERR("Read failed: %s", strerror(errno)); close(fd); return; } - read(fd, body, s.st_size); body[s.st_size] = '\0'; send_config(pHandle, body); @@ -896,7 +906,9 @@ int SbgEcom::init() error_code = sbgInterfaceSerialCreate(&_sbg_interface, _device_name, _baudrate); if (error_code == SBG_NO_ERROR) { - PX4_INFO("Serial interface created successfully on port: %s, baudrate: %ld", _device_name, _baudrate); + PX4_INFO("Serial interface created successfully on port: %s, baudrate: %ld", + _device_name, + static_cast(_baudrate)); } pSerialHandle = (int *)_sbg_interface.handle; diff --git a/src/drivers/ins/sbgecom/sbgecom.hpp b/src/drivers/ins/sbgecom/sbgecom.hpp index f73ade46f9..39ff5e5a77 100644 --- a/src/drivers/ins/sbgecom/sbgecom.hpp +++ b/src/drivers/ins/sbgecom/sbgecom.hpp @@ -218,7 +218,7 @@ private: SbgErrorCode sendMagLog(SbgEComHandle *handle, SbgEcom *instance); void set_device_id(uint32_t device_id); - uint32_t get_device_id(void); + uint32_t get_device_id(); // SBG interface and state variables SbgInterface _sbg_interface; @@ -241,7 +241,7 @@ private: int init_result; MapProjection _pos_ref{}; - double _gps_alt_ref{NAN}; + double _gps_alt_ref{static_cast(NAN)}; struct GnssData { bool pos_received = false;