2016-01-14 15:30:56 -04:00
|
|
|
#include "Sub.h"
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2018-03-09 12:15:08 -04:00
|
|
|
#include <AP_RTC/AP_RTC.h>
|
|
|
|
|
2017-03-08 22:59:39 -04:00
|
|
|
static enum AutoSurfaceState auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// start_command - this function will be called when the ap_mission lib wishes to start a new command
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::start_command(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2024-01-10 00:34:30 -04:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2015-12-30 18:57:56 -04:00
|
|
|
// To-Do: logging when new commands start/end
|
|
|
|
if (should_log(MASK_LOG_CMD)) {
|
2019-01-18 00:24:08 -04:00
|
|
|
logger.Write_Mission_Cmd(mission, cmd);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
2024-01-10 00:34:30 -04:00
|
|
|
#endif
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2019-01-02 00:40:53 -04:00
|
|
|
const Location &target_loc = cmd.content.location;
|
2024-03-07 13:38:03 -04:00
|
|
|
auto alt_frame = target_loc.get_alt_frame();
|
2017-04-17 12:25:41 -03:00
|
|
|
|
2024-03-07 13:38:03 -04:00
|
|
|
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");
|
2018-08-22 17:55:50 -03:00
|
|
|
return false;
|
2017-04-17 12:25:41 -03:00
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
switch (cmd.id) {
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
///
|
|
|
|
/// navigation commands
|
|
|
|
///
|
2015-12-30 18:57:56 -04:00
|
|
|
case MAV_CMD_NAV_WAYPOINT: // 16 Navigate to Waypoint
|
|
|
|
do_nav_wp(cmd);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint
|
2017-03-08 22:59:39 -04:00
|
|
|
do_surface(cmd);
|
2015-12-30 18:57:56 -04:00
|
|
|
break;
|
|
|
|
|
2017-03-11 12:06:03 -04:00
|
|
|
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
|
|
|
do_RTL();
|
|
|
|
break;
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
case MAV_CMD_NAV_LOITER_UNLIM: // 17 Loiter indefinitely
|
|
|
|
do_loiter_unlimited(cmd);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times
|
|
|
|
do_circle(cmd);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_NAV_LOITER_TIME: // 19
|
|
|
|
do_loiter_time(cmd);
|
|
|
|
break;
|
|
|
|
|
2024-08-13 08:42:38 -03:00
|
|
|
#if NAV_GUIDED
|
2015-12-30 18:57:56 -04:00
|
|
|
case MAV_CMD_NAV_GUIDED_ENABLE: // 92 accept navigation commands from external nav computer
|
|
|
|
do_nav_guided_enable(cmd);
|
|
|
|
break;
|
|
|
|
#endif
|
|
|
|
|
2018-02-23 17:41:32 -04:00
|
|
|
case MAV_CMD_NAV_DELAY: // 93 Delay the next navigation command
|
2016-05-22 21:50:44 -03:00
|
|
|
do_nav_delay(cmd);
|
|
|
|
break;
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
//
|
|
|
|
// conditional commands
|
|
|
|
//
|
2015-12-30 18:57:56 -04:00
|
|
|
case MAV_CMD_CONDITION_DELAY: // 112
|
|
|
|
do_wait_delay(cmd);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_CONDITION_DISTANCE: // 114
|
|
|
|
do_within_distance(cmd);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_CONDITION_YAW: // 115
|
|
|
|
do_yaw(cmd);
|
|
|
|
break;
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
///
|
|
|
|
/// do commands
|
|
|
|
///
|
2015-12-30 18:57:56 -04:00
|
|
|
case MAV_CMD_DO_CHANGE_SPEED: // 178
|
|
|
|
do_change_speed(cmd);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_DO_SET_HOME: // 179
|
|
|
|
do_set_home(cmd);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_DO_SET_ROI: // 201
|
2017-02-10 13:46:54 -04:00
|
|
|
// point the vehicle and camera at a region of interest (ROI)
|
2015-12-30 18:57:56 -04:00
|
|
|
do_roi(cmd);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_CMD_DO_MOUNT_CONTROL: // 205
|
|
|
|
// point the camera to a specified angle
|
|
|
|
do_mount_control(cmd);
|
|
|
|
break;
|
|
|
|
|
2024-08-13 08:42:38 -03:00
|
|
|
#if NAV_GUIDED
|
2018-02-23 17:41:32 -04:00
|
|
|
case MAV_CMD_DO_GUIDED_LIMITS: // 222 accept guided mode limits
|
2015-12-30 18:57:56 -04:00
|
|
|
do_guided_limits(cmd);
|
|
|
|
break;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
default:
|
2018-08-22 17:55:50 -03:00
|
|
|
// unable to use the command, allow the vehicle to try the next command
|
2024-03-07 13:38:03 -04:00
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Ignoring command %d", cmd.id);
|
2018-08-22 17:55:50 -03:00
|
|
|
return false;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// always return success
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
/********************************************************************************/
|
|
|
|
// Verify command Handlers
|
|
|
|
/********************************************************************************/
|
|
|
|
|
2017-10-18 21:36:37 -03:00
|
|
|
// check to see if current command goal has been achieved
|
2017-04-07 00:21:37 -03:00
|
|
|
// called by mission library in mission.update()
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_command_callback(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2023-04-03 09:11:21 -03:00
|
|
|
if (control_mode == Mode::Number::AUTO) {
|
2015-12-30 18:57:56 -04:00
|
|
|
bool cmd_complete = verify_command(cmd);
|
|
|
|
|
|
|
|
// send message to GCS
|
|
|
|
if (cmd_complete) {
|
2017-07-07 23:03:58 -03:00
|
|
|
gcs().send_mission_item_reached_message(cmd.index);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
return cmd_complete;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
2017-04-07 00:21:37 -03:00
|
|
|
// check if current mission command has completed
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_command(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-02-03 17:33:27 -04:00
|
|
|
switch (cmd.id) {
|
|
|
|
//
|
|
|
|
// navigation commands
|
|
|
|
//
|
2015-12-30 18:57:56 -04:00
|
|
|
case MAV_CMD_NAV_WAYPOINT:
|
|
|
|
return verify_nav_wp(cmd);
|
|
|
|
|
2017-03-08 22:59:39 -04:00
|
|
|
case MAV_CMD_NAV_LAND:
|
|
|
|
return verify_surface(cmd);
|
|
|
|
|
2017-03-11 12:06:03 -04:00
|
|
|
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
|
|
|
return verify_RTL();
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
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();
|
|
|
|
|
2024-08-13 08:42:38 -03:00
|
|
|
#if NAV_GUIDED
|
2015-12-30 18:57:56 -04:00
|
|
|
case MAV_CMD_NAV_GUIDED_ENABLE:
|
|
|
|
return verify_nav_guided_enable(cmd);
|
|
|
|
#endif
|
|
|
|
|
2016-05-22 21:50:44 -03:00
|
|
|
case MAV_CMD_NAV_DELAY:
|
|
|
|
return verify_nav_delay(cmd);
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
///
|
|
|
|
/// conditional commands
|
|
|
|
///
|
2015-12-30 18:57:56 -04:00
|
|
|
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();
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
// do commands (always return true)
|
2016-11-17 01:12:06 -04:00
|
|
|
case MAV_CMD_DO_CHANGE_SPEED:
|
|
|
|
case MAV_CMD_DO_SET_HOME:
|
|
|
|
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:
|
2015-12-30 18:57:56 -04:00
|
|
|
return true;
|
|
|
|
|
|
|
|
default:
|
2016-11-17 01:12:06 -04:00
|
|
|
// error message
|
2017-07-08 22:51:41 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING,"Skipping invalid cmd #%i",cmd.id);
|
2015-12-30 18:57:56 -04:00
|
|
|
// return true if we do not recognize the command so that we move on to the next command
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// exit_mission - function that is called once the mission completes
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::exit_mission()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// play a tone
|
|
|
|
AP_Notify::events.mission_complete = 1;
|
2016-08-25 00:08:30 -03:00
|
|
|
|
2017-02-07 20:42:28 -04:00
|
|
|
// Try to enter loiter, if that fails, go to depth hold
|
2023-04-03 09:11:21 -03:00
|
|
|
if (!mode_auto.auto_loiter_start()) {
|
|
|
|
set_mode(Mode::Number::ALT_HOLD, ModeReason::MISSION_END);
|
2017-02-07 20:42:28 -04:00
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/********************************************************************************/
|
2017-02-03 17:33:27 -04:00
|
|
|
// Nav (Must) commands
|
2015-12-30 18:57:56 -04:00
|
|
|
/********************************************************************************/
|
|
|
|
|
|
|
|
// do_nav_wp - initiate move to next waypoint
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_nav_wp(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2019-01-02 00:40:53 -04:00
|
|
|
Location target_loc(cmd.content.location);
|
2016-05-17 12:10:02 -03:00
|
|
|
// use current lat, lon if zero
|
|
|
|
if (target_loc.lat == 0 && target_loc.lng == 0) {
|
|
|
|
target_loc.lat = current_loc.lat;
|
|
|
|
target_loc.lng = current_loc.lng;
|
|
|
|
}
|
|
|
|
// use current altitude if not provided
|
|
|
|
if (target_loc.alt == 0) {
|
|
|
|
// set to current altitude but in command's alt frame
|
|
|
|
int32_t curr_alt;
|
|
|
|
if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
|
|
|
|
target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
|
|
|
|
} else {
|
|
|
|
// default to current altitude as alt-above-home
|
|
|
|
target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// this will be used to remember the time in millis after we reach or pass the WP.
|
|
|
|
loiter_time = 0;
|
|
|
|
// this is the delay, stored in seconds
|
2016-05-03 01:45:37 -03:00
|
|
|
loiter_time_max = cmd.p1;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// Set wp navigation target
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_auto.auto_wp_start(target_loc);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2017-03-08 22:59:39 -04:00
|
|
|
// do_surface - initiate surface procedure
|
|
|
|
void Sub::do_surface(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2019-01-02 00:40:53 -04:00
|
|
|
Location target_location;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// if location provided we fly to that location at current altitude
|
|
|
|
if (cmd.content.location.lat != 0 || cmd.content.location.lng != 0) {
|
2017-03-08 22:59:39 -04:00
|
|
|
// set state to go to location
|
|
|
|
auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCATION;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-03-08 22:59:39 -04:00
|
|
|
// calculate and set desired location below surface target
|
2016-05-03 01:45:37 -03:00
|
|
|
// convert to location class
|
2019-01-02 00:40:53 -04:00
|
|
|
target_location = Location(cmd.content.location);
|
2016-05-03 01:45:37 -03:00
|
|
|
|
|
|
|
// decide if we will use terrain following
|
|
|
|
int32_t curr_terr_alt_cm, target_terr_alt_cm;
|
2019-03-14 22:44:59 -03:00
|
|
|
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)) {
|
2016-05-03 01:45:37 -03:00
|
|
|
// if using terrain, set target altitude to current altitude above terrain
|
2019-03-14 22:44:59 -03:00
|
|
|
target_location.set_alt_cm(curr_terr_alt_cm, Location::AltFrame::ABOVE_TERRAIN);
|
2016-05-03 01:45:37 -03:00
|
|
|
} else {
|
|
|
|
// set target altitude to current altitude above home
|
2019-03-14 22:44:59 -03:00
|
|
|
target_location.set_alt_cm(current_loc.alt, Location::AltFrame::ABOVE_HOME);
|
2016-05-03 01:45:37 -03:00
|
|
|
}
|
2017-02-03 17:33:27 -04:00
|
|
|
} else {
|
2017-03-08 22:59:39 -04:00
|
|
|
// set surface state to ascend
|
|
|
|
auto_surface_state = AUTO_SURFACE_STATE_ASCEND;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-03-08 22:59:39 -04:00
|
|
|
// Set waypoint destination to current location at zero depth
|
2019-03-14 22:44:59 -03:00
|
|
|
target_location = Location(current_loc.lat, current_loc.lng, 0, Location::AltFrame::ABOVE_HOME);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
2017-03-08 22:59:39 -04:00
|
|
|
|
|
|
|
// Go to wp location
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_auto.auto_wp_start(target_location);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2017-03-11 12:06:03 -04:00
|
|
|
void Sub::do_RTL()
|
|
|
|
{
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_auto.auto_wp_start(ahrs.get_home());
|
2017-03-11 12:06:03 -04:00
|
|
|
}
|
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// do_loiter_unlimited - start loitering with no end conditions
|
|
|
|
// note: caller should set yaw_mode
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_loiter_unlimited(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-02-03 17:33:27 -04:00
|
|
|
// convert back to location
|
2019-01-02 00:40:53 -04:00
|
|
|
Location target_loc(cmd.content.location);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// use current location if not provided
|
2017-02-03 17:33:27 -04:00
|
|
|
if (target_loc.lat == 0 && target_loc.lng == 0) {
|
2016-05-03 01:45:37 -03:00
|
|
|
// To-Do: make this simpler
|
|
|
|
Vector3f temp_pos;
|
2021-06-21 04:23:03 -03:00
|
|
|
wp_nav.get_wp_stopping_point_xy(temp_pos.xy());
|
2021-03-17 18:17:48 -03:00
|
|
|
const Location temp_loc(temp_pos, Location::AltFrame::ABOVE_ORIGIN);
|
2016-05-17 12:10:02 -03:00
|
|
|
target_loc.lat = temp_loc.lat;
|
|
|
|
target_loc.lng = temp_loc.lng;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
// In mavproxy misseditor: Abs = 0 = ALT_FRAME_ABSOLUTE
|
|
|
|
// Rel = 1 = ALT_FRAME_ABOVE_HOME
|
|
|
|
// AGL = 3 = ALT_FRAME_ABOVE_TERRAIN
|
|
|
|
// 2 = ALT_FRAME_ABOVE_ORIGIN, not an option in mavproxy misseditor
|
2017-02-07 20:42:28 -04:00
|
|
|
|
2015-12-30 18:57:56 -04:00
|
|
|
// use current altitude if not provided
|
|
|
|
// To-Do: use z-axis stopping point instead of current alt
|
2017-02-03 17:33:27 -04:00
|
|
|
if (target_loc.alt == 0) {
|
2016-05-03 01:45:37 -03:00
|
|
|
// set to current altitude but in command's alt frame
|
|
|
|
int32_t curr_alt;
|
|
|
|
if (current_loc.get_alt_cm(target_loc.get_alt_frame(),curr_alt)) {
|
|
|
|
target_loc.set_alt_cm(curr_alt, target_loc.get_alt_frame());
|
|
|
|
} else {
|
|
|
|
// default to current altitude as alt-above-home
|
|
|
|
target_loc.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// start way point navigator and provide it the desired location
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_auto.auto_wp_start(target_loc);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// do_circle - initiate moving in a circle
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_circle(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2019-01-02 00:40:53 -04:00
|
|
|
Location circle_center(cmd.content.location);
|
2016-05-03 01:45:37 -03:00
|
|
|
|
|
|
|
// default lat/lon to current position if not provided
|
|
|
|
// To-Do: use stopping point or position_controller's target instead of current location to avoid jerk?
|
|
|
|
if (circle_center.lat == 0 && circle_center.lng == 0) {
|
|
|
|
circle_center.lat = current_loc.lat;
|
|
|
|
circle_center.lng = current_loc.lng;
|
|
|
|
}
|
|
|
|
|
|
|
|
// default target altitude to current altitude if not provided
|
|
|
|
if (circle_center.alt == 0) {
|
|
|
|
int32_t curr_alt;
|
|
|
|
if (current_loc.get_alt_cm(circle_center.get_alt_frame(),curr_alt)) {
|
|
|
|
// circle altitude uses frame from command
|
|
|
|
circle_center.set_alt_cm(curr_alt,circle_center.get_alt_frame());
|
|
|
|
} else {
|
|
|
|
// default to current altitude above origin
|
|
|
|
circle_center.set_alt_cm(current_loc.alt, current_loc.get_alt_frame());
|
2024-01-10 00:34:30 -04:00
|
|
|
LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA);
|
2016-05-03 01:45:37 -03:00
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2016-05-03 01:45:37 -03:00
|
|
|
// calculate radius
|
2022-05-11 00:56:07 -03:00
|
|
|
uint16_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1
|
|
|
|
if (cmd.type_specific_bits & (1U << 0)) {
|
|
|
|
circle_radius_m *= 10;
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2023-02-14 18:17:46 -04:00
|
|
|
|
|
|
|
// true if circle should be ccw
|
|
|
|
const bool circle_direction_ccw = cmd.content.location.loiter_ccw;
|
|
|
|
|
2016-05-03 01:45:37 -03:00
|
|
|
// move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_auto.auto_circle_movetoedge_start(circle_center, circle_radius_m, circle_direction_ccw);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// do_loiter_time - initiate loitering at a point for a given time period
|
|
|
|
// note: caller should set yaw_mode
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_loiter_time(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-02-03 17:33:27 -04:00
|
|
|
// re-use loiter unlimited
|
|
|
|
do_loiter_unlimited(cmd);
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// setup loiter timer
|
|
|
|
loiter_time = 0;
|
|
|
|
loiter_time_max = cmd.p1; // units are (seconds)
|
|
|
|
}
|
|
|
|
|
2024-08-13 08:42:38 -03:00
|
|
|
#if NAV_GUIDED
|
2015-12-30 18:57:56 -04:00
|
|
|
// do_nav_guided_enable - initiate accepting commands from external nav computer
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
if (cmd.p1 > 0) {
|
|
|
|
// initialise guided limits
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_auto.guided_limit_init_time_and_pos();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2020-06-09 21:15:51 -03:00
|
|
|
// set navigation target
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_auto.auto_nav_guided_start();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif // NAV_GUIDED
|
|
|
|
|
2016-05-22 21:50:44 -03:00
|
|
|
// do_nav_delay - Delay the next navigation command
|
|
|
|
void Sub::do_nav_delay(const AP_Mission::Mission_Command& cmd)
|
|
|
|
{
|
2019-08-09 15:42:00 -03:00
|
|
|
nav_delay_time_start_ms = AP_HAL::millis();
|
2016-05-22 21:50:44 -03:00
|
|
|
|
|
|
|
if (cmd.content.nav_delay.seconds > 0) {
|
|
|
|
// relative delay
|
2019-08-09 15:42:00 -03:00
|
|
|
nav_delay_time_max_ms = cmd.content.nav_delay.seconds * 1000; // convert seconds to milliseconds
|
2016-05-22 21:50:44 -03:00
|
|
|
} else {
|
|
|
|
// absolute delay to utc time
|
2023-10-05 04:40:35 -03:00
|
|
|
#if AP_RTC_ENABLED
|
2019-08-09 15:42:00 -03:00
|
|
|
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);
|
2023-10-05 04:40:35 -03:00
|
|
|
#else
|
|
|
|
nav_delay_time_max_ms = 0;
|
|
|
|
#endif
|
2016-05-22 21:50:44 -03:00
|
|
|
}
|
2019-08-21 06:46:44 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Delaying %u sec", (unsigned)(nav_delay_time_max_ms/1000));
|
2016-05-22 21:50:44 -03:00
|
|
|
}
|
|
|
|
|
2024-08-13 08:42:38 -03:00
|
|
|
#if NAV_GUIDED
|
2015-12-30 18:57:56 -04:00
|
|
|
// do_guided_limits - pass guided limits to guided controller
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_guided_limits(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_guided.guided_limit_set(cmd.p1 * 1000, // convert seconds to ms
|
2015-12-30 18:57:56 -04:00
|
|
|
cmd.content.guided_limits.alt_min * 100.0f, // convert meters to cm
|
|
|
|
cmd.content.guided_limits.alt_max * 100.0f, // convert meters to cm
|
|
|
|
cmd.content.guided_limits.horiz_max * 100.0f); // convert meters to cm
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
/********************************************************************************/
|
2017-02-03 17:33:27 -04:00
|
|
|
// Verify Nav (Must) commands
|
2015-12-30 18:57:56 -04:00
|
|
|
/********************************************************************************/
|
|
|
|
|
|
|
|
// verify_nav_wp - check if we have reached the next way point
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// check if we have reached the waypoint
|
2017-02-03 17:33:27 -04:00
|
|
|
if (!wp_nav.reached_wp_destination()) {
|
2015-12-30 18:57:56 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// play a tone
|
|
|
|
AP_Notify::events.waypoint_complete = 1;
|
|
|
|
|
|
|
|
// start timer if necessary
|
2017-02-03 17:33:27 -04:00
|
|
|
if (loiter_time == 0) {
|
2018-04-13 20:05:16 -03:00
|
|
|
loiter_time = AP_HAL::millis();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// check if timer has run out
|
2018-04-13 20:05:16 -03:00
|
|
|
if (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max) {
|
2017-07-08 22:51:41 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Reached command #%i",cmd.index);
|
2015-12-30 18:57:56 -04:00
|
|
|
return true;
|
|
|
|
}
|
2018-05-15 10:19:45 -03:00
|
|
|
|
|
|
|
return false;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2017-03-09 13:25:54 -04:00
|
|
|
// verify_surface - returns true if surface procedure has been completed
|
2017-03-08 22:59:39 -04:00
|
|
|
bool Sub::verify_surface(const AP_Mission::Mission_Command& cmd)
|
|
|
|
{
|
|
|
|
bool retval = false;
|
|
|
|
|
|
|
|
switch (auto_surface_state) {
|
|
|
|
case AUTO_SURFACE_STATE_GO_TO_LOCATION:
|
|
|
|
// check if we've reached the location
|
|
|
|
if (wp_nav.reached_wp_destination()) {
|
|
|
|
// Set target to current xy and zero depth
|
|
|
|
// TODO get xy target from current wp destination, because current location may be acceptance-radius away from original destination
|
2019-03-14 22:44:59 -03:00
|
|
|
Location target_location(cmd.content.location.lat, cmd.content.location.lng, 0, Location::AltFrame::ABOVE_HOME);
|
2017-03-08 22:59:39 -04:00
|
|
|
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_auto.auto_wp_start(target_location);
|
2017-03-08 22:59:39 -04:00
|
|
|
|
|
|
|
// advance to next state
|
|
|
|
auto_surface_state = AUTO_SURFACE_STATE_ASCEND;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case AUTO_SURFACE_STATE_ASCEND:
|
|
|
|
if (wp_nav.reached_wp_destination()) {
|
|
|
|
retval = true;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
default:
|
|
|
|
// this should never happen
|
|
|
|
// TO-DO: log an error
|
|
|
|
retval = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// true is returned if we've successfully surfaced
|
|
|
|
return retval;
|
|
|
|
}
|
|
|
|
|
2017-03-11 12:06:03 -04:00
|
|
|
bool Sub::verify_RTL() {
|
|
|
|
return wp_nav.reached_wp_destination();
|
|
|
|
}
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_loiter_unlimited()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// verify_loiter_time - check if we have loitered long enough
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_loiter_time()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// return immediately if we haven't reached our destination
|
|
|
|
if (!wp_nav.reached_wp_destination()) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// start our loiter timer
|
2017-02-03 17:33:27 -04:00
|
|
|
if (loiter_time == 0) {
|
2018-04-13 20:05:16 -03:00
|
|
|
loiter_time = AP_HAL::millis();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// check if loiter timer has run out
|
2018-04-13 20:05:16 -03:00
|
|
|
return (((AP_HAL::millis() - loiter_time) / 1000) >= loiter_time_max);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// verify_circle - check if we have circled the point enough
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_circle(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// check if we've reached the edge
|
|
|
|
if (auto_mode == Auto_CircleMoveToEdge) {
|
|
|
|
if (wp_nav.reached_wp_destination()) {
|
2022-02-05 01:35:32 -04:00
|
|
|
Vector3f circle_center;
|
|
|
|
UNUSED_RESULT(cmd.content.location.get_vector_from_origin_NEU(circle_center));
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// set target altitude if not provided
|
|
|
|
if (is_zero(circle_center.z)) {
|
2021-10-20 05:30:56 -03:00
|
|
|
circle_center.z = inertial_nav.get_position_z_up_cm();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// set lat/lon position if not provided
|
|
|
|
if (cmd.content.location.lat == 0 && cmd.content.location.lng == 0) {
|
2021-10-20 05:30:56 -03:00
|
|
|
circle_center.xy() = inertial_nav.get_position_xy_cm();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// start circling
|
2023-04-03 09:11:21 -03:00
|
|
|
mode_auto.auto_circle_start();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2024-01-12 00:14:20 -04:00
|
|
|
const float turns = cmd.get_loiter_turns();
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
// check if we have completed circling
|
2024-01-12 00:14:20 -04:00
|
|
|
return fabsf(sub.circle_nav.get_angle_total()/M_2PI) >= turns;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
2024-08-13 08:42:38 -03:00
|
|
|
#if NAV_GUIDED
|
2015-12-30 18:57:56 -04:00
|
|
|
// verify_nav_guided - check if we have breached any limits
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_nav_guided_enable(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// if disabling guided mode then immediately return true so we move to next command
|
|
|
|
if (cmd.p1 == 0) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check time and position limits
|
2023-04-03 09:11:21 -03:00
|
|
|
return mode_auto.guided_limit_check();
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
#endif // NAV_GUIDED
|
|
|
|
|
2016-05-22 21:50:44 -03:00
|
|
|
// verify_nav_delay - check if we have waited long enough
|
|
|
|
bool Sub::verify_nav_delay(const AP_Mission::Mission_Command& cmd)
|
|
|
|
{
|
2019-08-09 15:42:00 -03:00
|
|
|
if (AP_HAL::millis() - nav_delay_time_start_ms > nav_delay_time_max_ms) {
|
|
|
|
nav_delay_time_max_ms = 0;
|
2017-02-03 17:33:27 -04:00
|
|
|
return true;
|
2016-05-22 21:50:44 -03:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
|
|
|
|
/********************************************************************************/
|
2017-02-03 17:33:27 -04:00
|
|
|
// Condition (May) commands
|
2015-12-30 18:57:56 -04:00
|
|
|
/********************************************************************************/
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_wait_delay(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2018-04-13 20:05:16 -03:00
|
|
|
condition_start = AP_HAL::millis();
|
2015-12-30 18:57:56 -04:00
|
|
|
condition_value = cmd.content.delay.seconds * 1000; // convert seconds to milliseconds
|
|
|
|
}
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_within_distance(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
condition_value = cmd.content.distance.meters * 100;
|
|
|
|
}
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_yaw(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2023-04-03 09:11:21 -03:00
|
|
|
sub.mode_auto.set_auto_yaw_look_at_heading(
|
2017-02-03 17:33:27 -04:00
|
|
|
cmd.content.yaw.angle_deg,
|
|
|
|
cmd.content.yaw.turn_rate_dps,
|
|
|
|
cmd.content.yaw.direction,
|
|
|
|
cmd.content.yaw.relative_angle);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/********************************************************************************/
|
|
|
|
// Verify Condition (May) commands
|
|
|
|
/********************************************************************************/
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_wait_delay()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2018-04-13 20:05:16 -03:00
|
|
|
if (AP_HAL::millis() - condition_start > (uint32_t)MAX(condition_value, 0)) {
|
2015-12-30 18:57:56 -04:00
|
|
|
condition_value = 0;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_within_distance()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-04-07 00:21:37 -03:00
|
|
|
if (wp_nav.get_wp_distance_to_destination() < (uint32_t)MAX(condition_value,0)) {
|
2015-12-30 18:57:56 -04:00
|
|
|
condition_value = 0;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// verify_yaw - return true if we have reached the desired heading
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::verify_yaw()
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// set yaw mode if it has been changed (the waypoint controller often retakes control of yaw as it executes a new waypoint command)
|
|
|
|
if (auto_yaw_mode != AUTO_YAW_LOOK_AT_HEADING) {
|
2023-04-03 09:11:21 -03:00
|
|
|
sub.mode_auto.set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// check if we are within 2 degrees of the target heading
|
2019-09-09 20:47:55 -03:00
|
|
|
return (abs(wrap_180_cd(ahrs.yaw_sensor-yaw_look_at_heading)) <= 200);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/********************************************************************************/
|
2017-02-03 17:33:27 -04:00
|
|
|
// Do (Now) commands
|
2015-12-30 18:57:56 -04:00
|
|
|
/********************************************************************************/
|
|
|
|
|
|
|
|
// do_guided - start guided mode
|
2016-01-14 15:30:56 -04:00
|
|
|
bool Sub::do_guided(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
// only process guided waypoint if we are in guided mode
|
2023-04-03 09:11:21 -03:00
|
|
|
if (control_mode != Mode::Number::GUIDED && !(control_mode == Mode::Number::AUTO && auto_mode == Auto_NavGuided)) {
|
2015-12-30 18:57:56 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// switch to handle different commands
|
|
|
|
switch (cmd.id) {
|
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAV_CMD_NAV_WAYPOINT: {
|
|
|
|
// set wp_nav's destination
|
2023-04-03 09:11:21 -03:00
|
|
|
return sub.mode_guided.guided_set_destination(cmd.content.location);
|
2017-02-03 17:33:27 -04:00
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
case MAV_CMD_CONDITION_YAW:
|
|
|
|
do_yaw(cmd);
|
|
|
|
return true;
|
2015-12-30 18:57:56 -04:00
|
|
|
|
2017-02-03 17:33:27 -04:00
|
|
|
default:
|
|
|
|
// reject unrecognised command
|
|
|
|
return false;
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_change_speed(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
|
|
|
if (cmd.content.speed.target_ms > 0) {
|
|
|
|
wp_nav.set_speed_xy(cmd.content.speed.target_ms * 100.0f);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_set_home(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2017-02-03 17:33:27 -04:00
|
|
|
if (cmd.p1 == 1 || (cmd.content.location.lat == 0 && cmd.content.location.lng == 0 && cmd.content.location.alt == 0)) {
|
2018-05-29 21:47:13 -03:00
|
|
|
if (!set_home_to_current_location(false)) {
|
|
|
|
// silently ignore this failure
|
|
|
|
}
|
2015-12-30 18:57:56 -04:00
|
|
|
} else {
|
2024-04-09 04:41:12 -03:00
|
|
|
if (!set_home(cmd.content.location, false)) {
|
|
|
|
// silently ignore this failure
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// do_roi - starts actions required by MAV_CMD_NAV_ROI
|
|
|
|
// this involves either moving the camera to point at the ROI (region of interest)
|
2017-02-10 13:46:54 -04:00
|
|
|
// and possibly rotating the vehicle to point at the ROI if our mount type does not support a yaw feature
|
2017-02-03 17:33:27 -04:00
|
|
|
// TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_roi(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2023-04-03 09:11:21 -03:00
|
|
|
sub.mode_auto.set_auto_yaw_roi(cmd.content.location);
|
2015-12-30 18:57:56 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// point the camera to a specified angle
|
2016-01-14 15:30:56 -04:00
|
|
|
void Sub::do_mount_control(const AP_Mission::Mission_Command& cmd)
|
2015-12-30 18:57:56 -04:00
|
|
|
{
|
2020-07-24 14:30:21 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
2022-06-21 03:00:37 -03:00
|
|
|
camera_mount.set_angle_target(cmd.content.mount_control.roll, cmd.content.mount_control.pitch, cmd.content.mount_control.yaw, false);
|
2015-12-30 18:57:56 -04:00
|
|
|
#endif
|
|
|
|
}
|