ardupilot/ArduCopter/commands_logic.pde

696 lines
22 KiB
Plaintext

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/********************************************************************************/
// Command Event Handlers
/********************************************************************************/
// process_nav_command - main switch statement to initiate the next nav command in the command_nav_queue
static void process_nav_command()
{
switch(command_nav_queue.id) {
case MAV_CMD_NAV_TAKEOFF: // 22
do_takeoff();
break;
case MAV_CMD_NAV_WAYPOINT: // 16 Navigate to Waypoint
do_nav_wp();
break;
case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint
do_land(&command_nav_queue);
break;
case MAV_CMD_NAV_LOITER_UNLIM: // 17 Loiter indefinitely
do_loiter_unlimited();
break;
case MAV_CMD_NAV_LOITER_TURNS: //18 Loiter N Times
do_circle();
break;
case MAV_CMD_NAV_LOITER_TIME: // 19
do_loiter_time();
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH: //20
do_RTL();
break;
default:
break;
}
}
// process_cond_command - main switch statement to initiate the next conditional command in the command_cond_queue
static void process_cond_command()
{
switch(command_cond_queue.id) {
case MAV_CMD_CONDITION_DELAY: // 112
do_wait_delay();
break;
case MAV_CMD_CONDITION_DISTANCE: // 114
do_within_distance();
break;
case MAV_CMD_CONDITION_CHANGE_ALT: // 113
do_change_alt();
break;
case MAV_CMD_CONDITION_YAW: // 115
do_yaw();
break;
default:
break;
}
}
// process_now_command - main switch statement to initiate the next now command in the command_cond_queue
// now commands are conditional commands that are executed immediately so they do not require a corresponding verify to be run later
static void process_now_command()
{
switch(command_cond_queue.id) {
case MAV_CMD_DO_JUMP: // 177
do_jump();
break;
case MAV_CMD_DO_CHANGE_SPEED: // 178
do_change_speed();
break;
case MAV_CMD_DO_SET_HOME: // 179
do_set_home();
break;
case MAV_CMD_DO_SET_SERVO:
ServoRelayEvents.do_set_servo(command_cond_queue.p1, command_cond_queue.alt);
break;
case MAV_CMD_DO_SET_RELAY:
ServoRelayEvents.do_set_relay(command_cond_queue.p1, command_cond_queue.alt);
break;
case MAV_CMD_DO_REPEAT_SERVO:
ServoRelayEvents.do_repeat_servo(command_cond_queue.p1, command_cond_queue.alt,
command_cond_queue.lat, command_cond_queue.lng);
break;
case MAV_CMD_DO_REPEAT_RELAY:
ServoRelayEvents.do_repeat_relay(command_cond_queue.p1, command_cond_queue.alt,
command_cond_queue.lat);
break;
case MAV_CMD_DO_SET_ROI: // 201
// point the copter and camera at a region of interest (ROI)
do_roi();
break;
#if CAMERA == ENABLED
case MAV_CMD_DO_CONTROL_VIDEO: // Control on-board camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty|
break;
case MAV_CMD_DO_DIGICAM_CONFIGURE: // Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)|
break;
case MAV_CMD_DO_DIGICAM_CONTROL: // Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty|
do_take_picture();
break;
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
camera.set_trigger_distance(command_cond_queue.alt);
break;
#endif
#if MOUNT == ENABLED
case MAV_CMD_DO_MOUNT_CONFIGURE: // Mission command to configure a camera mount |Mount operation mode (see MAV_CONFIGURE_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty|
camera_mount.configure_cmd();
break;
case MAV_CMD_DO_MOUNT_CONTROL: // Mission command to control a camera mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty|
camera_mount.control_cmd();
break;
#endif
default:
// do nothing with unrecognized MAVLink messages
break;
}
}
/********************************************************************************/
// Verify command Handlers
/********************************************************************************/
// verify_nav_command - switch statement to ensure the active navigation command is progressing
// returns true once the active navigation command completes successfully
static bool verify_nav_command()
{
switch(command_nav_queue.id) {
case MAV_CMD_NAV_TAKEOFF:
return verify_takeoff();
break;
case MAV_CMD_NAV_WAYPOINT:
return verify_nav_wp();
break;
case MAV_CMD_NAV_LAND:
return verify_land();
break;
case MAV_CMD_NAV_LOITER_UNLIM:
return verify_loiter_unlimited();
break;
case MAV_CMD_NAV_LOITER_TURNS:
return verify_circle();
break;
case MAV_CMD_NAV_LOITER_TIME:
return verify_loiter_time();
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
return verify_RTL();
break;
default:
return false;
break;
}
}
// verify_cond_command - switch statement to ensure the active conditional command is progressing
// returns true once the active conditional command completes successfully
static bool verify_cond_command()
{
switch(command_cond_queue.id) {
case MAV_CMD_CONDITION_DELAY:
return verify_wait_delay();
break;
case MAV_CMD_CONDITION_DISTANCE:
return verify_within_distance();
break;
case MAV_CMD_CONDITION_CHANGE_ALT:
return verify_change_alt();
break;
case MAV_CMD_CONDITION_YAW:
return verify_yaw();
break;
default:
return false;
break;
}
}
/********************************************************************************/
//
/********************************************************************************/
// do_RTL - start Return-to-Launch
static void do_RTL(void)
{
// start rtl in auto flight mode
auto_rtl_start();
}
/********************************************************************************/
// Nav (Must) commands
/********************************************************************************/
// do_takeoff - initiate takeoff navigation command
static void do_takeoff()
{
// Set wp navigation target to safe altitude above current position
float takeoff_alt = command_nav_queue.alt;
takeoff_alt = max(takeoff_alt,current_loc.alt);
takeoff_alt = max(takeoff_alt,100.0f);
auto_takeoff_start(takeoff_alt);
}
// do_nav_wp - initiate move to next waypoint
static void do_nav_wp()
{
// Set wp navigation target
auto_wp_start(pv_location_to_vector(command_nav_queue));
// initialise original_wp_bearing which is used to check if we have missed the waypoint
wp_bearing = wp_nav.get_wp_bearing_to_destination();
original_wp_bearing = wp_bearing;
// 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 and expanded to millis
loiter_time_max = command_nav_queue.p1;
// if no delay set the waypoint as "fast"
if (loiter_time_max == 0 ) {
wp_nav.set_fast_waypoint(true);
}
}
// do_land - initiate landing procedure
static void do_land(const struct Location *cmd)
{
// To-Do: check if we have already landed
// if location provided we fly to that location at current altitude
if (cmd != NULL && (cmd->lat != 0 || cmd->lng != 0)) {
// set state to fly to location
land_state = LAND_STATE_FLY_TO_LOCATION;
// calculate and set desired location above landing target
Vector3f pos = pv_location_to_vector(*cmd);
pos.z = min(current_loc.alt, RTL_ALT_MAX);
auto_wp_start(pos);
// initialise original_wp_bearing which is used to check if we have missed the waypoint
wp_bearing = wp_nav.get_wp_bearing_to_destination();
original_wp_bearing = wp_bearing;
}else{
// set landing state
land_state = LAND_STATE_DESCENDING;
// initialise landing controller
auto_land_start();
}
}
// do_loiter_unlimited - start loitering with no end conditions
// note: caller should set yaw_mode
static void do_loiter_unlimited()
{
Vector3f target_pos;
// get current position
Vector3f curr_pos = inertial_nav.get_position();
// default to use position provided
target_pos = pv_location_to_vector(command_nav_queue);
// use current location if not provided
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
wp_nav.get_wp_stopping_point_xy(target_pos);
}
// use current altitude if not provided
// To-Do: use z-axis stopping point instead of current alt
if( command_nav_queue.alt == 0 ) {
target_pos.z = curr_pos.z;
}
// start way point navigator and provide it the desired location
auto_wp_start(target_pos);
}
// do_circle - initiate moving in a circle
static void do_circle()
{
Vector3f curr_pos = inertial_nav.get_position();
Vector3f circle_center = pv_location_to_vector(command_nav_queue);
// set target altitude if not provided
if (circle_center.z == 0) {
circle_center.z = curr_pos.z;
}
// set lat/lon position if not provided
// To-Do: use stopping point instead of current location
if (command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
circle_center.x = curr_pos.x;
circle_center.y = curr_pos.y;
}
// start auto_circle
auto_circle_start(circle_center);
// record number of desired rotations from mission command
circle_desired_rotations = command_nav_queue.p1;
}
// do_loiter_time - initiate loitering at a point for a given time period
// note: caller should set yaw_mode
static void do_loiter_time()
{
Vector3f target_pos;
// get current position
Vector3f curr_pos = inertial_nav.get_position();
// default to use position provided
target_pos = pv_location_to_vector(command_nav_queue);
// use current location if not provided
if(command_nav_queue.lat == 0 && command_nav_queue.lng == 0) {
wp_nav.get_wp_stopping_point_xy(target_pos);
}
// use current altitude if not provided
if( command_nav_queue.alt == 0 ) {
target_pos.z = curr_pos.z;
}
// start way point navigator and provide it the desired location
auto_wp_start(target_pos);
// setup loiter timer
loiter_time = 0;
loiter_time_max = command_nav_queue.p1; // units are (seconds)
}
/********************************************************************************/
// Verify Nav (Must) commands
/********************************************************************************/
// verify_takeoff - check if we have completed the takeoff
static bool verify_takeoff()
{
// have we reached our target altitude?
return wp_nav.reached_wp_destination();
}
// verify_land - returns true if landing has been completed
static bool verify_land()
{
bool retval = false;
switch( land_state ) {
case LAND_STATE_FLY_TO_LOCATION:
// check if we've reached the location
if (wp_nav.reached_wp_destination()) {
// get destination so we can use it for loiter target
Vector3f dest = wp_nav.get_wp_destination();
// initialise landing controller
auto_land_start(dest);
// advance to next state
land_state = LAND_STATE_DESCENDING;
}
break;
case LAND_STATE_DESCENDING:
// rely on THROTTLE_LAND mode to correctly update landing status
retval = ap.land_complete;
break;
default:
// this should never happen
// TO-DO: log an error
retval = true;
break;
}
// true is returned if we've successfully landed
return retval;
}
// verify_nav_wp - check if we have reached the next way point
static bool verify_nav_wp()
{
// check if we have reached the waypoint
if( !wp_nav.reached_wp_destination() ) {
return false;
}
// start timer if necessary
if(loiter_time == 0) {
loiter_time = millis();
}
// check if timer has run out
if (((millis() - loiter_time) / 1000) >= loiter_time_max) {
gcs_send_text_fmt(PSTR("Reached Command #%i"),command_nav_index);
return true;
}else{
return false;
}
}
static bool verify_loiter_unlimited()
{
return false;
}
// verify_loiter_time - check if we have loitered long enough
static bool verify_loiter_time()
{
// return immediately if we haven't reached our destination
if (!wp_nav.reached_wp_destination()) {
return false;
}
// start our loiter timer
if( loiter_time == 0 ) {
loiter_time = millis();
}
// check if loiter timer has run out
return (((millis() - loiter_time) / 1000) >= loiter_time_max);
}
// verify_circle - check if we have circled the point enough
static bool verify_circle()
{
// have we rotated around the center enough times?
return fabsf(circle_nav.get_angle_total()/(2*M_PI)) >= circle_desired_rotations;
}
// externs to remove compiler warning
extern bool rtl_state_complete;
// verify_RTL - handles any state changes required to implement RTL
// do_RTL should have been called once first to initialise all variables
// returns true with RTL has completed successfully
static bool verify_RTL()
{
return (rtl_state_complete && (rtl_state == FinalDescent || rtl_state == Land));
}
/********************************************************************************/
// Condition (May) commands
/********************************************************************************/
static void do_wait_delay()
{
//cliSerial->print("dwd ");
condition_start = millis();
condition_value = command_cond_queue.lat * 1000; // convert to milliseconds
//cliSerial->println(condition_value,DEC);
}
static void do_change_alt()
{
// adjust target appropriately for each nav mode
if (control_mode == AUTO) {
switch (auto_mode) {
case Auto_TakeOff:
// To-Do: adjust waypoint target altitude to new provided altitude
break;
case Auto_WP:
// To-Do; reset origin to current location + stopping distance at new altitude
break;
case Auto_Land:
case Auto_RTL:
// ignore altitude
break;
case Auto_Circle:
// move circle altitude up to target (we will need to store this target in circle class)
break;
}
}
// To-Do: store desired altitude in a variable so that it can be verified later
}
static void do_within_distance()
{
condition_value = command_cond_queue.lat * 100;
}
static void do_yaw()
{
// get current yaw target
int32_t curr_yaw_target = attitude_control.angle_ef_targets().z;
// get final angle, 1 = Relative, 0 = Absolute
if( command_cond_queue.lng == 0 ) {
// absolute angle
yaw_look_at_heading = wrap_360_cd(command_cond_queue.alt * 100);
}else{
// relative angle
yaw_look_at_heading = wrap_360_cd(curr_yaw_target + command_cond_queue.alt * 100);
}
// get turn speed
if( command_cond_queue.lat == 0 ) {
// default to regular auto slew rate
yaw_look_at_heading_slew = AUTO_YAW_SLEW_RATE;
}else{
int32_t turn_rate = (wrap_180_cd(yaw_look_at_heading - curr_yaw_target) / 100) / command_cond_queue.lat;
yaw_look_at_heading_slew = constrain_int32(turn_rate, 1, 360); // deg / sec
}
// set yaw mode
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_HEADING);
// TO-DO: restore support for clockwise / counter clockwise rotation held in command_cond_queue.p1
// command_cond_queue.p1; // 0 = undefined, 1 = clockwise, -1 = counterclockwise
}
/********************************************************************************/
// Verify Condition (May) commands
/********************************************************************************/
static bool verify_wait_delay()
{
//cliSerial->print("vwd");
if (millis() - condition_start > (uint32_t)max(condition_value,0)) {
//cliSerial->println("y");
condition_value = 0;
return true;
}
//cliSerial->println("n");
return false;
}
static bool verify_change_alt()
{
// To-Do: use recorded target altitude to verify we have reached the target
return true;
}
static bool verify_within_distance()
{
if (wp_distance < max(condition_value,0)) {
condition_value = 0;
return true;
}
return false;
}
// verify_yaw - return true if we have reached the desired heading
static bool verify_yaw()
{
if( labs(wrap_180_cd(ahrs.yaw_sensor-yaw_look_at_heading)) <= 200 ) {
return true;
}else{
return false;
}
}
/********************************************************************************/
// Do (Now) commands
/********************************************************************************/
// do_guided - start guided mode
// this is not actually a mission command but rather a
static void do_guided(const struct Location *cmd)
{
// switch to guided mode if we're not already in guided mode
if (control_mode != GUIDED) {
if (!set_mode(GUIDED)) {
// if we failed to enter guided mode return immediately
return;
}
}
// set wp_nav's destination
Vector3f pos = pv_location_to_vector(*cmd);
guided_set_destination(pos);
}
static void do_change_speed()
{
wp_nav.set_horizontal_velocity(command_cond_queue.p1 * 100);
}
static void do_jump()
{
// Used to track the state of the jump command in Mission scripting
// -10 is a value that means the register is unused
// when in use, it contains the current remaining jumps
static int8_t jump = -10; // used to track loops in jump command
if(jump == -10) {
// we use a locally stored index for jump
jump = command_cond_queue.lat;
}
if(jump > 0) {
jump--;
change_command(command_cond_queue.p1);
} else if (jump == 0) {
// we're done, move along
jump = -11;
} else if (jump == -1) {
// repeat forever
change_command(command_cond_queue.p1);
}
}
static void do_set_home()
{
if(command_cond_queue.p1 == 1) {
init_home();
} else {
home.id = MAV_CMD_NAV_WAYPOINT;
home.lng = command_cond_queue.lng; // Lon * 10**7
home.lat = command_cond_queue.lat; // Lat * 10**7
home.alt = 0;
//home_is_set = true;
set_home_is_set(true);
}
}
// do_roi - starts actions required by MAV_CMD_NAV_ROI
// this involves either moving the camera to point at the ROI (region of interest)
// and possibly rotating the copter to point at the ROI if our mount type does not support a yaw feature
// Note: the ROI should already be in the command_nav_queue global variable
// TO-DO: add support for other features of MAV_CMD_DO_SET_ROI including pointing at a given waypoint
static void do_roi()
{
#if MOUNT == ENABLED
// check if mount type requires us to rotate the quad
if( camera_mount.get_mount_type() != AP_Mount::k_pan_tilt && camera_mount.get_mount_type() != AP_Mount::k_pan_tilt_roll ) {
yaw_look_at_WP = pv_location_to_vector(command_cond_queue);
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_LOCATION);
}
// send the command to the camera mount
camera_mount.set_roi_cmd(&command_cond_queue);
// TO-DO: expand handling of the do_nav_roi to support all modes of the MAVLink. Currently we only handle mode 4 (see below)
// 0: do nothing
// 1: point at next waypoint
// 2: point at a waypoint taken from WP# parameter (2nd parameter?)
// 3: point at a location given by alt, lon, lat parameters
// 4: point at a target given a target id (can't be implemented)
#else
// if we have no camera mount aim the quad at the location
yaw_look_at_WP = pv_location_to_vector(command_cond_queue);
set_auto_yaw_mode(AUTO_YAW_LOOK_AT_LOCATION);
#endif
}
// do_take_picture - take a picture with the camera library
static void do_take_picture()
{
#if CAMERA == ENABLED
camera.trigger_pic();
if (g.log_bitmask & MASK_LOG_CAMERA) {
Log_Write_Camera();
}
#endif
}