diff --git a/libraries/SITL/SIM_Buzzer.h b/libraries/SITL/SIM_Buzzer.h index 74c2309472..1af1635b77 100644 --- a/libraries/SITL/SIM_Buzzer.h +++ b/libraries/SITL/SIM_Buzzer.h @@ -40,11 +40,6 @@ public: AP_Int8 _enable; // enable buzzer sim AP_Int8 _pin; - bool was_on; - - uint32_t on_time; - - bool prep_done; }; } diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.h b/libraries/SITL/SIM_EFI_MegaSquirt.h index d32707874d..f957a296c7 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.h +++ b/libraries/SITL/SIM_EFI_MegaSquirt.h @@ -44,8 +44,6 @@ public: private: void send_table(); - uint32_t time_send_ms; - struct PACKED { uint16_t size; uint8_t command; diff --git a/libraries/SITL/SIM_Helicopter.h b/libraries/SITL/SIM_Helicopter.h index a2d757385e..5845ae2770 100644 --- a/libraries/SITL/SIM_Helicopter.h +++ b/libraries/SITL/SIM_Helicopter.h @@ -62,7 +62,6 @@ private: float hover_throttle = 0.5f; float terminal_velocity = 80; float hover_lean = 3.2f; - float yaw_zero = 0.1f; float rotor_rot_accel = radians(20); float roll_rate_max = radians(1400); float pitch_rate_max = radians(1400); @@ -70,10 +69,8 @@ private: float rsc_setpoint = 0.8f; float izz = 0.2f; float tr_dist = 0.85f; - float tr_accel_max = 50.0f; //rad/s/s float cyclic_scalar = 7.2; // converts swashplate servo ouputs to cyclic blade pitch float thrust_scale; - float tail_thrust_scale; Vector2f _tpp_angle; float torque_scale; float torque_mpog; diff --git a/libraries/SITL/SIM_MS5XXX.h b/libraries/SITL/SIM_MS5XXX.h index 345722b2ba..532fcdc119 100644 --- a/libraries/SITL/SIM_MS5XXX.h +++ b/libraries/SITL/SIM_MS5XXX.h @@ -23,10 +23,6 @@ private: // float pressure; // float temperature; - // time we last updated the measurements (simulated internal - // workings of sensor) - uint32_t last_update_ms; - void reset(); enum class Command : uint8_t { diff --git a/libraries/SITL/SIM_RichenPower.h b/libraries/SITL/SIM_RichenPower.h index 962eb3a609..8b5eba90a4 100644 --- a/libraries/SITL/SIM_RichenPower.h +++ b/libraries/SITL/SIM_RichenPower.h @@ -71,8 +71,6 @@ private: // So we set batt fs high 46s // Gennie keeps batts charged to 49v + typically - class SIM *_sitl; - uint32_t last_sent_ms; void update_control_pin(const struct sitl_input &input); @@ -122,7 +120,7 @@ private: uint8_t footermagic1; uint8_t footermagic2; }; - assert_storage_size _assert_storage_size_RichenPacket; + assert_storage_size _assert_storage_size_RichenPacket UNUSED_PRIVATE_MEMBER; union RichenUnion { uint8_t parse_buffer[70]; diff --git a/libraries/SITL/SIM_Scrimmage.cpp b/libraries/SITL/SIM_Scrimmage.cpp index 64b623094f..e4d91548ac 100644 --- a/libraries/SITL/SIM_Scrimmage.cpp +++ b/libraries/SITL/SIM_Scrimmage.cpp @@ -35,8 +35,7 @@ Scrimmage::Scrimmage(const char *_frame_str) : Aircraft(_frame_str), prev_timestamp_us(0), recv_sock(true), - send_sock(true), - frame_str(_frame_str) + send_sock(true) { } diff --git a/libraries/SITL/SIM_Scrimmage.h b/libraries/SITL/SIM_Scrimmage.h index 5887d3368f..e6228cb281 100644 --- a/libraries/SITL/SIM_Scrimmage.h +++ b/libraries/SITL/SIM_Scrimmage.h @@ -86,8 +86,6 @@ private: uint64_t prev_timestamp_us; SocketAPM recv_sock; SocketAPM send_sock; - - const char *frame_str; }; } // namespace SITL diff --git a/libraries/SITL/SIM_Temperature_MCP9600.h b/libraries/SITL/SIM_Temperature_MCP9600.h index 29b60a3d6e..d8109cbaed 100644 --- a/libraries/SITL/SIM_Temperature_MCP9600.h +++ b/libraries/SITL/SIM_Temperature_MCP9600.h @@ -30,7 +30,6 @@ private: // should be a call on aircraft: float some_temperature = 26.5; - float last_temperature = -1000.0f; uint32_t last_temperature_update_ms; }; diff --git a/libraries/SITL/SIM_VectorNav.h b/libraries/SITL/SIM_VectorNav.h index c072807da5..4e73f69478 100644 --- a/libraries/SITL/SIM_VectorNav.h +++ b/libraries/SITL/SIM_VectorNav.h @@ -41,10 +41,6 @@ public: void update(void); private: - // TODO: make these parameters: - const uint8_t system_id = 17; - const uint8_t component_id = 18; - uint32_t last_pkt1_us; uint32_t last_pkt2_us;