Plane: Remove _navigate indirection in Mode.

This commit is contained in:
Samuel Tabor 2020-08-19 08:51:00 +01:00 committed by Peter Barker
parent 6a27866df4
commit 836be4b4b4
9 changed files with 22 additions and 24 deletions

View File

@ -85,8 +85,3 @@ bool Mode::enter()
return enter_result;
}
void Mode::navigate()
{
_navigate();
}

View File

@ -74,8 +74,8 @@ public:
// true if mode can have terrain following disabled by switch
virtual bool allows_terrain_disable() const { return false; }
// navigation
void navigate();
// subclasses override this if they require navigation.
virtual void navigate() { return; }
protected:
@ -84,9 +84,6 @@ protected:
// subclasses override this to perform any required cleanup when exiting the mode
virtual void _exit() { return; }
// subclasses override this if they require navigation.
virtual void _navigate() { return; }
};
@ -117,11 +114,12 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
protected:
bool _enter() override;
void _exit() override;
void _navigate() override;
};
@ -153,10 +151,11 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
protected:
bool _enter() override;
void _navigate() override;
};
class ModeCircle: public Mode
@ -186,13 +185,14 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
bool isHeadingLinedUp(const Location loiterCenterLoc, const Location targetLoc);
bool isHeadingLinedUp_cd(const int32_t bearing_cd);
protected:
bool _enter() override;
void _navigate() override;
};
class ModeManual : public Mode
@ -224,10 +224,11 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
protected:
bool _enter() override;
void _navigate() override;
};
class ModeStabilize : public Mode
@ -326,10 +327,11 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
protected:
bool _enter() override;
void _navigate() override;
};
class ModeAvoidADSB : public Mode
@ -343,10 +345,10 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
protected:
bool _enter() override;
void _navigate() override;
};
class ModeQStabilize : public Mode
@ -497,6 +499,8 @@ public:
// methods that affect movement of the vehicle in this mode
void update() override;
void navigate() override;
// var_info for holding parameter information
static const struct AP_Param::GroupInfo var_info[];
@ -510,5 +514,4 @@ protected:
Location start_loc;
bool _enter() override;
void _navigate() override;
};

View File

@ -88,7 +88,7 @@ void ModeAuto::update()
}
}
void ModeAuto::_navigate()
void ModeAuto::navigate()
{
if (AP::ahrs().home_is_set()) {
plane.mission.update();

View File

@ -11,7 +11,7 @@ void ModeAvoidADSB::update()
plane.mode_guided.update();
}
void ModeAvoidADSB::_navigate()
void ModeAvoidADSB::navigate()
{
// Zero indicates to use WP_LOITER_RAD
plane.update_loiter(0);

View File

@ -44,7 +44,7 @@ void ModeCruise::update()
handle CRUISE mode, locking heading to GPS course when we have
sufficient ground speed, and no aileron or rudder input
*/
void ModeCruise::_navigate()
void ModeCruise::navigate()
{
if (!plane.cruise_state.locked_heading &&
plane.channel_roll->get_control_in() == 0 &&

View File

@ -28,7 +28,7 @@ void ModeGuided::update()
}
}
void ModeGuided::_navigate()
void ModeGuided::navigate()
{
// Zero indicates to use WP_LOITER_RAD
plane.update_loiter(0);

View File

@ -81,7 +81,7 @@ bool ModeLoiter::isHeadingLinedUp_cd(const int32_t bearing_cd)
return false;
}
void ModeLoiter::_navigate()
void ModeLoiter::navigate()
{
// Zero indicates to use WP_LOITER_RAD
plane.update_loiter(0);

View File

@ -34,7 +34,7 @@ void ModeRTL::update()
}
}
void ModeRTL::_navigate()
void ModeRTL::navigate()
{
uint16_t qrtl_radius = abs(plane.g.rtl_radius);
if (qrtl_radius == 0) {

View File

@ -131,7 +131,7 @@ void ModeTakeoff::update()
}
}
void ModeTakeoff::_navigate()
void ModeTakeoff::navigate()
{
// Zero indicates to use WP_LOITER_RAD
plane.update_loiter(0);