Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: remove unused definitions #29210

Merged
merged 3 commits into from
Feb 3, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
16 changes: 0 additions & 16 deletions ArduPlane/Plane.h
Original file line number Diff line number Diff line change
Expand Up @@ -347,10 +347,6 @@ class Plane : public AP_Vehicle {
// time of last mode change
uint32_t last_mode_change_ms;

// Used to maintain the state of the previous control switch position
// This is set to 254 when we need to re-read the switch
uint8_t oldSwitchPosition = 254;

// This is used to enable the inverted flight feature
bool inverted_flight;

Expand Down Expand Up @@ -758,8 +754,6 @@ class Plane : public AP_Vehicle {
// A starting value used to check the status of a conditional command.
// For example in a delay command the condition_start records that start time for the delay
uint32_t condition_start;
// A value used in condition commands. For example the rate at which to change altitude.
int16_t condition_rate;

// 3D Location vectors
// Location structure defined in AP_Common
Expand Down Expand Up @@ -808,8 +802,6 @@ class Plane : public AP_Vehicle {

float relative_altitude;

// loop performance monitoring:
AP::PerfInfo perf_info;
struct {
uint32_t last_trim_check;
uint32_t last_trim_save;
Expand Down Expand Up @@ -904,7 +896,6 @@ class Plane : public AP_Vehicle {
float relative_ground_altitude(bool use_rangefinder_if_available);
float relative_ground_altitude(bool use_rangefinder_if_available, bool use_terrain_if_available);
void set_target_altitude_current(void);
void set_target_altitude_current_adjusted(void);
void set_target_altitude_location(const Location &loc);
int32_t relative_target_altitude_cm(void);
void change_target_altitude(int32_t change_cm);
Expand Down Expand Up @@ -1042,13 +1033,10 @@ class Plane : public AP_Vehicle {
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;

// control_modes.cpp
void read_control_switch();
uint8_t readSwitch(void) const;
void autotune_start(void);
void autotune_restore(void);
void autotune_enable(bool enable);
bool fly_inverted(void);
bool mode_allows_autotuning(void);
uint8_t get_mode() const override { return (uint8_t)control_mode->mode_number(); }
Mode *mode_from_mode_num(const enum Mode::Number num);
bool current_mode_requires_mission() const override {
Expand Down Expand Up @@ -1077,7 +1065,6 @@ class Plane : public AP_Vehicle {
bool trigger_land_abort(const float climb_to_alt_m);
void get_osd_roll_pitch_rad(float &roll, float &pitch) const override;
float tecs_hgt_afe(void);
void efi_update(void);
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
Expand Down Expand Up @@ -1113,7 +1100,6 @@ class Plane : public AP_Vehicle {
void calc_gndspeed_undershoot();
void update_loiter(uint16_t radius);
void update_loiter_update_nav(uint16_t radius);
void update_cruise();
void update_fbwb_speed_height(void);
void setup_turn_angle(void);
bool reached_loiter_target(void);
Expand Down Expand Up @@ -1168,7 +1154,6 @@ class Plane : public AP_Vehicle {
float apply_throttle_limits(float throttle_in);
void set_throttle(void);
void set_takeoff_expected(void);
void set_servos_old_elevons(void);
void set_servos_flaps(void);
void set_landing_gear(void);
void dspoiler_update(void);
Expand Down Expand Up @@ -1196,7 +1181,6 @@ class Plane : public AP_Vehicle {
// parachute.cpp
void parachute_check();
#if HAL_PARACHUTE_ENABLED
void do_parachute(const AP_Mission::Mission_Command& cmd);
void parachute_release();
bool parachute_manual_release();
#endif
Expand Down
11 changes: 0 additions & 11 deletions ArduPlane/altitude.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -208,17 +208,6 @@ void Plane::set_target_altitude_current(void)
#endif
}

/*
set the target altitude to the current altitude, with ALT_OFFSET adjustment
*/
void Plane::set_target_altitude_current_adjusted(void)
{
set_target_altitude_current();

// use adjusted_altitude_cm() to take account of ALTITUDE_OFFSET
target_altitude.amsl_cm = adjusted_altitude_cm();
}

/*
set target altitude based on a location structure
*/
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@ void Plane::takeoff_calc_throttle() {
const float current_baro_alt = barometer.get_altitude();
const bool below_lvl_alt = current_baro_alt < auto_state.baro_takeoff_alt + mode_takeoff.level_alt;
// Set the minimum throttle limit.
const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
const bool use_throttle_range = tkoff_option_is_set(AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
if (!use_throttle_range // We don't want to employ a throttle range.
|| !ahrs.using_airspeed_sensor() // We don't have an airspeed sensor.
|| below_lvl_alt // We are below TKOFF_LVL_ALT.
Expand Down
Loading