#include "Plane.h"
bool Plane::start_command(const AP_Mission::Mission_Command& cmd)
{
auto_state.vtol_loiter = false;
#if AP_TERRAIN_AVAILABLE
plane.target_altitude.terrain_following_pending = false;
#endif
if (AP_Mission::is_nav_cmd(cmd)) {
auto_state.takeoff_complete = true;
nav_controller->set_data_is_stale();
auto_state.idle_mode = false;
loiter.start_time_ms = 0;
if (control_mode == &mode_auto) {
AP_Mission::Mission_Command next_nav_cmd;
const uint16_t next_index = mission.get_current_nav_index() + 1;
const bool have_next_cmd = mission.get_next_nav_cmd(next_index, next_nav_cmd);
auto_state.wp_is_land_approach = have_next_cmd && (next_nav_cmd.id == MAV_CMD_NAV_LAND);
#if HAL_QUADPLANE_ENABLED
if (have_next_cmd && quadplane.is_vtol_land(next_nav_cmd.id)) {
auto_state.wp_is_land_approach = false;
}
#endif
}
}
switch(cmd.id) {
case MAV_CMD_NAV_TAKEOFF:
crash_state.is_crashed = false;
#if HAL_QUADPLANE_ENABLED
if (quadplane.is_vtol_takeoff(cmd.id)) {
return quadplane.do_vtol_takeoff(cmd);
}
#endif
do_takeoff(cmd);
break;
case MAV_CMD_NAV_WAYPOINT:
do_nav_wp(cmd);
break;
case MAV_CMD_NAV_LAND:
#if HAL_QUADPLANE_ENABLED
if (quadplane.is_vtol_land(cmd.id)) {
crash_state.is_crashed = false;
return quadplane.do_vtol_land(cmd);
}
#endif
do_land(cmd);
break;
case MAV_CMD_NAV_LOITER_UNLIM:
do_loiter_unlimited(cmd);
break;
case MAV_CMD_NAV_LOITER_TURNS:
do_loiter_turns(cmd);
break;
case MAV_CMD_NAV_LOITER_TIME:
do_loiter_time(cmd);
break;
case MAV_CMD_NAV_LOITER_TO_ALT:
do_loiter_to_alt(cmd);
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
set_mode(mode_rtl, ModeReason::MISSION_CMD);
break;
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
do_continue_and_change_alt(cmd);
break;
case MAV_CMD_NAV_ALTITUDE_WAIT:
do_altitude_wait(cmd);
break;
#if HAL_QUADPLANE_ENABLED
case MAV_CMD_NAV_VTOL_TAKEOFF:
crash_state.is_crashed = false;
return quadplane.do_vtol_takeoff(cmd);
case MAV_CMD_NAV_VTOL_LAND:
case MAV_CMD_NAV_PAYLOAD_PLACE:
if (quadplane.landing_with_fixed_wing_spiral_approach()) {
do_landing_vtol_approach(cmd);
break;
} else {
return quadplane.do_vtol_land(cmd);
}
#endif
case MAV_CMD_CONDITION_DELAY:
do_wait_delay(cmd);
break;
case MAV_CMD_CONDITION_DISTANCE:
do_within_distance(cmd);
break;
case MAV_CMD_DO_CHANGE_SPEED:
do_change_speed(cmd);
break;
case MAV_CMD_DO_SET_HOME:
do_set_home(cmd);
break;
case MAV_CMD_DO_INVERTED_FLIGHT:
if (cmd.p1 == 0 || cmd.p1 == 1) {
auto_state.inverted_flight = (bool)cmd.p1;
gcs().send_text(MAV_SEVERITY_INFO, "Set inverted %u", cmd.p1);
}
break;
case MAV_CMD_DO_RETURN_PATH_START:
case MAV_CMD_DO_LAND_START:
break;
case MAV_CMD_DO_AUTOTUNE_ENABLE:
autotune_enable(cmd.p1);
break;
#if HAL_MOUNT_ENABLED
case MAV_CMD_DO_SET_ROI_LOCATION:
case MAV_CMD_DO_SET_ROI_NONE:
case MAV_CMD_DO_SET_ROI:
if (!cmd.content.location.initialised()) {
if (camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
camera_mount.set_mode_to_default();
}
} else {
camera_mount.set_roi_target(cmd.content.location);
}
break;
case MAV_CMD_DO_MOUNT_CONTROL:
camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false);
break;
#endif
#if HAL_QUADPLANE_ENABLED
case MAV_CMD_DO_VTOL_TRANSITION:
plane.quadplane.handle_do_vtol_transition((enum MAV_VTOL_STATE)cmd.content.do_vtol_transition.target_state);
break;
#endif
#if AP_ICENGINE_ENABLED
case MAV_CMD_DO_ENGINE_CONTROL:
plane.g2.ice_control.engine_control(cmd.content.do_engine_control.start_control,
cmd.content.do_engine_control.cold_start,
cmd.content.do_engine_control.height_delay_cm*0.01f,
cmd.content.do_engine_control.allow_disarmed_start);
break;
#endif
#if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME:
do_nav_script_time(cmd);
break;
#endif
case MAV_CMD_NAV_DELAY:
mode_auto.do_nav_delay(cmd);
break;
default:
return false;
}
return true;
}
bool Plane::verify_command(const AP_Mission::Mission_Command& cmd)
{
switch(cmd.id) {
case MAV_CMD_NAV_TAKEOFF:
#if HAL_QUADPLANE_ENABLED
if (quadplane.is_vtol_takeoff(cmd.id)) {
return quadplane.verify_vtol_takeoff(cmd);
}
#endif
return verify_takeoff();
case MAV_CMD_NAV_WAYPOINT:
return verify_nav_wp(cmd);
case MAV_CMD_NAV_LAND:
#if HAL_QUADPLANE_ENABLED
if (quadplane.is_vtol_land(cmd.id)) {
return quadplane.verify_vtol_land();
}
#endif
if (flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {
return landing.verify_abort_landing(prev_WP_loc, next_WP_loc, current_loc, auto_state.takeoff_altitude_rel_cm, throttle_suppressed);
} else {
bool rangefinder_active = false;
float height = plane.get_landing_height(rangefinder_active);
height -= auto_state.terrain_correction;
return landing.verify_land(prev_WP_loc, next_WP_loc, current_loc,
height, auto_state.sink_rate, auto_state.wp_proportion, auto_state.last_flying_ms, arming.is_armed(), is_flying(),
rangefinder_active);
}
case MAV_CMD_NAV_LOITER_UNLIM:
return verify_loiter_unlim(cmd);
case MAV_CMD_NAV_LOITER_TURNS:
return verify_loiter_turns(cmd);
case MAV_CMD_NAV_LOITER_TIME:
return verify_loiter_time();
case MAV_CMD_NAV_LOITER_TO_ALT:
return verify_loiter_to_alt(cmd);
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT:
return verify_continue_and_change_alt();
case MAV_CMD_NAV_ALTITUDE_WAIT:
return mode_auto.verify_altitude_wait(cmd);
#if HAL_QUADPLANE_ENABLED
case MAV_CMD_NAV_VTOL_TAKEOFF:
return quadplane.verify_vtol_takeoff(cmd);
case MAV_CMD_NAV_VTOL_LAND:
case MAV_CMD_NAV_PAYLOAD_PLACE:
if (quadplane.landing_with_fixed_wing_spiral_approach() && !verify_landing_vtol_approach(cmd)) {
return false;
} else {
return quadplane.verify_vtol_land();
}
#endif
case MAV_CMD_CONDITION_DELAY:
return verify_wait_delay();
case MAV_CMD_CONDITION_DISTANCE:
return verify_within_distance();
#if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME:
return verify_nav_script_time(cmd);
#endif
case MAV_CMD_NAV_DELAY:
return mode_auto.verify_nav_delay(cmd);
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_SET_HOME:
case MAV_CMD_DO_INVERTED_FLIGHT:
case MAV_CMD_DO_RETURN_PATH_START:
case MAV_CMD_DO_LAND_START:
case MAV_CMD_DO_FENCE_ENABLE:
case MAV_CMD_DO_AUTOTUNE_ENABLE:
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
case MAV_CMD_DO_SET_ROI_LOCATION:
case MAV_CMD_DO_SET_ROI_NONE:
case MAV_CMD_DO_SET_ROI:
case MAV_CMD_DO_MOUNT_CONTROL:
case MAV_CMD_DO_VTOL_TRANSITION:
case MAV_CMD_DO_ENGINE_CONTROL:
return true;
default:
gcs().send_text(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);
return true;
}
}
void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm)
{
auto_state.next_wp_crosstrack = false;
auto_state.crosstrack = false;
prev_WP_loc = current_loc;
next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm);
fix_terrain_WP(next_WP_loc, __LINE__);
setup_terrain_target_alt(next_WP_loc);
set_target_altitude_location(next_WP_loc);
if (aparm.loiter_radius < 0) {
loiter.direction = -1;
} else {
loiter.direction = 1;
}
setup_alt_slope();
setup_turn_angle();
}
Location Plane::calc_best_rally_or_home_location(const Location &_current_loc, float rtl_home_alt_amsl_cm) const
{
#if HAL_RALLY_ENABLED
return plane.rally.calc_best_rally_or_home_location(_current_loc, rtl_home_alt_amsl_cm);
#else
return Location {
plane.home.lat,
plane.home.lng,
int32_t(rtl_home_alt_amsl_cm),
Location::AltFrame::ABSOLUTE
};
#endif
}
void Plane::do_takeoff(const AP_Mission::Mission_Command& cmd)
{
prev_WP_loc = current_loc;
set_next_WP(cmd.content.location);
auto_state.takeoff_pitch_cd = (int16_t)cmd.p1 * 100;
if (auto_state.takeoff_pitch_cd <= 0) {
auto_state.takeoff_pitch_cd = 400;
}
auto_state.takeoff_altitude_rel_cm = next_WP_loc.alt - home.alt;
next_WP_loc.lat = home.lat + 10;
next_WP_loc.lng = home.lng + 10;
auto_state.takeoff_complete = false;
auto_state.rotation_complete = false;
auto_state.height_below_takeoff_to_level_off_cm = 0;
steer_state.locked_course_err = 0;
steer_state.hold_course_cd = -1;
auto_state.baro_takeoff_alt = barometer.get_altitude();
}
void Plane::do_nav_wp(const AP_Mission::Mission_Command& cmd)
{
set_next_WP(cmd.content.location);
}
void Plane::do_land(const AP_Mission::Mission_Command& cmd)
{
set_next_WP(cmd.content.location);
if (cmd.p1 > 0) {
auto_state.takeoff_altitude_rel_cm = (int16_t)cmd.p1 * 100;
} else if (auto_state.takeoff_altitude_rel_cm <= 0) {
auto_state.takeoff_altitude_rel_cm = 3000;
}
if (auto_state.takeoff_pitch_cd <= 0) {
auto_state.takeoff_pitch_cd = 1000;
}
#if AP_RANGEFINDER_ENABLED
memset(&rangefinder_state, 0, sizeof(rangefinder_state));
#endif
landing.do_land(cmd, relative_altitude);
if (flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) {
set_flight_stage(AP_FixedWing::FlightStage::LAND);
}
}
#if HAL_QUADPLANE_ENABLED
void Plane::do_landing_vtol_approach(const AP_Mission::Mission_Command& cmd)
{
Location loc = cmd.content.location;
loc.sanitize(current_loc);
set_next_WP(loc);
vtol_approach_s.approach_stage = VTOLApproach::Stage::LOITER_TO_ALT;
}
#endif
void Plane::loiter_set_direction_wp(const AP_Mission::Mission_Command& cmd)
{
if (cmd.content.location.loiter_ccw) {
loiter.direction = -1;
} else {
loiter.direction = 1;
}
}
void Plane::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
{
Location cmdloc = cmd.content.location;
cmdloc.sanitize(current_loc);
set_next_WP(cmdloc);
loiter_set_direction_wp(cmd);
}
void Plane::do_loiter_turns(const AP_Mission::Mission_Command& cmd)
{
Location cmdloc = cmd.content.location;
cmdloc.sanitize(current_loc);
set_next_WP(cmdloc);
loiter_set_direction_wp(cmd);
const float turns = cmd.get_loiter_turns();
loiter.total_cd = (uint32_t)(turns * 36000UL);
condition_value = 1;
}
void Plane::do_loiter_time(const AP_Mission::Mission_Command& cmd)
{
Location cmdloc = cmd.content.location;
cmdloc.sanitize(current_loc);
set_next_WP(cmdloc);
loiter_set_direction_wp(cmd);
loiter.time_max_ms = cmd.p1 * (uint32_t)1000;
condition_value = 1;
}
void Plane::do_continue_and_change_alt(const AP_Mission::Mission_Command& cmd)
{
float bearing;
if (!prev_WP_loc.same_latlon_as(next_WP_loc)) {
steer_state.hold_course_cd = -1;
} else if (AP::gps().status() >= AP_GPS::GPS_OK_FIX_2D) {
steer_state.hold_course_cd = -1;
bearing = AP::gps().ground_course();
next_WP_loc.offset_bearing(bearing, 1000);
} else {
steer_state.hold_course_cd = wrap_360_cd(ahrs.yaw_sensor);
bearing = ahrs.get_yaw_deg();
next_WP_loc.offset_bearing(bearing, 1000);
}
if (cmd.content.location.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) {
next_WP_loc.copy_alt_from(cmd.content.location);
} else {
int32_t alt_abs_cm;
if (cmd.content.location.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_abs_cm)) {
next_WP_loc.set_alt_cm(alt_abs_cm,
Location::AltFrame::ABSOLUTE);
}
}
condition_value = cmd.p1;
reset_offset_altitude();
}
void Plane::do_altitude_wait(const AP_Mission::Mission_Command& cmd)
{
auto_state.idle_mode = true;
#if AP_PLANE_GLIDER_PULLUP_ENABLED
mode_auto.pullup.reset();
#endif
}
void Plane::do_loiter_to_alt(const AP_Mission::Mission_Command& cmd)
{
Location loc = cmd.content.location;
loc.sanitize(current_loc);
set_next_WP(loc);
loiter_set_direction_wp(cmd);
condition_value = 0;
}
void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)
{
nav_delay.time_start_ms = millis();
if (cmd.content.nav_delay.seconds > 0) {
nav_delay.time_max_ms = cmd.content.nav_delay.seconds * 1000;
} else {
#if AP_RTC_ENABLED
nav_delay.time_max_ms = AP::rtc().get_time_utc(cmd.content.nav_delay.hour_utc, cmd.content.nav_delay.min_utc, cmd.content.nav_delay.sec_utc, 0);
#else
nav_delay.time_max_ms = 0;
#endif
}
gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay.time_max_ms/1000));
}
bool Plane::verify_takeoff()
{
bool trust_ahrs_yaw = AP::ahrs().initialised();
#if AP_AHRS_DCM_ENABLED
trust_ahrs_yaw |= ahrs.dcm_yaw_initialised();
#endif
if (trust_ahrs_yaw && steer_state.hold_course_cd == -1) {
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
gps.ground_speed() > GPS_GND_CRS_MIN_SPD &&
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED) {
float takeoff_course = wrap_PI(radians(gps.ground_course())) - steer_state.locked_course_err;
takeoff_course = wrap_PI(takeoff_course);
steer_state.hold_course_cd = wrap_360_cd(degrees(takeoff_course)*100);
gcs().send_text(MAV_SEVERITY_INFO, "Holding course %d at %.1fm/s (%.1f)",
(int)steer_state.hold_course_cd,
(double)gps.ground_speed(),
(double)degrees(steer_state.locked_course_err));
}
}
if (steer_state.hold_course_cd != -1) {
nav_controller->update_heading_hold(steer_state.hold_course_cd);
} else {
nav_controller->update_level_flight();
}
if (plane.check_takeoff_timeout()) {
mission.reset();
}
int32_t relative_alt_cm = adjusted_relative_altitude_cm();
if (
relative_alt_cm > auto_state.takeoff_altitude_rel_cm ||
plane.check_takeoff_timeout_level_off()
) {
gcs().send_text(MAV_SEVERITY_INFO, "Takeoff complete at %.2fm",
(double)(relative_alt_cm*0.01f));
steer_state.hold_course_cd = -1;
auto_state.takeoff_complete = true;
next_WP_loc = prev_WP_loc = current_loc;
#if AP_FENCE_ENABLED
plane.fence.auto_enable_fence_after_takeoff();
#endif
auto_state.next_wp_crosstrack = false;
return true;
} else {
return false;
}
}
bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
{
steer_state.hold_course_cd = -1;
Location flex_next_WP_loc = next_WP_loc;
uint8_t cmd_passby = HIGHBYTE(cmd.p1);
uint8_t cmd_acceptance_distance = LOWBYTE(cmd.p1);
if (cmd_passby > 0) {
const float dist = prev_WP_loc.get_distance(flex_next_WP_loc);
const float bearing_deg = degrees(prev_WP_loc.get_bearing(flex_next_WP_loc));
if (is_positive(dist)) {
flex_next_WP_loc.offset_bearing(bearing_deg, cmd_passby);
}
}
if (auto_state.crosstrack) {
nav_controller->update_waypoint(prev_WP_loc, flex_next_WP_loc);
} else {
nav_controller->update_waypoint(current_loc, flex_next_WP_loc);
}
if (g.waypoint_max_radius > 0 &&
auto_state.wp_distance > (uint16_t)g.waypoint_max_radius) {
if (current_loc.past_interval_finish_line(prev_WP_loc, flex_next_WP_loc)) {
if (cmd_passby == 0) {
prev_WP_loc = current_loc;
}
}
return false;
}
float acceptance_distance_m = 0;
if (cmd_acceptance_distance > 0) {
acceptance_distance_m = cmd_acceptance_distance;
} else if (cmd_passby == 0) {
acceptance_distance_m = nav_controller->turn_distance(get_wp_radius(), auto_state.next_turn_angle);
}
const float wp_dist = current_loc.get_distance(flex_next_WP_loc);
if (wp_dist <= acceptance_distance_m) {
gcs().send_text(MAV_SEVERITY_INFO, "Reached waypoint #%i dist %um",
(unsigned)mission.get_current_nav_cmd().index,
(unsigned)current_loc.get_distance(flex_next_WP_loc));
return true;
}
if (current_loc.past_interval_finish_line(prev_WP_loc, flex_next_WP_loc)) {
gcs().send_text(MAV_SEVERITY_INFO, "Passed waypoint #%i dist %um",
(unsigned)mission.get_current_nav_cmd().index,
(unsigned)current_loc.get_distance(flex_next_WP_loc));
return true;
}
return false;
}
bool Plane::verify_loiter_unlim(const AP_Mission::Mission_Command &cmd)
{
update_loiter(cmd.p1);
return false;
}
bool Plane::verify_loiter_time()
{
bool result = false;
update_loiter(0);
if (loiter.start_time_ms == 0) {
if (reached_loiter_target() && loiter.sum_cd > 1) {
loiter.start_time_ms = millis();
}
} else if (condition_value != 0) {
if ((millis() - loiter.start_time_ms) > loiter.time_max_ms) {
condition_value = 0;
result = verify_loiter_heading(true);
}
} else {
result = verify_loiter_heading(false);
}
if (result) {
gcs().send_text(MAV_SEVERITY_INFO,"Loiter time complete");
auto_state.vtol_loiter = false;
}
return result;
}
bool Plane::verify_loiter_turns(const AP_Mission::Mission_Command &cmd)
{
bool result = false;
uint16_t radius = HIGHBYTE(cmd.p1);
if (cmd.type_specific_bits & (1U<<0)) {
radius *= 10;
}
update_loiter(radius);
auto_state.vtol_loiter = false;
if (!reached_loiter_target()) {
result = false;
} else if (condition_value != 0) {
if (loiter.sum_cd > loiter.total_cd && loiter.sum_cd > 1) {
condition_value = 0;
result = verify_loiter_heading(true);
}
} else {
result = verify_loiter_heading(false);
}
if (result) {
gcs().send_text(MAV_SEVERITY_INFO,"Loiter orbits complete");
}
return result;
}
bool Plane::verify_loiter_to_alt(const AP_Mission::Mission_Command &cmd)
{
bool result = false;
update_loiter(cmd.p1);
if (condition_value == 0) {
if (labs(loiter.sum_cd) > 1 && (loiter.reached_target_alt || loiter.unable_to_achieve_target_alt)) {
if (loiter.unable_to_achieve_target_alt) {
gcs().send_text(MAV_SEVERITY_INFO,"Loiter to alt was stuck at %d", int(current_loc.alt/100));
}
condition_value = 1;
result = verify_loiter_heading(true);
}
} else {
result = verify_loiter_heading(false);
}
if (result) {
gcs().send_text(MAV_SEVERITY_INFO,"Loiter to alt complete");
}
return result;
}
bool Plane::verify_continue_and_change_alt()
{
if (prev_WP_loc.same_latlon_as(next_WP_loc) &&
steer_state.hold_course_cd != -1) {
nav_controller->update_heading_hold(steer_state.hold_course_cd);
}
else {
if (current_loc.get_distance(next_WP_loc) < 200.0f) {
int32_t next_wp_bearing_cd = prev_WP_loc.get_bearing_to(next_WP_loc);
next_WP_loc.offset_bearing(next_wp_bearing_cd * 0.01f, 300.0f);
}
nav_controller->update_waypoint(prev_WP_loc, next_WP_loc);
}
if (condition_value == 1 && adjusted_altitude_cm() >= next_WP_loc.alt) {
return true;
}
else if (condition_value == 2 &&
adjusted_altitude_cm() <= next_WP_loc.alt) {
return true;
}
else if (labs(adjusted_altitude_cm() - next_WP_loc.alt) <= 500) {
return true;
}
return false;
}
bool ModeAuto::verify_altitude_wait(const AP_Mission::Mission_Command &cmd)
{
#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (pullup.in_pullup()) {
return pullup.verify_pullup();
}
#endif
const float alt_diff = plane.current_loc.alt*0.01 - cmd.content.altitude_wait.altitude;
bool completed = false;
if (alt_diff > 0) {
gcs().send_text(MAV_SEVERITY_INFO,"Reached altitude");
completed = true;
} else if (cmd.content.altitude_wait.descent_rate > 0 &&
plane.auto_state.sink_rate > cmd.content.altitude_wait.descent_rate) {
gcs().send_text(MAV_SEVERITY_INFO, "Reached descent rate %.1f m/s", (double)plane.auto_state.sink_rate);
completed = true;
}
if (completed) {
#if AP_PLANE_GLIDER_PULLUP_ENABLED
if (pullup.pullup_start()) {
return false;
}
#endif
return true;
}
const float time_to_alt = alt_diff / MIN(plane.auto_state.sink_rate, -0.01);
if (cmd.content.altitude_wait.wiggle_time != 0 &&
(plane.auto_state.sink_rate > 0 || time_to_alt > cmd.content.altitude_wait.wiggle_time*5)) {
if (wiggle.stage == 0 &&
AP_HAL::millis() - wiggle.last_ms > cmd.content.altitude_wait.wiggle_time*1000) {
wiggle.stage = 1;
wiggle.last_ms = AP_HAL::millis();
}
}
return false;
}
bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
{
if (AP::arming().is_armed_and_safety_off()) {
return true;
}
if (millis() - nav_delay.time_start_ms > nav_delay.time_max_ms) {
nav_delay.time_max_ms = 0;
return true;
}
return false;
}
void Plane::do_wait_delay(const AP_Mission::Mission_Command& cmd)
{
condition_start = millis();
condition_value = cmd.content.delay.seconds * 1000;
}
void Plane::do_within_distance(const AP_Mission::Mission_Command& cmd)
{
condition_value = cmd.content.distance.meters;
}
bool Plane::verify_wait_delay()
{
if ((unsigned)(millis() - condition_start) > (unsigned)condition_value) {
condition_value = 0;
return true;
}
return false;
}
bool Plane::verify_within_distance()
{
if (auto_state.wp_distance < MAX(condition_value,0)) {
condition_value = 0;
return true;
}
return false;
}
void Plane::do_loiter_at_location()
{
if (aparm.loiter_radius < 0) {
loiter.direction = -1;
} else {
loiter.direction = 1;
}
next_WP_loc = current_loc;
}
bool Plane::do_change_speed(const AP_Mission::Mission_Command& cmd)
{
return do_change_speed(
(SPEED_TYPE)cmd.content.speed.speed_type,
cmd.content.speed.target_ms,
cmd.content.speed.throttle_pct
);
}
bool Plane::do_change_speed(SPEED_TYPE speedtype, float speed_target_ms, float throttle_pct)
{
switch (speedtype) {
case SPEED_TYPE_AIRSPEED:
if (is_equal(speed_target_ms, -2.0f)) {
new_airspeed_cm = -1;
return true;
} else if ((speed_target_ms >= aparm.airspeed_min.get()) &&
(speed_target_ms <= aparm.airspeed_max.get())) {
new_airspeed_cm = speed_target_ms * 100;
gcs().send_text(MAV_SEVERITY_INFO, "Set airspeed %u m/s", (unsigned)speed_target_ms);
return true;
}
break;
case SPEED_TYPE_GROUNDSPEED:
gcs().send_text(MAV_SEVERITY_INFO, "Set groundspeed %u", (unsigned)speed_target_ms);
aparm.min_groundspeed.set(speed_target_ms);
return true;
case SPEED_TYPE_CLIMB_SPEED:
case SPEED_TYPE_DESCENT_SPEED:
case SPEED_TYPE_ENUM_END:
break;
}
if (throttle_pct > 0 && throttle_pct <= 100) {
gcs().send_text(MAV_SEVERITY_INFO, "Set throttle %u", (unsigned)throttle_pct);
aparm.throttle_cruise.set(throttle_pct);
return true;
}
return false;
}
void Plane::do_set_home(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 == 1 && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
if (!set_home_persistently(gps.location())) {
}
} else {
if (!AP::ahrs().set_home(cmd.content.location)) {
}
}
}
bool Plane::start_command_callback(const AP_Mission::Mission_Command &cmd)
{
if (control_mode == &mode_auto) {
return start_command(cmd);
}
return true;
}
bool Plane::verify_command_callback(const AP_Mission::Mission_Command& cmd)
{
if (control_mode == &mode_auto) {
bool cmd_complete = verify_command(cmd);
if (cmd_complete) {
gcs().send_mission_item_reached_message(cmd.index);
}
return cmd_complete;
}
return false;
}
void Plane::exit_mission_callback()
{
if (control_mode == &mode_auto) {
set_mode(mode_rtl, ModeReason::MISSION_END);
gcs().send_text(MAV_SEVERITY_INFO, "Mission complete, changing mode to RTL");
}
}
#if HAL_QUADPLANE_ENABLED
bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd)
{
const float radius = is_zero(quadplane.fw_land_approach_radius_m)? aparm.loiter_radius : quadplane.fw_land_approach_radius_m;
const int8_t direction = is_negative(radius) ? -1 : 1;
const float abs_radius = fabsf(radius);
loiter.direction = direction;
switch (vtol_approach_s.approach_stage) {
case VTOLApproach::Stage::RTL:
{
nav_controller->update_loiter(cmd.content.location, abs_radius, direction);
if (plane.reached_loiter_target()) {
plane.do_RTL(plane.home.alt + plane.quadplane.qrtl_alt_m*100UL);
plane.loiter_angle_reset();
vtol_approach_s.approach_stage = VTOLApproach::Stage::LOITER_TO_ALT;
}
break;
}
case VTOLApproach::Stage::LOITER_TO_ALT:
{
nav_controller->update_loiter(cmd.content.location, abs_radius, direction);
if (labs(loiter.sum_cd) > 1 && (loiter.reached_target_alt || loiter.unable_to_achieve_target_alt)) {
Vector3f wind = ahrs.wind_estimate();
vtol_approach_s.approach_direction_deg = degrees(atan2f(-wind.y, -wind.x));
gcs().send_text(MAV_SEVERITY_INFO, "Selected an approach path of %.1f", (double)vtol_approach_s.approach_direction_deg);
vtol_approach_s.approach_stage = VTOLApproach::Stage::ENSURE_RADIUS;
}
break;
}
case VTOLApproach::Stage::ENSURE_RADIUS:
{
if (((fabsF(cmd.content.location.get_distance(current_loc) - abs_radius) > 5.0f) &&
(cmd.content.location.get_distance(current_loc) < abs_radius)) ||
(labs(loiter.sum_cd) < 2)) {
nav_controller->update_loiter(cmd.content.location, abs_radius, direction);
break;
}
vtol_approach_s.approach_stage = VTOLApproach::Stage::WAIT_FOR_BREAKOUT;
FALLTHROUGH;
}
case VTOLApproach::Stage::WAIT_FOR_BREAKOUT:
{
nav_controller->update_loiter(cmd.content.location, radius, direction);
const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90));
if (fabsF(wrap_PI(ahrs.get_yaw_rad() - breakout_direction_rad)) < radians(5.0f)) {
gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path");
vtol_approach_s.approach_stage = VTOLApproach::Stage::APPROACH_LINE;
set_next_WP(cmd.content.location);
} else {
break;
}
FALLTHROUGH;
}
case VTOLApproach::Stage::APPROACH_LINE:
{
Location start = cmd.content.location;
Location end = cmd.content.location;
start.offset_bearing(vtol_approach_s.approach_direction_deg + 180, 1000);
end.offset_bearing(vtol_approach_s.approach_direction_deg, 1000);
nav_controller->update_waypoint(start, end);
Location breakout_stopping_loc = cmd.content.location;
breakout_stopping_loc.offset_bearing(vtol_approach_s.approach_direction_deg + 180, quadplane.stopping_distance_m());
const bool past_finish_line = current_loc.past_interval_finish_line(start, breakout_stopping_loc);
Location breakout_loc = cmd.content.location;
breakout_loc.offset_bearing(vtol_approach_s.approach_direction_deg + 180, abs_radius);
const bool half_radius = current_loc.line_path_proportion(breakout_loc, cmd.content.location) > 0.5;
bool lined_up = true;
Vector3f vel_NED;
if (ahrs.get_velocity_NED(vel_NED)) {
const Vector2f target_vec = current_loc.get_distance_NE(cmd.content.location);
const float angle_err = fabsf(wrap_180(degrees(vel_NED.xy().angle(target_vec))));
lined_up = (angle_err < 30);
}
if (past_finish_line && (lined_up || half_radius)) {
vtol_approach_s.approach_stage = VTOLApproach::Stage::VTOL_LANDING;
quadplane.do_vtol_land(cmd);
} else {
break;
}
FALLTHROUGH;
}
case VTOLApproach::Stage::VTOL_LANDING:
return true;
}
return false;
}
#endif
bool Plane::verify_loiter_heading(bool init)
{
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_vtol_auto()) {
return true;
}
#endif
#if MODE_AUTOLAND_ENABLED
if (control_mode == &mode_autoland) {
return mode_autoland.landing_lined_up();
}
#endif
AP_Mission::Mission_Command next_nav_cmd;
if (! mission.get_next_nav_cmd(mission.get_current_nav_index() + 1,
next_nav_cmd)) {
return true;
}
if (init) {
loiter.sum_cd = 0;
}
return plane.mode_loiter.isHeadingLinedUp(next_WP_loc, next_nav_cmd.content.location);
}
float Plane::get_wp_radius() const
{
#if HAL_QUADPLANE_ENABLED
if (plane.quadplane.in_vtol_mode()) {
return plane.quadplane.wp_nav->get_wp_radius_m();
}
#endif
return g.waypoint_radius;
}
#if AP_SCRIPTING_ENABLED
void Plane::do_nav_script_time(const AP_Mission::Mission_Command& cmd)
{
nav_scripting.enabled = true;
nav_scripting.id++;
nav_scripting.start_ms = AP_HAL::millis();
nav_scripting.current_ms = nav_scripting.start_ms;
nav_scripting.roll_rate_dps = plane.rollController.get_pid_info().target;
nav_scripting.pitch_rate_dps = plane.pitchController.get_pid_info().target;
nav_scripting.yaw_rate_dps = degrees(ahrs.get_gyro().z);
nav_scripting.throttle_pct = SRV_Channels::get_output_scaled(SRV_Channel::k_throttle);
}
bool Plane::verify_nav_script_time(const AP_Mission::Mission_Command& cmd)
{
if (cmd.content.nav_script_time.timeout_s > 0) {
const uint32_t now = AP_HAL::millis();
if (now - nav_scripting.start_ms > cmd.content.nav_script_time.timeout_s*1000U) {
gcs().send_text(MAV_SEVERITY_INFO, "NavScriptTime timed out");
nav_scripting.enabled = false;
nav_scripting.rudder_offset_pct = 0;
nav_scripting.run_yaw_rate_controller = true;
}
}
return !nav_scripting.enabled;
}
bool Plane::nav_scripting_active(void)
{
if (nav_scripting.enabled && AP_HAL::millis() - nav_scripting.current_ms > 1000) {
nav_scripting.enabled = false;
nav_scripting.current_ms = 0;
nav_scripting.rudder_offset_pct = 0;
nav_scripting.run_yaw_rate_controller = true;
gcs().send_text(MAV_SEVERITY_INFO, "NavScript time out");
}
if (control_mode == &mode_auto &&
mission.get_current_nav_cmd().id != MAV_CMD_NAV_SCRIPT_TIME) {
nav_scripting.enabled = false;
}
return nav_scripting.enabled;
}
bool Plane::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
{
if (!nav_scripting_active()) {
return false;
}
const auto &c = mission.get_current_nav_cmd().content.nav_script_time;
id = nav_scripting.id;
cmd = c.command;
arg1 = c.arg1.get();
arg2 = c.arg2.get();
arg3 = c.arg3;
arg4 = c.arg4;
return true;
}
void Plane::nav_script_time_done(uint16_t id)
{
if (id == nav_scripting.id) {
nav_scripting.enabled = false;
}
}
void Plane::set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps)
{
nav_scripting.roll_rate_dps = constrain_float(roll_rate_dps, -g.acro_roll_rate, g.acro_roll_rate);
nav_scripting.pitch_rate_dps = constrain_float(pitch_rate_dps, -g.acro_pitch_rate, g.acro_pitch_rate);
nav_scripting.yaw_rate_dps = constrain_float(yaw_rate_dps, -g.acro_yaw_rate, g.acro_yaw_rate);
nav_scripting.throttle_pct = constrain_float(throttle_pct, aparm.throttle_min, aparm.throttle_max);
nav_scripting.current_ms = AP_HAL::millis();
}
void Plane::set_rudder_offset(float rudder_pct, bool run_yaw_rate_controller)
{
nav_scripting.rudder_offset_pct = rudder_pct;
nav_scripting.run_yaw_rate_controller = run_yaw_rate_controller;
}
bool Plane::nav_scripting_enable(uint8_t mode)
{
uint8_t current_control_mode = control_mode->mode_number();
if (current_control_mode == mode) {
switch (current_control_mode) {
case Mode::Number::CIRCLE:
case Mode::Number::STABILIZE:
case Mode::Number::ACRO:
case Mode::Number::FLY_BY_WIRE_A:
case Mode::Number::FLY_BY_WIRE_B:
case Mode::Number::CRUISE:
case Mode::Number::LOITER:
nav_scripting.enabled = true;
nav_scripting.current_ms = AP_HAL::millis();
break;
default:
nav_scripting.enabled = false;
}
} else {
nav_scripting.enabled = false;
}
return nav_scripting.enabled;
}
#endif
bool Plane::is_land_command(uint16_t command) const
{
return
command == MAV_CMD_NAV_VTOL_LAND ||
command == MAV_CMD_NAV_LAND ||
command == MAV_CMD_NAV_PAYLOAD_PLACE;
}
bool Plane::in_auto_mission_id(uint16_t command) const
{
return control_mode == &mode_auto && mission.get_current_nav_id() == command;
}