mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
SITL: nuke clang warnings
This commit is contained in:
parent
173a43e361
commit
72d01aa8da
@ -40,11 +40,6 @@ public:
|
||||
|
||||
AP_Int8 _enable; // enable buzzer sim
|
||||
AP_Int8 _pin;
|
||||
bool was_on;
|
||||
|
||||
uint32_t on_time;
|
||||
|
||||
bool prep_done;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -44,8 +44,6 @@ public:
|
||||
private:
|
||||
void send_table();
|
||||
|
||||
uint32_t time_send_ms;
|
||||
|
||||
struct PACKED {
|
||||
uint16_t size;
|
||||
uint8_t command;
|
||||
|
@ -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;
|
||||
|
@ -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 {
|
||||
|
@ -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<RichenPacket, 70> _assert_storage_size_RichenPacket;
|
||||
assert_storage_size<RichenPacket, 70> _assert_storage_size_RichenPacket UNUSED_PRIVATE_MEMBER;
|
||||
|
||||
union RichenUnion {
|
||||
uint8_t parse_buffer[70];
|
||||
|
@ -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)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -86,8 +86,6 @@ private:
|
||||
uint64_t prev_timestamp_us;
|
||||
SocketAPM recv_sock;
|
||||
SocketAPM send_sock;
|
||||
|
||||
const char *frame_str;
|
||||
};
|
||||
|
||||
} // namespace SITL
|
||||
|
@ -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;
|
||||
};
|
||||
|
@ -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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user