Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Nuke macOS warnings #26264

Merged
merged 6 commits into from Feb 22, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
2 changes: 1 addition & 1 deletion libraries/AP_Filesystem/AP_Filesystem.h
Expand Up @@ -84,7 +84,7 @@ class AP_Filesystem {
int stat(const char *pathname, struct stat *stbuf);

// stat variant for scripting
typedef struct {
typedef struct Stat {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

curious, what warning is this for?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

../../libraries/AP_Filesystem/AP_Filesystem.h:87:19: warning: anonymous non-C-compatible type given name for linkage purposes by typedef declaration; add a tag name here [-Wnon-c-typedef-for-linkage]
    typedef struct {
                  ^
                   stat_t
../../libraries/AP_Filesystem/AP_Filesystem.h:93:9: note: type is not C-compatible due to this member declaration
        bool is_directory(void) const {
        ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~
../../libraries/AP_Filesystem/AP_Filesystem.h:96:7: note: type is given name 'stat_t' for linkage purposes by this typedef declaration
    } stat_t;
      ^
1 warning generated.

uint32_t size;
int32_t mode;
uint32_t mtime;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Logger/AP_Logger_File.h
Expand Up @@ -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

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Mount/AP_Mount_Siyi.h
Expand Up @@ -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 {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Mount/AP_Mount_Xacti.h
Expand Up @@ -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
Expand Down
2 changes: 0 additions & 2 deletions libraries/AP_Param/AP_Param.cpp
Expand Up @@ -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)) {
Expand All @@ -981,7 +980,6 @@ AP_Param* AP_Param::find_by_name(const char* name, enum ap_var_type *ptype, Para
break;
}
}
count++;
}
return ap;
}
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_RCProtocol/AP_RCProtocol_Backend.cpp
Expand Up @@ -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
Expand Down
1 change: 0 additions & 1 deletion libraries/AP_RCProtocol/AP_RCProtocol_GHST.h
Expand Up @@ -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;
Expand Down
20 changes: 10 additions & 10 deletions libraries/SITL/SIM_GPS_Trimble.cpp
Expand Up @@ -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));
Expand Down Expand Up @@ -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<double>(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));
Expand Down Expand Up @@ -180,7 +180,7 @@ void GPS_Trimble::publish(const GPS_Data *d)
// Intentionally narrow from double.
gsof_pack_float(static_cast<float>(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));
Expand All @@ -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));
Expand All @@ -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);
Expand Down Expand Up @@ -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;
Expand All @@ -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;
Expand Down
2 changes: 1 addition & 1 deletion libraries/SITL/SIM_InertialLabs.cpp
Expand Up @@ -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;

Expand Down
6 changes: 0 additions & 6 deletions libraries/SITL/SIM_Loweheiser.h
Expand Up @@ -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();
Expand Down
4 changes: 1 addition & 3 deletions libraries/SITL/SIM_QMC5883L.h
Expand Up @@ -41,13 +41,11 @@ class QMC5883L : public I2CDevice
} registers;

// 256 1-byte registers:
assert_storage_size<Registers::ByName, 256> assert_storage_size_registers_reg;
assert_storage_size<Registers::ByName, 256> assert_storage_size_registers_reg UNUSED_PRIVATE_MEMBER;

Bitmask<256> writable_registers;

void reset();

uint32_t cmd_take_reading_received_ms;
};

} // namespace SITL
Expand Down