mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: remove unused update_navigation and run_autopilot
This commit is contained in:
parent
1c350514ca
commit
32fb3cb929
@ -406,12 +406,6 @@ void Copter::notify_flight_mode() {
|
|||||||
notify.set_flight_mode_str(flightmode->name4());
|
notify.set_flight_mode_str(flightmode->name4());
|
||||||
}
|
}
|
||||||
|
|
||||||
void Mode::update_navigation()
|
|
||||||
{
|
|
||||||
// run autopilot to make high level decisions about control modes
|
|
||||||
run_autopilot();
|
|
||||||
}
|
|
||||||
|
|
||||||
// get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle
|
// get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle
|
||||||
// returns desired angle in centi-degrees
|
// returns desired angle in centi-degrees
|
||||||
void Mode::get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
|
void Mode::get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
|
||||||
|
@ -77,8 +77,6 @@ public:
|
|||||||
virtual uint32_t wp_distance() const { return 0; }
|
virtual uint32_t wp_distance() const { return 0; }
|
||||||
virtual float crosstrack_error() const { return 0.0f;}
|
virtual float crosstrack_error() const { return 0.0f;}
|
||||||
|
|
||||||
void update_navigation();
|
|
||||||
|
|
||||||
int32_t get_alt_above_ground_cm(void);
|
int32_t get_alt_above_ground_cm(void);
|
||||||
|
|
||||||
// pilot input processing
|
// pilot input processing
|
||||||
@ -98,9 +96,6 @@ public:
|
|||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
// navigation support functions
|
|
||||||
virtual void run_autopilot() {}
|
|
||||||
|
|
||||||
// helper functions
|
// helper functions
|
||||||
bool is_disarmed_or_landed() const;
|
bool is_disarmed_or_landed() const;
|
||||||
void zero_throttle_and_relax_ac(bool spool_up = false);
|
void zero_throttle_and_relax_ac(bool spool_up = false);
|
||||||
|
@ -6,8 +6,6 @@
|
|||||||
void Copter::run_nav_updates(void)
|
void Copter::run_nav_updates(void)
|
||||||
{
|
{
|
||||||
update_super_simple_bearing(false);
|
update_super_simple_bearing(false);
|
||||||
|
|
||||||
flightmode->update_navigation();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// distance between vehicle and home in cm
|
// distance between vehicle and home in cm
|
||||||
|
Loading…
Reference in New Issue
Block a user