#include "Sub.h"
#include <AP_RTC/AP_RTC.h>
static enum AutoSurfaceState auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;
bool Sub::start_command(const AP_Mission::Mission_Command& cmd)
{
const Location &target_loc = cmd.content.location;
auto alt_frame = target_loc.get_alt_frame();
if (alt_frame == Location::AltFrame::ABOVE_HOME) {
if (target_loc.alt > 0) {
gcs().send_text(MAV_SEVERITY_WARNING, "Alt above home must be negative");
return false;
}
} else if (alt_frame == Location::AltFrame::ABOVE_TERRAIN) {
if (target_loc.alt < 0) {
gcs().send_text(MAV_SEVERITY_WARNING, "Alt above terrain must be positive");
return false;
}
} else {
gcs().send_text(MAV_SEVERITY_WARNING, "Bad alt frame");
return false;
}
switch (cmd.id) {
case MAV_CMD_NAV_WAYPOINT:
do_nav_wp(cmd);
break;
case MAV_CMD_NAV_LAND:
do_surface(cmd);
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
do_RTL();
break;
case MAV_CMD_NAV_LOITER_UNLIM:
do_loiter_unlimited(cmd);
break;
case MAV_CMD_NAV_LOITER_TURNS:
do_circle(cmd);
break;
case MAV_CMD_NAV_LOITER_TIME:
do_loiter_time(cmd);
break;
#if NAV_GUIDED
case MAV_CMD_NAV_GUIDED_ENABLE:
do_nav_guided_enable(cmd);
break;
#endif
case MAV_CMD_NAV_DELAY:
do_nav_delay(cmd);
break;
case MAV_CMD_CONDITION_DELAY:
do_wait_delay(cmd);
break;
case MAV_CMD_CONDITION_DISTANCE:
do_within_distance(cmd);
break;
case MAV_CMD_CONDITION_YAW:
do_yaw(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_SET_ROI_LOCATION:
case MAV_CMD_DO_SET_ROI_NONE:
case MAV_CMD_DO_SET_ROI:
do_roi(cmd);
break;
case MAV_CMD_DO_MOUNT_CONTROL:
do_mount_control(cmd);
break;
#if NAV_GUIDED
case MAV_CMD_DO_GUIDED_LIMITS:
do_guided_limits(cmd);
break;
#endif
default:
gcs().send_text(MAV_SEVERITY_WARNING, "Ignoring command %d", cmd.id);
return false;
}
return true;
}
bool Sub::verify_command_callback(const AP_Mission::Mission_Command& cmd)
{
if (control_mode == Mode::Number::AUTO) {
bool cmd_complete = verify_command(cmd);
if (cmd_complete) {
gcs().send_mission_item_reached_message(cmd.index);
}
return cmd_complete;
}
return false;
}
bool Sub::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_LAND:
return verify_surface(cmd);
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
return verify_RTL();
case MAV_CMD_NAV_LOITER_UNLIM:
return verify_loiter_unlimited();
case MAV_CMD_NAV_LOITER_TURNS:
return verify_circle(cmd);
case MAV_CMD_NAV_LOITER_TIME:
return verify_loiter_time();
#if NAV_GUIDED
case MAV_CMD_NAV_GUIDED_ENABLE:
return verify_nav_guided_enable(cmd);
#endif
case MAV_CMD_NAV_DELAY:
return verify_nav_delay(cmd);
case MAV_CMD_CONDITION_DELAY:
return verify_wait_delay();
case MAV_CMD_CONDITION_DISTANCE:
return verify_within_distance();
case MAV_CMD_CONDITION_YAW:
return verify_yaw();
case MAV_CMD_DO_CHANGE_SPEED:
case MAV_CMD_DO_SET_HOME:
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_SET_CAM_TRIGG_DIST:
case MAV_CMD_DO_GUIDED_LIMITS:
return true;
default:
gcs().send_text(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);
return true;
}
}
void Sub::exit_mission()
{
AP_Notify::events.mission_complete = 1;
if (!mode_auto.auto_loiter_start()) {
set_mode(Mode::Number::ALT_HOLD, ModeReason::MISSION_END);
}
}
void Sub::do_nav_wp(const AP_Mission::Mission_Command& cmd)
{
Location target_loc(cmd.content.location);
if (target_loc.lat == 0 && target_loc.lng == 0) {
target_loc.lat = current_loc.lat;
target_loc.lng = current_loc.lng;
}
loiter_time = 0;
loiter_time_max = cmd.p1;
mode_auto.auto_wp_start(target_loc);
}
void Sub::do_surface(const AP_Mission::Mission_Command& cmd)
{
Location target_location;
if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) {
auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;
target_location = Location(cmd.content.location);
int32_t curr_terr_alt_cm, target_terr_alt_cm;
if (current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, curr_terr_alt_cm) &&
target_location.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, target_terr_alt_cm)) {
target_location.set_alt_cm(curr_terr_alt_cm, Location::AltFrame::ABOVE_TERRAIN);
} else {
target_location.set_alt_cm(current_loc.alt, Location::AltFrame::ABOVE_HOME);
}
} else {
auto_surface_state = AUTO_SURFACE_STATE_ASCEND;
target_location = Location(current_loc.lat, current_loc.lng, 0, Location::AltFrame::ABOVE_HOME);
}
mode_auto.auto_wp_start(target_location);
}
void Sub::do_RTL()
{
mode_auto.auto_wp_start(ahrs.get_home());
}
void Sub::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
{
Location target_loc(cmd.content.location);
if (target_loc.lat == 0 && target_loc.lng == 0) {
Vector3f temp_pos;
wp_nav.get_wp_stopping_point_NE_cm(temp_pos.xy());
const Location temp_loc(temp_pos, Location::AltFrame::ABOVE_ORIGIN);
target_loc.lat = temp_loc.lat;
target_loc.lng = temp_loc.lng;
}
mode_auto.auto_wp_start(target_loc);
}
void Sub::do_circle(const AP_Mission::Mission_Command& cmd)
{
Location circle_center(cmd.content.location);
if (circle_center.lat == 0 && circle_center.lng == 0) {
circle_center.lat = current_loc.lat;
circle_center.lng = current_loc.lng;
}
uint16_t circle_radius_m = HIGHBYTE(cmd.p1);
if (cmd.type_specific_bits & (1U << 0)) {
circle_radius_m *= 10;
}
const bool circle_direction_ccw = cmd.content.location.loiter_ccw;
mode_auto.auto_circle_movetoedge_start(circle_center, circle_radius_m, circle_direction_ccw);
}
void Sub::do_loiter_time(const AP_Mission::Mission_Command& cmd)
{
do_loiter_unlimited(cmd);
loiter_time = 0;
loiter_time_max = cmd.p1;
}
#if NAV_GUIDED
void Sub::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 > 0) {
mode_auto.guided_limit_init_time_and_pos();
mode_auto.auto_nav_guided_start();
}
}
#endif
void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd)
{
nav_delay_time_start_ms = AP_HAL::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));
}
#if NAV_GUIDED
void Sub::do_guided_limits(const AP_Mission::Mission_Command& cmd)
{
mode_guided.guided_limit_set(cmd.p1 * 1000,
cmd.content.guided_limits.alt_min * 100.0f,
cmd.content.guided_limits.alt_max * 100.0f,
cmd.content.guided_limits.horiz_max * 100.0f);
}
#endif
bool Sub::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
{
if (!wp_nav.reached_wp_destination()) {
return false;
}
AP_Notify::events.waypoint_complete = 1;
if (loiter_time == 0) {
loiter_time = AP_HAL::millis();
}
if (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max) {
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
return true;
}
return false;
}
bool Sub::verify_surface(const AP_Mission::Mission_Command& cmd)
{
bool retval = false;
switch (auto_surface_state) {
case AUTO_SURFACE_STATE_GO_TO_LOCATION:
if (wp_nav.reached_wp_destination()) {
Location target_location(cmd.content.location.lat, cmd.content.location.lng, 0, Location::AltFrame::ABOVE_HOME);
mode_auto.auto_wp_start(target_location);
auto_surface_state = AUTO_SURFACE_STATE_ASCEND;
}
break;
case AUTO_SURFACE_STATE_ASCEND:
if (wp_nav.reached_wp_destination()) {
retval = true;
}
break;
default:
retval = true;
break;
}
return retval;
}
bool Sub::verify_RTL() {
return wp_nav.reached_wp_destination();
}
bool Sub::verify_loiter_unlimited()
{
return false;
}
bool Sub::verify_loiter_time()
{
if (!wp_nav.reached_wp_destination()) {
return false;
}
if (loiter_time == 0) {
loiter_time = AP_HAL::millis();
}
return (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max);
}
bool Sub::verify_circle(const AP_Mission::Mission_Command& cmd)
{
if (auto_mode == Auto_CircleMoveToEdge) {
if (wp_nav.reached_wp_destination()) {
Vector3f circle_center;
UNUSED_RESULT(cmd.content.location.get_vector_from_origin_NEU_cm(circle_center));
if (cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {
circle_center.xy() = inertial_nav.get_position_xy_cm();
}
mode_auto.auto_circle_start();
}
return false;
}
const float turns = cmd.get_loiter_turns();
return fabsf(sub.circle_nav.get_angle_total_rad()/M_2PI) >= turns;
}
#if NAV_GUIDED
bool Sub::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 == 0) {
return true;
}
return mode_auto.guided_limit_check();
}
#endif
bool Sub::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
{
if (AP_HAL::millis() - nav_delay_time_start_ms > nav_delay_time_max_ms) {
nav_delay_time_max_ms = 0;
return true;
}
return false;
}
void Sub::do_wait_delay(const AP_Mission::Mission_Command& cmd)
{
condition_start = AP_HAL::millis();
condition_value = cmd.content.delay.seconds * 1000;
}
void Sub::do_within_distance(const AP_Mission::Mission_Command& cmd)
{
condition_value = cmd.content.distance.meters;
}
void Sub::do_yaw(const AP_Mission::Mission_Command& cmd)
{
sub.mode_auto.set_auto_yaw_look_at_heading(
cmd.content.yaw.angle_deg,
cmd.content.yaw.turn_rate_dps,
cmd.content.yaw.direction,
cmd.content.yaw.relative_angle);
}
bool Sub::verify_wait_delay()
{
if (AP_HAL::millis() - condition_start > (uint32_t)MAX(condition_value, 0)) {
condition_value = 0;
return true;
}
return false;
}
bool Sub::verify_within_distance()
{
if (wp_nav.get_wp_distance_to_destination_cm() < (uint32_t)MAX(condition_value,0)) {
condition_value = 0;
return true;
}
return false;
}
bool Sub::verify_yaw()
{
if (auto_yaw_mode != AUTO_YAW_LOOK_AT_HEADING) {
sub.mode_auto.set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
}
return (abs(wrap_180_cd(ahrs.yaw_sensor-yaw_look_at_heading)) <= 200);
}
bool Sub::do_guided(const AP_Mission::Mission_Command& cmd)
{
if (control_mode != Mode::Number::GUIDED && !(control_mode == Mode::Number::AUTO && auto_mode == Auto_NavGuided)) {
return false;
}
switch (cmd.id) {
case MAV_CMD_NAV_WAYPOINT: {
return sub.mode_guided.guided_set_destination(cmd.content.location);
}
case MAV_CMD_CONDITION_YAW:
do_yaw(cmd);
return true;
default:
return false;
}
return true;
}
void Sub::do_change_speed(const AP_Mission::Mission_Command& cmd)
{
if (cmd.content.speed.target_ms > 0) {
wp_nav.set_speed_NE_cms(cmd.content.speed.target_ms * 100.0f);
}
}
void Sub::do_set_home(const AP_Mission::Mission_Command& cmd)
{
if (cmd.p1 == 1 || !cmd.content.location.initialised()) {
if (!set_home_to_current_location(false)) {
}
} else {
if (!set_home(cmd.content.location, false)) {
}
}
}
void Sub::do_roi(const AP_Mission::Mission_Command& cmd)
{
sub.mode_auto.set_auto_yaw_roi(cmd.content.location);
}
void Sub::do_mount_control(const AP_Mission::Mission_Command& cmd)
{
#if HAL_MOUNT_ENABLED
camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false);
#endif
}