mirror of https://github.com/ArduPilot/ardupilot
Plane: move auto_throttle_mode to being a method on each mode
This commit is contained in:
parent
f6cb1b5ad6
commit
6baaf03c8c
|
@ -156,7 +156,7 @@ bool AP_Arming_Plane::arm_checks(AP_Arming::Method method)
|
||||||
|
|
||||||
// if not in a manual throttle mode and not in CRUISE or FBWB
|
// if not in a manual throttle mode and not in CRUISE or FBWB
|
||||||
// modes then disallow rudder arming/disarming
|
// modes then disallow rudder arming/disarming
|
||||||
if (plane.auto_throttle_mode &&
|
if (plane.control_mode->does_auto_throttle() &&
|
||||||
(plane.control_mode != &plane.mode_cruise && plane.control_mode != &plane.mode_fbwb)) {
|
(plane.control_mode != &plane.mode_cruise && plane.control_mode != &plane.mode_fbwb)) {
|
||||||
check_failed(true, "Mode not rudder-armable");
|
check_failed(true, "Mode not rudder-armable");
|
||||||
return false;
|
return false;
|
||||||
|
@ -254,7 +254,7 @@ bool AP_Arming_Plane::disarm(const AP_Arming::Method method)
|
||||||
}
|
}
|
||||||
|
|
||||||
// suppress the throttle in auto-throttle modes
|
// suppress the throttle in auto-throttle modes
|
||||||
plane.throttle_suppressed = plane.auto_throttle_mode;
|
plane.throttle_suppressed = plane.control_mode->does_auto_throttle();
|
||||||
|
|
||||||
// if no airmode switch assigned, ensure airmode is off:
|
// if no airmode switch assigned, ensure airmode is off:
|
||||||
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr) {
|
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr) {
|
||||||
|
|
|
@ -169,7 +169,7 @@ void Plane::ahrs_update()
|
||||||
*/
|
*/
|
||||||
void Plane::update_speed_height(void)
|
void Plane::update_speed_height(void)
|
||||||
{
|
{
|
||||||
if (auto_throttle_mode) {
|
if (control_mode->does_auto_throttle()) {
|
||||||
// Call TECS 50Hz update. Note that we call this regardless of
|
// Call TECS 50Hz update. Note that we call this regardless of
|
||||||
// throttle suppressed, as this needs to be running for
|
// throttle suppressed, as this needs to be running for
|
||||||
// takeoff detection
|
// takeoff detection
|
||||||
|
@ -481,7 +481,7 @@ void Plane::update_alt()
|
||||||
|
|
||||||
update_flight_stage();
|
update_flight_stage();
|
||||||
|
|
||||||
if (auto_throttle_mode && !throttle_suppressed) {
|
if (control_mode->does_auto_throttle() && !throttle_suppressed) {
|
||||||
|
|
||||||
float distance_beyond_land_wp = 0;
|
float distance_beyond_land_wp = 0;
|
||||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND && current_loc.past_interval_finish_line(prev_WP_loc, next_WP_loc)) {
|
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND && current_loc.past_interval_finish_line(prev_WP_loc, next_WP_loc)) {
|
||||||
|
@ -514,7 +514,7 @@ void Plane::update_alt()
|
||||||
void Plane::update_flight_stage(void)
|
void Plane::update_flight_stage(void)
|
||||||
{
|
{
|
||||||
// Update the speed & height controller states
|
// Update the speed & height controller states
|
||||||
if (auto_throttle_mode && !throttle_suppressed) {
|
if (control_mode->does_auto_throttle() && !throttle_suppressed) {
|
||||||
if (control_mode == &mode_auto) {
|
if (control_mode == &mode_auto) {
|
||||||
if (quadplane.in_vtol_auto()) {
|
if (quadplane.in_vtol_auto()) {
|
||||||
set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_VTOL);
|
set_flight_stage(AP_Vehicle::FixedWing::FLIGHT_VTOL);
|
||||||
|
|
|
@ -54,7 +54,7 @@ float Plane::get_speed_scaler(void)
|
||||||
*/
|
*/
|
||||||
bool Plane::stick_mixing_enabled(void)
|
bool Plane::stick_mixing_enabled(void)
|
||||||
{
|
{
|
||||||
if (auto_throttle_mode && plane.control_mode->does_auto_navigation()) {
|
if (control_mode->does_auto_throttle() && plane.control_mode->does_auto_navigation()) {
|
||||||
// we're in an auto mode. Check the stick mixing flag
|
// we're in an auto mode. Check the stick mixing flag
|
||||||
if (g.stick_mixing != STICK_MIXING_DISABLED &&
|
if (g.stick_mixing != STICK_MIXING_DISABLED &&
|
||||||
g.stick_mixing != STICK_MIXING_VTOL_YAW &&
|
g.stick_mixing != STICK_MIXING_VTOL_YAW &&
|
||||||
|
@ -125,7 +125,7 @@ void Plane::stabilize_pitch(float speed_scaler)
|
||||||
}
|
}
|
||||||
|
|
||||||
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_CD if flight option FORCE_FLARE_ATTITUDE is set
|
// if LANDING_FLARE RCx_OPTION switch is set and in FW mode, manual throttle,throttle idle then set pitch to LAND_PITCH_CD if flight option FORCE_FLARE_ATTITUDE is set
|
||||||
if (!quadplane.in_transition() && !control_mode->is_vtol_mode() && channel_throttle->in_trim_dz() && !auto_throttle_mode && flare_mode == FlareMode::ENABLED_PITCH_TARGET) {
|
if (!quadplane.in_transition() && !control_mode->is_vtol_mode() && channel_throttle->in_trim_dz() && !control_mode->does_auto_throttle() && flare_mode == FlareMode::ENABLED_PITCH_TARGET) {
|
||||||
demanded_pitch = landing.get_pitch_cd();
|
demanded_pitch = landing.get_pitch_cd();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -572,10 +572,6 @@ private:
|
||||||
uint32_t impact_timer_ms;
|
uint32_t impact_timer_ms;
|
||||||
} crash_state;
|
} crash_state;
|
||||||
|
|
||||||
// true if we are in an auto-throttle mode, which means
|
|
||||||
// we need to run the speed/height controller
|
|
||||||
bool auto_throttle_mode:1;
|
|
||||||
|
|
||||||
// this controls throttle suppression in auto modes
|
// this controls throttle suppression in auto modes
|
||||||
bool throttle_suppressed;
|
bool throttle_suppressed;
|
||||||
|
|
||||||
|
|
|
@ -90,7 +90,7 @@ void AP_AdvancedFailsafe_Plane::setup_IO_failsafe(void)
|
||||||
*/
|
*/
|
||||||
AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Plane::afs_mode(void)
|
AP_AdvancedFailsafe::control_mode AP_AdvancedFailsafe_Plane::afs_mode(void)
|
||||||
{
|
{
|
||||||
if (plane.auto_throttle_mode) {
|
if (plane.control_mode->does_auto_throttle()) {
|
||||||
return AP_AdvancedFailsafe::AFS_AUTO;
|
return AP_AdvancedFailsafe::AFS_AUTO;
|
||||||
}
|
}
|
||||||
if (plane.control_mode == &plane.mode_manual) {
|
if (plane.control_mode == &plane.mode_manual) {
|
||||||
|
|
|
@ -71,7 +71,7 @@ bool Mode::enter()
|
||||||
// these must be done AFTER _enter() because they use the results to set more flags
|
// these must be done AFTER _enter() because they use the results to set more flags
|
||||||
|
|
||||||
// start with throttle suppressed in auto_throttle modes
|
// start with throttle suppressed in auto_throttle modes
|
||||||
plane.throttle_suppressed = plane.auto_throttle_mode;
|
plane.throttle_suppressed = does_auto_throttle();
|
||||||
#if HAL_ADSB_ENABLED
|
#if HAL_ADSB_ENABLED
|
||||||
plane.adsb.set_is_auto_mode(does_auto_navigation());
|
plane.adsb.set_is_auto_mode(does_auto_navigation());
|
||||||
#endif
|
#endif
|
||||||
|
@ -93,8 +93,8 @@ bool Mode::is_vtol_man_throttle() const
|
||||||
// We are a tailsitter that has fully transitioned to Q-assisted forward flight.
|
// We are a tailsitter that has fully transitioned to Q-assisted forward flight.
|
||||||
// In this case the forward throttle directly drives the vertical throttle so
|
// In this case the forward throttle directly drives the vertical throttle so
|
||||||
// set vertical throttle state to match the forward throttle state. Confusingly the booleans are inverted,
|
// set vertical throttle state to match the forward throttle state. Confusingly the booleans are inverted,
|
||||||
// forward throttle uses 'auto_throttle_mode' whereas vertical uses 'is_vtol_man_throttle'.
|
// forward throttle uses 'does_auto_throttle' whereas vertical uses 'is_vtol_man_throttle'.
|
||||||
return !plane.auto_throttle_mode;
|
return !does_auto_throttle();
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
|
@ -91,6 +91,10 @@ public:
|
||||||
// whether control input is ignored with STICK_MIXING=0
|
// whether control input is ignored with STICK_MIXING=0
|
||||||
virtual bool does_auto_navigation() const { return false; }
|
virtual bool does_auto_navigation() const { return false; }
|
||||||
|
|
||||||
|
// true if the mode sets the vehicle destination, which controls
|
||||||
|
// whether control input is ignored with STICK_MIXING=0
|
||||||
|
virtual bool does_auto_throttle() const { return false; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
// subclasses override this to perform checks before entering the mode
|
// subclasses override this to perform checks before entering the mode
|
||||||
|
@ -134,6 +138,8 @@ public:
|
||||||
|
|
||||||
bool does_auto_navigation() const override { return true; }
|
bool does_auto_navigation() const override { return true; }
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -177,6 +183,8 @@ public:
|
||||||
|
|
||||||
bool does_auto_navigation() const override { return true; }
|
bool does_auto_navigation() const override { return true; }
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -195,6 +203,8 @@ public:
|
||||||
|
|
||||||
bool does_auto_navigation() const override { return true; }
|
bool does_auto_navigation() const override { return true; }
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -216,8 +226,12 @@ public:
|
||||||
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);
|
||||||
|
|
||||||
|
bool allows_throttle_nudging() const override { return true; }
|
||||||
|
|
||||||
bool does_auto_navigation() const override { return true; }
|
bool does_auto_navigation() const override { return true; }
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -236,7 +250,6 @@ public:
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
|
||||||
void _exit() override;
|
void _exit() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -258,6 +271,8 @@ public:
|
||||||
|
|
||||||
bool does_auto_navigation() const override { return true; }
|
bool does_auto_navigation() const override { return true; }
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -273,10 +288,6 @@ 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;
|
||||||
|
|
||||||
protected:
|
|
||||||
|
|
||||||
bool _enter() override;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class ModeTraining : public Mode
|
class ModeTraining : public Mode
|
||||||
|
@ -289,10 +300,6 @@ 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;
|
||||||
|
|
||||||
protected:
|
|
||||||
|
|
||||||
bool _enter() override;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class ModeInitializing : public Mode
|
class ModeInitializing : public Mode
|
||||||
|
@ -308,9 +315,7 @@ public:
|
||||||
|
|
||||||
bool allows_throttle_nudging() const override { return true; }
|
bool allows_throttle_nudging() const override { return true; }
|
||||||
|
|
||||||
protected:
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
bool _enter() override;
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class ModeFBWA : public Mode
|
class ModeFBWA : public Mode
|
||||||
|
@ -324,10 +329,6 @@ 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;
|
||||||
|
|
||||||
bool _enter() override;
|
|
||||||
|
|
||||||
protected:
|
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
class ModeFBWB : public Mode
|
class ModeFBWB : public Mode
|
||||||
|
@ -343,6 +344,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;
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -365,6 +368,8 @@ public:
|
||||||
|
|
||||||
bool get_target_heading_cd(int32_t &target_heading);
|
bool get_target_heading_cd(int32_t &target_heading);
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -390,6 +395,8 @@ public:
|
||||||
|
|
||||||
virtual bool is_guided_mode() const override { return true; }
|
virtual bool is_guided_mode() const override { return true; }
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -433,6 +440,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;
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -452,6 +461,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;
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -470,6 +481,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;
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -488,6 +501,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;
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -527,6 +542,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;
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
@ -552,6 +569,8 @@ public:
|
||||||
|
|
||||||
bool does_auto_navigation() const override { return true; }
|
bool does_auto_navigation() const override { return true; }
|
||||||
|
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
// 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[];
|
||||||
|
|
||||||
|
@ -589,6 +608,10 @@ public:
|
||||||
|
|
||||||
bool does_auto_navigation() const override { return true; }
|
bool does_auto_navigation() const override { return true; }
|
||||||
|
|
||||||
|
// true if we are in an auto-throttle mode, which means
|
||||||
|
// we need to run the speed/height controller
|
||||||
|
bool does_auto_throttle() const override { return true; }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool exit_heading_aligned() const;
|
bool exit_heading_aligned() const;
|
||||||
|
|
|
@ -3,7 +3,6 @@
|
||||||
|
|
||||||
bool ModeAcro::_enter()
|
bool ModeAcro::_enter()
|
||||||
{
|
{
|
||||||
plane.auto_throttle_mode = false;
|
|
||||||
plane.acro_state.locked_roll = false;
|
plane.acro_state.locked_roll = false;
|
||||||
plane.acro_state.locked_pitch = false;
|
plane.acro_state.locked_pitch = false;
|
||||||
|
|
||||||
|
|
|
@ -3,7 +3,6 @@
|
||||||
|
|
||||||
bool ModeAuto::_enter()
|
bool ModeAuto::_enter()
|
||||||
{
|
{
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
if (plane.quadplane.available() && plane.quadplane.enable == 2) {
|
if (plane.quadplane.available() && plane.quadplane.enable == 2) {
|
||||||
plane.auto_state.vtol_mode = true;
|
plane.auto_state.vtol_mode = true;
|
||||||
} else {
|
} else {
|
||||||
|
|
|
@ -3,7 +3,6 @@
|
||||||
|
|
||||||
bool ModeAutoTune::_enter()
|
bool ModeAutoTune::_enter()
|
||||||
{
|
{
|
||||||
plane.auto_throttle_mode = false;
|
|
||||||
plane.autotune_start();
|
plane.autotune_start();
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -4,7 +4,6 @@
|
||||||
bool ModeCircle::_enter()
|
bool ModeCircle::_enter()
|
||||||
{
|
{
|
||||||
// the altitude to circle at is taken from the current altitude
|
// the altitude to circle at is taken from the current altitude
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
plane.next_WP_loc.alt = plane.current_loc.alt;
|
plane.next_WP_loc.alt = plane.current_loc.alt;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -3,7 +3,6 @@
|
||||||
|
|
||||||
bool ModeCruise::_enter()
|
bool ModeCruise::_enter()
|
||||||
{
|
{
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
locked_heading = false;
|
locked_heading = false;
|
||||||
lock_timer_ms = 0;
|
lock_timer_ms = 0;
|
||||||
|
|
||||||
|
|
|
@ -1,13 +1,6 @@
|
||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
#include "Plane.h"
|
#include "Plane.h"
|
||||||
|
|
||||||
bool ModeFBWA::_enter()
|
|
||||||
{
|
|
||||||
plane.auto_throttle_mode = false;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ModeFBWA::update()
|
void ModeFBWA::update()
|
||||||
{
|
{
|
||||||
// set nav_roll and nav_pitch using sticks
|
// set nav_roll and nav_pitch using sticks
|
||||||
|
|
|
@ -3,8 +3,6 @@
|
||||||
|
|
||||||
bool ModeFBWB::_enter()
|
bool ModeFBWB::_enter()
|
||||||
{
|
{
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
|
|
||||||
#if HAL_SOARING_ENABLED
|
#if HAL_SOARING_ENABLED
|
||||||
// for ArduSoar soaring_controller
|
// for ArduSoar soaring_controller
|
||||||
plane.g2.soaring_controller.init_cruising();
|
plane.g2.soaring_controller.init_cruising();
|
||||||
|
|
|
@ -3,7 +3,6 @@
|
||||||
|
|
||||||
bool ModeGuided::_enter()
|
bool ModeGuided::_enter()
|
||||||
{
|
{
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
plane.guided_throttle_passthru = false;
|
plane.guided_throttle_passthru = false;
|
||||||
/*
|
/*
|
||||||
when entering guided mode we set the target as the current
|
when entering guided mode we set the target as the current
|
||||||
|
|
|
@ -1,10 +0,0 @@
|
||||||
#include "mode.h"
|
|
||||||
#include "Plane.h"
|
|
||||||
|
|
||||||
bool ModeInitializing::_enter()
|
|
||||||
{
|
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
|
@ -3,7 +3,6 @@
|
||||||
|
|
||||||
bool ModeLoiter::_enter()
|
bool ModeLoiter::_enter()
|
||||||
{
|
{
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
plane.do_loiter_at_location();
|
plane.do_loiter_at_location();
|
||||||
plane.loiter_angle_reset();
|
plane.loiter_angle_reset();
|
||||||
|
|
||||||
|
|
|
@ -1,13 +1,6 @@
|
||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
#include "Plane.h"
|
#include "Plane.h"
|
||||||
|
|
||||||
bool ModeManual::_enter()
|
|
||||||
{
|
|
||||||
plane.auto_throttle_mode = false;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ModeManual::_exit()
|
void ModeManual::_exit()
|
||||||
{
|
{
|
||||||
if (plane.g.auto_trim > 0) {
|
if (plane.g.auto_trim > 0) {
|
||||||
|
|
|
@ -6,7 +6,6 @@ bool ModeQAcro::_enter()
|
||||||
if (!plane.quadplane.init_mode() && plane.previous_mode != nullptr) {
|
if (!plane.quadplane.init_mode() && plane.previous_mode != nullptr) {
|
||||||
plane.control_mode = plane.previous_mode;
|
plane.control_mode = plane.previous_mode;
|
||||||
} else {
|
} else {
|
||||||
plane.auto_throttle_mode = false;
|
|
||||||
plane.auto_state.vtol_mode = true;
|
plane.auto_state.vtol_mode = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -6,7 +6,6 @@ bool ModeQStabilize::_enter()
|
||||||
if (!plane.quadplane.init_mode() && plane.previous_mode != nullptr) {
|
if (!plane.quadplane.init_mode() && plane.previous_mode != nullptr) {
|
||||||
plane.control_mode = plane.previous_mode;
|
plane.control_mode = plane.previous_mode;
|
||||||
} else {
|
} else {
|
||||||
plane.auto_throttle_mode = false;
|
|
||||||
plane.auto_state.vtol_mode = true;
|
plane.auto_state.vtol_mode = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -3,7 +3,6 @@
|
||||||
|
|
||||||
bool ModeRTL::_enter()
|
bool ModeRTL::_enter()
|
||||||
{
|
{
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
plane.prev_WP_loc = plane.current_loc;
|
plane.prev_WP_loc = plane.current_loc;
|
||||||
plane.do_RTL(plane.get_RTL_altitude());
|
plane.do_RTL(plane.get_RTL_altitude());
|
||||||
plane.rtl.done_climb = false;
|
plane.rtl.done_climb = false;
|
||||||
|
|
|
@ -1,13 +1,6 @@
|
||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
#include "Plane.h"
|
#include "Plane.h"
|
||||||
|
|
||||||
bool ModeStabilize::_enter()
|
|
||||||
{
|
|
||||||
plane.auto_throttle_mode = false;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ModeStabilize::update()
|
void ModeStabilize::update()
|
||||||
{
|
{
|
||||||
plane.nav_roll_cd = 0;
|
plane.nav_roll_cd = 0;
|
||||||
|
|
|
@ -51,9 +51,6 @@ ModeTakeoff::ModeTakeoff()
|
||||||
|
|
||||||
bool ModeTakeoff::_enter()
|
bool ModeTakeoff::_enter()
|
||||||
{
|
{
|
||||||
// the altitude to circle at is taken from the current altitude
|
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
|
|
||||||
takeoff_started = false;
|
takeoff_started = false;
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -9,7 +9,6 @@ bool ModeThermal::_enter()
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
plane.auto_throttle_mode = true;
|
|
||||||
plane.do_loiter_at_location();
|
plane.do_loiter_at_location();
|
||||||
plane.loiter_angle_reset();
|
plane.loiter_angle_reset();
|
||||||
|
|
||||||
|
|
|
@ -1,13 +1,6 @@
|
||||||
#include "mode.h"
|
#include "mode.h"
|
||||||
#include "Plane.h"
|
#include "Plane.h"
|
||||||
|
|
||||||
bool ModeTraining::_enter()
|
|
||||||
{
|
|
||||||
plane.auto_throttle_mode = false;
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void ModeTraining::update()
|
void ModeTraining::update()
|
||||||
{
|
{
|
||||||
plane.training_manual_roll = false;
|
plane.training_manual_roll = false;
|
||||||
|
|
|
@ -204,7 +204,7 @@ void Plane::calc_airspeed_errors()
|
||||||
// Set target to current airspeed + ground speed undershoot,
|
// Set target to current airspeed + ground speed undershoot,
|
||||||
// but only when this is faster than the target airspeed commanded
|
// but only when this is faster than the target airspeed commanded
|
||||||
// above.
|
// above.
|
||||||
if (auto_throttle_mode &&
|
if (control_mode->does_auto_throttle() &&
|
||||||
aparm.min_gndspeed_cm > 0 &&
|
aparm.min_gndspeed_cm > 0 &&
|
||||||
control_mode != &mode_circle) {
|
control_mode != &mode_circle) {
|
||||||
int32_t min_gnd_target_airspeed = airspeed_measured*100 + groundspeed_undershoot;
|
int32_t min_gnd_target_airspeed = airspeed_measured*100 + groundspeed_undershoot;
|
||||||
|
|
|
@ -1482,7 +1482,7 @@ float QuadPlane::get_pilot_input_yaw_rate_cds(void) const
|
||||||
{
|
{
|
||||||
bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && (air_mode == AirMode::ON);
|
bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && (air_mode == AirMode::ON);
|
||||||
if (!manual_air_mode &&
|
if (!manual_air_mode &&
|
||||||
plane.get_throttle_input() <= 0 && !plane.auto_throttle_mode &&
|
plane.get_throttle_input() <= 0 && !plane.control_mode->does_auto_throttle() &&
|
||||||
plane.arming.get_rudder_arming_type() != AP_Arming::RudderArming::IS_DISABLED) {
|
plane.arming.get_rudder_arming_type() != AP_Arming::RudderArming::IS_DISABLED) {
|
||||||
// the user may be trying to disarm
|
// the user may be trying to disarm
|
||||||
return 0;
|
return 0;
|
||||||
|
@ -1516,7 +1516,7 @@ float QuadPlane::get_desired_yaw_rate_cds(void)
|
||||||
yaw_cds += desired_auto_yaw_rate_cds();
|
yaw_cds += desired_auto_yaw_rate_cds();
|
||||||
}
|
}
|
||||||
bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && (air_mode == AirMode::ON);
|
bool manual_air_mode = plane.control_mode->is_vtol_man_throttle() && (air_mode == AirMode::ON);
|
||||||
if (plane.get_throttle_input() <= 0 && !plane.auto_throttle_mode && !manual_air_mode) {
|
if (plane.get_throttle_input() <= 0 && !plane.control_mode->does_auto_throttle() && !manual_air_mode) {
|
||||||
// the user may be trying to disarm
|
// the user may be trying to disarm
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
@ -1571,7 +1571,7 @@ void QuadPlane::set_armed(bool armed)
|
||||||
float QuadPlane::assist_climb_rate_cms(void) const
|
float QuadPlane::assist_climb_rate_cms(void) const
|
||||||
{
|
{
|
||||||
float climb_rate;
|
float climb_rate;
|
||||||
if (plane.auto_throttle_mode) {
|
if (plane.control_mode->does_auto_throttle()) {
|
||||||
// use altitude_error_cm, spread over 10s interval
|
// use altitude_error_cm, spread over 10s interval
|
||||||
climb_rate = plane.altitude_error_cm * 0.1f;
|
climb_rate = plane.altitude_error_cm * 0.1f;
|
||||||
} else {
|
} else {
|
||||||
|
@ -1698,7 +1698,7 @@ bool QuadPlane::assistance_needed(float aspeed, bool have_airspeed)
|
||||||
// return true if it is safe to provide assistance
|
// return true if it is safe to provide assistance
|
||||||
bool QuadPlane::assistance_safe()
|
bool QuadPlane::assistance_safe()
|
||||||
{
|
{
|
||||||
return hal.util->get_soft_armed() && ( (plane.auto_throttle_mode && !plane.throttle_suppressed)
|
return hal.util->get_soft_armed() && ( (plane.control_mode->does_auto_throttle() && !plane.throttle_suppressed)
|
||||||
|| plane.get_throttle_input()>0
|
|| plane.get_throttle_input()>0
|
||||||
|| plane.is_flying() );
|
|| plane.is_flying() );
|
||||||
}
|
}
|
||||||
|
@ -2084,7 +2084,7 @@ void QuadPlane::update_throttle_suppression(void)
|
||||||
|
|
||||||
// if we are in a fixed wing auto throttle mode and we have
|
// if we are in a fixed wing auto throttle mode and we have
|
||||||
// unsuppressed the throttle then allow motors to run
|
// unsuppressed the throttle then allow motors to run
|
||||||
if (plane.auto_throttle_mode && !plane.throttle_suppressed) {
|
if (plane.control_mode->does_auto_throttle() && !plane.throttle_suppressed) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -54,7 +54,7 @@ void Plane::throttle_slew_limit(SRV_Channel::Aux_servo_function_t func)
|
||||||
bool Plane::suppress_throttle(void)
|
bool Plane::suppress_throttle(void)
|
||||||
{
|
{
|
||||||
#if PARACHUTE == ENABLED
|
#if PARACHUTE == ENABLED
|
||||||
if (auto_throttle_mode && parachute.release_initiated()) {
|
if (control_mode->does_auto_throttle() && parachute.release_initiated()) {
|
||||||
// throttle always suppressed in auto-throttle modes after parachute release initiated
|
// throttle always suppressed in auto-throttle modes after parachute release initiated
|
||||||
throttle_suppressed = true;
|
throttle_suppressed = true;
|
||||||
return true;
|
return true;
|
||||||
|
@ -69,7 +69,7 @@ bool Plane::suppress_throttle(void)
|
||||||
// we've previously met a condition for unsupressing the throttle
|
// we've previously met a condition for unsupressing the throttle
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (!auto_throttle_mode) {
|
if (!control_mode->does_auto_throttle()) {
|
||||||
// the user controls the throttle
|
// the user controls the throttle
|
||||||
throttle_suppressed = false;
|
throttle_suppressed = false;
|
||||||
return false;
|
return false;
|
||||||
|
@ -579,7 +579,7 @@ void Plane::set_servos_flaps(void)
|
||||||
manual_flap_percent = channel_flap->percent_input();
|
manual_flap_percent = channel_flap->percent_input();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (auto_throttle_mode) {
|
if (control_mode->does_auto_throttle()) {
|
||||||
int16_t flapSpeedSource = 0;
|
int16_t flapSpeedSource = 0;
|
||||||
if (ahrs.airspeed_sensor_enabled()) {
|
if (ahrs.airspeed_sensor_enabled()) {
|
||||||
flapSpeedSource = target_airspeed_cm * 0.01f;
|
flapSpeedSource = target_airspeed_cm * 0.01f;
|
||||||
|
@ -726,7 +726,7 @@ void Plane::servos_twin_engine_mix(void)
|
||||||
*/
|
*/
|
||||||
void Plane::force_flare(void)
|
void Plane::force_flare(void)
|
||||||
{
|
{
|
||||||
if (!quadplane.in_transition() && !control_mode->is_vtol_mode() && !auto_throttle_mode && channel_throttle->in_trim_dz() && flare_mode != FlareMode::FLARE_DISABLED) {
|
if (!quadplane.in_transition() && !control_mode->is_vtol_mode() && !control_mode->does_auto_throttle() && channel_throttle->in_trim_dz() && flare_mode != FlareMode::FLARE_DISABLED) {
|
||||||
int32_t tilt = -SERVO_MAX; //this is tilts up for a normal tiltrotor
|
int32_t tilt = -SERVO_MAX; //this is tilts up for a normal tiltrotor
|
||||||
if (quadplane.tilt.tilt_type == QuadPlane::TILT_TYPE_BICOPTER) {
|
if (quadplane.tilt.tilt_type == QuadPlane::TILT_TYPE_BICOPTER) {
|
||||||
tilt = 0; // this is tilts up for a Bicopter
|
tilt = 0; // this is tilts up for a Bicopter
|
||||||
|
@ -830,8 +830,8 @@ void Plane::set_servos(void)
|
||||||
|
|
||||||
// set airbrake outputs
|
// set airbrake outputs
|
||||||
airbrake_update();
|
airbrake_update();
|
||||||
|
|
||||||
if (auto_throttle_mode ||
|
if (control_mode->does_auto_throttle() ||
|
||||||
quadplane.in_assisted_flight() ||
|
quadplane.in_assisted_flight() ||
|
||||||
quadplane.in_vtol_mode()) {
|
quadplane.in_vtol_mode()) {
|
||||||
/* only do throttle slew limiting in modes where throttle
|
/* only do throttle slew limiting in modes where throttle
|
||||||
|
@ -956,7 +956,7 @@ void Plane::update_throttle_hover() {
|
||||||
void Plane::servos_auto_trim(void)
|
void Plane::servos_auto_trim(void)
|
||||||
{
|
{
|
||||||
// only in auto modes and FBWA
|
// only in auto modes and FBWA
|
||||||
if (!auto_throttle_mode && control_mode != &mode_fbwa) {
|
if (!control_mode->does_auto_throttle() && control_mode != &mode_fbwa) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if (!hal.util->get_soft_armed()) {
|
if (!hal.util->get_soft_armed()) {
|
||||||
|
|
Loading…
Reference in New Issue