From 675e75fedb3f16b1f81dec4ee988c413c79fece5 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 19 Feb 2024 18:41:27 +0000 Subject: [PATCH 1/6] AP_Filesystem: remove unused variables --- libraries/AP_Filesystem/AP_Filesystem.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem.h b/libraries/AP_Filesystem/AP_Filesystem.h index b139713a751f5..9a5e01e6933c2 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.h +++ b/libraries/AP_Filesystem/AP_Filesystem.h @@ -84,7 +84,7 @@ class AP_Filesystem { int stat(const char *pathname, struct stat *stbuf); // stat variant for scripting - typedef struct { + typedef struct Stat { uint32_t size; int32_t mode; uint32_t mtime; From fa8fbe183cd797d08ae3c59b9172b2380fc0b75d Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 19 Feb 2024 18:41:50 +0000 Subject: [PATCH 2/6] AP_Mount: squash static_assert warnings --- libraries/AP_Mount/AP_Mount_Siyi.h | 2 +- libraries/AP_Mount/AP_Mount_Xacti.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index 2245e4ca0dd34..5a3f228a91f5e 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -204,7 +204,7 @@ class AP_Mount_Siyi : public AP_Mount_Backend GimbalMountingDirection mounting_dir; VideoOutputStatus video_mode; } GimbalConfigInfo; - static_assert(sizeof(GimbalConfigInfo) == 7); + static_assert(sizeof(GimbalConfigInfo) == 7, "GimbalConfigInfo must be 7 bytes"); // camera image types (aka lens) enum class CameraImageType : uint8_t { diff --git a/libraries/AP_Mount/AP_Mount_Xacti.h b/libraries/AP_Mount/AP_Mount_Xacti.h index 247a66bac1cbb..444acd37195d8 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.h +++ b/libraries/AP_Mount/AP_Mount_Xacti.h @@ -252,7 +252,7 @@ class AP_Mount_Xacti : public AP_Mount_Backend uint16_t apeture; // cameras' aperture * 100 uint16_t iso_sensitivity; // camera's iso sensitivity } _status; // latest status received - static_assert(sizeof(_status) == 48); // status should be 48 bytes + static_assert(sizeof(_status) == 48, "status must be 48 bytes"); // status should be 48 bytes struct { uint32_t last_request_ms; // system time that status was last requested uint32_t last_error_status; // last error status reported to user From 37f7895ccf34332ed18cfd18835049c53fff0b2b Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 19 Feb 2024 18:42:26 +0000 Subject: [PATCH 3/6] AP_RCProtocol: squash compile warning --- libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp | 2 +- libraries/AP_RCProtocol/AP_RCProtocol_GHST.h | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp index 7c61f5355d373..75e84ade9a701 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp @@ -181,7 +181,7 @@ void AP_RCProtocol_Backend::log_data(AP_RCProtocol::rcprotocol_t prot, uint32_t #if HAL_LOGGING_ENABLED && AP_RC_CHANNEL_ENABLED #if (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX) - if (&rc() == nullptr) { // allow running without RC_Channels if we are doing the examples + if (RC_Channels::get_singleton() == nullptr) { // allow running without RC_Channels if we are doing the examples return; } #endif diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h index 248fb3f1790d3..8b439c97c31c9 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h @@ -180,7 +180,6 @@ class AP_RCProtocol_GHST : public AP_RCProtocol_Backend { uint32_t _last_frame_time_us; uint32_t _last_tx_frame_time_us; - uint32_t _last_uart_start_time_ms; uint32_t _last_rx_frame_time_us; uint32_t _start_frame_time_us; bool telem_available; From d043e9353ad62604b4282f399d148b15ffdf96f8 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 19 Feb 2024 18:42:47 +0000 Subject: [PATCH 4/6] AP_Param: remove unused variable --- libraries/AP_Param/AP_Param.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 996960a0b5819..57a82684956d0 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -969,7 +969,6 @@ AP_Param::find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token AP_Param* AP_Param::find_by_name(const char* name, enum ap_var_type *ptype, ParamToken *token) { AP_Param *ap; - uint16_t count = 0; for (ap = AP_Param::first(token, ptype); ap && *ptype != AP_PARAM_GROUP && *ptype != AP_PARAM_NONE; ap = AP_Param::next_scalar(token, ptype)) { @@ -981,7 +980,6 @@ AP_Param* AP_Param::find_by_name(const char* name, enum ap_var_type *ptype, Para break; } } - count++; } return ap; } From 7fcb7de3a1a2e40ca99ccdbdf1ab59033b3e6ea9 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 19 Feb 2024 18:43:08 +0000 Subject: [PATCH 5/6] AP_Logger: remove unused variables --- libraries/AP_Logger/AP_Logger_File.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h index 07709d3e9350c..038324e92e227 100644 --- a/libraries/AP_Logger/AP_Logger_File.h +++ b/libraries/AP_Logger/AP_Logger_File.h @@ -72,7 +72,7 @@ class AP_Logger_File : public AP_Logger_Backend char *_write_filename; bool last_log_is_marked_discard; uint32_t _last_write_ms; -#if AP_RTC_ENABLED +#if AP_RTC_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS bool _need_rtc_update; #endif From b0f9fc5495522d9e6e250c0f24043fb561b58831 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 19 Feb 2024 18:43:24 +0000 Subject: [PATCH 6/6] SITL: squash static_assert warnings --- libraries/SITL/SIM_GPS_Trimble.cpp | 20 ++++++++++---------- libraries/SITL/SIM_InertialLabs.cpp | 2 +- libraries/SITL/SIM_Loweheiser.h | 6 ------ libraries/SITL/SIM_QMC5883L.h | 4 +--- 4 files changed, 12 insertions(+), 20 deletions(-) diff --git a/libraries/SITL/SIM_GPS_Trimble.cpp b/libraries/SITL/SIM_GPS_Trimble.cpp index 9ddaf64027d2b..1e1726b33376b 100644 --- a/libraries/SITL/SIM_GPS_Trimble.cpp +++ b/libraries/SITL/SIM_GPS_Trimble.cpp @@ -98,7 +98,7 @@ void GPS_Trimble::publish(const GPS_Data *d) pos_flags_2, bootcount }; - static_assert(sizeof(gsof_pos_time) - (sizeof(gsof_pos_time::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_time::RECORD_LEN)) == GSOF_POS_TIME_LEN); + static_assert(sizeof(gsof_pos_time) - (sizeof(gsof_pos_time::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_time::RECORD_LEN)) == GSOF_POS_TIME_LEN, "Trimble size check failed"); payload_sz += sizeof(pos_time); memcpy(&buf[offset], &pos_time, sizeof(pos_time)); @@ -127,7 +127,7 @@ void GPS_Trimble::publish(const GPS_Data *d) gsof_pack_double(d->longitude * DEG_TO_RAD_DOUBLE), gsof_pack_double(static_cast(d->altitude)) }; - static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN); + static_assert(sizeof(gsof_pos) - (sizeof(gsof_pos::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos::RECORD_LEN)) == GSOF_POS_LEN, "Trimble size check failed"); payload_sz += sizeof(pos); memcpy(&buf[offset], &pos, sizeof(pos)); @@ -180,7 +180,7 @@ void GPS_Trimble::publish(const GPS_Data *d) // Intentionally narrow from double. gsof_pack_float(static_cast(d->speedD)) }; - static_assert(sizeof(gsof_vel) - (sizeof(gsof_vel::OUTPUT_RECORD_TYPE) + sizeof(gsof_vel::RECORD_LEN)) == GSOF_VEL_LEN); + static_assert(sizeof(gsof_vel) - (sizeof(gsof_vel::OUTPUT_RECORD_TYPE) + sizeof(gsof_vel::RECORD_LEN)) == GSOF_VEL_LEN, "Trimble size check failed"); payload_sz += sizeof(vel); memcpy(&buf[offset], &vel, sizeof(vel)); @@ -204,13 +204,13 @@ void GPS_Trimble::publish(const GPS_Data *d) } dop {}; // Check the payload size calculation in the compiler constexpr auto dop_size = sizeof(gsof_dop); - static_assert(dop_size == 18); + static_assert(dop_size == 18, "gsof_dop must be 8 bytes"); constexpr auto dop_record_type_size = sizeof(gsof_dop::OUTPUT_RECORD_TYPE); - static_assert(dop_record_type_size == 1); + static_assert(dop_record_type_size == 1, "gsof_dop::OUTPUT_RECORD_TYPE must be 1 byte"); constexpr auto len_size = sizeof(gsof_dop::RECORD_LEN); - static_assert(len_size == 1); + static_assert(len_size == 1, "gsof_dop::RECORD_LEN must be 1 bytes"); constexpr auto dop_payload_size = dop_size - (dop_record_type_size + len_size); - static_assert(dop_payload_size == GSOF_DOP_LEN); + static_assert(dop_payload_size == GSOF_DOP_LEN, "dop_payload_size must be GSOF_DOP_LEN bytes"); payload_sz += sizeof(dop); memcpy(&buf[offset], &dop, sizeof(dop)); @@ -237,7 +237,7 @@ void GPS_Trimble::publish(const GPS_Data *d) uint32_t unit_variance = htobe32(0); uint16_t n_epocs = htobe32(1); // Always 1 for kinematic. } pos_sigma {}; - static_assert(sizeof(gsof_pos_sigma) - (sizeof(gsof_pos_sigma::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_sigma::RECORD_LEN)) == GSOF_POS_SIGMA_LEN); + static_assert(sizeof(gsof_pos_sigma) - (sizeof(gsof_pos_sigma::OUTPUT_RECORD_TYPE) + sizeof(gsof_pos_sigma::RECORD_LEN)) == GSOF_POS_SIGMA_LEN, "Trimble size check failed"); payload_sz += sizeof(pos_sigma); memcpy(&buf[offset], &pos_sigma, sizeof(pos_sigma)); offset += sizeof(pos_sigma); @@ -536,7 +536,7 @@ void GPS_Trimble::send_gsof(const uint8_t *buf, const uint16_t size) uint64_t GPS_Trimble::gsof_pack_double(const double& src) { uint64_t dst; - static_assert(sizeof(src) == sizeof(dst)); + static_assert(sizeof(src) == sizeof(dst), "src and dst must have equal size"); memcpy(&dst, &src, sizeof(dst)); dst = htobe64(dst); return dst; @@ -545,7 +545,7 @@ uint64_t GPS_Trimble::gsof_pack_double(const double& src) uint32_t GPS_Trimble::gsof_pack_float(const float& src) { uint32_t dst; - static_assert(sizeof(src) == sizeof(dst)); + static_assert(sizeof(src) == sizeof(dst), "src and dst must have equal size"); memcpy(&dst, &src, sizeof(dst)); dst = htobe32(dst); return dst; diff --git a/libraries/SITL/SIM_InertialLabs.cpp b/libraries/SITL/SIM_InertialLabs.cpp index 728c7934f9cf7..edaadf0b8756d 100644 --- a/libraries/SITL/SIM_InertialLabs.cpp +++ b/libraries/SITL/SIM_InertialLabs.cpp @@ -93,7 +93,7 @@ void InertialLabs::send_packet(void) pkt.gnss_extended_info.fix_type = 2; } - pkt.differential_pressure = 0.5*sq(fdm.airspeed+fabsf(rand_float()*0.25))*1.0e4; + pkt.differential_pressure = 0.5*sq(fdm.airspeed+fabsF(rand_float()*0.25))*1.0e4; pkt.supply_voltage = 12.3*100; pkt.temperature = 23.4*10; diff --git a/libraries/SITL/SIM_Loweheiser.h b/libraries/SITL/SIM_Loweheiser.h index ae4f28cdd73bf..edad99a556942 100644 --- a/libraries/SITL/SIM_Loweheiser.h +++ b/libraries/SITL/SIM_Loweheiser.h @@ -117,12 +117,6 @@ class Loweheiser : public SerialDevice { const float max_current = 50.0f; const float base_supply_voltage = 50.0; - // we share channels with the ArduPilot binary! - // Beware: the mavlink rangefinder and other stuff shares this channel. - const mavlink_channel_t mavlink_ch = (mavlink_channel_t)(MAVLINK_COMM_0+5); - - class SIM *_sitl; - uint32_t last_sent_ms; void update_receive(); diff --git a/libraries/SITL/SIM_QMC5883L.h b/libraries/SITL/SIM_QMC5883L.h index 10aa1719656c4..52346250b3351 100644 --- a/libraries/SITL/SIM_QMC5883L.h +++ b/libraries/SITL/SIM_QMC5883L.h @@ -41,13 +41,11 @@ class QMC5883L : public I2CDevice } registers; // 256 1-byte registers: - assert_storage_size assert_storage_size_registers_reg; + assert_storage_size assert_storage_size_registers_reg UNUSED_PRIVATE_MEMBER; Bitmask<256> writable_registers; void reset(); - - uint32_t cmd_take_reading_received_ms; }; } // namespace SITL