2015-05-29 23:12:49 -03:00
# include "Copter.h"
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
2014-01-23 01:14:58 -04:00
/*
2016-07-25 15:45:29 -03:00
* 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
*/
2018-02-07 22:21:09 -04:00
// update mission
void Copter : : ModeAuto : : run_autopilot ( )
{
copter . mission . update ( ) ;
}
uint32_t Copter : : ModeAuto : : wp_distance ( ) const
{
return wp_nav - > get_wp_distance_to_destination ( ) ;
}
int32_t Copter : : ModeAuto : : wp_bearing ( ) const
{
return wp_nav - > get_wp_bearing_to_destination ( ) ;
}
2014-01-23 01:14:58 -04:00
// auto_init - initialise auto controller
2017-12-10 23:51:13 -04:00
bool Copter : : ModeAuto : : init ( bool ignore_checks )
2014-01-23 01:14:58 -04:00
{
2018-02-07 22:21:09 -04:00
if ( ( copter . position_ok ( ) & & copter . mission . num_commands ( ) > 1 ) | | ignore_checks ) {
2016-03-21 00:45:50 -03:00
_mode = Auto_Loiter ;
2014-10-12 05:06:51 -03:00
2017-01-05 14:07:14 -04:00
// reject switching to auto mode if landed with motors armed but first command is not a takeoff (reduce chance of flips)
2018-02-07 22:21:09 -04:00
if ( motors - > armed ( ) & & ap . land_complete & & ! copter . mission . starts_with_takeoff_cmd ( ) ) {
2017-07-08 21:56:49 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_CRITICAL , " Auto: Missing Takeoff Cmd " ) ;
2016-05-19 07:34:07 -03:00
return false ;
}
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
2018-02-07 22:21:09 -04:00
if ( copter . auto_yaw_mode = = AUTO_YAW_ROI ) {
2014-02-18 08:35:29 -04:00
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
2014-05-07 03:03:26 -03:00
// initialise waypoint and spline controller
2017-01-09 03:31:26 -04:00
wp_nav - > wp_and_spline_init ( ) ;
2014-05-07 03:03:26 -03:00
2014-10-13 05:41:48 -03:00
// clear guided limits
2018-02-07 22:21:09 -04:00
copter . mode_guided . limit_clear ( ) ;
2014-10-13 05:41:48 -03:00
2014-05-15 04:20:02 -03:00
// start/resume the mission (based on MIS_RESTART parameter)
2018-02-07 22:21:09 -04:00
copter . mission . start_or_resume ( ) ;
2014-01-23 01:14:58 -04:00
return true ;
2017-11-09 15:20:53 -04:00
} else {
2014-01-23 01:14:58 -04:00
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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : run ( )
2014-01-23 01:14:58 -04:00
{
2014-01-24 22:37:42 -04:00
// call the correct auto controller
2016-03-21 00:45:50 -03:00
switch ( _mode ) {
2014-01-24 22:37:42 -04:00
2014-01-25 04:25:17 -04:00
case Auto_TakeOff :
2016-03-21 00:45:50 -03:00
takeoff_run ( ) ;
2014-01-24 22:37:42 -04:00
break ;
2014-01-25 04:25:17 -04:00
case Auto_WP :
2014-04-16 04:23:24 -03:00
case Auto_CircleMoveToEdge :
2016-03-21 00:45:50 -03:00
wp_run ( ) ;
2014-01-24 22:37:42 -04:00
break ;
2014-01-25 04:25:17 -04:00
case Auto_Land :
2016-03-21 00:45:50 -03:00
land_run ( ) ;
2014-01-24 22:37:42 -04:00
break ;
2014-01-27 10:43:48 -04:00
2014-01-27 23:20:39 -04:00
case Auto_RTL :
2016-03-21 00:45:50 -03:00
rtl_run ( ) ;
2014-01-27 23:20:39 -04:00
break ;
2014-01-27 10:43:48 -04:00
case Auto_Circle :
2016-03-21 00:45:50 -03:00
circle_run ( ) ;
2014-01-27 10:43:48 -04:00
break ;
2014-03-22 00:48:54 -03:00
case Auto_Spline :
2016-03-21 00:45:50 -03:00
spline_run ( ) ;
2014-03-22 00:48:54 -03:00
break ;
2014-05-23 02:29:08 -03:00
case Auto_NavGuided :
2014-10-16 09:30:07 -03:00
# if NAV_GUIDED == ENABLED
2016-03-21 00:45:50 -03:00
nav_guided_run ( ) ;
2014-05-23 02:29:08 -03:00
# endif
2014-10-16 09:30:07 -03:00
break ;
2014-10-12 05:06:51 -03:00
case Auto_Loiter :
2016-03-21 00:45:50 -03:00
loiter_run ( ) ;
2014-10-12 05:06:51 -03:00
break ;
2016-11-17 01:19:22 -04:00
case Auto_NavPayloadPlace :
2016-03-21 00:45:50 -03:00
payload_place_run ( ) ;
2016-11-17 01:19:22 -04:00
break ;
2014-01-24 22:37:42 -04:00
}
}
// auto_takeoff_start - initialises waypoint controller to implement take-off
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : takeoff_start ( const Location & dest_loc )
2014-01-24 22:37:42 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_TakeOff ;
2014-01-24 22:37:42 -04:00
2015-10-05 05:23:58 -03:00
// convert location to class
Location_Class dest ( dest_loc ) ;
// set horizontal target
2018-02-07 22:21:09 -04:00
dest . lat = copter . current_loc . lat ;
dest . lng = copter . current_loc . lng ;
2015-10-05 05:23:58 -03:00
// get altitude target
int32_t alt_target ;
if ( ! dest . get_alt_cm ( Location_Class : : ALT_FRAME_ABOVE_HOME , alt_target ) ) {
// this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data
2018-02-07 22:21:09 -04:00
copter . Log_Write_Error ( ERROR_SUBSYSTEM_TERRAIN , ERROR_CODE_MISSING_TERRAIN_DATA ) ;
2015-10-05 05:23:58 -03:00
// fall back to altitude above current altitude
2018-02-07 22:21:09 -04:00
alt_target = copter . current_loc . alt + dest . alt ;
2015-10-05 05:23:58 -03:00
}
// sanity check target
2018-02-07 22:21:09 -04:00
if ( alt_target < copter . current_loc . alt ) {
dest . set_alt_cm ( copter . current_loc . alt , Location_Class : : ALT_FRAME_ABOVE_HOME ) ;
2015-10-05 05:23:58 -03:00
}
// Note: if taking off from below home this could cause a climb to an unexpectedly high altitude
if ( alt_target < 100 ) {
2016-04-28 07:53:45 -03:00
dest . set_alt_cm ( 100 , Location_Class : : ALT_FRAME_ABOVE_HOME ) ;
2015-10-05 05:23:58 -03:00
}
// set waypoint controller target
2017-01-09 03:31:26 -04:00
if ( ! wp_nav - > set_wp_destination ( dest ) ) {
2016-04-22 08:45:28 -03:00
// failure to set destination can only be because of missing terrain data
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_on_event ( ) ;
2015-10-05 05:23:58 -03:00
return ;
}
2014-01-24 22:37:42 -04:00
// 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 ( ) ;
2016-06-04 23:37:55 -03:00
2016-08-15 00:57:38 -03:00
// get initial alt for WP_NAVALT_MIN
2018-02-07 22:21:09 -04:00
copter . auto_takeoff_set_start_alt ( ) ;
2014-01-24 22:37:42 -04:00
}
// auto_takeoff_run - takeoff in auto mode
// called by auto_run at 100hz or more
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : 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
2017-01-09 03:31:26 -04:00
if ( ! motors - > armed ( ) | | ! ap . auto_armed | | ! motors - > get_interlock ( ) ) {
2014-09-29 03:26:54 -03:00
// initialise wpnav targets
2017-01-09 03:31:26 -04:00
wp_nav - > shift_wp_origin_to_current_pos ( ) ;
2016-11-17 01:47:41 -04:00
zero_throttle_and_relax_ac ( ) ;
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 ;
2018-02-07 22:21:09 -04:00
if ( ! copter . failsafe . radio ) {
2014-01-24 22:37:42 -04:00
// get pilot's desired yaw rate
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
2014-01-24 22:37:42 -04:00
}
2016-11-30 23:10:32 -04:00
# if FRAME_CONFIG == HELI_FRAME
// helicopters stay in landed state until rotor speed runup has finished
2017-01-09 03:31:26 -04:00
if ( motors - > rotor_runup_complete ( ) ) {
2016-11-30 23:10:32 -04:00
set_land_complete ( false ) ;
} else {
// initialise wpnav targets
2017-01-09 03:31:26 -04:00
wp_nav - > shift_wp_origin_to_current_pos ( ) ;
2016-11-30 23:10:32 -04:00
}
# else
set_land_complete ( false ) ;
# endif
2016-01-13 03:09:03 -04:00
// set motors to full range
2017-01-09 03:31:26 -04:00
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-01-13 03:09:03 -04:00
2014-01-24 22:37:42 -04:00
// run waypoint controller
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
2014-01-24 22:37:42 -04:00
// call z-axis position controller (wpnav should have already updated it's alt target)
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2014-01-24 22:37:42 -04:00
2016-06-04 23:37:55 -03:00
// call attitude controller
2018-02-07 22:21:09 -04:00
copter . auto_takeoff_attitude_run ( target_yaw_rate ) ;
2014-01-24 22:37:42 -04:00
}
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : wp_start ( const Vector3f & destination )
2014-01-24 22:37:42 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_WP ;
2014-01-24 22:37:42 -04:00
2016-04-22 08:45:28 -03:00
// initialise wpnav (no need to check return status because terrain data is not used)
2017-01-09 03:31:26 -04:00
wp_nav - > set_wp_destination ( destination , false ) ;
2014-01-24 22:37:42 -04:00
// 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
2018-02-07 22:21:09 -04:00
if ( copter . auto_yaw_mode ! = AUTO_YAW_ROI ) {
set_auto_yaw_mode ( copter . get_default_auto_yaw_mode ( false ) ) ;
2014-02-18 08:35:29 -04:00
}
2014-01-24 22:37:42 -04:00
}
2014-01-23 01:14:58 -04:00
2015-08-16 16:10:23 -03:00
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : wp_start ( const Location_Class & dest_loc )
2015-08-16 16:10:23 -03:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_WP ;
2015-08-16 16:10:23 -03:00
// send target to waypoint controller
2017-01-09 03:31:26 -04:00
if ( ! wp_nav - > set_wp_destination ( dest_loc ) ) {
2016-04-22 08:45:28 -03:00
// failure to set destination can only be because of missing terrain data
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_on_event ( ) ;
2016-05-07 04:26:49 -03:00
return ;
2015-08-16 16:10:23 -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
2018-02-07 22:21:09 -04:00
if ( copter . auto_yaw_mode ! = AUTO_YAW_ROI ) {
set_auto_yaw_mode ( copter . get_default_auto_yaw_mode ( false ) ) ;
2015-08-16 16:10:23 -03: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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : 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
2017-01-09 03:31:26 -04:00
if ( ! motors - > armed ( ) | | ! 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)
2016-11-17 01:47:41 -04:00
zero_throttle_and_relax_ac ( ) ;
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 ;
2018-02-07 22:21:09 -04:00
if ( ! copter . failsafe . radio ) {
2014-01-23 01:14:58 -04:00
// get pilot's desired yaw rate
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_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 ) ;
}
}
2016-01-13 03:09:03 -04:00
// set motors to full range
2017-01-09 03:31:26 -04:00
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-01-13 03:09:03 -04:00
2014-01-23 01:14:58 -04:00
// run waypoint controller
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
2014-01-23 01:14:58 -04:00
// call z-axis position controller (wpnav should have already updated it's alt target)
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2014-03-22 00:48:54 -03:00
// call attitude controller
2018-02-07 22:21:09 -04:00
if ( copter . auto_yaw_mode = = AUTO_YAW_HOLD ) {
2014-03-22 00:48:54 -03:00
// roll & pitch from waypoint controller, yaw rate from pilot
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
2017-11-09 15:20:53 -04:00
} else {
2014-03-22 00:48:54 -03:00
// roll, pitch from waypoint controller, yaw heading from auto_heading()
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , get_auto_heading ( ) , true ) ;
2014-03-22 00:48:54 -03:00
}
}
// 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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : spline_start ( const Location_Class & destination , bool stopped_at_start ,
2015-05-29 23:12:49 -03:00
AC_WPNav : : spline_segment_end_type seg_end_type ,
2016-03-11 03:45:00 -04:00
const Location_Class & next_destination )
2014-03-22 00:48:54 -03:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_Spline ;
2014-03-22 00:48:54 -03:00
// initialise wpnav
2017-01-09 03:31:26 -04:00
if ( ! wp_nav - > set_spline_destination ( destination , stopped_at_start , seg_end_type , next_destination ) ) {
2016-05-07 04:26:49 -03:00
// failure to set destination can only be because of missing terrain data
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_on_event ( ) ;
2016-05-07 04:26:49 -03:00
return ;
2016-03-11 03:45:00 -04:00
}
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
2018-02-07 22:21:09 -04:00
if ( copter . auto_yaw_mode ! = AUTO_YAW_ROI ) {
set_auto_yaw_mode ( copter . get_default_auto_yaw_mode ( false ) ) ;
2014-03-22 00:48:54 -03:00
}
}
// auto_spline_run - runs the auto spline controller
// called by auto_run at 100hz or more
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : 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
2017-01-09 03:31:26 -04:00
if ( ! motors - > armed ( ) | | ! 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)
2016-11-17 01:47:41 -04:00
zero_throttle_and_relax_ac ( ) ;
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 ;
2018-02-07 22:21:09 -04:00
if ( ! copter . failsafe . radio ) {
2015-05-19 10:38:57 -03:00
// get pilot's desired yaw rat
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_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 ) ;
}
}
2016-01-13 03:09:03 -04:00
// set motors to full range
2017-01-09 03:31:26 -04:00
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-01-13 03:09:03 -04:00
2014-03-22 00:48:54 -03:00
// run waypoint controller
2017-01-09 03:31:26 -04:00
wp_nav - > update_spline ( ) ;
2014-03-22 00:48:54 -03:00
// call z-axis position controller (wpnav should have already updated it's alt target)
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2014-01-23 01:14:58 -04:00
// call attitude controller
2018-02-07 22:21:09 -04:00
if ( copter . auto_yaw_mode = = AUTO_YAW_HOLD ) {
2014-01-23 01:14:58 -04:00
// roll & pitch from waypoint controller, yaw rate from pilot
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
2017-11-09 15:20:53 -04:00
} else {
2014-01-23 01:14:58 -04:00
// roll, pitch from waypoint controller, yaw heading from auto_heading()
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : 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 ;
2017-01-09 03:31:26 -04:00
wp_nav - > get_loiter_stopping_point_xy ( stopping_point ) ;
2014-01-24 22:37:42 -04:00
// call location specific land start function
2016-03-21 00:45:50 -03:00
land_start ( stopping_point ) ;
2014-01-24 22:37:42 -04:00
}
// auto_land_start - initialises controller to implement a landing
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : land_start ( const Vector3f & destination )
2014-01-24 22:37:42 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_Land ;
2014-01-24 22:37:42 -04:00
2014-01-25 00:40:32 -04:00
// initialise loiter target destination
2017-01-09 03:31:26 -04:00
wp_nav - > init_loiter_target ( destination ) ;
2014-01-25 00:40:32 -04:00
2016-07-07 21:41:38 -03:00
// initialise position and desired velocity
2017-01-09 03:31:26 -04:00
if ( ! pos_control - > is_active_z ( ) ) {
pos_control - > set_alt_target ( inertial_nav . get_altitude ( ) ) ;
pos_control - > set_desired_velocity_z ( inertial_nav . get_velocity_z ( ) ) ;
2016-10-14 09:28:32 -03:00
}
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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : land_run ( )
2014-01-24 22:37:42 -04:00
{
2016-07-07 21:41:38 -03:00
// if not auto armed or landed or motor interlock not enabled set throttle to zero and exit immediately
2017-01-09 03:31:26 -04:00
if ( ! motors - > armed ( ) | | ! ap . auto_armed | | ap . land_complete | | ! motors - > get_interlock ( ) ) {
2016-11-17 01:47:41 -04:00
zero_throttle_and_relax_ac ( ) ;
2014-01-25 00:40:32 -04:00
// set target to current position
2017-01-09 03:31:26 -04:00
wp_nav - > init_loiter_target ( ) ;
2014-01-24 22:37:42 -04:00
return ;
}
2016-01-13 03:09:03 -04:00
// set motors to full range
2017-01-09 03:31:26 -04:00
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-07-07 21:41:38 -03:00
2018-02-07 22:21:09 -04:00
copter . land_run_horizontal_control ( ) ;
copter . land_run_vertical_control ( ) ;
2016-03-21 00:45:50 -03:00
}
2017-12-06 07:18:34 -04:00
bool Copter : : ModeAuto : : landing_gear_should_be_deployed ( ) const
2016-03-21 00:45:50 -03:00
{
switch ( _mode ) {
case Auto_Land :
return true ;
case Auto_RTL :
2018-02-07 22:21:09 -04:00
return copter . mode_rtl . landing_gear_should_be_deployed ( ) ;
2016-03-21 00:45:50 -03:00
default :
return false ;
}
return false ;
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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : rtl_start ( )
2014-01-27 23:20:39 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_RTL ;
2014-01-27 23:20:39 -04:00
// call regular rtl flight mode initialisation and ask it to ignore checks
2018-02-07 22:21:09 -04:00
copter . mode_rtl . init ( true ) ;
2014-01-27 23:20:39 -04:00
}
// auto_rtl_run - rtl in AUTO flight mode
// called by auto_run at 100hz or more
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : rtl_run ( )
2014-01-27 23:20:39 -04:00
{
// call regular rtl flight mode run function
2018-02-07 22:21:09 -04:00
copter . mode_rtl . run ( false ) ;
2014-01-27 23:20:39 -04:00
}
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 performed all required GPS_ok checks
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : circle_movetoedge_start ( const Location_Class & circle_center , float radius_m )
2014-04-16 04:23:24 -03:00
{
2016-03-09 07:21:08 -04:00
// convert location to vector from ekf origin
Vector3f circle_center_neu ;
if ( ! circle_center . get_vector_from_origin_NEU ( circle_center_neu ) ) {
// default to current position and log error
circle_center_neu = inertial_nav . get_position ( ) ;
2018-02-07 22:21:09 -04:00
copter . Log_Write_Error ( ERROR_SUBSYSTEM_NAVIGATION , ERROR_CODE_FAILED_CIRCLE_INIT ) ;
2016-03-09 07:21:08 -04:00
}
2018-02-07 22:21:09 -04:00
copter . circle_nav - > set_center ( circle_center_neu ) ;
2014-04-16 04:23:24 -03:00
2016-03-09 07:21:08 -04:00
// set circle radius
if ( ! is_zero ( radius_m ) ) {
2018-02-07 22:21:09 -04:00
copter . circle_nav - > set_radius ( radius_m * 100.0f ) ;
2016-03-09 07:21:08 -04:00
}
2014-04-16 04:23:24 -03:00
2016-03-09 07:21:08 -04:00
// check our distance from edge of circle
Vector3f circle_edge_neu ;
2018-02-07 22:21:09 -04:00
copter . circle_nav - > get_closest_point_on_circle ( circle_edge_neu ) ;
2016-03-09 07:21:08 -04:00
float dist_to_edge = ( inertial_nav . get_position ( ) - circle_edge_neu ) . length ( ) ;
// if more than 3m then fly to edge
if ( dist_to_edge > 300.0f ) {
// set the state to move to the edge of the circle
2016-03-21 00:45:50 -03:00
_mode = Auto_CircleMoveToEdge ;
2016-03-09 07:21:08 -04:00
// convert circle_edge_neu to Location_Class
Location_Class circle_edge ( circle_edge_neu ) ;
// convert altitude to same as command
2016-04-28 07:53:45 -03:00
circle_edge . set_alt_cm ( circle_center . alt , circle_center . get_alt_frame ( ) ) ;
2016-03-09 07:21:08 -04:00
// initialise wpnav to move to edge of circle
2017-01-09 03:31:26 -04:00
if ( ! wp_nav - > set_wp_destination ( circle_edge ) ) {
2016-04-22 08:45:28 -03:00
// failure to set destination can only be because of missing terrain data
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_on_event ( ) ;
2016-03-09 07:21:08 -04:00
}
2014-04-16 04:23:24 -03:00
2016-03-09 07:21:08 -04:00
// if we are outside the circle, point at the edge, otherwise hold yaw
const Vector3f & curr_pos = inertial_nav . get_position ( ) ;
2016-04-16 06:58:46 -03:00
float dist_to_center = norm ( circle_center_neu . x - curr_pos . x , circle_center_neu . y - curr_pos . y ) ;
2018-02-07 22:21:09 -04:00
if ( dist_to_center > copter . circle_nav - > get_radius ( ) & & dist_to_center > 500 ) {
set_auto_yaw_mode ( copter . get_default_auto_yaw_mode ( false ) ) ;
2016-03-09 07:21:08 -04:00
} 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-04-16 04:23:24 -03:00
} else {
2016-03-21 00:45:50 -03:00
circle_start ( ) ;
2014-04-16 04:23:24 -03:00
}
}
2014-01-27 10:43:48 -04:00
// auto_circle_start - initialises controller to fly a circle in AUTO flight mode
2016-03-09 07:21:08 -04:00
// assumes that circle_nav object has already been initialised with circle center and radius
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : circle_start ( )
2014-01-27 10:43:48 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_Circle ;
2014-01-27 23:20:39 -04:00
2014-04-16 04:23:24 -03:00
// initialise circle controller
2018-02-07 22:21:09 -04:00
copter . circle_nav - > init ( copter . 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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : circle_run ( )
2014-01-27 10:43:48 -04:00
{
// call circle controller
2018-02-07 22:21:09 -04:00
copter . circle_nav - > update ( ) ;
2014-01-27 10:43:48 -04:00
// call z-axis position controller
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2014-01-27 10:43:48 -04:00
// roll & pitch from waypoint controller, yaw rate from pilot
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( copter . circle_nav - > get_roll ( ) , copter . circle_nav - > get_pitch ( ) , copter . 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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : nav_guided_start ( )
2014-05-23 02:29:08 -03:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_NavGuided ;
2014-05-23 02:29:08 -03:00
// call regular guided flight mode initialisation
2018-02-07 22:21:09 -04:00
copter . mode_guided . init ( true ) ;
2014-10-13 05:41:48 -03:00
// initialise guided start time and position as reference for limit checking
2018-02-07 22:21:09 -04:00
copter . mode_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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : nav_guided_run ( )
2014-05-23 02:29:08 -03:00
{
// call regular guided flight mode run function
2018-02-07 22:21:09 -04:00
copter . mode_guided . run ( ) ;
2014-05-23 02:29:08 -03:00
}
# 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
2017-12-10 23:51:13 -04:00
bool Copter : : ModeAuto : : loiter_start ( )
2014-10-12 05:06:51 -03:00
{
2014-10-19 22:54:57 -03:00
// return failure if GPS is bad
2018-02-07 22:21:09 -04:00
if ( ! copter . position_ok ( ) ) {
2014-10-12 05:06:51 -03:00
return false ;
}
2016-03-21 00:45:50 -03:00
_mode = Auto_Loiter ;
2014-10-12 05:06:51 -03:00
2014-10-19 22:54:57 -03:00
// calculate stopping point
2014-10-12 05:06:51 -03:00
Vector3f stopping_point ;
2017-04-27 03:55:13 -03:00
wp_nav - > get_wp_stopping_point ( stopping_point ) ;
2014-10-12 05:06:51 -03:00
2014-10-19 22:54:57 -03:00
// initialise waypoint controller target to stopping point
2017-04-27 03:55:13 -03:00
wp_nav - > set_wp_destination ( stopping_point ) ;
2014-10-12 05:06:51 -03:00
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
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : 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
2017-01-09 03:31:26 -04:00
if ( ! motors - > armed ( ) | | ! ap . auto_armed | | ap . land_complete | | ! motors - > get_interlock ( ) ) {
2016-11-17 01:47:41 -04:00
zero_throttle_and_relax_ac ( ) ;
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 ;
2018-02-07 22:21:09 -04:00
if ( ! copter . failsafe . radio ) {
ArduCopter: Fix up after refactoring RC_Channel class
Further to refactor of RC_Channel class which included
adding get_xx set_xx methods, change reads and writes to the public members
to calls to get and set functionsss
old public member(int16_t) get function -> int16_t set function (int16_t)
(expression where c is an object of type RC_Channel)
c.radio_in c.get_radio_in() c.set_radio_in(v)
c.control_in c.get_control_in() c.set_control_in(v)
c.servo_out c.get_servo_out() c.set_servo_out(v)
c.pwm_out c.get_pwm_out() // use existing
c.radio_out c.get_radio_out() c.set_radio_out(v)
c.radio_max c.get_radio_max() c.set_radio_max(v)
c.radio_min c.get_radio_min() c.set_radio_min(v)
c.radio_trim c.get_radio_trim() c.set_radio_trim(v);
c.min_max_configured() // return true if min and max are configured
Because data members of RC_Channels are now private and so cannot be written directly
some overloads are provided in the Plane classes to provide the old functionality
new overload Plane::stick_mix_channel(RC_Channel *channel)
which forwards to the previously existing
void stick_mix_channel(RC_Channel *channel, int16_t &servo_out);
new overload Plane::channel_output_mixer(Rc_Channel* , RC_Channel*)const
which forwards to
(uint8_t mixing_type, int16_t & chan1, int16_t & chan2)const;
Rename functions
RC_Channel_aux::set_radio_trim(Aux_servo_function_t function)
to RC_Channel_aux::set_trim_to_radio_in_for(Aux_servo_function_t function)
RC_Channel_aux::set_servo_out(Aux_servo_function_t function, int16_t value)
to RC_Channel_aux::set_servo_out_for(Aux_servo_function_t function, int16_t value)
Rationale:
RC_Channel is a complicated class, which combines
several functionalities dealing with stick inputs
in pwm and logical units, logical and actual actuator
outputs, unit conversion etc, etc
The intent of this PR is to clarify existing use of
the class. At the basic level it should now be possible
to grep all places where private variable is set by
searching for the set_xx function.
(The wider purpose is to provide a more generic and
logically simpler method of output mixing. This is a small step)
2016-05-08 05:46:59 -03:00
target_yaw_rate = get_pilot_desired_yaw_rate ( channel_yaw - > get_control_in ( ) ) ;
2014-10-12 05:06:51 -03:00
}
2016-01-13 03:09:03 -04:00
// set motors to full range
2017-01-09 03:31:26 -04:00
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-01-13 03:09:03 -04:00
2016-03-11 04:15:47 -04:00
// run waypoint and z-axis position controller
2018-02-07 22:21:09 -04:00
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
2016-04-22 08:45:28 -03:00
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
2014-10-12 05:06:51 -03:00
}
2018-02-21 22:06:07 -04:00
# endif
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 ;
2014-01-23 01:14:58 -04:00
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL :
if ( rtl ) {
return AUTO_YAW_HOLD ;
2017-11-09 15:20:53 -04:00
} else {
2014-01-23 01:14:58 -04:00
return AUTO_YAW_LOOK_AT_NEXT_WP ;
}
case WP_YAW_BEHAVIOR_LOOK_AHEAD :
return AUTO_YAW_LOOK_AHEAD ;
case WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP :
default :
return AUTO_YAW_LOOK_AT_NEXT_WP ;
}
}
// 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 ;
2017-07-10 09:51:43 -03:00
case AUTO_YAW_RATE :
// initialise target yaw rate to zero
auto_yaw_rate_cds = 0.0f ;
break ;
2014-01-23 01:14:58 -04:00
}
}
2014-10-20 23:52:22 -03:00
// set_auto_yaw_look_at_heading - sets the yaw look at heading for auto mode
2017-07-11 02:04:58 -03:00
void Copter : : set_auto_yaw_look_at_heading ( float angle_deg , float turn_rate_dps , int8_t direction , bool relative_angle )
2014-06-13 06:17:35 -03:00
{
// get current yaw target
2017-01-09 03:31:26 -04:00
int32_t curr_yaw_target = attitude_control - > get_att_target_euler_cd ( ) . z ;
2014-06-13 06:17:35 -03:00
2017-07-11 23:37:03 -03:00
// calculate final angle as relative to vehicle heading or absolute
2017-07-11 02:04:58 -03:00
if ( ! relative_angle ) {
2014-06-13 06:17:35 -03:00
// 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 ;
}
2016-12-01 11:50:14 -04:00
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 ;
2017-11-09 15:20:53 -04:00
} else {
2014-06-13 06:17:35 -03:00
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
2017-11-09 15:20:53 -04:00
} else {
2014-07-04 03:40:12 -03:00
# 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
}
}
2017-07-10 09:51:43 -03:00
// set auto yaw rate in centi-degrees per second
void Copter : : set_auto_yaw_rate ( float turn_rate_cds )
{
set_auto_yaw_mode ( AUTO_YAW_RATE ) ;
auto_yaw_rate_cds = turn_rate_cds ;
}
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
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 ;
case AUTO_YAW_LOOK_AHEAD :
// Commanded Yaw to automatically look ahead.
return get_look_ahead_yaw ( ) ;
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
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
2017-01-09 03:31:26 -04:00
return wp_nav - > get_yaw ( ) ;
2014-01-23 01:14:58 -04:00
}
}
2017-07-10 09:51:43 -03:00
// returns yaw rate held in auto_yaw_rate and normally set by SET_POSITION_TARGET mavlink messages (positive it clockwise, negative is counter clockwise)
float Copter : : get_auto_yaw_rate_cds ( void )
{
if ( auto_yaw_mode = = AUTO_YAW_RATE ) {
return auto_yaw_rate_cds ;
}
// return zero turn rate (this should never happen)
return 0.0f ;
}
2018-02-21 22:06:07 -04:00
# if MODE_AUTO_ENABLED == ENABLED
2016-11-17 01:19:22 -04:00
// auto_payload_place_start - initialises controller to implement a placing
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : payload_place_start ( )
2016-11-17 01:19:22 -04:00
{
// set target to stopping point
Vector3f stopping_point ;
2017-01-09 03:31:26 -04:00
wp_nav - > get_loiter_stopping_point_xy ( stopping_point ) ;
2016-11-17 01:19:22 -04:00
// call location specific place start function
2016-03-21 00:45:50 -03:00
payload_place_start ( stopping_point ) ;
2016-11-17 01:19:22 -04:00
}
// auto_payload_place_start - initialises controller to implement placement of a load
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : payload_place_start ( const Vector3f & destination )
2016-11-17 01:19:22 -04:00
{
2016-03-21 00:45:50 -03:00
_mode = Auto_NavPayloadPlace ;
2017-12-10 22:50:49 -04:00
nav_payload_place . state = PayloadPlaceStateType_Calibrating_Hover_Start ;
2016-11-17 01:19:22 -04:00
// initialise loiter target destination
2017-01-09 03:31:26 -04:00
wp_nav - > init_loiter_target ( destination ) ;
2016-11-17 01:19:22 -04:00
// initialise position and desired velocity
2017-01-09 03:31:26 -04:00
if ( ! pos_control - > is_active_z ( ) ) {
pos_control - > set_alt_target ( inertial_nav . get_altitude ( ) ) ;
pos_control - > set_desired_velocity_z ( inertial_nav . get_velocity_z ( ) ) ;
2016-11-17 01:19:22 -04:00
}
// initialise yaw
set_auto_yaw_mode ( AUTO_YAW_HOLD ) ;
}
2017-12-10 23:51:13 -04:00
bool Copter : : ModeAuto : : payload_place_run_should_run ( )
2016-11-17 01:19:22 -04:00
{
// muts be armed
2017-01-09 03:31:26 -04:00
if ( ! motors - > armed ( ) ) {
2016-11-17 01:19:22 -04:00
return false ;
}
// muts be auto-armed
if ( ! ap . auto_armed ) {
return false ;
}
// must not be landed
if ( ap . land_complete ) {
return false ;
}
// interlock must be enabled (i.e. unsafe)
2017-01-09 03:31:26 -04:00
if ( ! motors - > get_interlock ( ) ) {
2016-11-17 01:19:22 -04:00
return false ;
}
return true ;
}
// auto_payload_place_run - places an object in auto mode
// called by auto_run at 100hz or more
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : payload_place_run ( )
2016-11-17 01:19:22 -04:00
{
2016-03-21 00:45:50 -03:00
if ( ! payload_place_run_should_run ( ) ) {
2017-12-28 22:36:18 -04:00
zero_throttle_and_relax_ac ( ) ;
2016-11-17 01:19:22 -04:00
// set target to current position
2017-01-09 03:31:26 -04:00
wp_nav - > init_loiter_target ( ) ;
2016-11-17 01:19:22 -04:00
return ;
}
// set motors to full range
2017-01-09 03:31:26 -04:00
motors - > set_desired_spool_state ( AP_Motors : : DESIRED_THROTTLE_UNLIMITED ) ;
2016-11-17 01:19:22 -04:00
2017-12-10 22:50:49 -04:00
switch ( nav_payload_place . state ) {
2016-11-17 01:19:22 -04:00
case PayloadPlaceStateType_FlyToLocation :
case PayloadPlaceStateType_Calibrating_Hover_Start :
case PayloadPlaceStateType_Calibrating_Hover :
2016-03-21 00:45:50 -03:00
return payload_place_run_loiter ( ) ;
2016-11-17 01:19:22 -04:00
case PayloadPlaceStateType_Descending_Start :
case PayloadPlaceStateType_Descending :
2016-03-21 00:45:50 -03:00
return payload_place_run_descend ( ) ;
2016-11-17 01:19:22 -04:00
case PayloadPlaceStateType_Releasing_Start :
case PayloadPlaceStateType_Releasing :
case PayloadPlaceStateType_Released :
case PayloadPlaceStateType_Ascending_Start :
case PayloadPlaceStateType_Ascending :
case PayloadPlaceStateType_Done :
2016-03-21 00:45:50 -03:00
return payload_place_run_loiter ( ) ;
2016-11-17 01:19:22 -04:00
}
}
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : payload_place_run_loiter ( )
2016-11-17 01:19:22 -04:00
{
// loiter...
2018-02-07 22:21:09 -04:00
copter . land_run_horizontal_control ( ) ;
2016-11-17 01:19:22 -04:00
// run loiter controller
2017-01-09 03:31:26 -04:00
wp_nav - > update_loiter ( ekfGndSpdLimit , ekfNavVelGainScaler ) ;
2016-11-17 01:19:22 -04:00
// call attitude controller
const float target_yaw_rate = 0 ;
2017-06-26 05:48:04 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( wp_nav - > get_roll ( ) , wp_nav - > get_pitch ( ) , target_yaw_rate ) ;
2016-11-17 01:19:22 -04:00
2017-01-05 02:25:10 -04:00
// call position controller
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2016-11-17 01:19:22 -04:00
}
2017-12-10 23:51:13 -04:00
void Copter : : ModeAuto : : payload_place_run_descend ( )
2016-11-17 01:19:22 -04:00
{
2018-02-07 22:21:09 -04:00
copter . land_run_horizontal_control ( ) ;
copter . land_run_vertical_control ( ) ;
2016-11-17 01:19:22 -04:00
}
2018-02-21 22:06:07 -04:00
# endif