#include "Rover.h"
bool ModeSmartRTL::_enter()
{
Location ekf_origin;
if (!ahrs.get_origin(ekf_origin)) {
return false;
}
if (!g2.smart_rtl.is_active()) {
return false;
}
g2.wp_nav.init(MAX(0, g2.rtl_speed));
if (!g2.wp_nav.set_desired_location_to_stopping_location()) {
return false;
}
smart_rtl_state = SmartRTLState::WaitForPathCleanup;
_loitering = false;
return true;
}
void ModeSmartRTL::update()
{
switch (smart_rtl_state) {
case SmartRTLState::WaitForPathCleanup:
if (g2.smart_rtl.request_thorough_cleanup()) {
smart_rtl_state = SmartRTLState::PathFollow;
_load_point = true;
}
stop_vehicle();
break;
case SmartRTLState::PathFollow:
if (_load_point) {
Vector3p dest_NED;
if (!g2.smart_rtl.pop_point(dest_NED)) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Reached destination");
smart_rtl_state = SmartRTLState::StopAtHome;
break;
} else {
Vector3p next_dest_NED;
if (g2.smart_rtl.peek_point(next_dest_NED)) {
if (!g2.wp_nav.set_desired_location_NED(dest_NED.tofloat(), next_dest_NED.tofloat())) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SmartRTL: failed to set destination");
smart_rtl_state = SmartRTLState::Failure;
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
}
} else {
if (!g2.wp_nav.set_desired_location_NED(dest_NED.tofloat())) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SmartRTL: failed to set destination");
smart_rtl_state = SmartRTLState::Failure;
INTERNAL_ERROR(AP_InternalError::error_t::flow_of_control);
}
}
}
_load_point = false;
}
navigate_to_waypoint();
if (g2.wp_nav.reached_destination()) {
_load_point = true;
}
break;
case SmartRTLState::StopAtHome:
case SmartRTLState::Failure:
_reached_destination = true;
if (!rover.is_boat()) {
stop_vehicle();
} else {
if (!_loitering) {
_loitering = rover.mode_loiter.enter();
}
if (_loitering) {
rover.mode_loiter.update();
} else {
stop_vehicle();
}
}
break;
}
}
bool ModeSmartRTL::get_desired_location(Location& destination) const
{
switch (smart_rtl_state) {
case SmartRTLState::WaitForPathCleanup:
return false;
case SmartRTLState::PathFollow:
if (g2.wp_nav.is_destination_valid()) {
destination = g2.wp_nav.get_destination();
return true;
}
return false;
case SmartRTLState::StopAtHome:
case SmartRTLState::Failure:
return false;
}
return false;
}
bool ModeSmartRTL::set_desired_speed(float speed)
{
return g2.wp_nav.set_speed_max(speed);
}
void ModeSmartRTL::save_position()
{
const bool save_pos = (rover.control_mode != &rover.mode_smartrtl);
g2.smart_rtl.update(true, save_pos);
}