mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: move get_wp_xxx declarations higher in Copter.h
The declarations are grouped by the file in which they appear except for these 3
This commit is contained in:
parent
c19d5391d9
commit
cd1a62b7bc
@ -673,6 +673,9 @@ private:
|
|||||||
void update_super_simple_bearing(bool force_update);
|
void update_super_simple_bearing(bool force_update);
|
||||||
void read_AHRS(void);
|
void read_AHRS(void);
|
||||||
void update_altitude();
|
void update_altitude();
|
||||||
|
bool get_wp_distance_m(float &distance) const override;
|
||||||
|
bool get_wp_bearing_deg(float &bearing) const override;
|
||||||
|
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
|
||||||
|
|
||||||
// Attitude.cpp
|
// Attitude.cpp
|
||||||
void update_throttle_hover();
|
void update_throttle_hover();
|
||||||
@ -914,11 +917,6 @@ private:
|
|||||||
void userhook_auxSwitch2(const RC_Channel::AuxSwitchPos ch_flag);
|
void userhook_auxSwitch2(const RC_Channel::AuxSwitchPos ch_flag);
|
||||||
void userhook_auxSwitch3(const RC_Channel::AuxSwitchPos ch_flag);
|
void userhook_auxSwitch3(const RC_Channel::AuxSwitchPos ch_flag);
|
||||||
|
|
||||||
// vehicle specific waypoint info helpers
|
|
||||||
bool get_wp_distance_m(float &distance) const override;
|
|
||||||
bool get_wp_bearing_deg(float &bearing) const override;
|
|
||||||
bool get_wp_crosstrack_error_m(float &xtrack_error) const override;
|
|
||||||
|
|
||||||
#if MODE_ACRO_ENABLED == ENABLED
|
#if MODE_ACRO_ENABLED == ENABLED
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
ModeAcro_Heli mode_acro;
|
ModeAcro_Heli mode_acro;
|
||||||
|
Loading…
Reference in New Issue
Block a user