2014-01-23 01:14:58 -04:00
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-05-29 23:12:49 -03:00
# include "Copter.h"
2014-01-23 01:14:58 -04:00
/*
2014-01-28 09:44:53 -04:00
* control_auto . pde - init and run calls for auto flight mode
2014-01-24 22:37:42 -04:00
*
* This file contains the implementation for Land , Waypoint navigation and Takeoff from Auto mode
* Command execution code ( i . e . command_logic . pde ) should :
2014-01-27 23:20:39 -04:00
* a ) switch to Auto flight mode with set_mode ( ) function . This will cause auto_init to be called
* b ) call one of the three auto initialisation functions : auto_wp_start ( ) , auto_takeoff_start ( ) , auto_land_start ( )
2014-01-24 22:37:42 -04:00
* c ) call one of the verify functions auto_wp_verify ( ) , auto_takeoff_verify , auto_land_verify repeated to check if the command has completed
* The main loop ( i . e . fast loop ) will call update_flight_modes ( ) which will in turn call auto_run ( ) which , based upon the auto_mode variable will call
* correct auto_wp_run , auto_takeoff_run or auto_land_run to actually implement the feature
*/
/*
* While in the auto flight mode , navigation or do / now commands can be run .
2014-01-27 23:20:39 -04:00
* Code in this file implements the navigation commands
2014-01-23 01:14:58 -04:00
*/
// auto_init - initialise auto controller
2015-05-29 23:12:49 -03:00
bool Copter : : auto_init ( bool ignore_checks )
2014-01-23 01:14:58 -04:00
{
2015-01-05 04:56:05 -04:00
if ( ( position_ok ( ) & & mission . num_commands ( ) > 1 ) | | ignore_checks ) {
2014-10-12 05:06:51 -03:00
auto_mode = Auto_Loiter ;
2014-02-18 08:35:29 -04:00
// stop ROI from carrying over from previous runs of the mission
// To-Do: reset the yaw as part of auto_wp_start when the previous command was not a wp command to remove the need for this special ROI check
if ( auto_yaw_mode = = AUTO_YAW_ROI ) {
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
2014-05-07 03:03:26 -03:00
// initialise waypoint and spline controller
wp_nav . wp_and_spline_init ( ) ;
2014-10-13 05:41:48 -03:00
// clear guided limits
guided_limit_clear ( ) ;
2014-05-15 04:20:02 -03:00
// start/resume the mission (based on MIS_RESTART parameter)
2014-05-03 15:26:58 -03:00
mission . start_or_resume ( ) ;
2014-01-23 01:14:58 -04:00
return true ;
} else {
return false ;
}
}
// auto_run - runs the auto controller
// should be called at 100hz or more
// relies on run_autopilot being called at 10hz which handles decision making and non-navigation related commands
2015-05-29 23:12:49 -03:00
void Copter : : auto_run ( )
2014-01-23 01:14:58 -04:00
{
2014-01-24 22:37:42 -04:00
// call the correct auto controller
switch ( auto_mode ) {
2014-01-25 04:25:17 -04:00
case Auto_TakeOff :
2014-01-24 22:37:42 -04:00
auto_takeoff_run ( ) ;
break ;
2014-01-25 04:25:17 -04:00
case Auto_WP :
2014-04-16 04:23:24 -03:00
case Auto_CircleMoveToEdge :
2014-01-24 22:37:42 -04:00
auto_wp_run ( ) ;
break ;
2014-01-25 04:25:17 -04:00
case Auto_Land :
2014-01-24 22:37:42 -04:00
auto_land_run ( ) ;
break ;
2014-01-27 10:43:48 -04:00
2014-01-27 23:20:39 -04:00
case Auto_RTL :
auto_rtl_run ( ) ;
break ;
2014-01-27 10:43:48 -04:00
case Auto_Circle :
auto_circle_run ( ) ;
break ;
2014-03-22 00:48:54 -03:00
case Auto_Spline :
auto_spline_run ( ) ;
break ;
2014-05-23 02:29:08 -03:00
case Auto_NavGuided :
2014-10-16 09:30:07 -03:00
# if NAV_GUIDED == ENABLED
2014-05-23 02:29:08 -03:00
auto_nav_guided_run ( ) ;
# endif
2014-10-16 09:30:07 -03:00
break ;
2014-10-12 05:06:51 -03:00
case Auto_Loiter :
auto_loiter_run ( ) ;
break ;
2014-01-24 22:37:42 -04:00
}
}
// auto_takeoff_start - initialises waypoint controller to implement take-off
2015-05-29 23:12:49 -03:00
void Copter : : auto_takeoff_start ( float final_alt_above_home )
2014-01-24 22:37:42 -04:00
{
2014-01-25 04:25:17 -04:00
auto_mode = Auto_TakeOff ;
2014-01-24 22:37:42 -04:00
// initialise wpnav destination
Vector3f target_pos = inertial_nav . get_position ( ) ;
2015-02-10 08:33:07 -04:00
target_pos . z = pv_alt_above_origin ( final_alt_above_home ) ;
2014-01-24 22:37:42 -04:00
wp_nav . set_wp_destination ( target_pos ) ;
// initialise yaw
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
2014-02-03 09:04:35 -04:00
2015-07-01 22:37:12 -03:00
// clear i term when we're taking off
set_throttle_takeoff ( ) ;
2014-01-24 22:37:42 -04:00
}
// auto_takeoff_run - takeoff in auto mode
// called by auto_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : auto_takeoff_run ( )
2014-01-24 22:37:42 -04:00
{
2015-04-17 14:49:08 -03:00
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if ( ! ap . auto_armed | | ! motors . get_interlock ( ) ) {
2014-09-29 03:26:54 -03:00
// initialise wpnav targets
wp_nav . shift_wp_origin_to_current_pos ( ) ;
2015-07-01 15:38:32 -03:00
# if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
attitude_control . angle_ef_roll_pitch_rate_ef_yaw_smooth ( 0 , 0 , 0 , get_smoothing_gain ( ) ) ;
attitude_control . set_throttle_out ( 0 , false , g . throttle_filt ) ;
2015-07-15 07:47:46 -03:00
# else // multicopters do not stabilize roll/pitch/yaw when disarmed
2014-01-24 22:37:42 -04:00
// reset attitude control targets
2015-04-16 01:54:29 -03:00
attitude_control . set_throttle_out_unstabilized ( 0 , true , g . throttle_filt ) ;
2015-07-01 15:38:32 -03:00
# endif
2015-07-01 22:37:12 -03:00
// clear i term when we're taking off
set_throttle_takeoff ( ) ;
2014-01-24 22:37:42 -04:00
return ;
}
// process pilot's yaw input
2014-01-23 01:14:58 -04:00
float target_yaw_rate = 0 ;
2014-01-24 22:37:42 -04:00
if ( ! failsafe . radio ) {
// get pilot's desired yaw rate
2015-05-11 23:24:13 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > control_in ) ;
2014-01-24 22:37:42 -04:00
}
// run waypoint controller
wp_nav . update_wpnav ( ) ;
// call z-axis position controller (wpnav should have already updated it's alt target)
pos_control . update_z_controller ( ) ;
// roll & pitch from waypoint controller, yaw rate from pilot
2014-02-13 22:56:46 -04:00
attitude_control . angle_ef_roll_pitch_rate_ef_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , target_yaw_rate ) ;
2014-01-24 22:37:42 -04:00
}
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
2015-05-29 23:12:49 -03:00
void Copter : : auto_wp_start ( const Vector3f & destination )
2014-01-24 22:37:42 -04:00
{
2014-01-25 04:25:17 -04:00
auto_mode = Auto_WP ;
2014-01-24 22:37:42 -04:00
// initialise wpnav
wp_nav . set_wp_destination ( destination ) ;
// initialise yaw
2014-02-18 08:35:29 -04:00
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
if ( auto_yaw_mode ! = AUTO_YAW_ROI ) {
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
}
2014-01-24 22:37:42 -04:00
}
2014-01-23 01:14:58 -04:00
2014-01-24 22:37:42 -04:00
// auto_wp_run - runs the auto waypoint controller
// called by auto_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : auto_wp_run ( )
2014-01-24 22:37:42 -04:00
{
2015-04-17 14:49:08 -03:00
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if ( ! ap . auto_armed | | ! motors . get_interlock ( ) ) {
2014-01-24 22:37:42 -04:00
// To-Do: reset waypoint origin to current location because copter is probably on the ground so we don't want it lurching left or right on take-off
// (of course it would be better if people just used take-off)
2015-07-01 15:38:32 -03:00
# if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
attitude_control . angle_ef_roll_pitch_rate_ef_yaw_smooth ( 0 , 0 , 0 , get_smoothing_gain ( ) ) ;
attitude_control . set_throttle_out ( 0 , false , g . throttle_filt ) ;
2015-07-15 07:47:46 -03:00
# else // multicopters do not stabilize roll/pitch/yaw when disarmed
2015-04-16 01:54:29 -03:00
attitude_control . set_throttle_out_unstabilized ( 0 , true , g . throttle_filt ) ;
2015-07-01 15:38:32 -03:00
# endif
2015-07-01 22:37:12 -03:00
// clear i term when we're taking off
set_throttle_takeoff ( ) ;
2014-01-23 01:14:58 -04:00
return ;
}
// process pilot's yaw input
2014-01-24 22:37:42 -04:00
float target_yaw_rate = 0 ;
2014-01-23 01:14:58 -04:00
if ( ! failsafe . radio ) {
// get pilot's desired yaw rate
2015-05-19 10:38:57 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > control_in ) ;
2015-05-04 23:34:21 -03:00
if ( ! is_zero ( target_yaw_rate ) ) {
2014-01-23 01:14:58 -04:00
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
}
// run waypoint controller
wp_nav . update_wpnav ( ) ;
// call z-axis position controller (wpnav should have already updated it's alt target)
2014-03-22 00:48:54 -03:00
pos_control . update_z_controller ( ) ;
// call attitude controller
if ( auto_yaw_mode = = AUTO_YAW_HOLD ) {
// roll & pitch from waypoint controller, yaw rate from pilot
attitude_control . angle_ef_roll_pitch_rate_ef_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , target_yaw_rate ) ;
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
attitude_control . angle_ef_roll_pitch_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , get_auto_heading ( ) , true ) ;
}
}
// auto_spline_start - initialises waypoint controller to implement flying to a particular destination using the spline controller
2014-03-29 05:52:38 -03:00
// seg_end_type can be SEGMENT_END_STOP, SEGMENT_END_STRAIGHT or SEGMENT_END_SPLINE. If Straight or Spline the next_destination should be provided
2015-05-29 23:12:49 -03:00
void Copter : : auto_spline_start ( const Vector3f & destination , bool stopped_at_start ,
AC_WPNav : : spline_segment_end_type seg_end_type ,
const Vector3f & next_destination )
2014-03-22 00:48:54 -03:00
{
auto_mode = Auto_Spline ;
// initialise wpnav
2014-03-29 05:52:38 -03:00
wp_nav . set_spline_destination ( destination , stopped_at_start , seg_end_type , next_destination ) ;
2014-03-22 00:48:54 -03:00
// initialise yaw
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
if ( auto_yaw_mode ! = AUTO_YAW_ROI ) {
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
}
}
// auto_spline_run - runs the auto spline controller
// called by auto_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : auto_spline_run ( )
2014-03-22 00:48:54 -03:00
{
2015-04-17 14:49:08 -03:00
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if ( ! ap . auto_armed | | ! motors . get_interlock ( ) ) {
2014-03-22 00:48:54 -03:00
// To-Do: reset waypoint origin to current location because copter is probably on the ground so we don't want it lurching left or right on take-off
// (of course it would be better if people just used take-off)
2015-07-01 15:38:32 -03:00
# if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
attitude_control . angle_ef_roll_pitch_rate_ef_yaw_smooth ( 0 , 0 , 0 , get_smoothing_gain ( ) ) ;
attitude_control . set_throttle_out ( 0 , false , g . throttle_filt ) ;
2015-07-15 07:47:46 -03:00
# else // multicopters do not stabilize roll/pitch/yaw when disarmed
2015-04-16 01:54:29 -03:00
attitude_control . set_throttle_out_unstabilized ( 0 , true , g . throttle_filt ) ;
2015-07-01 15:38:32 -03:00
# endif
2015-07-01 22:37:12 -03:00
// clear i term when we're taking off
set_throttle_takeoff ( ) ;
2014-03-22 00:48:54 -03:00
return ;
}
// process pilot's yaw input
float target_yaw_rate = 0 ;
if ( ! failsafe . radio ) {
2015-05-19 10:38:57 -03:00
// get pilot's desired yaw rat
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > control_in ) ;
2015-05-04 23:34:21 -03:00
if ( ! is_zero ( target_yaw_rate ) ) {
2014-03-22 00:48:54 -03:00
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
}
// run waypoint controller
wp_nav . update_spline ( ) ;
// call z-axis position controller (wpnav should have already updated it's alt target)
2014-01-23 01:14:58 -04:00
pos_control . update_z_controller ( ) ;
// call attitude controller
if ( auto_yaw_mode = = AUTO_YAW_HOLD ) {
// roll & pitch from waypoint controller, yaw rate from pilot
2014-02-13 22:56:46 -04:00
attitude_control . angle_ef_roll_pitch_rate_ef_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , target_yaw_rate ) ;
2014-01-23 01:14:58 -04:00
} else {
// roll, pitch from waypoint controller, yaw heading from auto_heading()
2014-03-23 08:41:32 -03:00
attitude_control . angle_ef_roll_pitch_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , get_auto_heading ( ) , true ) ;
2014-01-23 01:14:58 -04:00
}
2014-01-24 22:37:42 -04:00
}
// auto_land_start - initialises controller to implement a landing
2015-05-29 23:12:49 -03:00
void Copter : : auto_land_start ( )
2014-01-24 22:37:42 -04:00
{
2014-01-25 00:40:32 -04:00
// set target to stopping point
Vector3f stopping_point ;
wp_nav . get_loiter_stopping_point_xy ( stopping_point ) ;
2014-01-24 22:37:42 -04:00
// call location specific land start function
2014-01-25 00:40:32 -04:00
auto_land_start ( stopping_point ) ;
2014-01-24 22:37:42 -04:00
}
// auto_land_start - initialises controller to implement a landing
2015-05-29 23:12:49 -03:00
void Copter : : auto_land_start ( const Vector3f & destination )
2014-01-24 22:37:42 -04:00
{
2014-01-25 04:25:17 -04:00
auto_mode = Auto_Land ;
2014-01-24 22:37:42 -04:00
2014-01-25 00:40:32 -04:00
// initialise loiter target destination
2014-05-15 10:19:18 -03:00
wp_nav . init_loiter_target ( destination ) ;
2014-01-25 00:40:32 -04:00
// initialise altitude target to stopping point
pos_control . set_target_to_stopping_point_z ( ) ;
2014-01-24 22:37:42 -04:00
// initialise yaw
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
// auto_land_run - lands in auto mode
// called by auto_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : auto_land_run ( )
2014-01-24 22:37:42 -04:00
{
2014-07-06 06:05:43 -03:00
int16_t roll_control = 0 , pitch_control = 0 ;
float target_yaw_rate = 0 ;
2015-04-17 14:49:08 -03:00
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
2014-06-10 10:32:48 -03:00
if ( ! ap . auto_armed | | ap . land_complete ) {
2015-07-01 15:38:32 -03:00
# if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
attitude_control . angle_ef_roll_pitch_rate_ef_yaw_smooth ( 0 , 0 , 0 , get_smoothing_gain ( ) ) ;
attitude_control . set_throttle_out ( 0 , false , g . throttle_filt ) ;
2015-07-15 07:47:46 -03:00
# else // multicopters do not stabilize roll/pitch/yaw when disarmed
2015-04-16 01:54:29 -03:00
attitude_control . set_throttle_out_unstabilized ( 0 , true , g . throttle_filt ) ;
2015-07-01 15:38:32 -03:00
# endif
2014-01-25 00:40:32 -04:00
// set target to current position
wp_nav . init_loiter_target ( ) ;
2014-01-24 22:37:42 -04:00
return ;
}
2014-09-19 04:28:11 -03:00
// relax loiter targets if we might be landed
2015-05-06 01:38:38 -03:00
if ( ap . land_complete_maybe ) {
2014-08-29 03:25:37 -03:00
wp_nav . loiter_soften_for_landing ( ) ;
}
2014-07-06 06:05:43 -03:00
// process pilot's input
2014-01-24 22:37:42 -04:00
if ( ! failsafe . radio ) {
2014-07-06 06:05:43 -03:00
if ( g . land_repositioning ) {
// apply SIMPLE mode transform to pilot inputs
update_simple_mode ( ) ;
// process pilot's roll and pitch input
2015-05-11 23:24:13 -03:00
roll_control = channel_roll - > control_in ;
pitch_control = channel_pitch - > control_in ;
2014-07-06 06:05:43 -03:00
}
2014-01-24 22:37:42 -04:00
// get pilot's desired yaw rate
2015-05-11 23:24:13 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > control_in ) ;
2014-01-24 22:37:42 -04:00
}
2014-07-06 06:05:43 -03:00
// process roll, pitch inputs
wp_nav . set_pilot_desired_acceleration ( roll_control , pitch_control ) ;
2014-01-25 00:40:32 -04:00
// run loiter controller
2014-11-15 23:06:05 -04:00
wp_nav . update_loiter ( ekfGndSpdLimit , ekfNavVelGainScaler ) ;
2014-01-24 22:37:42 -04:00
2014-01-25 00:40:32 -04:00
// call z-axis position controller
2014-12-18 03:13:48 -04:00
float cmb_rate = get_land_descent_speed ( ) ;
2014-12-18 00:11:28 -04:00
pos_control . set_alt_target_from_climb_rate ( cmb_rate , G_Dt , true ) ;
2014-01-24 22:37:42 -04:00
pos_control . update_z_controller ( ) ;
2014-12-18 03:13:48 -04:00
// record desired climb rate for logging
2014-12-18 00:11:28 -04:00
desired_climb_rate = cmb_rate ;
2014-01-24 22:37:42 -04:00
// roll & pitch from waypoint controller, yaw rate from pilot
2014-02-13 22:56:46 -04:00
attitude_control . angle_ef_roll_pitch_rate_ef_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , target_yaw_rate ) ;
2014-01-23 01:14:58 -04:00
}
2014-01-27 23:20:39 -04:00
// auto_rtl_start - initialises RTL in AUTO flight mode
2015-05-29 23:12:49 -03:00
void Copter : : auto_rtl_start ( )
2014-01-27 23:20:39 -04:00
{
auto_mode = Auto_RTL ;
// call regular rtl flight mode initialisation and ask it to ignore checks
rtl_init ( true ) ;
}
// auto_rtl_run - rtl in AUTO flight mode
// called by auto_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : auto_rtl_run ( )
2014-01-27 23:20:39 -04:00
{
// call regular rtl flight mode run function
rtl_run ( ) ;
}
2014-04-16 04:23:24 -03:00
// auto_circle_movetoedge_start - initialise waypoint controller to move to edge of a circle with it's center at the specified location
// we assume the caller has set the circle's circle with circle_nav.set_center()
// we assume the caller has performed all required GPS_ok checks
2015-05-29 23:12:49 -03:00
void Copter : : auto_circle_movetoedge_start ( )
2014-04-16 04:23:24 -03:00
{
// check our distance from edge of circle
Vector3f circle_edge ;
circle_nav . get_closest_point_on_circle ( circle_edge ) ;
// set the state to move to the edge of the circle
auto_mode = Auto_CircleMoveToEdge ;
// initialise wpnav to move to edge of circle
wp_nav . set_wp_destination ( circle_edge ) ;
// if we are outside the circle, point at the edge, otherwise hold yaw
const Vector3f & curr_pos = inertial_nav . get_position ( ) ;
const Vector3f & circle_center = circle_nav . get_center ( ) ;
float dist_to_center = pythagorous2 ( circle_center . x - curr_pos . x , circle_center . y - curr_pos . y ) ;
if ( dist_to_center > circle_nav . get_radius ( ) & & dist_to_center > 500 ) {
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
} else {
// vehicle is within circle so hold yaw to avoid spinning as we move to edge of circle
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
}
2014-01-27 10:43:48 -04:00
// auto_circle_start - initialises controller to fly a circle in AUTO flight mode
2015-05-29 23:12:49 -03:00
void Copter : : auto_circle_start ( )
2014-01-27 10:43:48 -04:00
{
2014-01-27 23:20:39 -04:00
auto_mode = Auto_Circle ;
2014-04-16 04:23:24 -03:00
// initialise circle controller
// center was set in do_circle so initialise with current center
circle_nav . init ( circle_nav . get_center ( ) ) ;
2014-01-27 10:43:48 -04:00
}
// auto_circle_run - circle in AUTO flight mode
// called by auto_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : auto_circle_run ( )
2014-01-27 10:43:48 -04:00
{
// call circle controller
circle_nav . update ( ) ;
// call z-axis position controller
pos_control . update_z_controller ( ) ;
// roll & pitch from waypoint controller, yaw rate from pilot
2014-02-13 22:56:46 -04:00
attitude_control . angle_ef_roll_pitch_yaw ( circle_nav . get_roll ( ) , circle_nav . get_pitch ( ) , circle_nav . get_yaw ( ) , true ) ;
2014-01-27 10:43:48 -04:00
}
2014-05-23 02:29:08 -03:00
# if NAV_GUIDED == ENABLED
// auto_nav_guided_start - hand over control to external navigation controller in AUTO mode
2015-05-29 23:12:49 -03:00
void Copter : : auto_nav_guided_start ( )
2014-05-23 02:29:08 -03:00
{
auto_mode = Auto_NavGuided ;
// call regular guided flight mode initialisation
guided_init ( true ) ;
2014-10-13 05:41:48 -03:00
// initialise guided start time and position as reference for limit checking
guided_limit_init_time_and_pos ( ) ;
2014-05-23 02:29:08 -03:00
}
// auto_nav_guided_run - allows control by external navigation controller
// called by auto_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : auto_nav_guided_run ( )
2014-05-23 02:29:08 -03:00
{
// call regular guided flight mode run function
guided_run ( ) ;
}
# endif // NAV_GUIDED
2014-10-19 22:54:57 -03:00
// auto_loiter_start - initialises loitering in auto mode
// returns success/failure because this can be called by exit_mission
2015-05-29 23:12:49 -03:00
bool Copter : : auto_loiter_start ( )
2014-10-12 05:06:51 -03:00
{
2014-10-19 22:54:57 -03:00
// return failure if GPS is bad
2015-01-02 07:43:50 -04:00
if ( ! position_ok ( ) ) {
2014-10-12 05:06:51 -03:00
return false ;
}
auto_mode = Auto_Loiter ;
Vector3f origin = inertial_nav . get_position ( ) ;
2014-10-19 22:54:57 -03:00
// calculate stopping point
2014-10-12 05:06:51 -03:00
Vector3f stopping_point ;
pos_control . get_stopping_point_xy ( stopping_point ) ;
pos_control . get_stopping_point_z ( stopping_point ) ;
2014-10-19 22:54:57 -03:00
// initialise waypoint controller target to stopping point
2014-10-12 05:06:51 -03:00
wp_nav . set_wp_origin_and_destination ( origin , stopping_point ) ;
2014-10-19 22:54:57 -03:00
// hold yaw at current heading
2014-10-12 05:06:51 -03:00
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
return true ;
}
2014-10-19 22:54:57 -03:00
// auto_loiter_run - loiter in AUTO flight mode
// called by auto_run at 100hz or more
2015-05-29 23:12:49 -03:00
void Copter : : auto_loiter_run ( )
2014-10-19 22:54:57 -03:00
{
2015-04-17 14:49:08 -03:00
// if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
if ( ! ap . auto_armed | | ap . land_complete | | ! motors . get_interlock ( ) ) {
2015-07-01 15:38:32 -03:00
# if FRAME_CONFIG == HELI_FRAME // Helicopters always stabilize roll/pitch/yaw
// call attitude controller
attitude_control . angle_ef_roll_pitch_rate_ef_yaw_smooth ( 0 , 0 , 0 , get_smoothing_gain ( ) ) ;
attitude_control . set_throttle_out ( 0 , false , g . throttle_filt ) ;
2015-07-15 07:47:46 -03:00
# else // multicopters do not stabilize roll/pitch/yaw when disarmed
2015-04-16 01:54:29 -03:00
attitude_control . set_throttle_out_unstabilized ( 0 , true , g . throttle_filt ) ;
2015-07-01 15:38:32 -03:00
# endif
2014-10-12 05:06:51 -03:00
return ;
}
2014-10-19 22:54:57 -03:00
// accept pilot input of yaw
2014-10-12 05:06:51 -03:00
float target_yaw_rate = 0 ;
if ( ! failsafe . radio ) {
2015-05-11 23:24:13 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > control_in ) ;
2014-10-12 05:06:51 -03:00
}
2014-10-19 22:54:57 -03:00
// run waypoint and z-axis postion controller
2014-10-12 05:06:51 -03:00
wp_nav . update_wpnav ( ) ;
pos_control . update_z_controller ( ) ;
attitude_control . angle_ef_roll_pitch_rate_ef_yaw ( wp_nav . get_roll ( ) , wp_nav . get_pitch ( ) , target_yaw_rate ) ;
}
2014-01-23 01:14:58 -04:00
// get_default_auto_yaw_mode - returns auto_yaw_mode based on WP_YAW_BEHAVIOR parameter
// set rtl parameter to true if this is during an RTL
2015-05-29 23:12:49 -03:00
uint8_t Copter : : get_default_auto_yaw_mode ( bool rtl )
2014-01-23 01:14:58 -04:00
{
switch ( g . wp_yaw_behavior ) {
2014-04-17 04:52:24 -03:00
case WP_YAW_BEHAVIOR_NONE :
return AUTO_YAW_HOLD ;
break ;
2014-01-23 01:14:58 -04:00
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL :
if ( rtl ) {
return AUTO_YAW_HOLD ;
} else {
return AUTO_YAW_LOOK_AT_NEXT_WP ;
}
break ;
case WP_YAW_BEHAVIOR_LOOK_AHEAD :
return AUTO_YAW_LOOK_AHEAD ;
break ;
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP :
default :
return AUTO_YAW_LOOK_AT_NEXT_WP ;
break ;
}
}
// set_auto_yaw_mode - sets the yaw mode for auto
2015-05-29 23:12:49 -03:00
void Copter : : set_auto_yaw_mode ( uint8_t yaw_mode )
2014-01-23 01:14:58 -04:00
{
// return immediately if no change
if ( auto_yaw_mode = = yaw_mode ) {
return ;
}
auto_yaw_mode = yaw_mode ;
// perform initialisation
switch ( auto_yaw_mode ) {
case AUTO_YAW_LOOK_AT_NEXT_WP :
2014-03-23 08:41:32 -03:00
// wpnav will initialise heading when wpnav's set_destination method is called
2014-01-23 01:14:58 -04:00
break ;
2014-02-18 08:35:29 -04:00
case AUTO_YAW_ROI :
2014-01-23 01:14:58 -04:00
// point towards a location held in yaw_look_at_WP
yaw_look_at_WP_bearing = ahrs . yaw_sensor ;
break ;
case AUTO_YAW_LOOK_AT_HEADING :
2014-04-17 04:14:18 -03:00
// keep heading pointing in the direction held in yaw_look_at_heading
// caller should set the yaw_look_at_heading
2014-01-23 01:14:58 -04:00
break ;
case AUTO_YAW_LOOK_AHEAD :
// Commanded Yaw to automatically look ahead.
yaw_look_ahead_bearing = ahrs . yaw_sensor ;
break ;
case AUTO_YAW_RESETTOARMEDYAW :
// initial_armed_bearing will be set during arming so no init required
break ;
}
}
2014-10-20 23:52:22 -03:00
// set_auto_yaw_look_at_heading - sets the yaw look at heading for auto mode
2015-05-29 23:12:49 -03:00
void Copter : : set_auto_yaw_look_at_heading ( float angle_deg , float turn_rate_dps , int8_t direction , uint8_t relative_angle )
2014-06-13 06:17:35 -03:00
{
// get current yaw target
int32_t curr_yaw_target = attitude_control . angle_ef_targets ( ) . z ;
// get final angle, 1 = Relative, 0 = Absolute
if ( relative_angle = = 0 ) {
// absolute angle
yaw_look_at_heading = wrap_360_cd ( angle_deg * 100 ) ;
} else {
// relative angle
2014-09-26 00:20:40 -03:00
if ( direction < 0 ) {
angle_deg = - angle_deg ;
}
yaw_look_at_heading = wrap_360_cd ( ( angle_deg * 100 + curr_yaw_target ) ) ;
2014-06-13 06:17:35 -03:00
}
// get turn speed
2015-05-04 23:34:21 -03:00
if ( is_zero ( turn_rate_dps ) ) {
2014-06-13 06:17:35 -03:00
// 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 ) / turn_rate_dps ;
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 and counter clockwise rotation held in cmd.content.yaw.direction. 1 = clockwise, -1 = counterclockwise
}
2014-07-04 03:40:12 -03:00
// set_auto_yaw_roi - sets the yaw to look at roi for auto mode
2015-05-29 23:12:49 -03:00
void Copter : : set_auto_yaw_roi ( const Location & roi_location )
2014-07-04 03:40:12 -03:00
{
// if location is zero lat, lon and altitude turn off ROI
2014-10-18 19:19:47 -03:00
if ( roi_location . alt = = 0 & & roi_location . lat = = 0 & & roi_location . lng = = 0 ) {
2014-07-04 03:40:12 -03:00
// set auto yaw mode back to default assuming the active command is a waypoint command. A more sophisticated method is required to ensure we return to the proper yaw control for the active command
set_auto_yaw_mode ( get_default_auto_yaw_mode ( false ) ) ;
# if MOUNT == ENABLED
// switch off the camera tracking if enabled
if ( camera_mount . get_mode ( ) = = MAV_MOUNT_MODE_GPS_POINT ) {
camera_mount . set_mode_to_default ( ) ;
}
# endif // MOUNT == ENABLED
} else {
# if MOUNT == ENABLED
// check if mount type requires us to rotate the quad
2015-01-11 02:37:26 -04:00
if ( ! camera_mount . has_pan_control ( ) ) {
2014-07-04 03:40:12 -03:00
roi_WP = pv_location_to_vector ( roi_location ) ;
set_auto_yaw_mode ( AUTO_YAW_ROI ) ;
}
// send the command to the camera mount
2015-01-08 16:11:55 -04:00
camera_mount . set_roi_target ( roi_location ) ;
2014-07-04 03:40:12 -03:00
// 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
roi_WP = pv_location_to_vector ( roi_location ) ;
set_auto_yaw_mode ( AUTO_YAW_ROI ) ;
# endif // MOUNT == ENABLED
}
}
2014-01-23 01:14:58 -04:00
// get_auto_heading - returns target heading depending upon auto_yaw_mode
// 100hz update rate
2015-05-29 23:12:49 -03:00
float Copter : : get_auto_heading ( void )
2014-01-23 01:14:58 -04:00
{
switch ( auto_yaw_mode ) {
2014-02-18 08:35:29 -04:00
case AUTO_YAW_ROI :
// point towards a location held in roi_WP
return get_roi_yaw ( ) ;
2014-01-23 01:14:58 -04:00
break ;
case AUTO_YAW_LOOK_AT_HEADING :
// keep heading pointing in the direction held in yaw_look_at_heading with no pilot input allowed
return yaw_look_at_heading ;
break ;
case AUTO_YAW_LOOK_AHEAD :
// Commanded Yaw to automatically look ahead.
return get_look_ahead_yaw ( ) ;
break ;
case AUTO_YAW_RESETTOARMEDYAW :
// changes yaw to be same as when quad was armed
2014-01-24 02:48:07 -04:00
return initial_armed_bearing ;
2014-01-23 01:14:58 -04:00
break ;
case AUTO_YAW_LOOK_AT_NEXT_WP :
default :
// point towards next waypoint.
// we don't use wp_bearing because we don't want the copter to turn too much during flight
2014-03-23 08:41:32 -03:00
return wp_nav . get_yaw ( ) ;
2014-01-23 01:14:58 -04:00
break ;
}
}