Browse Source

Plane: Remove _navigate indirection in Mode.

zr-v5.1
Samuel Tabor 5 years ago committed by Peter Barker
parent
commit
836be4b4b4
  1. 5
      ArduPlane/mode.cpp
  2. 27
      ArduPlane/mode.h
  3. 2
      ArduPlane/mode_auto.cpp
  4. 2
      ArduPlane/mode_avoidADSB.cpp
  5. 2
      ArduPlane/mode_cruise.cpp
  6. 2
      ArduPlane/mode_guided.cpp
  7. 2
      ArduPlane/mode_loiter.cpp
  8. 2
      ArduPlane/mode_rtl.cpp
  9. 2
      ArduPlane/mode_takeoff.cpp

5
ArduPlane/mode.cpp

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

27
ArduPlane/mode.h

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

2
ArduPlane/mode_auto.cpp

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

2
ArduPlane/mode_avoidADSB.cpp

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

2
ArduPlane/mode_cruise.cpp

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

2
ArduPlane/mode_guided.cpp

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

2
ArduPlane/mode_loiter.cpp

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

2
ArduPlane/mode_rtl.cpp

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

2
ArduPlane/mode_takeoff.cpp

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

Loading…
Cancel
Save