SITL: re-order initialiser lines so -Werror=reorder will work

This commit is contained in:
Peter Barker 2024-09-21 15:21:57 +10:00 committed by Peter Barker
parent 68e003fd74
commit ebe9a75a66
7 changed files with 19 additions and 19 deletions

View File

@ -70,9 +70,9 @@ private:
class PACKED PackedMessage { class PACKED PackedMessage {
public: public:
PackedMessage(T _msg, MsgType _msgtype, uint8_t _msgid) : PackedMessage(T _msg, MsgType _msgtype, uint8_t _msgid) :
msg{_msg},
msgtype{_msgtype}, msgtype{_msgtype},
msgid{_msgid} msgid{_msgid},
msg{_msg}
{ {
update_checksum(); update_checksum();
} }

View File

@ -22,18 +22,18 @@ using namespace SITL;
ELRS::ELRS(const uint8_t portNumber, HALSITL::SITL_State_Common *sitl_state) : ELRS::ELRS(const uint8_t portNumber, HALSITL::SITL_State_Common *sitl_state) :
// Mirror typical ELRS UART buffer sizes // Mirror typical ELRS UART buffer sizes
SerialDevice::SerialDevice(64, 128), SerialDevice::SerialDevice(64, 128),
target_address("127.0.0.1"),
target_port(5761 + portNumber),
// Mirror MAVLink buffer sizes // Mirror MAVLink buffer sizes
mavlinkInputBuffer(2048), mavlinkInputBuffer(2048),
mavlinkOutputBuffer(2048), mavlinkOutputBuffer(2048),
// Typical setup is about 500 B /s
input_data_rate(500),
output_data_rate(500),
// 255 is typically used by the GCS, for RC override to work in ArduPilot `SYSID_MYGCS` must be set to this value (255 is the default) // 255 is typically used by the GCS, for RC override to work in ArduPilot `SYSID_MYGCS` must be set to this value (255 is the default)
this_system_id(255), this_system_id(255),
// Strictly this is not a valid source component ID // Strictly this is not a valid source component ID
this_component_id(MAV_COMPONENT::MAV_COMP_ID_ALL) this_component_id(MAV_COMPONENT::MAV_COMP_ID_ALL),
// Typical setup is about 500 B /s
input_data_rate(500),
output_data_rate(500),
target_address("127.0.0.1"),
target_port(5761 + portNumber)
{ {
// Setup TCP server // Setup TCP server

View File

@ -38,9 +38,9 @@ extern const AP_HAL::HAL& hal;
using namespace SITL; using namespace SITL;
// ensure the backend we have allocated matches the one that's configured: // ensure the backend we have allocated matches the one that's configured:
GPS_Backend::GPS_Backend(GPS &_front, uint8_t _instance) GPS_Backend::GPS_Backend(GPS &_front, uint8_t _instance) :
: front{_front}, instance{_instance},
instance{_instance} front{_front}
{ {
_sitl = AP::sitl(); _sitl = AP::sitl();
} }

View File

@ -46,9 +46,9 @@ public:
float last_roll_value, last_pitch_value; float last_roll_value, last_pitch_value;
Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order) : Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order) :
servo(_servo), // what servo output drives this motor
angle(_angle), // angle in degrees from front angle(_angle), // angle in degrees from front
yaw_factor(_yaw_factor), // positive is clockwise yaw_factor(_yaw_factor), // positive is clockwise
servo(_servo), // what servo output drives this motor
display_order(_display_order) // order for clockwise display display_order(_display_order) // order for clockwise display
{ {
position.x = cosf(radians(angle)); position.x = cosf(radians(angle));
@ -66,9 +66,9 @@ public:
Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order, Motor(uint8_t _servo, float _angle, float _yaw_factor, uint8_t _display_order,
int8_t _roll_servo, float _roll_min, float _roll_max, int8_t _roll_servo, float _roll_min, float _roll_max,
int8_t _pitch_servo, float _pitch_min, float _pitch_max) : int8_t _pitch_servo, float _pitch_min, float _pitch_max) :
servo(_servo), // what servo output drives this motor
angle(_angle), // angle in degrees from front angle(_angle), // angle in degrees from front
yaw_factor(_yaw_factor), // positive is clockwise yaw_factor(_yaw_factor), // positive is clockwise
servo(_servo), // what servo output drives this motor
display_order(_display_order), // order for clockwise display display_order(_display_order), // order for clockwise display
roll_servo(_roll_servo), roll_servo(_roll_servo),
roll_min(_roll_min), roll_min(_roll_min),

View File

@ -71,8 +71,8 @@ private:
class PACKED PackedMessage { class PACKED PackedMessage {
public: public:
PackedMessage(T _msg, uint16_t _flags) : PackedMessage(T _msg, uint16_t _flags) :
msg(_msg), flags(_flags),
flags(_flags) msg(_msg)
{ {
flags |= (sizeof(T)) << 6; flags |= (sizeof(T)) << 6;
} }

View File

@ -42,9 +42,9 @@ namespace SITL {
Sailboat::Sailboat(const char *frame_str) : Sailboat::Sailboat(const char *frame_str) :
Aircraft(frame_str), Aircraft(frame_str),
sail_area(1.0),
steering_angle_max(35), steering_angle_max(35),
turning_circle(1.8), turning_circle(1.8)
sail_area(1.0)
{ {
motor_connected = (strcmp(frame_str, "sailboat-motor") == 0); motor_connected = (strcmp(frame_str, "sailboat-motor") == 0);
skid_steering = strstr(frame_str, "skid") != nullptr; skid_steering = strstr(frame_str, "skid") != nullptr;

View File

@ -57,10 +57,10 @@ SilentWings::SilentWings(const char *frame_str) :
Aircraft(frame_str), Aircraft(frame_str),
last_data_time_ms(0), last_data_time_ms(0),
first_pkt_timestamp_ms(0), first_pkt_timestamp_ms(0),
inited_first_pkt_timestamp(false),
time_base_us(0), time_base_us(0),
sock(true), sock(true),
home_initialized(false), home_initialized(false)
inited_first_pkt_timestamp(false)
{ {
// Force ArduPlane to use sensor data from SilentWings as the actual state, // Force ArduPlane to use sensor data from SilentWings as the actual state,
// without using EKF, i.e., using "fake EKF (type 10)". Disable gyro calibration. // without using EKF, i.e., using "fake EKF (type 10)". Disable gyro calibration.