mirror of https://github.com/ArduPilot/ardupilot
SITL: remove unused variables
This commit is contained in:
parent
2e2491f4ff
commit
3224cf19a8
|
@ -407,7 +407,7 @@ void Frame::load_frame_params(const char *model_json)
|
||||||
char label_name[20];
|
char label_name[20];
|
||||||
for (uint8_t i=0; i<ARRAY_SIZE(per_motor_vars); i++) {
|
for (uint8_t i=0; i<ARRAY_SIZE(per_motor_vars); i++) {
|
||||||
for (uint8_t j=0; j<12; j++) {
|
for (uint8_t j=0; j<12; j++) {
|
||||||
sprintf(label_name, "motor%i_%s", j+1, per_motor_vars[i].label);
|
snprintf(label_name, 20, "motor%i_%s", j+1, per_motor_vars[i].label);
|
||||||
auto v = obj->get(label_name);
|
auto v = obj->get(label_name);
|
||||||
if (v.is<picojson::null>()) {
|
if (v.is<picojson::null>()) {
|
||||||
// use default value
|
// use default value
|
||||||
|
@ -553,11 +553,9 @@ void Frame::calculate_forces(const Aircraft &aircraft,
|
||||||
|
|
||||||
Vector3f vel_air_bf = aircraft.get_dcm().transposed() * aircraft.get_velocity_air_ef();
|
Vector3f vel_air_bf = aircraft.get_dcm().transposed() * aircraft.get_velocity_air_ef();
|
||||||
|
|
||||||
float current = 0;
|
|
||||||
for (uint8_t i=0; i<num_motors; i++) {
|
for (uint8_t i=0; i<num_motors; i++) {
|
||||||
Vector3f mtorque, mthrust;
|
Vector3f mtorque, mthrust;
|
||||||
motors[i].calculate_forces(input, motor_offset, mtorque, mthrust, vel_air_bf, gyro, air_density, battery->get_voltage(), use_drag);
|
motors[i].calculate_forces(input, motor_offset, mtorque, mthrust, vel_air_bf, gyro, air_density, battery->get_voltage(), use_drag);
|
||||||
current += motors[i].get_current();
|
|
||||||
torque += mtorque;
|
torque += mtorque;
|
||||||
thrust += mthrust;
|
thrust += mthrust;
|
||||||
// simulate motor rpm
|
// simulate motor rpm
|
||||||
|
|
|
@ -59,14 +59,11 @@ protected:
|
||||||
|
|
||||||
private:
|
private:
|
||||||
float terminal_rotation_rate = 4*radians(360.0f);
|
float terminal_rotation_rate = 4*radians(360.0f);
|
||||||
float hover_throttle = 0.5f;
|
|
||||||
float terminal_velocity = 80;
|
|
||||||
float hover_lean = 3.2f;
|
float hover_lean = 3.2f;
|
||||||
float rotor_rot_accel = radians(20);
|
float rotor_rot_accel = radians(20);
|
||||||
float roll_rate_max = radians(1400);
|
float roll_rate_max = radians(1400);
|
||||||
float pitch_rate_max = radians(1400);
|
float pitch_rate_max = radians(1400);
|
||||||
float yaw_rate_max = radians(1400);
|
float yaw_rate_max = radians(1400);
|
||||||
float rsc_setpoint = 0.8f;
|
|
||||||
float izz = 0.2f;
|
float izz = 0.2f;
|
||||||
float iyy;
|
float iyy;
|
||||||
float tr_dist = 0.85f;
|
float tr_dist = 0.85f;
|
||||||
|
|
|
@ -72,12 +72,7 @@ private:
|
||||||
uint8_t &_ramp_down_step_time,
|
uint8_t &_ramp_down_step_time,
|
||||||
uint8_t &_timing) :
|
uint8_t &_timing) :
|
||||||
high_level{_high_level},
|
high_level{_high_level},
|
||||||
low_level{_low_level},
|
low_level{_low_level}
|
||||||
delay{_delay},
|
|
||||||
ramp_up_step_time{_ramp_up_step_time},
|
|
||||||
time_high{_time_high},
|
|
||||||
ramp_down_step_time{_ramp_down_step_time},
|
|
||||||
timing{_timing}
|
|
||||||
{ }
|
{ }
|
||||||
|
|
||||||
void update();
|
void update();
|
||||||
|
@ -88,11 +83,6 @@ private:
|
||||||
private:
|
private:
|
||||||
uint8_t &high_level;
|
uint8_t &high_level;
|
||||||
uint8_t &low_level;
|
uint8_t &low_level;
|
||||||
uint8_t &delay;
|
|
||||||
uint8_t &ramp_up_step_time;
|
|
||||||
uint8_t &time_high;
|
|
||||||
uint8_t &ramp_down_step_time;
|
|
||||||
uint8_t &timing;
|
|
||||||
|
|
||||||
uint8_t output_value;
|
uint8_t output_value;
|
||||||
};
|
};
|
||||||
|
|
|
@ -48,8 +48,6 @@ private:
|
||||||
void send_packet1();
|
void send_packet1();
|
||||||
void send_packet2();
|
void send_packet2();
|
||||||
void nmea_printf(const char *fmt, ...);
|
void nmea_printf(const char *fmt, ...);
|
||||||
|
|
||||||
uint64_t start_us;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -133,7 +133,6 @@ private:
|
||||||
void check_reload_dref(void);
|
void check_reload_dref(void);
|
||||||
|
|
||||||
uint32_t xplane_version;
|
uint32_t xplane_version;
|
||||||
bool have_ref_lat;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue