Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/ArduSub/commands_logic.cpp
Views: 1798
#include "Sub.h"12#include <AP_RTC/AP_RTC.h>34static enum AutoSurfaceState auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;56// start_command - this function will be called when the ap_mission lib wishes to start a new command7bool Sub::start_command(const AP_Mission::Mission_Command& cmd)8{9const Location &target_loc = cmd.content.location;10auto alt_frame = target_loc.get_alt_frame();1112if (alt_frame == Location::AltFrame::ABOVE_HOME) {13if (target_loc.alt > 0) {14gcs().send_text(MAV_SEVERITY_WARNING, "Alt above home must be negative");15return false;16}17} else if (alt_frame == Location::AltFrame::ABOVE_TERRAIN) {18if (target_loc.alt < 0) {19gcs().send_text(MAV_SEVERITY_WARNING, "Alt above terrain must be positive");20return false;21}22} else {23gcs().send_text(MAV_SEVERITY_WARNING, "Bad alt frame");24return false;25}2627switch (cmd.id) {2829///30/// navigation commands31///32case MAV_CMD_NAV_WAYPOINT: // 16 Navigate to Waypoint33do_nav_wp(cmd);34break;3536case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint37do_surface(cmd);38break;3940case MAV_CMD_NAV_RETURN_TO_LAUNCH:41do_RTL();42break;4344case MAV_CMD_NAV_LOITER_UNLIM: // 17 Loiter indefinitely45do_loiter_unlimited(cmd);46break;4748case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times49do_circle(cmd);50break;5152case MAV_CMD_NAV_LOITER_TIME: // 1953do_loiter_time(cmd);54break;5556#if NAV_GUIDED57case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer58do_nav_guided_enable(cmd);59break;60#endif6162case MAV_CMD_NAV_DELAY: // 93 Delay the next navigation command63do_nav_delay(cmd);64break;6566//67// conditional commands68//69case MAV_CMD_CONDITION_DELAY: // 11270do_wait_delay(cmd);71break;7273case MAV_CMD_CONDITION_DISTANCE: // 11474do_within_distance(cmd);75break;7677case MAV_CMD_CONDITION_YAW: // 11578do_yaw(cmd);79break;8081///82/// do commands83///84case MAV_CMD_DO_CHANGE_SPEED: // 17885do_change_speed(cmd);86break;8788case MAV_CMD_DO_SET_HOME: // 17989do_set_home(cmd);90break;9192case MAV_CMD_DO_SET_ROI: // 20193// point the vehicle and camera at a region of interest (ROI)94do_roi(cmd);95break;9697case MAV_CMD_DO_MOUNT_CONTROL: // 20598// point the camera to a specified angle99do_mount_control(cmd);100break;101102#if NAV_GUIDED103case MAV_CMD_DO_GUIDED_LIMITS: // 222 accept guided mode limits104do_guided_limits(cmd);105break;106#endif107108default:109// unable to use the command, allow the vehicle to try the next command110gcs().send_text(MAV_SEVERITY_WARNING, "Ignoring command %d", cmd.id);111return false;112}113114// always return success115return true;116}117118/********************************************************************************/119// Verify command Handlers120/********************************************************************************/121122// check to see if current command goal has been achieved123// called by mission library in mission.update()124bool Sub::verify_command_callback(const AP_Mission::Mission_Command& cmd)125{126if (control_mode == Mode::Number::AUTO) {127bool cmd_complete = verify_command(cmd);128129// send message to GCS130if (cmd_complete) {131gcs().send_mission_item_reached_message(cmd.index);132}133134return cmd_complete;135}136return false;137}138139140// check if current mission command has completed141bool Sub::verify_command(const AP_Mission::Mission_Command& cmd)142{143switch (cmd.id) {144//145// navigation commands146//147case MAV_CMD_NAV_WAYPOINT:148return verify_nav_wp(cmd);149150case MAV_CMD_NAV_LAND:151return verify_surface(cmd);152153case MAV_CMD_NAV_RETURN_TO_LAUNCH:154return verify_RTL();155156case MAV_CMD_NAV_LOITER_UNLIM:157return verify_loiter_unlimited();158159case MAV_CMD_NAV_LOITER_TURNS:160return verify_circle(cmd);161162case MAV_CMD_NAV_LOITER_TIME:163return verify_loiter_time();164165#if NAV_GUIDED166case MAV_CMD_NAV_GUIDED_ENABLE:167return verify_nav_guided_enable(cmd);168#endif169170case MAV_CMD_NAV_DELAY:171return verify_nav_delay(cmd);172173///174/// conditional commands175///176case MAV_CMD_CONDITION_DELAY:177return verify_wait_delay();178179case MAV_CMD_CONDITION_DISTANCE:180return verify_within_distance();181182case MAV_CMD_CONDITION_YAW:183return verify_yaw();184185// do commands (always return true)186case MAV_CMD_DO_CHANGE_SPEED:187case MAV_CMD_DO_SET_HOME:188case MAV_CMD_DO_SET_ROI:189case MAV_CMD_DO_MOUNT_CONTROL:190case MAV_CMD_DO_SET_CAM_TRIGG_DIST:191case MAV_CMD_DO_GUIDED_LIMITS:192return true;193194default:195// error message196gcs().send_text(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);197// return true if we do not recognize the command so that we move on to the next command198return true;199}200}201202// exit_mission - function that is called once the mission completes203void Sub::exit_mission()204{205// play a tone206AP_Notify::events.mission_complete = 1;207208// Try to enter loiter, if that fails, go to depth hold209if (!mode_auto.auto_loiter_start()) {210set_mode(Mode::Number::ALT_HOLD, ModeReason::MISSION_END);211}212}213214/********************************************************************************/215// Nav (Must) commands216/********************************************************************************/217218// do_nav_wp - initiate move to next waypoint219void Sub::do_nav_wp(const AP_Mission::Mission_Command& cmd)220{221Location target_loc(cmd.content.location);222// use current lat, lon if zero223if (target_loc.lat == 0 && target_loc.lng == 0) {224target_loc.lat = current_loc.lat;225target_loc.lng = current_loc.lng;226}227// use current altitude if not provided228if (target_loc.alt == 0) {229// set to current altitude but in command's alt frame230int32_t curr_alt;231if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {232target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());233} else {234// default to current altitude as alt-above-home235target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());236}237}238239// this will be used to remember the time in millis after we reach or pass the WP.240loiter_time = 0;241// this is the delay, stored in seconds242loiter_time_max = cmd.p1;243244// Set wp navigation target245mode_auto.auto_wp_start(target_loc);246}247248// do_surface - initiate surface procedure249void Sub::do_surface(const AP_Mission::Mission_Command& cmd)250{251Location target_location;252253// if location provided we fly to that location at current altitude254if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) {255// set state to go to location256auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;257258// calculate and set desired location below surface target259// convert to location class260target_location = Location(cmd.content.location);261262// decide if we will use terrain following263int32_t curr_terr_alt_cm, target_terr_alt_cm;264if (current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, curr_terr_alt_cm) &&265target_location.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, target_terr_alt_cm)) {266// if using terrain, set target altitude to current altitude above terrain267target_location.set_alt_cm(curr_terr_alt_cm, Location::AltFrame::ABOVE_TERRAIN);268} else {269// set target altitude to current altitude above home270target_location.set_alt_cm(current_loc.alt, Location::AltFrame::ABOVE_HOME);271}272} else {273// set surface state to ascend274auto_surface_state = AUTO_SURFACE_STATE_ASCEND;275276// Set waypoint destination to current location at zero depth277target_location = Location(current_loc.lat, current_loc.lng, 0, Location::AltFrame::ABOVE_HOME);278}279280// Go to wp location281mode_auto.auto_wp_start(target_location);282}283284void Sub::do_RTL()285{286mode_auto.auto_wp_start(ahrs.get_home());287}288289// do_loiter_unlimited - start loitering with no end conditions290// note: caller should set yaw_mode291void Sub::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)292{293// convert back to location294Location target_loc(cmd.content.location);295296// use current location if not provided297if (target_loc.lat == 0 && target_loc.lng == 0) {298// To-Do: make this simpler299Vector3f temp_pos;300wp_nav.get_wp_stopping_point_xy(temp_pos.xy());301const Location temp_loc(temp_pos, Location::AltFrame::ABOVE_ORIGIN);302target_loc.lat = temp_loc.lat;303target_loc.lng = temp_loc.lng;304}305306// In mavproxy misseditor: Abs = 0 = ALT_FRAME_ABSOLUTE307// Rel = 1 = ALT_FRAME_ABOVE_HOME308// AGL = 3 = ALT_FRAME_ABOVE_TERRAIN309// 2 = ALT_FRAME_ABOVE_ORIGIN, not an option in mavproxy misseditor310311// use current altitude if not provided312// To-Do: use z-axis stopping point instead of current alt313if (target_loc.alt == 0) {314// set to current altitude but in command's alt frame315int32_t curr_alt;316if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {317target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());318} else {319// default to current altitude as alt-above-home320target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());321}322}323324// start way point navigator and provide it the desired location325mode_auto.auto_wp_start(target_loc);326}327328// do_circle - initiate moving in a circle329void Sub::do_circle(const AP_Mission::Mission_Command& cmd)330{331Location circle_center(cmd.content.location);332333// default lat/lon to current position if not provided334// To-Do: use stopping point or position_controller's target instead of current location to avoid jerk?335if (circle_center.lat == 0 && circle_center.lng == 0) {336circle_center.lat = current_loc.lat;337circle_center.lng = current_loc.lng;338}339340// default target altitude to current altitude if not provided341if (circle_center.alt == 0) {342int32_t curr_alt;343if (current_loc.get_alt_cm(circle_center.get_alt_frame(),curr_alt)) {344// circle altitude uses frame from command345circle_center.set_alt_cm(curr_alt,circle_center.get_alt_frame());346} else {347// default to current altitude above origin348circle_center.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());349LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA);350}351}352353// calculate radius354uint16_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1355if (cmd.type_specific_bits & (1U << 0)) {356circle_radius_m *= 10;357}358359360// true if circle should be ccw361const bool circle_direction_ccw = cmd.content.location.loiter_ccw;362363// move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge364mode_auto.auto_circle_movetoedge_start(circle_center, circle_radius_m, circle_direction_ccw);365}366367// do_loiter_time - initiate loitering at a point for a given time period368// note: caller should set yaw_mode369void Sub::do_loiter_time(const AP_Mission::Mission_Command& cmd)370{371// re-use loiter unlimited372do_loiter_unlimited(cmd);373374// setup loiter timer375loiter_time = 0;376loiter_time_max = cmd.p1; // units are (seconds)377}378379#if NAV_GUIDED380// do_nav_guided_enable - initiate accepting commands from external nav computer381void Sub::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)382{383if (cmd.p1 > 0) {384// initialise guided limits385mode_auto.guided_limit_init_time_and_pos();386387// set navigation target388mode_auto.auto_nav_guided_start();389}390}391#endif // NAV_GUIDED392393// do_nav_delay - Delay the next navigation command394void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd)395{396nav_delay_time_start_ms = AP_HAL::millis();397398if (cmd.content.nav_delay.seconds > 0) {399// relative delay400nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds401} else {402// absolute delay to utc time403#if AP_RTC_ENABLED404nav_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);405#else406nav_delay_time_max_ms = 0;407#endif408}409gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000));410}411412#if NAV_GUIDED413// do_guided_limits - pass guided limits to guided controller414void Sub::do_guided_limits(const AP_Mission::Mission_Command& cmd)415{416mode_guided.guided_limit_set(cmd.p1 * 1000, // convert seconds to ms417cmd.content.guided_limits.alt_min * 100.0f, // convert meters to cm418cmd.content.guided_limits.alt_max * 100.0f, // convert meters to cm419cmd.content.guided_limits.horiz_max * 100.0f); // convert meters to cm420}421#endif422423/********************************************************************************/424// Verify Nav (Must) commands425/********************************************************************************/426427// verify_nav_wp - check if we have reached the next way point428bool Sub::verify_nav_wp(const AP_Mission::Mission_Command& cmd)429{430// check if we have reached the waypoint431if (!wp_nav.reached_wp_destination()) {432return false;433}434435// play a tone436AP_Notify::events.waypoint_complete = 1;437438// start timer if necessary439if (loiter_time == 0) {440loiter_time = AP_HAL::millis();441}442443// check if timer has run out444if (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max) {445gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);446return true;447}448449return false;450}451452// verify_surface - returns true if surface procedure has been completed453bool Sub::verify_surface(const AP_Mission::Mission_Command& cmd)454{455bool retval = false;456457switch (auto_surface_state) {458case AUTO_SURFACE_STATE_GO_TO_LOCATION:459// check if we've reached the location460if (wp_nav.reached_wp_destination()) {461// Set target to current xy and zero depth462// TODO get xy target from current wp destination, because current location may be acceptance-radius away from original destination463Location target_location(cmd.content.location.lat, cmd.content.location.lng, 0, Location::AltFrame::ABOVE_HOME);464465mode_auto.auto_wp_start(target_location);466467// advance to next state468auto_surface_state = AUTO_SURFACE_STATE_ASCEND;469}470break;471472case AUTO_SURFACE_STATE_ASCEND:473if (wp_nav.reached_wp_destination()) {474retval = true;475}476break;477478default:479// this should never happen480// TO-DO: log an error481retval = true;482break;483}484485// true is returned if we've successfully surfaced486return retval;487}488489bool Sub::verify_RTL() {490return wp_nav.reached_wp_destination();491}492493bool Sub::verify_loiter_unlimited()494{495return false;496}497498// verify_loiter_time - check if we have loitered long enough499bool Sub::verify_loiter_time()500{501// return immediately if we haven't reached our destination502if (!wp_nav.reached_wp_destination()) {503return false;504}505506// start our loiter timer507if (loiter_time == 0) {508loiter_time = AP_HAL::millis();509}510511// check if loiter timer has run out512return (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max);513}514515// verify_circle - check if we have circled the point enough516bool Sub::verify_circle(const AP_Mission::Mission_Command& cmd)517{518// check if we've reached the edge519if (auto_mode == Auto_CircleMoveToEdge) {520if (wp_nav.reached_wp_destination()) {521Vector3f circle_center;522UNUSED_RESULT(cmd.content.location.get_vector_from_origin_NEU(circle_center));523524// set target altitude if not provided525if (is_zero(circle_center.z)) {526circle_center.z = inertial_nav.get_position_z_up_cm();527}528529// set lat/lon position if not provided530if (cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {531circle_center.xy() = inertial_nav.get_position_xy_cm();532}533534// start circling535mode_auto.auto_circle_start();536}537return false;538}539const float turns = cmd.get_loiter_turns();540541// check if we have completed circling542return fabsf(sub.circle_nav.get_angle_total()/M_2PI) >= turns;543}544545#if NAV_GUIDED546// verify_nav_guided - check if we have breached any limits547bool Sub::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)548{549// if disabling guided mode then immediately return true so we move to next command550if (cmd.p1 == 0) {551return true;552}553554// check time and position limits555return mode_auto.guided_limit_check();556}557#endif // NAV_GUIDED558559// verify_nav_delay - check if we have waited long enough560bool Sub::verify_nav_delay(const AP_Mission::Mission_Command& cmd)561{562if (AP_HAL::millis() - nav_delay_time_start_ms > nav_delay_time_max_ms) {563nav_delay_time_max_ms = 0;564return true;565}566return false;567}568569/********************************************************************************/570// Condition (May) commands571/********************************************************************************/572573void Sub::do_wait_delay(const AP_Mission::Mission_Command& cmd)574{575condition_start = AP_HAL::millis();576condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds577}578579void Sub::do_within_distance(const AP_Mission::Mission_Command& cmd)580{581condition_value = cmd.content.distance.meters * 100;582}583584void Sub::do_yaw(const AP_Mission::Mission_Command& cmd)585{586sub.mode_auto.set_auto_yaw_look_at_heading(587cmd.content.yaw.angle_deg,588cmd.content.yaw.turn_rate_dps,589cmd.content.yaw.direction,590cmd.content.yaw.relative_angle);591}592593594/********************************************************************************/595// Verify Condition (May) commands596/********************************************************************************/597598bool Sub::verify_wait_delay()599{600if (AP_HAL::millis() - condition_start > (uint32_t)MAX(condition_value, 0)) {601condition_value = 0;602return true;603}604return false;605}606607bool Sub::verify_within_distance()608{609if (wp_nav.get_wp_distance_to_destination() < (uint32_t)MAX(condition_value,0)) {610condition_value = 0;611return true;612}613return false;614}615616// verify_yaw - return true if we have reached the desired heading617bool Sub::verify_yaw()618{619// set yaw mode if it has been changed (the waypoint controller often retakes control of yaw as it executes a new waypoint command)620if (auto_yaw_mode != AUTO_YAW_LOOK_AT_HEADING) {621sub.mode_auto.set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);622}623624// check if we are within 2 degrees of the target heading625return (abs(wrap_180_cd(ahrs.yaw_sensor-yaw_look_at_heading)) <= 200);626}627628/********************************************************************************/629// Do (Now) commands630/********************************************************************************/631632// do_guided - start guided mode633bool Sub::do_guided(const AP_Mission::Mission_Command& cmd)634{635// only process guided waypoint if we are in guided mode636if (control_mode != Mode::Number::GUIDED && !(control_mode == Mode::Number::AUTO && auto_mode == Auto_NavGuided)) {637return false;638}639640// switch to handle different commands641switch (cmd.id) {642643case MAV_CMD_NAV_WAYPOINT: {644// set wp_nav's destination645return sub.mode_guided.guided_set_destination(cmd.content.location);646}647648case MAV_CMD_CONDITION_YAW:649do_yaw(cmd);650return true;651652default:653// reject unrecognised command654return false;655}656657return true;658}659660void Sub::do_change_speed(const AP_Mission::Mission_Command& cmd)661{662if (cmd.content.speed.target_ms > 0) {663wp_nav.set_speed_xy(cmd.content.speed.target_ms * 100.0f);664}665}666667void Sub::do_set_home(const AP_Mission::Mission_Command& cmd)668{669if (cmd.p1 == 1 || (cmd.content.location.lat == 0 && cmd.content.location.lng == 0 && cmd.content.location.alt == 0)) {670if (!set_home_to_current_location(false)) {671// silently ignore this failure672}673} else {674if (!set_home(cmd.content.location, false)) {675// silently ignore this failure676}677}678}679680// do_roi - starts actions required by MAV_CMD_NAV_ROI681// this involves either moving the camera to point at the ROI (region of interest)682// and possibly rotating the vehicle to point at the ROI if our mount type does not support a yaw feature683// TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint684void Sub::do_roi(const AP_Mission::Mission_Command& cmd)685{686sub.mode_auto.set_auto_yaw_roi(cmd.content.location);687}688689// point the camera to a specified angle690void Sub::do_mount_control(const AP_Mission::Mission_Command& cmd)691{692#if HAL_MOUNT_ENABLED693camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false);694#endif695}696697698