#include "Plane.h"
#define FORCE_VERSION_H_INCLUDE
#include "version.h"
#undef FORCE_VERSION_H_INCLUDE
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define SCHED_TASK(func, rate_hz, max_time_micros, priority) SCHED_TASK_CLASS(Plane, &plane, func, rate_hz, max_time_micros, priority)
#define FAST_TASK(func) FAST_TASK_CLASS(Plane, &plane, func)
const AP_Scheduler::Task Plane::scheduler_tasks[] = {
FAST_TASK(ahrs_update),
FAST_TASK(update_control_mode),
FAST_TASK(stabilize),
FAST_TASK(set_servos),
SCHED_TASK(read_radio, 50, 100, 6),
SCHED_TASK(check_short_rc_failsafe, 50, 100, 9),
SCHED_TASK(update_speed_height, 50, 200, 12),
SCHED_TASK(update_throttle_hover, 100, 90, 24),
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&plane.g2.rc_channels, read_mode_switch, 7, 100, 27),
SCHED_TASK(update_GPS_50Hz, 50, 300, 30),
SCHED_TASK(update_GPS_10Hz, 10, 400, 33),
SCHED_TASK(navigate, 10, 150, 36),
SCHED_TASK(update_compass, 10, 200, 39),
SCHED_TASK(calc_airspeed_errors, 10, 100, 42),
SCHED_TASK(update_alt, 10, 200, 45),
SCHED_TASK(adjust_altitude_target, 10, 200, 48),
#if AP_ADVANCEDFAILSAFE_ENABLED
SCHED_TASK(afs_fs_check, 10, 100, 51),
#endif
SCHED_TASK(ekf_check, 10, 75, 54),
SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_receive, 300, 500, 57),
SCHED_TASK_CLASS(GCS, (GCS*)&plane._gcs, update_send, 300, 750, 60),
#if AP_SERVORELAYEVENTS_ENABLED
SCHED_TASK_CLASS(AP_ServoRelayEvents, &plane.ServoRelayEvents, update_events, 50, 150, 63),
#endif
SCHED_TASK_CLASS(AP_BattMonitor, &plane.battery, read, 10, 300, 66),
#if AP_RANGEFINDER_ENABLED
SCHED_TASK(read_rangefinder, 50, 100, 78),
#endif
#if AP_ICENGINE_ENABLED
SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100, 81),
#endif
#if AP_OPTICALFLOW_ENABLED
SCHED_TASK_CLASS(AP_OpticalFlow, &plane.optflow, update, 50, 50, 87),
#endif
SCHED_TASK(one_second_loop, 1, 400, 90),
SCHED_TASK(three_hz_loop, 3, 75, 93),
SCHED_TASK(check_long_failsafe, 3, 400, 96),
#if AP_AIRSPEED_AUTOCAL_ENABLE
SCHED_TASK(airspeed_ratio_update, 1, 100, 102),
#endif
#if HAL_MOUNT_ENABLED
SCHED_TASK_CLASS(AP_Mount, &plane.camera_mount, update, 50, 100, 105),
#endif
#if AP_CAMERA_ENABLED
SCHED_TASK_CLASS(AP_Camera, &plane.camera, update, 50, 100, 108),
#endif
#if HAL_LOGGING_ENABLED
SCHED_TASK_CLASS(AP_Scheduler, &plane.scheduler, update_logging, 0.2, 100, 111),
#endif
#if HAL_LOGGING_ENABLED
SCHED_TASK(Log_Write_FullRate, 400, 300, 117),
SCHED_TASK(update_logging10, 10, 300, 120),
SCHED_TASK(update_logging25, 25, 300, 123),
#endif
#if HAL_SOARING_ENABLED
SCHED_TASK(update_soaring, 50, 400, 126),
#endif
SCHED_TASK(parachute_check, 10, 200, 129),
#if AP_TERRAIN_AVAILABLE
SCHED_TASK_CLASS(AP_Terrain, &plane.terrain, update, 10, 200, 132),
#endif
SCHED_TASK(update_is_flying_5Hz, 5, 100, 135),
#if HAL_LOGGING_ENABLED
SCHED_TASK_CLASS(AP_Logger, &plane.logger, periodic_tasks, 50, 400, 138),
#endif
SCHED_TASK_CLASS(AP_InertialSensor, &plane.ins, periodic, 50, 50, 141),
#if HAL_ADSB_ENABLED || AP_ADSB_AVOIDANCE_ENABLED
SCHED_TASK(avoidance_adsb_update, 10, 100, 144),
#endif
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&plane.g2.rc_channels, read_aux_all, 10, 200, 147),
#if HAL_BUTTON_ENABLED
SCHED_TASK_CLASS(AP_Button, &plane.button, update, 5, 100, 150),
#endif
#if AP_LANDINGGEAR_ENABLED
SCHED_TASK(landing_gear_update, 5, 50, 159),
#endif
#if AC_PRECLAND_ENABLED
SCHED_TASK(precland_update, 400, 50, 160),
#endif
#if AP_QUICKTUNE_ENABLED
SCHED_TASK(update_quicktune, 40, 100, 163),
#endif
};
void Plane::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit)
{
tasks = &scheduler_tasks[0];
task_count = ARRAY_SIZE(scheduler_tasks);
log_bit = MASK_LOG_PM;
}
#if HAL_QUADPLANE_ENABLED
constexpr int8_t Plane::_failsafe_priorities[7];
#else
constexpr int8_t Plane::_failsafe_priorities[6];
#endif
void Plane::ahrs_update()
{
arming.update_soft_armed();
ahrs.update();
#if HAL_LOGGING_ENABLED
if (should_log(MASK_LOG_IMU)) {
AP::ins().Write_IMU();
}
#endif
roll_limit_cd = aparm.roll_limit*100;
pitch_limit_min = aparm.pitch_limit_min;
bool rotate_limits = true;
#if HAL_QUADPLANE_ENABLED
if (quadplane.tailsitter.active()) {
rotate_limits = false;
}
#endif
if (rotate_limits) {
roll_limit_cd *= ahrs.cos_pitch();
pitch_limit_min *= fabsf(ahrs.cos_roll());
}
steer_state.locked_course_err += ahrs.get_yaw_rate_earth() * G_Dt;
steer_state.locked_course_err = wrap_PI(steer_state.locked_course_err);
#if HAL_QUADPLANE_ENABLED
quadplane.check_yaw_reset();
quadplane.inertial_nav.update();
if (quadplane.available()) {
quadplane.pos_control->update_estimates();
}
#endif
#if AP_SCRIPTING_ENABLED && AP_FOLLOW_ENABLED
g2.follow.update_estimates();
#endif
#if HAL_LOGGING_ENABLED
if (should_log(MASK_LOG_VIDEO_STABILISATION)) {
ahrs.write_video_stabilisation();
}
#endif
}
void Plane::update_speed_height(void)
{
bool should_run_tecs = control_mode->does_auto_throttle();
#if HAL_QUADPLANE_ENABLED
if (quadplane.should_disable_TECS()) {
should_run_tecs = false;
}
#endif
if (auto_state.idle_mode) {
should_run_tecs = false;
}
#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (mode_auto.in_pullup()) {
should_run_tecs = false;
}
#endif
if (should_run_tecs) {
TECS_controller.update_50hz();
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_mode() ||
quadplane.in_assisted_flight()) {
quadplane.update_throttle_mix();
}
#endif
}
void Plane::update_compass(void)
{
compass.read();
}
#if HAL_LOGGING_ENABLED
void Plane::update_logging10(void)
{
bool log_faster = (should_log(MASK_LOG_ATTITUDE_FULLRATE) || should_log(MASK_LOG_ATTITUDE_FAST));
if (should_log(MASK_LOG_ATTITUDE_MED) && !log_faster) {
Log_Write_Attitude();
ahrs.Write_AOA_SSA();
} else if (log_faster) {
ahrs.Write_AOA_SSA();
}
#if HAL_MOUNT_ENABLED
if (should_log(MASK_LOG_CAMERA)) {
camera_mount.write_log();
}
#endif
}
void Plane::update_logging25(void)
{
bool log_faster = should_log(MASK_LOG_ATTITUDE_FULLRATE);
if (should_log(MASK_LOG_ATTITUDE_FAST) && !log_faster) {
Log_Write_Attitude();
}
if (should_log(MASK_LOG_CTUN)) {
Log_Write_Control_Tuning();
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
if (!should_log(MASK_LOG_NOTCH_FULLRATE)) {
AP::ins().write_notch_log_messages();
}
#endif
#if HAL_GYROFFT_ENABLED
gyro_fft.write_log_messages();
#endif
}
if (should_log(MASK_LOG_NTUN)) {
Log_Write_Nav_Tuning();
Log_Write_Guided();
}
if (should_log(MASK_LOG_RC))
Log_Write_RC();
if (should_log(MASK_LOG_IMU))
AP::ins().Write_Vibration();
#if AP_PLANE_BLACKBOX_LOGGING
Log_Write_Blackbox();
#endif
}
#endif
#if AP_ADVANCEDFAILSAFE_ENABLED
void Plane::afs_fs_check(void)
{
afs.check(failsafe.AFS_last_valid_rc_ms);
}
#endif
#if HAL_WITH_IO_MCU
#include <AP_IOMCU/AP_IOMCU.h>
extern AP_IOMCU iomcu;
#endif
void Plane::one_second_loop()
{
set_control_channels();
#if HAL_WITH_IO_MCU
iomcu.setup_mixing(g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask);
#endif
#if HAL_ADSB_ENABLED
adsb.set_stall_speed_cm(aparm.airspeed_min * 100);
adsb.set_max_speed(aparm.airspeed_max);
#endif
if (flight_option_enabled(FlightOptions::ENABLE_DEFAULT_AIRSPEED)) {
ahrs.writeDefaultAirSpeed((float)((aparm.airspeed_min + aparm.airspeed_max)/2),
(float)((aparm.airspeed_max - aparm.airspeed_min)/2));
}
AP::srv().enable_aux_servos();
AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);
AP_Notify::flags.pre_arm_gps_check = true;
AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::Required::NO;
#if AP_TERRAIN_AVAILABLE && HAL_LOGGING_ENABLED
if (should_log(MASK_LOG_GPS)) {
terrain.log_terrain_data();
}
#endif
if (!arming.is_armed() &&
gps.last_message_time_ms() - last_home_update_ms > 5000 &&
gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
last_home_update_ms = gps.last_message_time_ms();
update_home();
landing.alt_offset = 0;
}
const float loop_rate = AP::scheduler().get_filtered_loop_rate_hz();
#if HAL_QUADPLANE_ENABLED
if (quadplane.available()) {
quadplane.attitude_control->set_notch_sample_rate(loop_rate);
}
#endif
rollController.set_notch_sample_rate(loop_rate);
pitchController.set_notch_sample_rate(loop_rate);
yawController.set_notch_sample_rate(loop_rate);
}
void Plane::three_hz_loop()
{
#if AP_FENCE_ENABLED
fence_check();
#endif
}
#if AP_AIRSPEED_AUTOCAL_ENABLE
void Plane::airspeed_ratio_update(void)
{
if (!hal.util->get_soft_armed() ||
!ahrs.get_fly_forward() ||
!is_flying() ||
!airspeed.enabled() ||
gps.status() < AP_GPS::GPS_OK_FIX_3D ||
gps.ground_speed() < 4) {
return;
}
if (airspeed.get_airspeed() < aparm.airspeed_min &&
gps.ground_speed() < (uint32_t)aparm.airspeed_min) {
return;
}
if (labs(ahrs.roll_sensor) > roll_limit_cd ||
ahrs.get_pitch_deg() > aparm.pitch_limit_max ||
ahrs.get_pitch_deg() < pitch_limit_min) {
return;
}
const Vector3f &vg = gps.velocity();
airspeed.update_calibration(vg, aparm.airspeed_max);
}
#endif
void Plane::update_GPS_50Hz(void)
{
gps.update();
update_current_loc();
}
void Plane::update_GPS_10Hz(void)
{
static uint32_t last_gps_msg_ms;
if (gps.last_message_time_ms() != last_gps_msg_ms && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
last_gps_msg_ms = gps.last_message_time_ms();
if (ground_start_count > 1) {
ground_start_count--;
} else if (ground_start_count == 1) {
if (current_loc.lat == 0 && current_loc.lng == 0) {
ground_start_count = 5;
} else if (!hal.util->was_watchdog_reset()) {
if (!set_home_persistently(gps.location())) {
}
next_WP_loc = prev_WP_loc = home;
ground_start_count = 0;
}
}
ahrs.estimate_wind();
} else if (gps.status() < AP_GPS::GPS_OK_FIX_3D && ground_start_count != 0) {
ground_start_count = 5;
}
calc_gndspeed_undershoot();
}
void Plane::update_control_mode(void)
{
if ((control_mode != &mode_auto) && (control_mode != &mode_takeoff)) {
steer_state.hold_course_cd = -1;
}
takeoff_state.throttle_lim_max = 100.0f;
takeoff_state.throttle_lim_min = -100.0f;
update_fly_forward();
control_mode->update();
#if MODE_AUTOLAND_ENABLED
mode_autoland.check_takeoff_direction();
#endif
}
void Plane::update_fly_forward(void)
{
#if HAL_QUADPLANE_ENABLED
if (quadplane.available()) {
if (quadplane.tailsitter.is_in_fw_flight()) {
ahrs.set_fly_forward(true);
return;
}
if (quadplane.in_vtol_mode()) {
ahrs.set_fly_forward(false);
return;
}
if (quadplane.in_assisted_flight()) {
ahrs.set_fly_forward(false);
return;
}
}
#endif
if (auto_state.idle_mode) {
ahrs.set_fly_forward(false);
return;
}
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
ahrs.set_fly_forward(landing.is_flying_forward());
return;
}
ahrs.set_fly_forward(true);
}
void Plane::set_flight_stage(AP_FixedWing::FlightStage fs)
{
if (fs == flight_stage) {
return;
}
const bool is_landing = (fs == AP_FixedWing::FlightStage::LAND);
landing.handle_flight_stage_change(is_landing);
#if AP_LANDINGGEAR_ENABLED
if (is_landing) {
plane.g2.landing_gear.deploy_for_landing();
}
const bool is_takeoff_complete = (flight_stage == AP_FixedWing::FlightStage::TAKEOFF &&
fs == AP_FixedWing::FlightStage::NORMAL);
if (is_takeoff_complete &&
arming.is_armed_and_safety_off() &&
is_flying()) {
g2.landing_gear.retract_after_takeoff();
}
#endif
if (fs == AP_FixedWing::FlightStage::ABORT_LANDING) {
gcs().send_text(MAV_SEVERITY_NOTICE, "Landing aborted, climbing to %dm",
int(auto_state.takeoff_altitude_rel_cm/100));
}
flight_stage = fs;
#if HAL_LOGGING_ENABLED
Log_Write_Status();
#endif
}
void Plane::update_alt()
{
barometer.update();
float sink_rate;
Vector3f vel;
if (ahrs.get_velocity_NED(vel)) {
sink_rate = vel.z;
} else if (gps.status() >= AP_GPS::GPS_OK_FIX_3D && gps.have_vertical_velocity()) {
sink_rate = gps.velocity().z;
} else {
sink_rate = -barometer.get_climb_rate();
}
auto_state.sink_rate = 0.8f * auto_state.sink_rate + 0.2f*sink_rate;
#if HAL_PARACHUTE_ENABLED
parachute.set_sink_rate(auto_state.sink_rate);
#endif
update_flight_stage();
#if AP_SCRIPTING_ENABLED
if (nav_scripting_active()) {
return;
}
#endif
bool should_run_tecs = control_mode->does_auto_throttle();
#if HAL_QUADPLANE_ENABLED
if (quadplane.should_disable_TECS()) {
should_run_tecs = false;
}
#endif
if (auto_state.idle_mode) {
should_run_tecs = false;
}
#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (mode_auto.in_pullup()) {
should_run_tecs = false;
}
#endif
if (should_run_tecs && !throttle_suppressed) {
float distance_beyond_land_wp = 0;
if (flight_stage == AP_FixedWing::FlightStage::LAND &&
current_loc.past_interval_finish_line(prev_WP_loc, next_WP_loc)) {
distance_beyond_land_wp = current_loc.get_distance(next_WP_loc);
}
tecs_target_alt_cm = relative_target_altitude_cm();
if (control_mode == &mode_rtl && !rtl.done_climb && (g2.rtl_climb_min > 0 || (plane.flight_option_enabled(FlightOptions::CLIMB_BEFORE_TURN)))) {
tecs_target_alt_cm = MAX(tecs_target_alt_cm, prev_WP_loc.alt - home.alt) + (g2.rtl_climb_min+10)*100;
}
TECS_controller.update_pitch_throttle(tecs_target_alt_cm,
target_airspeed_cm,
flight_stage,
distance_beyond_land_wp,
get_takeoff_pitch_min_cd(),
throttle_nudge,
tecs_hgt_afe(),
aerodynamic_load_factor,
g.pitch_trim.get());
}
}
void Plane::update_flight_stage(void)
{
if (control_mode->does_auto_throttle() && !throttle_suppressed) {
if (control_mode == &mode_auto) {
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_auto()) {
set_flight_stage(AP_FixedWing::FlightStage::VTOL);
return;
}
#endif
if (auto_state.takeoff_complete == false) {
set_flight_stage(AP_FixedWing::FlightStage::TAKEOFF);
return;
} else if (mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND) {
if (landing.is_commanded_go_around() || flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {
set_flight_stage(AP_FixedWing::FlightStage::ABORT_LANDING);
} else if (landing.get_abort_throttle_enable() && get_throttle_input() >= 90 &&
landing.request_go_around()) {
gcs().send_text(MAV_SEVERITY_INFO,"Landing aborted via throttle");
set_flight_stage(AP_FixedWing::FlightStage::ABORT_LANDING);
} else {
set_flight_stage(AP_FixedWing::FlightStage::LAND);
}
return;
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_assisted_flight()) {
set_flight_stage(AP_FixedWing::FlightStage::VTOL);
return;
}
#endif
set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
} else if ((control_mode != &mode_takeoff)
#if MODE_AUTOLAND_ENABLED
&& (control_mode != &mode_autoland)
#endif
) {
set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
}
return;
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_mode() ||
quadplane.in_assisted_flight()) {
set_flight_stage(AP_FixedWing::FlightStage::VTOL);
return;
}
#endif
set_flight_stage(AP_FixedWing::FlightStage::NORMAL);
}
void Plane::disarm_if_autoland_complete()
{
if (landing.get_disarm_delay() > 0 &&
!is_flying() &&
arming.arming_required() != AP_Arming::Required::NO &&
arming.is_armed()) {
if (millis() - auto_state.last_flying_ms >= landing.get_disarm_delay()*1000UL) {
if (arming.disarm(AP_Arming::Method::AUTOLANDED)) {
gcs().send_text(MAV_SEVERITY_INFO,"Auto disarmed");
}
}
}
}
bool Plane::trigger_land_abort(const float climb_to_alt_m)
{
if (plane.control_mode != &plane.mode_auto) {
return false;
}
#if HAL_QUADPLANE_ENABLED
if (plane.quadplane.in_vtol_auto()) {
return quadplane.abort_landing();
}
#endif
uint16_t mission_id = plane.mission.get_current_nav_cmd().id;
bool is_in_landing = (plane.flight_stage == AP_FixedWing::FlightStage::LAND) ||
plane.is_land_command(mission_id);
if (is_in_landing) {
if (plane.have_position && plane.mission.jump_to_abort_landing_sequence(plane.current_loc)) {
return true;
}
#if HAL_QUADPLANE_ENABLED
const bool attempt_go_around =
(!plane.quadplane.available()) ||
((!plane.quadplane.in_vtol_auto()) &&
(!plane.quadplane.landing_with_fixed_wing_spiral_approach()));
#else
const bool attempt_go_around = true;
#endif
if (attempt_go_around) {
if (!is_zero(climb_to_alt_m)) {
plane.auto_state.takeoff_altitude_rel_cm = climb_to_alt_m * 100;
}
if (plane.landing.request_go_around()) {
plane.auto_state.next_wp_crosstrack = false;
return true;
}
}
}
return false;
}
float Plane::tecs_hgt_afe(void)
{
float hgt_afe;
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
#if AP_MAVLINK_MAV_CMD_SET_HAGL_ENABLED
if (get_external_HAGL(hgt_afe)) {
return hgt_afe;
}
#endif
hgt_afe = height_above_target();
#if AP_RANGEFINDER_ENABLED
hgt_afe -= rangefinder_correction();
#endif
} else {
hgt_afe = relative_altitude;
}
return hgt_afe;
}
bool Plane::get_wp_distance_m(float &distance) const
{
if (control_mode == &mode_manual) {
return false;
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_mode()) {
distance = quadplane.using_wp_nav() ? quadplane.wp_nav->get_wp_distance_to_destination_m() : 0;
return true;
}
#endif
distance = auto_state.wp_distance;
return true;
}
bool Plane::get_wp_bearing_deg(float &bearing) const
{
if (control_mode == &mode_manual) {
return false;
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_mode()) {
bearing = quadplane.using_wp_nav() ? quadplane.wp_nav->get_wp_bearing_to_destination_cd() : 0;
return true;
}
#endif
bearing = nav_controller->target_bearing_cd() * 0.01;
return true;
}
bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const
{
if (control_mode == &mode_manual) {
return false;
}
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_mode()) {
xtrack_error = quadplane.using_wp_nav() ? quadplane.wp_nav->crosstrack_error_m() : 0;
return true;
}
#endif
xtrack_error = nav_controller->crosstrack_error();
return true;
}
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
bool Plane::set_target_location(const Location &target_loc)
{
Location loc{target_loc};
fix_terrain_WP(loc, __LINE__);
if (plane.control_mode != &plane.mode_guided) {
return false;
}
if (!loc.terrain_alt) {
loc.change_alt_frame(Location::AltFrame::ABSOLUTE);
}
plane.set_guided_WP(loc);
return true;
}
#endif
#if AP_SCRIPTING_ENABLED
bool Plane::get_target_location(Location& target_loc)
{
switch (control_mode->mode_number()) {
case Mode::Number::RTL:
case Mode::Number::AVOID_ADSB:
case Mode::Number::GUIDED:
case Mode::Number::AUTO:
case Mode::Number::LOITER:
case Mode::Number::TAKEOFF:
#if HAL_QUADPLANE_ENABLED
case Mode::Number::QLOITER:
case Mode::Number::QLAND:
case Mode::Number::QRTL:
#endif
target_loc = next_WP_loc;
return true;
break;
default:
break;
}
return false;
}
bool Plane::update_target_location(const Location &old_loc, const Location &new_loc)
{
if (!old_loc.same_loc_as(next_WP_loc) ||
old_loc.get_alt_frame() != new_loc.get_alt_frame()) {
return false;
}
next_WP_loc = new_loc;
fix_terrain_WP(next_WP_loc, __LINE__);
#if HAL_QUADPLANE_ENABLED
if (control_mode == &mode_qland || control_mode == &mode_qloiter) {
mode_qloiter.last_target_loc_set_ms = AP_HAL::millis();
}
#endif
return true;
}
bool Plane::set_velocity_match(const Vector2f &velocity)
{
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_mode() || quadplane.in_vtol_land_sequence()) {
quadplane.poscontrol.velocity_match_ms = velocity;
quadplane.poscontrol.last_velocity_match_ms = AP_HAL::millis();
return true;
}
#endif
return false;
}
bool Plane::set_land_descent_rate(float descent_rate)
{
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_land_descent() ||
control_mode == &mode_qland) {
quadplane.poscontrol.override_descent_rate_ms = descent_rate;
quadplane.poscontrol.last_override_descent_ms = AP_HAL::millis();
return true;
}
#endif
return false;
}
bool Plane::set_crosstrack_start(const Location &new_start_location)
{
prev_WP_loc = new_start_location;
auto_state.crosstrack = true;
return true;
}
#endif
bool Plane::is_landing() const
{
#if HAL_QUADPLANE_ENABLED
if (plane.quadplane.in_vtol_land_descent()) {
return true;
}
#endif
return control_mode->is_landing();
}
bool Plane::is_taking_off() const
{
#if HAL_QUADPLANE_ENABLED
if (plane.quadplane.in_vtol_takeoff()) {
return true;
}
#endif
return control_mode->is_taking_off();
}
#if HAL_QUADPLANE_ENABLED
bool Plane::start_takeoff(const float alt_m) {
return plane.quadplane.available() && quadplane.do_user_takeoff(alt_m);
}
#endif
void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const
{
#if HAL_QUADPLANE_ENABLED
if (quadplane.show_vtol_view()) {
pitch = quadplane.ahrs_view->pitch;
roll = quadplane.ahrs_view->roll;
return;
}
#endif
pitch = ahrs.get_pitch_rad();
roll = ahrs.get_roll_rad();
if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH))) {
pitch -= g.pitch_trim * DEG_TO_RAD;
}
}
void Plane::update_current_loc(void)
{
have_position = plane.ahrs.get_location(plane.current_loc);
ahrs.get_relative_position_D_home(plane.relative_altitude);
relative_altitude *= -1.0f;
}
bool Plane::flight_option_enabled(FlightOptions flight_option) const
{
return g2.flight_options & flight_option;
}
#if AC_PRECLAND_ENABLED
void Plane::precland_update(void)
{
#if AP_RANGEFINDER_ENABLED
return g2.precland.update(rangefinder_state.height_estimate*100, rangefinder_state.in_range);
#else
return g2.precland.update(0, false);
#endif
}
#endif
#if AP_QUICKTUNE_ENABLED
void Plane::update_quicktune(void)
{
quicktune.update(control_mode->supports_quicktune());
}
#endif
Plane::Plane(void)
{
auto_state.takeoff_complete = true;
}
Plane plane;
AP_Vehicle& vehicle = plane;
AP_HAL_MAIN_CALLBACKS(&plane);