diff --git a/libraries/SITL/SIM_ADSB_Sagetech_MXS.h b/libraries/SITL/SIM_ADSB_Sagetech_MXS.h index 67e4fbda92..18eba0f4db 100644 --- a/libraries/SITL/SIM_ADSB_Sagetech_MXS.h +++ b/libraries/SITL/SIM_ADSB_Sagetech_MXS.h @@ -70,9 +70,9 @@ private: class PACKED PackedMessage { public: PackedMessage(T _msg, MsgType _msgtype, uint8_t _msgid) : - msg{_msg}, msgtype{_msgtype}, - msgid{_msgid} + msgid{_msgid}, + msg{_msg} { update_checksum(); } diff --git a/libraries/SITL/SIM_ELRS.cpp b/libraries/SITL/SIM_ELRS.cpp index 3136c76212..687079289b 100644 --- a/libraries/SITL/SIM_ELRS.cpp +++ b/libraries/SITL/SIM_ELRS.cpp @@ -22,18 +22,18 @@ using namespace SITL; ELRS::ELRS(const uint8_t portNumber, HALSITL::SITL_State_Common *sitl_state) : // Mirror typical ELRS UART buffer sizes SerialDevice::SerialDevice(64, 128), - target_address("127.0.0.1"), - target_port(5761 + portNumber), // Mirror MAVLink buffer sizes mavlinkInputBuffer(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) this_system_id(255), // 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 diff --git a/libraries/SITL/SIM_GPS.cpp b/libraries/SITL/SIM_GPS.cpp index 35fe90d90a..d51521cf3b 100644 --- a/libraries/SITL/SIM_GPS.cpp +++ b/libraries/SITL/SIM_GPS.cpp @@ -38,9 +38,9 @@ extern const AP_HAL::HAL& hal; using namespace SITL; // ensure the backend we have allocated matches the one that's configured: -GPS_Backend::GPS_Backend(GPS &_front, uint8_t _instance) - : front{_front}, - instance{_instance} +GPS_Backend::GPS_Backend(GPS &_front, uint8_t _instance) : + instance{_instance}, + front{_front} { _sitl = AP::sitl(); } diff --git a/libraries/SITL/SIM_Motor.h b/libraries/SITL/SIM_Motor.h index 39745b6843..720bbced87 100644 --- a/libraries/SITL/SIM_Motor.h +++ b/libraries/SITL/SIM_Motor.h @@ -46,9 +46,9 @@ public: float last_roll_value, last_pitch_value; 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 yaw_factor(_yaw_factor), // positive is clockwise + servo(_servo), // what servo output drives this motor display_order(_display_order) // order for clockwise display { position.x = cosf(radians(angle)); @@ -66,9 +66,9 @@ public: 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 _pitch_servo, float _pitch_min, float _pitch_max) : - servo(_servo), // what servo output drives this motor angle(_angle), // angle in degrees from front yaw_factor(_yaw_factor), // positive is clockwise + servo(_servo), // what servo output drives this motor display_order(_display_order), // order for clockwise display roll_servo(_roll_servo), roll_min(_roll_min), diff --git a/libraries/SITL/SIM_PS_LightWare_SF45B.h b/libraries/SITL/SIM_PS_LightWare_SF45B.h index 16fd995573..2d0404b61e 100644 --- a/libraries/SITL/SIM_PS_LightWare_SF45B.h +++ b/libraries/SITL/SIM_PS_LightWare_SF45B.h @@ -71,8 +71,8 @@ private: class PACKED PackedMessage { public: PackedMessage(T _msg, uint16_t _flags) : - msg(_msg), - flags(_flags) + flags(_flags), + msg(_msg) { flags |= (sizeof(T)) << 6; } diff --git a/libraries/SITL/SIM_Sailboat.cpp b/libraries/SITL/SIM_Sailboat.cpp index 846f077f43..a22d8c7df3 100644 --- a/libraries/SITL/SIM_Sailboat.cpp +++ b/libraries/SITL/SIM_Sailboat.cpp @@ -42,9 +42,9 @@ namespace SITL { Sailboat::Sailboat(const char *frame_str) : Aircraft(frame_str), + sail_area(1.0), steering_angle_max(35), - turning_circle(1.8), - sail_area(1.0) + turning_circle(1.8) { motor_connected = (strcmp(frame_str, "sailboat-motor") == 0); skid_steering = strstr(frame_str, "skid") != nullptr; diff --git a/libraries/SITL/SIM_SilentWings.cpp b/libraries/SITL/SIM_SilentWings.cpp index 424108e5ff..4ebba41e0c 100644 --- a/libraries/SITL/SIM_SilentWings.cpp +++ b/libraries/SITL/SIM_SilentWings.cpp @@ -57,10 +57,10 @@ SilentWings::SilentWings(const char *frame_str) : Aircraft(frame_str), last_data_time_ms(0), first_pkt_timestamp_ms(0), + inited_first_pkt_timestamp(false), time_base_us(0), sock(true), - home_initialized(false), - inited_first_pkt_timestamp(false) + home_initialized(false) { // 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.