#include "Plane.h"
Mode::Mode() :
unused_integer{17},
#if HAL_QUADPLANE_ENABLED
pos_control(plane.quadplane.pos_control),
attitude_control(plane.quadplane.attitude_control),
loiter_nav(plane.quadplane.loiter_nav),
quadplane(plane.quadplane),
poscontrol(plane.quadplane.poscontrol),
#endif
ahrs(plane.ahrs)
{
}
void Mode::exit()
{
_exit();
if (plane.control_mode != &plane.mode_autotune){
plane.autotune_restore();
}
}
bool Mode::enter()
{
#if AP_SCRIPTING_ENABLED
plane.nav_scripting.enabled = false;
#endif
plane.auto_state.inverted_flight = false;
plane.takeoff_state.waiting_for_rudder_neutral = false;
plane.auto_state.next_wp_crosstrack = false;
plane.auto_state.checked_for_autoland = false;
plane.steer_state.locked_course_err = 0;
plane.steer_state.locked_course = false;
plane.crash_state.is_crashed = false;
plane.crash_state.impact_detected = false;
plane.guided_state.last_forced_rpy_ms.zero();
plane.guided_state.last_forced_throttle_ms = 0;
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
plane.guided_state.target_heading = -4;
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
plane.guided_state.target_airspeed_cm = -1;
plane.guided_state.target_alt_time_ms = 0;
plane.guided_state.target_location.set_alt_cm(-1, Location::AltFrame::ABSOLUTE);
#endif
#if AP_CAMERA_ENABLED
plane.camera.set_is_auto_mode(this == &plane.mode_auto);
#endif
plane.auto_state.highest_airspeed = 0;
plane.auto_state.initial_pitch_cd = ahrs.pitch_sensor;
plane.auto_state.fbwa_tdrag_takeoff_mode = false;
plane.auto_state.rotation_complete = false;
plane.prev_WP_loc = plane.current_loc;
plane.loiter.start_time_ms = 0;
plane.last_mode_change_ms = AP_HAL::millis();
plane.auto_state.vtol_mode = is_vtol_mode();
plane.auto_state.vtol_loiter = false;
plane.new_airspeed_cm = -1;
plane.long_failsafe_pending = false;
#if HAL_QUADPLANE_ENABLED
quadplane.mode_enter();
#endif
#if AP_TERRAIN_AVAILABLE
plane.target_altitude.terrain_following_pending = false;
#endif
#if AP_PLANE_SYSTEMID_ENABLED
plane.g2.systemid.stop();
#endif
plane.auto_state.idle_mode = false;
bool enter_result = _enter();
if (enter_result) {
plane.throttle_suppressed = does_auto_throttle();
#if HAL_ADSB_ENABLED
plane.adsb.set_is_auto_mode(does_auto_navigation());
#endif
plane.nav_controller->set_data_is_stale();
plane.steerController.reset_I();
plane.control_failsafe();
#if AP_FENCE_ENABLED
plane.fence.manual_recovery_start();
#endif
if (plane.mission.get_in_landing_sequence_flag() &&
!plane.is_flying() && !plane.arming.is_armed_and_safety_off() &&
!plane.control_mode->does_auto_navigation()) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "In landing sequence: mission reset");
plane.mission.reset();
}
plane.update_flight_stage();
plane.landing.reset();
#if HAL_QUADPLANE_ENABLED
if (quadplane.enabled()) {
float aspeed;
bool have_airspeed = quadplane.ahrs.airspeed_EAS(aspeed);
quadplane.assisted_flight = quadplane.assist.should_assist(aspeed, have_airspeed);
}
if (is_vtol_mode() && !quadplane.tailsitter.enabled()) {
plane.inverted_flight = false;
}
#endif
}
return enter_result;
}
bool Mode::is_vtol_man_throttle() const
{
#if HAL_QUADPLANE_ENABLED
if (plane.quadplane.tailsitter.is_in_fw_flight() &&
plane.quadplane.assisted_flight) {
return !does_auto_throttle();
}
#endif
return false;
}
void Mode::update_target_altitude()
{
Location target_location;
if (plane.landing.is_flaring()) {
plane.set_target_altitude_location(plane.next_WP_loc);
} else if (plane.landing.is_on_approach()) {
plane.landing.setup_landing_glide_slope(plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.target_altitude.offset_cm);
#if AP_RANGEFINDER_ENABLED
plane.landing.adjust_landing_slope_for_rangefinder_bump(plane.rangefinder_state, plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.auto_state.wp_distance, plane.target_altitude.offset_cm);
#endif
} else if (plane.landing.get_target_altitude_location(target_location)) {
plane.set_target_altitude_location(target_location);
#if HAL_SOARING_ENABLED
} else if (plane.g2.soaring_controller.is_active() && plane.g2.soaring_controller.get_throttle_suppressed()) {
plane.set_target_altitude_location(plane.current_loc);
plane.reset_offset_altitude();
#endif
} else if (plane.reached_loiter_target()) {
plane.set_target_altitude_location(plane.next_WP_loc);
#if AP_TERRAIN_AVAILABLE
} else if (plane.next_WP_loc.terrain_alt &&
plane.set_target_altitude_proportion_terrain()) {
#endif
} else if (plane.target_altitude.offset_cm != 0 &&
!plane.current_loc.past_interval_finish_line(plane.prev_WP_loc, plane.next_WP_loc)) {
plane.set_target_altitude_proportion(plane.next_WP_loc, 1.0f-plane.auto_state.wp_proportion);
plane.constrain_target_altitude_location(plane.next_WP_loc, plane.prev_WP_loc);
} else {
plane.set_target_altitude_location(plane.next_WP_loc);
}
}
bool Mode::pre_arm_checks(size_t buflen, char *buffer) const
{
if (!_pre_arm_checks(buflen, buffer)) {
if (strlen(buffer) == 0) {
hal.util->snprintf(buffer, buflen, "mode not armable");
}
return false;
}
return true;
}
bool Mode::_pre_arm_checks(size_t buflen, char *buffer) const
{
#if HAL_QUADPLANE_ENABLED
if (plane.quadplane.enabled() && !is_vtol_mode() &&
plane.quadplane.option_is_set(QuadPlane::Option::ONLY_ARM_IN_QMODE_OR_AUTO)) {
hal.util->snprintf(buffer, buflen, "not Q mode");
return false;
}
#endif
return true;
}
void Mode::run()
{
switch ((StickMixing)plane.g.stick_mixing) {
case StickMixing::FBW:
case StickMixing::FBW_NO_PITCH:
case StickMixing::DIRECT_REMOVED:
plane.stabilize_stick_mixing_fbw();
break;
case StickMixing::NONE:
case StickMixing::VTOL_YAW:
break;
}
plane.stabilize_roll();
plane.stabilize_pitch();
plane.stabilize_yaw();
}
void Mode::reset_controllers()
{
plane.rollController.reset_I();
plane.pitchController.reset_I();
plane.yawController.reset_I();
plane.steer_state.locked_course = false;
plane.steer_state.locked_course_err = 0;
plane.TECS_controller.reset();
}
bool Mode::is_taking_off() const
{
return (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF);
}
void Mode::output_rudder_and_steering(float val)
{
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, val);
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, val);
}
void Mode::output_pilot_throttle()
{
if (plane.g.throttle_passthru_stabilize) {
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.get_throttle_input(true));
return;
}
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.get_adjusted_throttle_input(true));
}
bool Mode::use_throttle_limits() const
{
#if AP_SCRIPTING_ENABLED
if (plane.nav_scripting_active()) {
return false;
}
#endif
if (this == &plane.mode_stabilize ||
this == &plane.mode_training ||
this == &plane.mode_acro ||
this == &plane.mode_fbwa ||
this == &plane.mode_autotune) {
return !plane.g.throttle_passthru_stabilize;
}
if (is_guided_mode() && plane.guided_throttle_passthru) {
return false;
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_mode()) {
return quadplane.allow_forward_throttle_in_vtol_mode();
}
#endif
return true;
}
bool Mode::use_battery_compensation() const
{
#if AP_SCRIPTING_ENABLED
if (plane.nav_scripting_active()) {
return false;
}
#endif
if (this == &plane.mode_stabilize ||
this == &plane.mode_training ||
this == &plane.mode_acro ||
this == &plane.mode_fbwa ||
this == &plane.mode_autotune) {
return false;
}
if (is_guided_mode() && plane.guided_throttle_passthru) {
return false;
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_mode()) {
return false;
}
#endif
return true;
}
#if AP_PLANE_SYSTEMID_ENABLED
bool Mode::allow_fw_systemid() const {
if (!supports_fw_systemid()) {
return false;
}
if (is_taking_off() || is_landing()) {
return false;
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.available()) {
if (quadplane.in_assisted_flight()) {
return false;
}
if (!quadplane.transition->complete()) {
return false;
}
}
#endif
return true;
}
#endif