SITL: squash static_assert warnings

This commit is contained in:
Andy Piper 2024-02-19 18:43:24 +00:00 committed by Andrew Tridgell
parent 4d419bb918
commit 76c0b0a8e0
4 changed files with 12 additions and 20 deletions

View File

@ -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<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));
@ -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));
@ -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;

View File

@ -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;

View File

@ -117,12 +117,6 @@ private:
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();

View File

@ -41,13 +41,11 @@ private:
} 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