#include "Rover.h"
#define AUTO_GUIDED_SEND_TARGET_MS 1000
bool ModeAuto::_enter()
{
if (!mission.present()) {
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "No Mission. Can't set AUTO.");
return false;
}
g2.wp_nav.init();
auto_triggered = false;
rover.mode_guided.limit_clear();
if (rover.is_boat()) {
if (!start_loiter()) {
start_stop();
}
} else {
start_stop();
}
waiting_to_start = true;
return true;
}
void ModeAuto::_exit()
{
if (mission.state() == AP_Mission::MISSION_RUNNING) {
mission.stop();
}
}
void ModeAuto::update()
{
if (!hal.util->get_soft_armed() && !mission.present()) {
start_stop();
}
if (waiting_to_start) {
Location loc;
if (ahrs.get_origin(loc)) {
mission.start_or_resume();
waiting_to_start = false;
IGNORE_RETURN(mis_change_detector.check_for_mission_change());
}
} else {
if (mis_change_detector.check_for_mission_change()) {
if ((mission.state() == AP_Mission::MISSION_RUNNING) && (_submode == SubMode::WP)) {
if (mission.restart_current_nav_cmd()) {
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Auto mission changed, restarted command");
} else {
GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Auto mission changed but failed to restart command");
}
}
}
mission.update();
}
switch (_submode) {
case SubMode::WP:
{
bool keep_navigating = true;
if (rover.is_boat() && g2.wp_nav.reached_destination() && !g2.wp_nav.is_fast_waypoint()) {
keep_navigating = !start_loiter();
}
if (keep_navigating) {
navigate_to_waypoint();
}
break;
}
case SubMode::HeadingAndSpeed:
{
if (!_reached_heading) {
calc_steering_to_heading(_desired_yaw_cd);
calc_throttle(calc_speed_nudge(_desired_speed, is_negative(_desired_speed)), true);
_reached_heading = (fabsf(_desired_yaw_cd - ahrs.yaw_sensor) < 500);
} else {
if (rover.is_boat()) {
if (!start_loiter()) {
stop_vehicle();
}
} else {
stop_vehicle();
}
}
break;
}
case SubMode::RTL:
rover.mode_rtl.update();
break;
case SubMode::Loiter:
rover.mode_loiter.update();
break;
case SubMode::Guided:
{
send_guided_position_target();
rover.mode_guided.update();
break;
}
case SubMode::Stop:
stop_vehicle();
break;
case SubMode::NavScriptTime:
rover.mode_guided.update();
break;
case SubMode::Circle:
g2.mode_circle.update();
break;
}
}
void ModeAuto::calc_throttle(float target_speed, bool avoidance_enabled)
{
if (!check_trigger()) {
stop_vehicle();
return;
}
Mode::calc_throttle(target_speed, avoidance_enabled);
}
float ModeAuto::wp_bearing() const
{
switch (_submode) {
case SubMode::WP:
return g2.wp_nav.wp_bearing_cd() * 0.01f;
case SubMode::HeadingAndSpeed:
case SubMode::Stop:
return 0.0f;
case SubMode::RTL:
return rover.mode_rtl.wp_bearing();
case SubMode::Loiter:
return rover.mode_loiter.wp_bearing();
case SubMode::Guided:
case SubMode::NavScriptTime:
return rover.mode_guided.wp_bearing();
case SubMode::Circle:
return g2.mode_circle.wp_bearing();
}
return 0.0f;
}
float ModeAuto::nav_bearing() const
{
switch (_submode) {
case SubMode::WP:
return g2.wp_nav.nav_bearing_cd() * 0.01f;
case SubMode::HeadingAndSpeed:
case SubMode::Stop:
return 0.0f;
case SubMode::RTL:
return rover.mode_rtl.nav_bearing();
case SubMode::Loiter:
return rover.mode_loiter.nav_bearing();
case SubMode::Guided:
case SubMode::NavScriptTime:
return rover.mode_guided.nav_bearing();
case SubMode::Circle:
return g2.mode_circle.nav_bearing();
}
return 0.0f;
}
float ModeAuto::crosstrack_error() const
{
switch (_submode) {
case SubMode::WP:
return g2.wp_nav.crosstrack_error();
case SubMode::HeadingAndSpeed:
case SubMode::Stop:
return 0.0f;
case SubMode::RTL:
return rover.mode_rtl.crosstrack_error();
case SubMode::Loiter:
return rover.mode_loiter.crosstrack_error();
case SubMode::Guided:
case SubMode::NavScriptTime:
return rover.mode_guided.crosstrack_error();
case SubMode::Circle:
return g2.mode_circle.crosstrack_error();
}
return 0.0f;
}
float ModeAuto::get_desired_lat_accel() const
{
switch (_submode) {
case SubMode::WP:
return g2.wp_nav.get_lat_accel();
case SubMode::HeadingAndSpeed:
case SubMode::Stop:
return 0.0f;
case SubMode::RTL:
return rover.mode_rtl.get_desired_lat_accel();
case SubMode::Loiter:
return rover.mode_loiter.get_desired_lat_accel();
case SubMode::Guided:
case SubMode::NavScriptTime:
return rover.mode_guided.get_desired_lat_accel();
case SubMode::Circle:
return g2.mode_circle.get_desired_lat_accel();
}
return 0.0f;
}
float ModeAuto::get_distance_to_destination() const
{
switch (_submode) {
case SubMode::WP:
return _distance_to_destination;
case SubMode::HeadingAndSpeed:
case SubMode::Stop:
return 0.0f;
case SubMode::RTL:
return rover.mode_rtl.get_distance_to_destination();
case SubMode::Loiter:
return rover.mode_loiter.get_distance_to_destination();
case SubMode::Guided:
case SubMode::NavScriptTime:
return rover.mode_guided.get_distance_to_destination();
case SubMode::Circle:
return g2.mode_circle.get_distance_to_destination();
}
return 0.0f;
}
bool ModeAuto::get_desired_location(Location& destination) const
{
switch (_submode) {
case SubMode::WP:
if (g2.wp_nav.is_destination_valid()) {
destination = g2.wp_nav.get_oa_destination();
return true;
}
return false;
case SubMode::HeadingAndSpeed:
case SubMode::Stop:
return false;
case SubMode::RTL:
return rover.mode_rtl.get_desired_location(destination);
case SubMode::Loiter:
return rover.mode_loiter.get_desired_location(destination);
case SubMode::Guided:
case SubMode::NavScriptTime:
return rover.mode_guided.get_desired_location(destination);
case SubMode::Circle:
return g2.mode_circle.get_desired_location(destination);
}
return false;
}
bool ModeAuto::set_desired_location(const Location &destination, Location next_destination)
{
if (!Mode::set_desired_location(destination, next_destination)) {
return false;
}
_submode = SubMode::WP;
return true;
}
bool ModeAuto::reached_destination() const
{
switch (_submode) {
case SubMode::WP:
return g2.wp_nav.reached_destination();
break;
case SubMode::HeadingAndSpeed:
case SubMode::Stop:
return true;
break;
case SubMode::RTL:
return rover.mode_rtl.reached_destination();
break;
case SubMode::Loiter:
return rover.mode_loiter.reached_destination();
break;
case SubMode::Guided:
case SubMode::NavScriptTime:
return rover.mode_guided.reached_destination();
case SubMode::Circle:
return g2.mode_circle.reached_destination();
}
return true;
}
bool ModeAuto::set_desired_speed(float speed)
{
switch (_submode) {
case SubMode::WP:
case SubMode::Stop:
return g2.wp_nav.set_speed_max(speed);
case SubMode::HeadingAndSpeed:
_desired_speed = speed;
return true;
case SubMode::RTL:
return rover.mode_rtl.set_desired_speed(speed);
case SubMode::Loiter:
return rover.mode_loiter.set_desired_speed(speed);
case SubMode::Guided:
case SubMode::NavScriptTime:
return rover.mode_guided.set_desired_speed(speed);
case SubMode::Circle:
return g2.mode_circle.set_desired_speed(speed);
}
return false;
}
void ModeAuto::start_RTL()
{
if (rover.mode_rtl.enter()) {
_submode = SubMode::RTL;
}
}
bool ModeAuto::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)
{
#if AP_SCRIPTING_ENABLED
if (_submode == SubMode::NavScriptTime) {
id = nav_scripting.id;
cmd = nav_scripting.command;
arg1 = nav_scripting.arg1;
arg2 = nav_scripting.arg2;
arg3 = nav_scripting.arg3;
arg4 = nav_scripting.arg4;
return true;
}
#endif
return false;
}
void ModeAuto::nav_script_time_done(uint16_t id)
{
#if AP_SCRIPTING_ENABLED
if ((_submode == SubMode::NavScriptTime) && (id == nav_scripting.id)) {
nav_scripting.done = true;
}
#endif
}
bool ModeAuto::check_trigger(void)
{
if (auto_triggered && g.auto_trigger_pin != -1 && rover.check_digital_pin(g.auto_trigger_pin) == 1) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "AUTO triggered off");
auto_triggered = false;
return false;
}
if (auto_triggered) {
return true;
}
if (g.auto_trigger_pin == -1 && is_zero(g.auto_kickstart)) {
auto_triggered = true;
return true;
}
if (g.auto_trigger_pin != -1 && rover.check_digital_pin(g.auto_trigger_pin) == 0) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Triggered AUTO with pin");
auto_triggered = true;
return true;
}
if (!is_zero(g.auto_kickstart)) {
const float xaccel = rover.ins.get_accel().x;
if (xaccel >= g.auto_kickstart) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Triggered AUTO xaccel=%.1f", static_cast<double>(xaccel));
auto_triggered = true;
return true;
}
}
return false;
}
bool ModeAuto::start_loiter()
{
if (rover.mode_loiter.enter()) {
_submode = SubMode::Loiter;
return true;
}
return false;
}
void ModeAuto::start_guided(const Location& loc)
{
if (rover.mode_guided.enter()) {
_submode = SubMode::Guided;
rover.mode_guided.limit_init_time_and_location();
if ((loc.lat != 0) || (loc.lng != 0)) {
guided_target.loc = loc;
guided_target.loc.sanitize(rover.current_loc);
guided_target.valid = true;
} else {
guided_target.valid = false;
}
}
}
void ModeAuto::start_stop()
{
_submode = SubMode::Stop;
}
void ModeAuto::send_guided_position_target()
{
if (!guided_target.valid) {
return;
}
const uint32_t now_ms = AP_HAL::millis();
if ((guided_target.last_sent_ms == 0) || (now_ms - guided_target.last_sent_ms > AUTO_GUIDED_SEND_TARGET_MS)) {
guided_target.last_sent_ms = now_ms;
uint8_t sysid;
uint8_t compid;
mavlink_channel_t chan;
if (GCS_MAVLINK::find_by_mavtype(MAV_TYPE_ONBOARD_CONTROLLER, sysid, compid, chan)) {
gcs().chan(chan-MAVLINK_COMM_0)->send_set_position_target_global_int(sysid, compid, guided_target.loc);
}
}
}
bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
{
switch (cmd.id) {
case MAV_CMD_NAV_WAYPOINT:
return do_nav_wp(cmd, false);
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
do_RTL();
break;
case MAV_CMD_NAV_LOITER_UNLIM:
case MAV_CMD_NAV_LOITER_TIME:
return do_nav_wp(cmd, true);
case MAV_CMD_NAV_LOITER_TURNS:
return do_circle(cmd);
case MAV_CMD_NAV_GUIDED_ENABLE:
do_nav_guided_enable(cmd);
break;
case MAV_CMD_NAV_SET_YAW_SPEED:
do_nav_set_yaw_speed(cmd);
break;
case MAV_CMD_NAV_DELAY:
do_nav_delay(cmd);
break;
#if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME:
do_nav_script_time(cmd);
break;
#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;
#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 (rover.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
rover.camera_mount.set_mode_to_default();
}
} else {
rover.camera_mount.set_roi_target(cmd.content.location);
}
break;
#endif
case MAV_CMD_DO_SET_REVERSE:
do_set_reverse(cmd);
break;
case MAV_CMD_DO_GUIDED_LIMITS:
do_guided_limits(cmd);
break;
default:
return false;
}
return true;
}
void ModeAuto::exit_mission()
{
AP_Notify::events.mission_complete = 1;
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Mission Complete");
switch ((DoneBehaviour)g2.mis_done_behave) {
case DoneBehaviour::HOLD:
break;
case DoneBehaviour::LOITER:
if (start_loiter()) {
return;
}
break;
case DoneBehaviour::ACRO:
if (rover.set_mode(rover.mode_acro, ModeReason::MISSION_END)) {
return;
}
break;
case DoneBehaviour::MANUAL:
if (rover.set_mode(rover.mode_manual, ModeReason::MISSION_END)) {
return;
}
break;
}
start_stop();
}
bool ModeAuto::verify_command_callback(const AP_Mission::Mission_Command& cmd)
{
const bool cmd_complete = verify_command(cmd);
if (cmd_complete) {
gcs().send_mission_item_reached_message(cmd.index);
}
return cmd_complete;
}
bool ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
{
switch (cmd.id) {
case MAV_CMD_NAV_WAYPOINT:
return verify_nav_wp(cmd);
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
return verify_RTL();
case MAV_CMD_NAV_LOITER_UNLIM:
return verify_loiter_unlimited(cmd);
case MAV_CMD_NAV_LOITER_TURNS:
return verify_circle(cmd);
case MAV_CMD_NAV_LOITER_TIME:
return verify_loiter_time(cmd);
case MAV_CMD_NAV_GUIDED_ENABLE:
return verify_nav_guided_enable(cmd);
case MAV_CMD_NAV_DELAY:
return verify_nav_delay(cmd);
#if AP_SCRIPTING_ENABLED
case MAV_CMD_NAV_SCRIPT_TIME:
return verify_nav_script_time();
#endif
case MAV_CMD_CONDITION_DELAY:
return verify_wait_delay();
case MAV_CMD_CONDITION_DISTANCE:
return verify_within_distance();
case MAV_CMD_NAV_SET_YAW_SPEED:
return verify_nav_set_yaw_speed();
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_SET_HOME:
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_SET_REVERSE:
case MAV_CMD_DO_FENCE_ENABLE:
case MAV_CMD_DO_GUIDED_LIMITS:
return true;
default:
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Skipping invalid cmd #%i", cmd.id);
return true;
}
}
void ModeAuto::do_RTL(void)
{
start_RTL();
}
bool ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool always_stop_at_destination)
{
Location cmdloc = cmd.content.location;
cmdloc.sanitize(rover.current_loc);
loiter_duration = ((int16_t) cmd.p1 < 0) ? 0 : cmd.p1;
loiter_start_time = 0;
if (loiter_duration > 0) {
always_stop_at_destination = true;
}
AP_Mission::Mission_Command next_cmd;
if (always_stop_at_destination || !mission.get_next_nav_cmd(cmd.index+1, next_cmd)) {
if (!set_desired_location(cmdloc)) {
return false;
}
} else {
Location next_cmdloc = next_cmd.content.location;
next_cmdloc.sanitize(cmdloc);
if (!set_desired_location(cmdloc, next_cmdloc)) {
return false;
}
}
previously_reached_wp = false;
return true;
}
void ModeAuto::do_nav_delay(const AP_Mission::Mission_Command& cmd)
{
nav_delay_time_start_ms = millis();
if (rover.is_boat()) {
if (!start_loiter()) {
start_stop();
}
} else {
start_stop();
}
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));
}
void ModeAuto::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 > 0) {
start_guided(cmd.content.location);
}
}
void ModeAuto::do_nav_set_yaw_speed(const AP_Mission::Mission_Command& cmd)
{
float desired_heading_cd;
if (cmd.content.set_yaw_speed.relative_angle > 0) {
desired_heading_cd = wrap_180_cd(ahrs.yaw_sensor + cmd.content.set_yaw_speed.angle_deg * 100.0f);
} else {
desired_heading_cd = cmd.content.set_yaw_speed.angle_deg * 100.0f;
}
const float speed_max = g2.wp_nav.get_default_speed();
_desired_speed = constrain_float(cmd.content.set_yaw_speed.speed, -speed_max, speed_max);
_desired_yaw_cd = desired_heading_cd;
_reached_heading = false;
_submode = SubMode::HeadingAndSpeed;
}
bool ModeAuto::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
{
if (!reached_destination()) {
return false;
}
if (!previously_reached_wp) {
previously_reached_wp = true;
if (loiter_duration > 0) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Reached waypoint #%u. Loiter for %u seconds",
(unsigned int)cmd.index,
(unsigned int)loiter_duration);
loiter_start_time = millis();
} else {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Reached waypoint #%u", (unsigned int)cmd.index);
}
}
if (loiter_duration == 0) {
return true;
} else {
return (((millis() - loiter_start_time) / 1000) >= loiter_duration);
}
}
bool ModeAuto::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
{
if (millis() - nav_delay_time_start_ms > nav_delay_time_max_ms) {
nav_delay_time_max_ms = 0;
return true;
}
return false;
}
bool ModeAuto::verify_RTL() const
{
return reached_destination();
}
bool ModeAuto::verify_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
{
verify_nav_wp(cmd);
return false;
}
bool ModeAuto::verify_loiter_time(const AP_Mission::Mission_Command& cmd)
{
const bool result = verify_nav_wp(cmd);
if (result) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Finished active loiter");
}
return result;
}
bool ModeAuto::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
{
if (_submode != SubMode::Guided || cmd.p1 == 0) {
return true;
}
if (guided_target.valid) {
if (rover.current_loc.get_distance(guided_target.loc) <= g2.wp_nav.get_radius()) {
return true;
}
}
return rover.mode_guided.limit_breached();
}
bool ModeAuto::verify_nav_set_yaw_speed()
{
if (_submode == SubMode::HeadingAndSpeed) {
return _reached_heading;
}
return true;
}
bool ModeAuto::do_circle(const AP_Mission::Mission_Command& cmd)
{
Location circle_center = cmd.content.location;
circle_center.sanitize(rover.current_loc);
uint16_t circle_radius_m = HIGHBYTE(cmd.p1);
if (cmd.id == MAV_CMD_NAV_LOITER_TURNS &&
cmd.type_specific_bits & (1U << 0)) {
circle_radius_m *= 10;
}
if (g2.mode_circle.set_center(circle_center, circle_radius_m, cmd.content.location.loiter_ccw)) {
_submode = SubMode::Circle;
return true;
}
return false;
}
bool ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd)
{
const float turns = cmd.get_loiter_turns();
return ((g2.mode_circle.get_angle_total_rad() / M_2PI) >= turns);
}
void ModeAuto::do_wait_delay(const AP_Mission::Mission_Command& cmd)
{
condition_start = millis();
condition_value = static_cast<int32_t>(cmd.content.delay.seconds * 1000);
}
void ModeAuto::do_within_distance(const AP_Mission::Mission_Command& cmd)
{
condition_value = cmd.content.distance.meters;
}
bool ModeAuto::verify_wait_delay()
{
if (static_cast<uint32_t>(millis() - condition_start) > static_cast<uint32_t>(condition_value)) {
condition_value = 0;
return true;
}
return false;
}
bool ModeAuto::verify_within_distance()
{
if (get_distance_to_destination() < condition_value) {
condition_value = 0;
return true;
}
return false;
}
void ModeAuto::do_change_speed(const AP_Mission::Mission_Command& cmd)
{
if (set_desired_speed(cmd.content.speed.target_ms)) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "speed: %.1f m/s", static_cast<double>(cmd.content.speed.target_ms));
}
}
void ModeAuto::do_set_home(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 == 1 && rover.have_position) {
if (!rover.set_home_to_current_location(false)) {
}
} else {
if (!rover.set_home(cmd.content.location, false)) {
}
}
}
void ModeAuto::do_set_reverse(const AP_Mission::Mission_Command& cmd)
{
set_reversed(cmd.p1 == 1);
}
void ModeAuto::do_guided_limits(const AP_Mission::Mission_Command& cmd)
{
rover.mode_guided.limit_set(
cmd.p1 * 1000,
cmd.content.guided_limits.horiz_max);
}
#if AP_SCRIPTING_ENABLED
void ModeAuto::do_nav_script_time(const AP_Mission::Mission_Command& cmd)
{
if (rover.mode_guided.enter()) {
_submode = SubMode::NavScriptTime;
nav_scripting.done = false;
nav_scripting.id++;
nav_scripting.start_ms = millis();
nav_scripting.command = cmd.content.nav_script_time.command;
nav_scripting.timeout_s = cmd.content.nav_script_time.timeout_s;
nav_scripting.arg1 = cmd.content.nav_script_time.arg1.get();
nav_scripting.arg2 = cmd.content.nav_script_time.arg2.get();
nav_scripting.arg3 = cmd.content.nav_script_time.arg3;
nav_scripting.arg4 = cmd.content.nav_script_time.arg4;
} else {
nav_scripting.done = true;
}
}
bool ModeAuto::verify_nav_script_time()
{
if (nav_scripting.done ||
((nav_scripting.timeout_s > 0) &&
(AP_HAL::millis() - nav_scripting.start_ms) > (nav_scripting.timeout_s * 1000))) {
return true;
}
return false;
}
#endif