2011-09-08 22:29:39 -03:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-05-13 03:09:36 -03:00
# include "Plane.h"
2014-03-13 23:48:58 -03:00
2011-09-08 22:29:39 -03:00
/********************************************************************************/
// Command Event Handlers
/********************************************************************************/
2015-05-13 03:09:36 -03:00
bool Plane : : start_command ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-03 09:50:45 -04:00
// log when new commands start
2014-03-18 23:42:15 -03:00
if ( should_log ( MASK_LOG_CMD ) ) {
2015-06-23 23:13:16 -03:00
DataFlash . Log_Write_Mission_Cmd ( mission , cmd ) ;
2014-03-03 09:50:45 -04:00
}
// special handling for nav vs non-nav commands
if ( AP_Mission : : is_nav_cmd ( cmd ) ) {
2014-04-23 08:57:51 -03:00
// set land_complete to false to stop us zeroing the throttle
auto_state . land_complete = false ;
2015-06-13 06:11:49 -03:00
auto_state . sink_rate = 0 ;
2012-08-22 03:17:55 -03:00
2014-04-23 08:57:51 -03:00
// set takeoff_complete to true so we don't add extra evevator
2014-03-03 09:50:45 -04:00
// except in a takeoff
2014-04-23 08:57:51 -03:00
auto_state . takeoff_complete = true ;
2014-10-21 12:26:33 -03:00
// if a go around had been commanded, clear it now.
auto_state . commanded_go_around = false ;
2015-06-13 06:12:54 -03:00
// start non-idle
auto_state . idle_mode = false ;
2014-04-23 08:57:51 -03:00
2015-08-17 18:14:10 -03:00
// once landed, post some landing statistics to the GCS
auto_state . post_landing_stats = false ;
2014-03-03 09:50:45 -04:00
gcs_send_text_fmt ( PSTR ( " Executing nav command ID #%i " ) , cmd . id ) ;
2014-04-23 08:57:51 -03:00
} else {
2014-03-03 09:50:45 -04:00
gcs_send_text_fmt ( PSTR ( " Executing command ID #%i " ) , cmd . id ) ;
}
switch ( cmd . id ) {
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_TAKEOFF :
2014-03-03 09:50:45 -04:00
do_takeoff ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_WAYPOINT : // Navigate to Waypoint
2014-03-03 09:50:45 -04:00
do_nav_wp ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LAND : // LAND to Waypoint
2014-03-03 09:50:45 -04:00
do_land ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_UNLIM : // Loiter indefinitely
2014-03-03 09:50:45 -04:00
do_loiter_unlimited ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_TURNS : // Loiter N Times
2014-03-03 09:50:45 -04:00
do_loiter_turns ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_TIME :
2014-03-03 09:50:45 -04:00
do_loiter_time ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2015-03-13 18:48:21 -03:00
case MAV_CMD_NAV_LOITER_TO_ALT :
do_loiter_to_alt ( cmd ) ;
break ;
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
2014-03-15 08:15:06 -03:00
set_mode ( RTL ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2014-10-21 17:46:01 -03:00
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT :
do_continue_and_change_alt ( cmd ) ;
2014-11-24 22:15:25 -04:00
break ;
2014-10-21 17:46:01 -03:00
2015-06-13 06:12:54 -03:00
case MAV_CMD_NAV_ALTITUDE_WAIT :
do_altitude_wait ( cmd ) ;
break ;
2014-03-03 09:50:45 -04:00
// Conditional commands
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_CONDITION_DELAY :
2014-03-03 09:50:45 -04:00
do_wait_delay ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_CONDITION_DISTANCE :
2014-03-03 09:50:45 -04:00
do_within_distance ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_CONDITION_CHANGE_ALT :
2014-03-03 09:50:45 -04:00
do_change_alt ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2014-03-03 09:50:45 -04:00
// Do commands
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_DO_CHANGE_SPEED :
2014-03-03 09:50:45 -04:00
do_change_speed ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_DO_SET_HOME :
2014-03-03 09:50:45 -04:00
do_set_home ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_DO_SET_SERVO :
2014-03-17 02:16:45 -03:00
ServoRelayEvents . do_set_servo ( cmd . content . servo . channel , cmd . content . servo . pwm ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_DO_SET_RELAY :
2014-03-17 02:16:45 -03:00
ServoRelayEvents . do_set_relay ( cmd . content . relay . num , cmd . content . relay . state ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_DO_REPEAT_SERVO :
2014-03-18 23:13:47 -03:00
ServoRelayEvents . do_repeat_servo ( cmd . content . repeat_servo . channel , cmd . content . repeat_servo . pwm ,
cmd . content . repeat_servo . repeat_count , cmd . content . repeat_servo . cycle_time * 1000.0f ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_DO_REPEAT_RELAY :
2014-03-18 23:13:47 -03:00
ServoRelayEvents . do_repeat_relay ( cmd . content . repeat_relay . num , cmd . content . repeat_relay . repeat_count ,
cmd . content . repeat_relay . cycle_time * 1000.0f ) ;
2012-08-16 21:50:15 -03:00
break ;
2011-10-31 18:55:58 -03:00
2014-06-05 03:12:10 -03:00
case MAV_CMD_DO_INVERTED_FLIGHT :
if ( cmd . p1 = = 0 | | cmd . p1 = = 1 ) {
auto_state . inverted_flight = ( bool ) cmd . p1 ;
gcs_send_text_fmt ( PSTR ( " Set inverted %u " ) , cmd . p1 ) ;
}
break ;
2014-10-17 22:40:31 -03:00
case MAV_CMD_DO_LAND_START :
2014-10-21 12:26:33 -03:00
//ensure go around hasn't been set
auto_state . commanded_go_around = false ;
2014-10-17 22:40:31 -03:00
break ;
2014-10-25 18:20:04 -03:00
case MAV_CMD_DO_FENCE_ENABLE :
# if GEOFENCE_ENABLED == ENABLED
2015-04-09 13:02:38 -03:00
if ( cmd . p1 ! = 2 ) {
if ( ! geofence_set_enabled ( ( bool ) cmd . p1 , AUTO_TOGGLED ) ) {
gcs_send_text_fmt ( PSTR ( " Unable to set fence enabled state to %u " ) , cmd . p1 ) ;
} else {
gcs_send_text_fmt ( PSTR ( " Set fence enabled state to %u " ) , cmd . p1 ) ;
}
} else { //commanding to only disable floor
if ( ! geofence_set_floor_enabled ( false ) ) {
gcs_send_text_fmt ( PSTR ( " Unabled to disable fence floor. \n " ) ) ;
} else {
gcs_send_text_fmt ( PSTR ( " Fence floor disabled. \n " ) ) ;
}
2014-10-25 18:20:04 -03:00
}
# endif
2015-06-19 23:35:07 -03:00
break ;
2015-06-13 06:16:02 -03:00
case MAV_CMD_DO_AUTOTUNE_ENABLE :
autotune_enable ( cmd . p1 ) ;
2014-10-25 18:20:04 -03:00
break ;
2012-06-13 16:00:20 -03:00
# if CAMERA == ENABLED
2012-08-16 21:50:15 -03:00
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 ;
2012-06-13 16:00:20 -03:00
2012-08-16 21:50:15 -03:00
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)|
2015-03-29 15:49:10 -03:00
do_digicam_configure ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2012-06-13 16:00:20 -03:00
2012-08-16 21:50:15 -03:00
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|
2015-03-29 15:49:10 -03:00
// do_digicam_control Send Digicam Control message with the camera library
do_digicam_control ( cmd ) ;
2012-08-16 21:50:15 -03:00
break ;
2013-10-11 07:30:01 -03:00
case MAV_CMD_DO_SET_CAM_TRIGG_DIST :
2014-03-17 02:16:45 -03:00
camera . set_trigger_distance ( cmd . content . cam_trigg_dist . meters ) ;
2013-10-11 07:30:01 -03:00
break ;
2012-06-13 16:00:20 -03:00
# endif
2011-10-31 18:55:58 -03:00
# if MOUNT == ENABLED
2012-08-16 21:50:15 -03:00
// Sets the region of interest (ROI) for a sensor set or the
// vehicle itself. This can then be used by the vehicles control
// system to control the vehicle attitude and the attitude of various
// devices such as cameras.
// |Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z|
2014-07-04 03:42:51 -03:00
case MAV_CMD_DO_SET_ROI :
if ( cmd . content . location . alt = = 0 & & cmd . content . location . lat = = 0 & & cmd . content . location . lng = = 0 ) {
// switch off the camera tracking if enabled
if ( camera_mount . get_mode ( ) = = MAV_MOUNT_MODE_GPS_POINT ) {
camera_mount . set_mode_to_default ( ) ;
}
} else {
2015-01-08 16:12:08 -04:00
// set mount's target location
camera_mount . set_roi_target ( cmd . content . location ) ;
2014-07-04 03:42:51 -03:00
}
2012-08-16 21:50:15 -03:00
break ;
2015-05-25 19:30:30 -03:00
case MAV_CMD_DO_MOUNT_CONTROL : // 205
// point the camera to a specified angle
camera_mount . set_angle_targets ( cmd . content . mount_control . roll ,
cmd . content . mount_control . pitch ,
cmd . content . mount_control . yaw ) ;
break ;
2011-10-31 18:55:58 -03:00
# endif
2012-08-16 21:50:15 -03:00
}
2014-03-03 09:50:45 -04:00
return true ;
2011-09-08 22:29:39 -03:00
}
2013-04-15 01:41:15 -03:00
/*******************************************************************************
Verify command Handlers
Each type of mission element has a " verify " operation . The verify
operation returns true when the mission element has completed and we
should move onto the next mission element .
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
2011-09-08 22:29:39 -03:00
2015-05-13 03:09:36 -03:00
bool Plane : : verify_command ( const AP_Mission : : Mission_Command & cmd ) // Returns true if command complete
2011-09-08 22:29:39 -03:00
{
2014-03-03 09:50:45 -04:00
switch ( cmd . id ) {
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_TAKEOFF :
return verify_takeoff ( ) ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LAND :
return verify_land ( ) ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_WAYPOINT :
2014-09-02 22:23:29 -03:00
return verify_nav_wp ( cmd ) ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_UNLIM :
return verify_loiter_unlim ( ) ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_TURNS :
return verify_loiter_turns ( ) ;
2011-09-08 22:29:39 -03:00
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_LOITER_TIME :
return verify_loiter_time ( ) ;
2011-09-08 22:29:39 -03:00
2015-03-13 18:48:21 -03:00
case MAV_CMD_NAV_LOITER_TO_ALT :
return verify_loiter_to_alt ( ) ;
2012-08-16 21:50:15 -03:00
case MAV_CMD_NAV_RETURN_TO_LAUNCH :
return verify_RTL ( ) ;
2011-09-08 22:29:39 -03:00
2014-10-21 17:46:01 -03:00
case MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT :
return verify_continue_and_change_alt ( ) ;
2015-06-13 06:12:54 -03:00
case MAV_CMD_NAV_ALTITUDE_WAIT :
return verify_altitude_wait ( cmd ) ;
2014-03-03 09:50:45 -04:00
// Conditional commands
2011-09-08 22:29:39 -03:00
case MAV_CMD_CONDITION_DELAY :
return verify_wait_delay ( ) ;
case MAV_CMD_CONDITION_DISTANCE :
return verify_within_distance ( ) ;
case MAV_CMD_CONDITION_CHANGE_ALT :
return verify_change_alt ( ) ;
2012-07-19 03:07:34 -03:00
2014-03-03 09:50:45 -04:00
// do commands (always return true)
case MAV_CMD_DO_CHANGE_SPEED :
case MAV_CMD_DO_SET_HOME :
case MAV_CMD_DO_SET_SERVO :
case MAV_CMD_DO_SET_RELAY :
case MAV_CMD_DO_REPEAT_SERVO :
case MAV_CMD_DO_REPEAT_RELAY :
case MAV_CMD_DO_CONTROL_VIDEO :
case MAV_CMD_DO_DIGICAM_CONFIGURE :
case MAV_CMD_DO_DIGICAM_CONTROL :
case MAV_CMD_DO_SET_CAM_TRIGG_DIST :
case MAV_CMD_NAV_ROI :
case MAV_CMD_DO_MOUNT_CONFIGURE :
2014-06-05 03:12:10 -03:00
case MAV_CMD_DO_INVERTED_FLIGHT :
2014-10-17 14:35:05 -03:00
case MAV_CMD_DO_LAND_START :
2014-10-25 18:20:04 -03:00
case MAV_CMD_DO_FENCE_ENABLE :
2015-06-13 06:16:02 -03:00
case MAV_CMD_DO_AUTOTUNE_ENABLE :
2014-03-03 09:50:45 -04:00
return true ;
2011-09-08 22:29:39 -03:00
default :
2014-03-03 09:50:45 -04:00
// error message
if ( AP_Mission : : is_nav_cmd ( cmd ) ) {
gcs_send_text_P ( SEVERITY_HIGH , PSTR ( " verify_nav: Invalid or no current Nav cmd " ) ) ;
} else {
2011-10-25 22:27:23 -03:00
gcs_send_text_P ( SEVERITY_HIGH , PSTR ( " verify_conditon: Invalid or no current Condition cmd " ) ) ;
2012-08-16 21:50:15 -03:00
}
2014-03-03 09:50:45 -04:00
// return true so that we do not get stuck at this command
return true ;
}
2011-09-08 22:29:39 -03:00
}
/********************************************************************************/
// Nav (Must) commands
/********************************************************************************/
2015-05-13 03:09:36 -03:00
void Plane : : do_RTL ( void )
2011-09-08 22:29:39 -03:00
{
2014-08-04 07:39:15 -03:00
auto_state . next_wp_no_crosstrack = true ;
auto_state . no_crosstrack = true ;
2014-03-16 01:53:10 -03:00
prev_WP_loc = current_loc ;
2014-07-24 03:21:30 -03:00
next_WP_loc = rally . calc_best_rally_or_home_location ( current_loc , get_RTL_altitude ( ) ) ;
2014-07-24 04:54:58 -03:00
setup_terrain_target_alt ( next_WP_loc ) ;
2014-08-04 03:55:15 -03:00
set_target_altitude_location ( next_WP_loc ) ;
2013-04-14 09:04:25 -03:00
if ( g . loiter_radius < 0 ) {
2013-04-15 08:31:11 -03:00
loiter . direction = - 1 ;
2013-04-14 09:04:25 -03:00
} else {
2013-04-15 08:31:11 -03:00
loiter . direction = 1 ;
2013-04-14 09:04:25 -03:00
}
2011-09-08 22:29:39 -03:00
2014-08-04 06:58:12 -03:00
update_flight_stage ( ) ;
2013-07-05 01:56:58 -03:00
setup_glide_slope ( ) ;
2014-07-24 03:21:30 -03:00
setup_turn_angle ( ) ;
2013-07-05 01:56:58 -03:00
2014-01-13 22:07:43 -04:00
if ( should_log ( MASK_LOG_MODE ) )
2015-01-16 12:30:49 -04:00
DataFlash . Log_Write_Mode ( control_mode ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_takeoff ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2015-01-02 19:36:14 -04:00
prev_WP_loc = current_loc ;
2014-03-17 04:45:45 -03:00
set_next_WP ( cmd . content . location ) ;
2012-08-16 21:50:15 -03:00
// pitch in deg, airspeed m/s, throttle %, track WP 1 or 0
2014-08-04 06:59:46 -03:00
auto_state . takeoff_pitch_cd = ( int16_t ) cmd . p1 * 100 ;
2015-02-25 07:54:52 -04:00
auto_state . takeoff_altitude_rel_cm = next_WP_loc . alt - home . alt ;
2014-03-16 01:53:10 -03:00
next_WP_loc . lat = home . lat + 10 ;
next_WP_loc . lng = home . lng + 10 ;
2014-10-06 17:17:33 -03:00
auto_state . takeoff_speed_time_ms = 0 ;
2014-04-23 08:57:51 -03:00
auto_state . takeoff_complete = false ; // set flag to use gps ground course during TO. IMU will be doing yaw drift correction
2012-08-16 21:50:15 -03:00
// Flag also used to override "on the ground" throttle disable
2014-10-06 17:17:33 -03:00
// zero locked course
steer_state . locked_course_err = 0 ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_nav_wp ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 04:45:45 -03:00
set_next_WP ( cmd . content . location ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_land ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-10-24 08:04:30 -03:00
auto_state . commanded_go_around = false ;
2014-03-17 04:45:45 -03:00
set_next_WP ( cmd . content . location ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : loiter_set_direction_wp ( const AP_Mission : : Mission_Command & cmd )
2013-01-13 09:29:53 -04:00
{
2014-03-03 09:50:45 -04:00
if ( cmd . content . location . flags . loiter_ccw ) {
2013-04-15 08:31:11 -03:00
loiter . direction = - 1 ;
2013-01-13 09:29:53 -04:00
} else {
2013-04-15 08:31:11 -03:00
loiter . direction = 1 ;
2013-01-13 09:29:53 -04:00
}
}
2015-05-13 03:09:36 -03:00
void Plane : : do_loiter_unlimited ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 04:45:45 -03:00
set_next_WP ( cmd . content . location ) ;
2014-03-03 09:50:45 -04:00
loiter_set_direction_wp ( cmd ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_loiter_turns ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 04:45:45 -03:00
set_next_WP ( cmd . content . location ) ;
2014-06-11 04:22:59 -03:00
loiter . total_cd = ( uint32_t ) ( LOWBYTE ( cmd . p1 ) ) * 36000UL ;
2014-03-03 09:50:45 -04:00
loiter_set_direction_wp ( cmd ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_loiter_time ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 04:45:45 -03:00
set_next_WP ( cmd . content . location ) ;
2013-04-15 08:39:14 -03:00
// we set start_time_ms when we reach the waypoint
loiter . start_time_ms = 0 ;
2014-03-03 09:50:45 -04:00
loiter . time_max_ms = cmd . p1 * ( uint32_t ) 1000 ; // units are seconds
loiter_set_direction_wp ( cmd ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_continue_and_change_alt ( const AP_Mission : : Mission_Command & cmd )
2014-10-21 17:46:01 -03:00
{
next_WP_loc . alt = cmd . content . location . alt + home . alt ;
2014-12-03 03:31:23 -04:00
reset_offset_altitude ( ) ;
2014-10-21 17:46:01 -03:00
}
2015-06-13 06:12:54 -03:00
void Plane : : do_altitude_wait ( const AP_Mission : : Mission_Command & cmd )
{
// set all servos to trim until we reach altitude or descent speed
auto_state . idle_mode = true ;
}
2015-05-13 03:09:36 -03:00
void Plane : : do_loiter_to_alt ( const AP_Mission : : Mission_Command & cmd )
2015-03-13 18:48:21 -03:00
{
//set target alt
next_WP_loc . alt = cmd . content . location . alt ;
// convert relative alt to absolute alt
if ( cmd . content . location . flags . relative_alt ) {
next_WP_loc . flags . relative_alt = false ;
next_WP_loc . alt + = home . alt ;
}
//I know I'm storing this twice -- I'm doing that on purpose --
//see verify_loiter_alt() function
condition_value = next_WP_loc . alt ;
//are lat and lon 0? if so, don't change the current wp lat/lon
2015-04-23 18:27:50 -03:00
if ( cmd . content . location . lat ! = 0 | | cmd . content . location . lng ! = 0 ) {
2015-03-13 18:48:21 -03:00
set_next_WP ( cmd . content . location ) ;
}
//set loiter direction
loiter_set_direction_wp ( cmd ) ;
//must the plane be heading towards the next waypoint before breaking?
condition_value2 = LOWBYTE ( cmd . p1 ) ;
}
2011-09-08 22:29:39 -03:00
/********************************************************************************/
// Verify Nav (Must) commands
/********************************************************************************/
2015-05-13 03:09:36 -03:00
bool Plane : : verify_takeoff ( )
2011-09-08 22:29:39 -03:00
{
2014-10-06 17:17:33 -03:00
if ( ahrs . yaw_initialised ( ) & & steer_state . hold_course_cd = = - 1 ) {
const float min_gps_speed = 5 ;
if ( auto_state . takeoff_speed_time_ms = = 0 & &
gps . status ( ) > = AP_GPS : : GPS_OK_FIX_3D & &
gps . ground_speed ( ) > min_gps_speed ) {
2015-05-13 19:05:32 -03:00
auto_state . takeoff_speed_time_ms = millis ( ) ;
2014-10-06 17:17:33 -03:00
}
if ( auto_state . takeoff_speed_time_ms ! = 0 & &
2015-05-13 19:05:32 -03:00
millis ( ) - auto_state . takeoff_speed_time_ms > = 2000 ) {
2014-10-06 17:17:33 -03:00
// once we reach sufficient speed for good GPS course
// estimation we save our current GPS ground course
// corrected for summed yaw to set the take off
// course. This keeps wings level until we are ready to
// rotate, and also allows us to cope with arbitary
// compass errors for auto takeoff
2015-04-11 06:43:13 -03:00
float takeoff_course = wrap_PI ( radians ( gps . ground_course_cd ( ) * 0.01f ) ) - steer_state . locked_course_err ;
2014-10-06 17:17:33 -03:00
takeoff_course = wrap_PI ( takeoff_course ) ;
steer_state . hold_course_cd = wrap_360_cd ( degrees ( takeoff_course ) * 100 ) ;
gcs_send_text_fmt ( PSTR ( " Holding course %ld at %.1fm/s (%.1f) " ) ,
steer_state . hold_course_cd ,
2015-05-03 03:00:05 -03:00
( double ) gps . ground_speed ( ) ,
( double ) degrees ( steer_state . locked_course_err ) ) ;
2012-08-16 21:50:15 -03:00
}
}
2011-09-08 22:29:39 -03:00
2013-10-03 09:01:43 -03:00
if ( steer_state . hold_course_cd ! = - 1 ) {
2013-04-11 21:25:46 -03:00
// call navigation controller for heading hold
2013-10-03 09:01:43 -03:00
nav_controller - > update_heading_hold ( steer_state . hold_course_cd ) ;
2013-04-11 21:25:46 -03:00
} else {
nav_controller - > update_level_flight ( ) ;
2012-08-16 21:50:15 -03:00
}
2011-09-08 22:29:39 -03:00
2013-06-26 05:36:53 -03:00
// see if we have reached takeoff altitude
2015-02-25 07:54:52 -04:00
int32_t relative_alt_cm = adjusted_relative_altitude_cm ( ) ;
if ( relative_alt_cm > auto_state . takeoff_altitude_rel_cm ) {
gcs_send_text_fmt ( PSTR ( " Takeoff complete at %.2fm " ) ,
2015-05-03 03:00:05 -03:00
( double ) ( relative_alt_cm * 0.01f ) ) ;
2013-10-03 09:01:43 -03:00
steer_state . hold_course_cd = - 1 ;
2014-04-23 08:57:51 -03:00
auto_state . takeoff_complete = true ;
2014-03-16 01:53:10 -03:00
next_WP_loc = prev_WP_loc = current_loc ;
2014-02-13 18:49:42 -04:00
# if GEOFENCE_ENABLED == ENABLED
2015-04-09 13:02:38 -03:00
if ( g . fence_autoenable > 0 ) {
2014-02-13 18:49:42 -04:00
if ( ! geofence_set_enabled ( true , AUTO_TOGGLED ) ) {
gcs_send_text_P ( SEVERITY_HIGH , PSTR ( " Enable fence failed (cannot autoenable " ) ) ;
} else {
gcs_send_text_P ( SEVERITY_HIGH , PSTR ( " Fence enabled. (autoenabled) " ) ) ;
}
}
# endif
2014-08-04 07:39:15 -03:00
// don't cross-track on completion of takeoff, as otherwise we
// can end up doing too sharp a turn
auto_state . next_wp_no_crosstrack = true ;
2012-08-16 21:50:15 -03:00
return true ;
} else {
return false ;
}
2011-09-08 22:29:39 -03:00
}
2014-08-04 07:39:15 -03:00
/*
update navigation for normal mission waypoints . Return true when the
waypoint is complete
*/
2015-05-13 03:09:36 -03:00
bool Plane : : verify_nav_wp ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2013-10-03 09:01:43 -03:00
steer_state . hold_course_cd = - 1 ;
2013-04-11 21:25:46 -03:00
2014-08-04 07:39:15 -03:00
if ( auto_state . no_crosstrack ) {
nav_controller - > update_waypoint ( current_loc , next_WP_loc ) ;
} else {
nav_controller - > update_waypoint ( prev_WP_loc , next_WP_loc ) ;
}
2013-09-13 04:43:00 -03:00
// see if the user has specified a maximum distance to waypoint
2015-01-01 00:17:45 -04:00
if ( g . waypoint_max_radius > 0 & &
auto_state . wp_distance > ( uint16_t ) g . waypoint_max_radius ) {
2014-03-16 01:53:10 -03:00
if ( location_passed_point ( current_loc , prev_WP_loc , next_WP_loc ) ) {
2013-09-13 04:43:00 -03:00
// this is needed to ensure completion of the waypoint
2014-03-16 01:53:10 -03:00
prev_WP_loc = current_loc ;
2013-09-13 04:43:00 -03:00
}
return false ;
}
2014-09-02 22:23:29 -03:00
float acceptance_distance = nav_controller - > turn_distance ( g . waypoint_radius , auto_state . next_turn_angle ) ;
if ( cmd . p1 > 0 ) {
// allow user to override acceptance radius
acceptance_distance = cmd . p1 ;
}
2013-04-11 21:25:46 -03:00
2015-01-01 00:17:45 -04:00
if ( auto_state . wp_distance < = acceptance_distance ) {
2012-08-16 21:50:15 -03:00
gcs_send_text_fmt ( PSTR ( " Reached Waypoint #%i dist %um " ) ,
2014-03-03 09:50:45 -04:00
( unsigned ) mission . get_current_nav_cmd ( ) . index ,
2014-03-16 01:53:10 -03:00
( unsigned ) get_distance ( current_loc , next_WP_loc ) ) ;
2012-08-16 21:50:15 -03:00
return true ;
2013-04-11 21:25:46 -03:00
}
2012-07-03 20:21:34 -03:00
// have we flown past the waypoint?
2014-03-16 01:53:10 -03:00
if ( location_passed_point ( current_loc , prev_WP_loc , next_WP_loc ) ) {
2012-08-16 21:50:15 -03:00
gcs_send_text_fmt ( PSTR ( " Passed Waypoint #%i dist %um " ) ,
2014-03-03 09:50:45 -04:00
( unsigned ) mission . get_current_nav_cmd ( ) . index ,
2014-03-16 01:53:10 -03:00
( unsigned ) get_distance ( current_loc , next_WP_loc ) ) ;
2012-07-03 20:21:34 -03:00
return true ;
}
2012-08-16 21:50:15 -03:00
return false ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_loiter_unlim ( )
2011-09-08 22:29:39 -03:00
{
2012-08-16 21:50:15 -03:00
update_loiter ( ) ;
return false ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_loiter_time ( )
2011-09-08 22:29:39 -03:00
{
2012-08-16 21:50:15 -03:00
update_loiter ( ) ;
2013-04-15 08:39:14 -03:00
if ( loiter . start_time_ms = = 0 ) {
if ( nav_controller - > reached_loiter_target ( ) ) {
// we've reached the target, start the timer
2015-05-13 19:05:32 -03:00
loiter . start_time_ms = millis ( ) ;
2013-04-15 08:39:14 -03:00
}
2015-05-13 19:05:32 -03:00
} else if ( ( millis ( ) - loiter . start_time_ms ) > loiter . time_max_ms ) {
2012-08-16 21:50:15 -03:00
gcs_send_text_P ( SEVERITY_LOW , PSTR ( " verify_nav: LOITER time complete " ) ) ;
return true ;
}
return false ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_loiter_turns ( )
2011-09-08 22:29:39 -03:00
{
2012-08-16 21:50:15 -03:00
update_loiter ( ) ;
2013-04-15 08:31:11 -03:00
if ( loiter . sum_cd > loiter . total_cd ) {
loiter . total_cd = 0 ;
2012-08-16 21:50:15 -03:00
gcs_send_text_P ( SEVERITY_LOW , PSTR ( " verify_nav: LOITER orbits complete " ) ) ;
// clear the command queue;
return true ;
}
return false ;
2011-09-08 22:29:39 -03:00
}
2015-04-23 18:39:25 -03:00
/*
verify a LOITER_TO_ALT command . This involves checking we have
reached both the desired altitude and desired heading . The desired
altitude only needs to be reached once .
*/
2015-05-13 03:09:36 -03:00
bool Plane : : verify_loiter_to_alt ( )
2015-04-23 18:39:25 -03:00
{
2015-03-13 18:48:21 -03:00
update_loiter ( ) ;
//has target altitude been reached?
if ( condition_value ! = 0 ) {
2015-05-08 15:40:55 -03:00
if ( labs ( condition_value - current_loc . alt ) < 500 ) {
2015-03-13 18:48:21 -03:00
//Only have to reach the altitude once -- that's why I need
//this global condition variable.
//
//This is in case of altitude oscillation when still trying
//to reach the target heading.
condition_value = 0 ;
} else {
return false ;
}
}
//has target heading been reached?
if ( condition_value2 ! = 0 ) {
//Get the lat/lon of next Nav waypoint after this one:
AP_Mission : : Mission_Command next_nav_cmd ;
if ( ! mission . get_next_nav_cmd ( mission . get_current_nav_index ( ) + 1 ,
next_nav_cmd ) ) {
//no next waypoint to shoot for -- go ahead and break out of loiter
return true ;
2015-07-20 19:28:25 -03:00
}
if ( get_distance ( next_WP_loc , next_nav_cmd . content . location ) < labs ( g . loiter_radius ) ) {
/* Whenever next waypoint is within the loiter radius,
maintaining loiter would prevent us from ever pointing toward the next waypoint .
Hence break out of loiter immediately
*/
return true ;
}
2015-03-13 18:48:21 -03:00
// Bearing in radians
2015-04-23 18:39:25 -03:00
int32_t bearing_cd = get_bearing_cd ( current_loc , next_nav_cmd . content . location ) ;
2015-03-13 18:48:21 -03:00
2015-04-23 18:39:25 -03:00
// get current heading. We should probably be using the ground
// course instead to improve the accuracy in wind
int32_t heading_cd = ahrs . yaw_sensor ;
2015-03-13 18:48:21 -03:00
2015-04-23 18:39:25 -03:00
int32_t heading_err_cd = wrap_180_cd ( bearing_cd - heading_cd ) ;
2015-03-13 18:48:21 -03:00
2015-04-23 18:39:25 -03:00
/*
Check to see if the the plane is heading toward the land
waypoint
We use 10 degrees of slop so that we can handle 100
degrees / second of yaw
*/
if ( abs ( heading_err_cd ) < = 1000 ) {
2015-03-13 18:48:21 -03:00
//Want to head in a straight line from _here_ to the next waypoint.
//DON'T want to head in a line from the center of the loiter to
//the next waypoint.
//Therefore: mark the "last" (next_wp_loc is about to be updated)
//wp lat/lon as the current location.
next_WP_loc = current_loc ;
return true ;
} else {
return false ;
}
}
return true ;
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_RTL ( )
2011-09-08 22:29:39 -03:00
{
2013-04-11 21:25:46 -03:00
update_loiter ( ) ;
2015-01-01 00:17:45 -04:00
if ( auto_state . wp_distance < = ( uint32_t ) max ( g . waypoint_radius , 0 ) | |
2013-04-11 21:25:46 -03:00
nav_controller - > reached_loiter_target ( ) ) {
gcs_send_text_P ( SEVERITY_LOW , PSTR ( " Reached home " ) ) ;
return true ;
} else {
2012-08-16 21:50:15 -03:00
return false ;
2013-04-11 21:25:46 -03:00
}
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_continue_and_change_alt ( )
2014-10-21 17:46:01 -03:00
{
if ( abs ( adjusted_altitude_cm ( ) - next_WP_loc . alt ) < = 500 ) {
return true ;
}
2014-10-25 17:43:03 -03:00
2014-11-24 19:39:29 -04:00
// Is the next_WP less than 200 m away?
2015-04-11 06:43:13 -03:00
if ( get_distance ( current_loc , next_WP_loc ) < 200.0f ) {
2014-10-25 17:43:03 -03:00
//push another 300 m down the line
int32_t next_wp_bearing_cd = get_bearing_cd ( prev_WP_loc , next_WP_loc ) ;
2015-04-11 06:43:13 -03:00
location_update ( next_WP_loc , next_wp_bearing_cd * 0.01f , 300.0f ) ;
2014-10-25 17:43:03 -03:00
}
2014-10-21 17:46:01 -03:00
//keep flying the same course
nav_controller - > update_waypoint ( prev_WP_loc , next_WP_loc ) ;
return false ;
}
2015-06-13 06:12:54 -03:00
/*
see if we have reached altitude or descent speed
*/
bool Plane : : verify_altitude_wait ( const AP_Mission : : Mission_Command & cmd )
{
if ( current_loc . alt > cmd . content . altitude_wait . altitude * 100.0f ) {
gcs_send_text_P ( SEVERITY_LOW , PSTR ( " Reached altitude " ) ) ;
return true ;
}
if ( auto_state . sink_rate > cmd . content . altitude_wait . descent_rate ) {
2015-07-05 04:26:30 -03:00
gcs_send_text_fmt ( PSTR ( " Reached descent rate %.1f m/s " ) , ( double ) auto_state . sink_rate ) ;
2015-06-13 06:12:54 -03:00
return true ;
}
// if requested, wiggle servos
if ( cmd . content . altitude_wait . wiggle_time ! = 0 ) {
static uint32_t last_wiggle_ms ;
if ( auto_state . idle_wiggle_stage = = 0 & &
hal . scheduler - > millis ( ) - last_wiggle_ms > cmd . content . altitude_wait . wiggle_time * 1000 ) {
auto_state . idle_wiggle_stage = 1 ;
last_wiggle_ms = hal . scheduler - > millis ( ) ;
}
// idle_wiggle_stage is updated in set_servos_idle()
}
return false ;
}
2011-09-08 22:29:39 -03:00
/********************************************************************************/
// Condition (May) commands
/********************************************************************************/
2015-05-13 03:09:36 -03:00
void Plane : : do_wait_delay ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2015-05-13 19:05:32 -03:00
condition_start = millis ( ) ;
2014-03-17 02:16:45 -03:00
condition_value = cmd . content . delay . seconds * 1000 ; // convert seconds to milliseconds
2011-09-08 22:29:39 -03:00
}
2014-07-24 04:54:58 -03:00
/*
process a DO_CHANGE_ALT request
*/
2015-05-13 03:09:36 -03:00
void Plane : : do_change_alt ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 02:16:45 -03:00
condition_rate = labs ( ( int ) cmd . content . location . lat ) ; // climb rate in cm/s
condition_value = cmd . content . location . alt ; // To-Do: ensure this altitude is an absolute altitude?
2012-09-19 03:22:53 -03:00
if ( condition_value < adjusted_altitude_cm ( ) ) {
condition_rate = - condition_rate ;
}
2014-07-24 03:21:30 -03:00
set_target_altitude_current_adjusted ( ) ;
change_target_altitude ( condition_rate / 10 ) ;
2014-03-17 02:16:45 -03:00
next_WP_loc . alt = condition_value ; // For future nav calculations
2014-07-24 03:21:30 -03:00
reset_offset_altitude ( ) ;
2014-12-03 03:31:23 -04:00
setup_glide_slope ( ) ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_within_distance ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 02:16:45 -03:00
condition_value = cmd . content . distance . meters ;
2011-09-08 22:29:39 -03:00
}
/********************************************************************************/
// Verify Condition (May) commands
/********************************************************************************/
2015-05-13 03:09:36 -03:00
bool Plane : : verify_wait_delay ( )
2011-09-08 22:29:39 -03:00
{
2015-05-13 19:05:32 -03:00
if ( ( unsigned ) ( millis ( ) - condition_start ) > ( unsigned ) condition_value ) {
2012-08-16 21:50:15 -03:00
condition_value = 0 ;
return true ;
}
return false ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_change_alt ( )
2011-09-08 22:29:39 -03:00
{
2012-09-19 03:22:53 -03:00
if ( ( condition_rate > = 0 & & adjusted_altitude_cm ( ) > = condition_value ) | |
( condition_rate < = 0 & & adjusted_altitude_cm ( ) < = condition_value ) ) {
2012-08-16 21:50:15 -03:00
condition_value = 0 ;
return true ;
}
2014-07-24 03:21:30 -03:00
// condition_rate is climb rate in cm/s.
// We divide by 10 because this function is called at 10hz
change_target_altitude ( condition_rate / 10 ) ;
2012-08-16 21:50:15 -03:00
return false ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
bool Plane : : verify_within_distance ( )
2011-09-08 22:29:39 -03:00
{
2015-01-01 00:17:45 -04:00
if ( auto_state . wp_distance < max ( condition_value , 0 ) ) {
2012-08-16 21:50:15 -03:00
condition_value = 0 ;
return true ;
}
return false ;
2011-09-08 22:29:39 -03:00
}
/********************************************************************************/
// Do (Now) commands
/********************************************************************************/
2015-05-13 03:09:36 -03:00
void Plane : : do_loiter_at_location ( )
2011-09-08 22:29:39 -03:00
{
2013-04-14 09:04:25 -03:00
if ( g . loiter_radius < 0 ) {
2013-04-15 08:31:11 -03:00
loiter . direction = - 1 ;
2013-04-14 09:04:25 -03:00
} else {
2013-04-15 08:31:11 -03:00
loiter . direction = 1 ;
2013-04-14 09:04:25 -03:00
}
2014-03-16 01:53:10 -03:00
next_WP_loc = current_loc ;
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_change_speed ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-17 02:16:45 -03:00
switch ( cmd . content . speed . speed_type )
2012-08-16 21:50:15 -03:00
{
case 0 : // Airspeed
2014-03-17 02:16:45 -03:00
if ( cmd . content . speed . target_ms > 0 ) {
g . airspeed_cruise_cm . set ( cmd . content . speed . target_ms * 100 ) ;
gcs_send_text_fmt ( PSTR ( " Set airspeed %u m/s " ) , ( unsigned ) cmd . content . speed . target_ms ) ;
2012-08-16 21:50:15 -03:00
}
break ;
case 1 : // Ground speed
2014-03-17 02:16:45 -03:00
gcs_send_text_fmt ( PSTR ( " Set groundspeed %u " ) , ( unsigned ) cmd . content . speed . target_ms ) ;
g . min_gndspeed_cm . set ( cmd . content . speed . target_ms * 100 ) ;
2012-08-16 21:50:15 -03:00
break ;
}
2011-09-08 22:29:39 -03:00
2014-03-18 23:13:47 -03:00
if ( cmd . content . speed . throttle_pct > 0 & & cmd . content . speed . throttle_pct < = 100 ) {
2014-03-17 02:16:45 -03:00
gcs_send_text_fmt ( PSTR ( " Set throttle %u " ) , ( unsigned ) cmd . content . speed . throttle_pct ) ;
aparm . throttle_cruise . set ( cmd . content . speed . throttle_pct ) ;
2012-09-12 00:09:32 -03:00
}
2011-09-08 22:29:39 -03:00
}
2015-05-13 03:09:36 -03:00
void Plane : : do_set_home ( const AP_Mission : : Mission_Command & cmd )
2011-09-08 22:29:39 -03:00
{
2014-03-28 16:52:48 -03:00
if ( cmd . p1 = = 1 & & gps . status ( ) > = AP_GPS : : GPS_OK_FIX_3D ) {
2012-08-16 21:50:15 -03:00
init_home ( ) ;
} else {
2014-03-28 16:52:48 -03:00
ahrs . set_home ( cmd . content . location ) ;
2015-02-20 19:14:18 -04:00
home_is_set = HOME_SET_NOT_LOCKED ;
2015-07-05 23:01:17 -03:00
Log_Write_Home_And_Origin ( ) ;
2012-08-16 21:50:15 -03:00
}
2011-09-08 22:29:39 -03:00
}
2015-03-29 15:49:10 -03:00
// do_digicam_configure Send Digicam Configure message with the camera library
2015-05-13 03:09:36 -03:00
void Plane : : do_digicam_configure ( const AP_Mission : : Mission_Command & cmd )
2015-03-29 15:49:10 -03:00
{
# if CAMERA == ENABLED
camera . configure_cmd ( cmd ) ;
# endif
}
// do_digicam_control Send Digicam Control message with the camera library
2015-05-13 03:09:36 -03:00
void Plane : : do_digicam_control ( const AP_Mission : : Mission_Command & cmd )
2015-03-29 15:49:10 -03:00
{
# if CAMERA == ENABLED
camera . control_cmd ( cmd ) ;
log_picture ( ) ;
# endif
}
2013-04-01 23:08:23 -03:00
// do_take_picture - take a picture with the camera library
2015-05-13 03:09:36 -03:00
void Plane : : do_take_picture ( )
2013-04-01 23:08:23 -03:00
{
# if CAMERA == ENABLED
2015-03-29 15:49:10 -03:00
camera . trigger_pic ( true ) ;
log_picture ( ) ;
# endif
}
// log_picture - log picture taken and send feedback to GCS
2015-05-13 03:09:36 -03:00
void Plane : : log_picture ( )
2015-03-29 15:49:10 -03:00
{
2015-07-29 23:17:48 -03:00
# if CAMERA == ENABLED
2014-11-10 21:23:17 -04:00
gcs_send_message ( MSG_CAMERA_FEEDBACK ) ;
2014-01-13 22:07:43 -04:00
if ( should_log ( MASK_LOG_CAMERA ) ) {
2014-06-10 23:58:30 -03:00
DataFlash . Log_Write_Camera ( ahrs , gps , current_loc ) ;
2013-07-09 23:23:36 -03:00
}
2015-07-29 23:17:48 -03:00
# endif
2013-04-01 23:08:23 -03:00
}
2014-03-13 23:48:58 -03:00
2014-03-17 04:09:29 -03:00
// start_command_callback - callback function called from ap-mission when it begins a new mission command
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
2015-05-13 03:09:36 -03:00
bool Plane : : start_command_callback ( const AP_Mission : : Mission_Command & cmd )
2014-03-17 04:09:29 -03:00
{
if ( control_mode = = AUTO ) {
return start_command ( cmd ) ;
}
return true ;
}
// verify_command_callback - callback function called from ap-mission at 10hz or higher when a command is being run
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
2015-05-13 03:09:36 -03:00
bool Plane : : verify_command_callback ( const AP_Mission : : Mission_Command & cmd )
2014-03-13 23:48:58 -03:00
{
if ( control_mode = = AUTO ) {
2015-07-20 03:11:34 -03:00
bool cmd_complete = verify_command ( cmd ) ;
// send message to GCS
if ( cmd_complete ) {
gcs_send_mission_item_reached_message ( cmd . index ) ;
}
return cmd_complete ;
2014-03-13 23:48:58 -03:00
}
return false ;
}
2014-03-17 04:09:29 -03:00
// exit_mission_callback - callback function called from ap-mission when the mission has completed
// we double check that the flight mode is AUTO to avoid the possibility of ap-mission triggering actions while we're not in AUTO mode
2015-05-13 03:09:36 -03:00
void Plane : : exit_mission_callback ( )
2014-03-13 23:48:58 -03:00
{
if ( control_mode = = AUTO ) {
gcs_send_text_fmt ( PSTR ( " Returning to Home " ) ) ;
2014-03-16 01:53:10 -03:00
memset ( & auto_rtl_command , 0 , sizeof ( auto_rtl_command ) ) ;
2014-04-18 16:19:13 -03:00
auto_rtl_command . content . location =
2014-07-24 03:21:30 -03:00
rally . calc_best_rally_or_home_location ( current_loc , get_RTL_altitude ( ) ) ;
2014-03-14 10:08:56 -03:00
auto_rtl_command . id = MAV_CMD_NAV_LOITER_UNLIM ;
2014-07-24 04:54:58 -03:00
setup_terrain_target_alt ( auto_rtl_command . content . location ) ;
2014-08-04 06:58:12 -03:00
update_flight_stage ( ) ;
2014-03-13 23:48:58 -03:00
setup_glide_slope ( ) ;
2014-07-24 03:21:30 -03:00
setup_turn_angle ( ) ;
2014-03-14 10:08:56 -03:00
start_command ( auto_rtl_command ) ;
2014-03-13 23:48:58 -03:00
}
}