2015-05-29 23:12:49 -03:00
# include "Copter.h"
2019-02-25 10:32:52 -04:00
# if MODE_GUIDED_ENABLED == ENABLED
2014-01-28 09:44:37 -04:00
/*
2016-07-25 15:45:29 -03:00
* Init and run calls for guided flight mode
2014-01-28 09:44:37 -04:00
*/
2021-06-17 22:20:26 -03:00
static Vector3p guided_pos_target_cm ; // position target (used by posvel controller only)
2021-06-25 22:10:03 -03:00
bool guided_pos_terrain_alt ; // true if guided_pos_target_cm.z is an alt above terrain
2021-05-11 01:33:13 -03:00
static Vector3f guided_vel_target_cms ; // velocity target (used by pos_vel_accel controller and vel_accel controller)
static Vector3f guided_accel_target_cmss ; // acceleration target (used by pos_vel_accel controller vel_accel controller and accel controller)
static uint32_t update_time_ms ; // system time of last target update to pos_vel_accel, vel_accel or accel controller
2014-11-25 16:15:45 -04:00
2015-10-08 08:13:53 -03:00
struct {
uint32_t update_time_ms ;
2022-01-18 14:01:02 -04:00
Quaternion attitude_quat ;
Vector3f ang_vel ;
2016-08-02 14:20:57 -03:00
float yaw_rate_cds ;
2020-07-27 06:18:34 -03:00
float climb_rate_cms ; // climb rate in cms. Used if use_thrust is false
float thrust ; // thrust from -1 to 1. Used if use_thrust is true
2016-08-02 14:20:57 -03:00
bool use_yaw_rate ;
2020-07-27 06:18:34 -03:00
bool use_thrust ;
2017-07-10 09:51:43 -03:00
} static guided_angle_state ;
2015-10-08 08:13:53 -03:00
2014-10-13 05:41:48 -03:00
struct Guided_Limit {
uint32_t timeout_ms ; // timeout (in seconds) from the time that guided is invoked
float alt_min_cm ; // lower altitude limit in cm above home (0 = no limit)
float alt_max_cm ; // upper altitude limit in cm above home (0 = no limit)
float horiz_max_cm ; // horizontal position limit in cm from where guided mode was initiated (0 = no limit)
uint32_t start_time ; // system time in milliseconds that control was handed to the external computer
Vector3f start_pos ; // start position as a distance from home in cm. used for checking horiz_max limit
} guided_limit ;
2021-05-11 01:33:13 -03:00
// init - initialise guided controller
2019-05-09 23:18:49 -03:00
bool ModeGuided : : init ( bool ignore_checks )
2014-01-28 09:44:37 -04:00
{
2021-05-11 01:33:13 -03:00
// start in velaccel control mode
velaccel_control_start ( ) ;
guided_vel_target_cms . zero ( ) ;
guided_accel_target_cmss . zero ( ) ;
2021-03-05 03:03:56 -04:00
send_notification = false ;
2022-01-27 14:36:21 -04:00
// clear pause state when entering guided mode
_paused = false ;
2019-02-28 20:52:28 -04:00
return true ;
2014-01-28 09:44:37 -04:00
}
2021-05-11 01:33:13 -03:00
// run - runs the guided controller
2020-10-14 02:30:01 -03:00
// should be called at 100hz or more
void ModeGuided : : run ( )
{
2022-01-27 14:36:21 -04:00
// run pause control if the vehicle is paused
if ( _paused ) {
pause_control_run ( ) ;
return ;
}
2022-01-27 05:00:15 -04:00
2020-10-14 02:30:01 -03:00
// call the correct auto controller
switch ( guided_mode ) {
2021-03-30 00:36:25 -03:00
case SubMode : : TakeOff :
2020-10-14 02:30:01 -03:00
// run takeoff controller
takeoff_run ( ) ;
break ;
2021-03-30 00:36:25 -03:00
case SubMode : : WP :
2021-09-07 09:30:25 -03:00
// run waypoint controller
wp_control_run ( ) ;
2021-03-05 03:03:56 -04:00
if ( send_notification & & wp_nav - > reached_wp_destination ( ) ) {
send_notification = false ;
gcs ( ) . send_mission_item_reached_message ( 0 ) ;
}
2020-10-14 02:30:01 -03:00
break ;
2021-09-07 09:30:25 -03:00
case SubMode : : Pos :
// run position controller
pos_control_run ( ) ;
break ;
2021-05-11 01:33:13 -03:00
case SubMode : : Accel :
accel_control_run ( ) ;
2020-10-14 02:30:01 -03:00
break ;
2021-05-11 01:33:13 -03:00
case SubMode : : VelAccel :
velaccel_control_run ( ) ;
break ;
case SubMode : : PosVelAccel :
posvelaccel_control_run ( ) ;
2020-10-14 02:30:01 -03:00
break ;
2021-03-30 00:36:25 -03:00
case SubMode : : Angle :
2020-10-14 02:30:01 -03:00
angle_control_run ( ) ;
break ;
}
}
2020-12-31 20:49:01 -04:00
bool ModeGuided : : allows_arming ( AP_Arming : : Method method ) const
2020-10-14 02:30:01 -03:00
{
2022-12-22 00:05:40 -04:00
// always allow arming from the ground station or scripting
2023-07-24 06:29:19 -03:00
if ( AP_Arming : : method_is_GCS ( method ) | | method = = AP_Arming : : Method : : SCRIPTING ) {
2020-10-14 02:30:01 -03:00
return true ;
}
// optionally allow arming from the transmitter
2020-10-19 01:39:51 -03:00
return ( copter . g2 . guided_options & ( uint32_t ) Options : : AllowArmingFromTX ) ! = 0 ;
2020-10-14 02:30:01 -03:00
} ;
2014-08-04 11:11:23 -03:00
2022-04-14 06:58:27 -03:00
# if WEATHERVANE_ENABLED == ENABLED
bool ModeGuided : : allows_weathervaning ( ) const
{
return ( copter . g2 . guided_options . get ( ) & ( uint32_t ) Options : : AllowWeatherVaning ) ! = 0 ;
}
# endif
2022-02-10 23:05:43 -04:00
// initialises position controller to implement take-off
// takeoff_alt_cm is interpreted as alt-above-home (in cm) or alt-above-terrain if a rangefinder is available
2020-03-06 22:28:43 -04:00
bool ModeGuided : : do_user_takeoff_start ( float takeoff_alt_cm )
2014-08-04 11:11:23 -03:00
{
2022-02-10 23:05:43 -04:00
// calculate target altitude and frame (either alt-above-ekf-origin or alt-above-terrain)
int32_t alt_target_cm ;
bool alt_target_terrain = false ;
2020-03-09 07:30:47 -03:00
if ( wp_nav - > rangefinder_used_and_healthy ( ) & &
2021-03-30 02:34:43 -03:00
wp_nav - > get_terrain_source ( ) = = AC_WPNav : : TerrainSource : : TERRAIN_FROM_RANGEFINDER & &
takeoff_alt_cm < copter . rangefinder . max_distance_cm_orient ( ROTATION_PITCH_270 ) ) {
2020-03-09 07:30:47 -03:00
// can't takeoff downwards
if ( takeoff_alt_cm < = copter . rangefinder_state . alt_cm ) {
return false ;
}
2022-02-10 23:05:43 -04:00
// provide target altitude as alt-above-terrain
alt_target_cm = takeoff_alt_cm ;
alt_target_terrain = true ;
} else {
// interpret altitude as alt-above-home
Location target_loc = copter . current_loc ;
target_loc . set_alt_cm ( takeoff_alt_cm , Location : : AltFrame : : ABOVE_HOME ) ;
2016-03-11 04:16:26 -04:00
2022-02-10 23:05:43 -04:00
// provide target altitude as alt-above-ekf-origin
if ( ! target_loc . get_alt_cm ( Location : : AltFrame : : ABOVE_ORIGIN , alt_target_cm ) ) {
// this should never happen but we reject the command just in case
return false ;
}
2016-03-11 04:16:26 -04:00
}
2014-08-04 11:11:23 -03:00
2022-03-16 00:18:37 -03:00
guided_mode = SubMode : : TakeOff ;
2014-08-04 11:11:23 -03:00
// initialise yaw
2022-09-24 11:12:33 -03:00
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2014-08-04 11:11:23 -03:00
2015-07-01 22:37:12 -03:00
// clear i term when we're taking off
2022-08-24 09:02:44 -03:00
pos_control - > init_z_controller ( ) ;
2016-03-11 04:16:26 -04:00
2022-02-10 23:05:43 -04:00
// initialise alt for WP_NAVALT_MIN and set completion alt
2023-09-28 02:05:51 -03:00
auto_takeoff . start ( alt_target_cm , alt_target_terrain ) ;
2016-03-21 23:13:34 -03:00
2021-09-17 22:33:58 -03:00
// record takeoff has not completed
takeoff_complete = false ;
2016-03-11 04:16:26 -04:00
return true ;
2014-08-04 11:11:23 -03:00
}
2021-09-07 09:30:25 -03:00
// initialise guided mode's waypoint navigation controller
void ModeGuided : : wp_control_start ( )
{
// set to position control mode
guided_mode = SubMode : : WP ;
// initialise waypoint and spline controller
wp_nav - > wp_and_spline_init ( ) ;
// initialise wpnav to stopping point
Vector3f stopping_point ;
wp_nav - > get_wp_stopping_point ( stopping_point ) ;
2022-03-16 00:18:37 -03:00
if ( ! wp_nav - > set_wp_destination ( stopping_point , false ) ) {
// this should never happen because terrain data is not used
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
}
2021-09-07 09:30:25 -03:00
// initialise yaw
auto_yaw . set_mode_to_default ( false ) ;
}
// run guided mode's waypoint navigation controller
void ModeGuided : : wp_control_run ( )
{
// if not armed set throttle to zero and exit immediately
if ( is_disarmed_or_landed ( ) ) {
// do not spool down tradheli when on the ground with motor interlock enabled
make_safe_ground_handling ( copter . is_tradheli ( ) & & motors - > get_interlock ( ) ) ;
return ;
}
// set motors to full range
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
// run waypoint controller
copter . failsafe_terrain_set_status ( wp_nav - > update_wpnav ( ) ) ;
// call z-axis position controller (wpnav should have already updated it's alt target)
pos_control - > update_z_controller ( ) ;
2022-09-24 11:12:33 -03:00
// call attitude controller with auto yaw
attitude_control - > input_thrust_vector_heading ( pos_control - > get_thrust_vector ( ) , auto_yaw . get_heading ( ) ) ;
2021-09-07 09:30:25 -03:00
}
2021-07-08 01:11:54 -03:00
// initialise position controller
void ModeGuided : : pva_control_start ( )
2014-06-02 06:06:11 -03:00
{
2021-05-11 01:33:13 -03:00
// initialise horizontal speed, acceleration
pos_control - > set_max_speed_accel_xy ( wp_nav - > get_default_speed_xy ( ) , wp_nav - > get_wp_acceleration ( ) ) ;
2021-07-08 01:17:41 -03:00
pos_control - > set_correction_speed_accel_xy ( wp_nav - > get_default_speed_xy ( ) , wp_nav - > get_wp_acceleration ( ) ) ;
2014-06-02 06:06:11 -03:00
2021-05-11 01:33:13 -03:00
// initialize vertical speeds and acceleration
pos_control - > set_max_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
2021-07-08 01:17:41 -03:00
pos_control - > set_correction_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
2016-04-22 08:46:36 -03:00
2021-05-11 01:33:13 -03:00
// initialise velocity controller
pos_control - > init_z_controller ( ) ;
pos_control - > init_xy_controller ( ) ;
2021-07-09 02:27:54 -03:00
// initialise yaw
auto_yaw . set_mode_to_default ( false ) ;
2021-08-04 00:12:13 -03:00
2021-09-03 00:58:37 -03:00
// initialise terrain alt
2021-08-04 00:12:13 -03:00
guided_pos_terrain_alt = false ;
2021-07-08 01:11:54 -03:00
}
// initialise guided mode's position controller
void ModeGuided : : pos_control_start ( )
{
// set to position control mode
2021-09-07 09:30:25 -03:00
guided_mode = SubMode : : Pos ;
2021-07-08 01:11:54 -03:00
// initialise position controller
pva_control_start ( ) ;
2014-06-02 06:06:11 -03:00
}
// initialise guided mode's velocity controller
2021-05-11 01:33:13 -03:00
void ModeGuided : : accel_control_start ( )
{
// set guided_mode to velocity controller
guided_mode = SubMode : : Accel ;
2021-07-08 01:11:54 -03:00
// initialise position controller
pva_control_start ( ) ;
2021-05-11 01:33:13 -03:00
}
2021-07-08 01:11:54 -03:00
// initialise guided mode's velocity and acceleration controller
2021-05-11 01:33:13 -03:00
void ModeGuided : : velaccel_control_start ( )
2014-06-02 06:06:11 -03:00
{
// set guided_mode to velocity controller
2021-05-11 01:33:13 -03:00
guided_mode = SubMode : : VelAccel ;
2014-06-02 06:06:11 -03:00
2021-07-08 01:11:54 -03:00
// initialise position controller
pva_control_start ( ) ;
2014-06-02 06:06:11 -03:00
}
2021-07-08 01:11:54 -03:00
// initialise guided mode's position, velocity and acceleration controller
2021-05-11 01:33:13 -03:00
void ModeGuided : : posvelaccel_control_start ( )
2014-11-25 16:15:45 -04:00
{
// set guided_mode to velocity controller
2021-05-11 01:33:13 -03:00
guided_mode = SubMode : : PosVelAccel ;
2014-11-25 16:15:45 -04:00
2021-07-08 01:11:54 -03:00
// initialise position controller
pva_control_start ( ) ;
2014-11-25 16:15:45 -04:00
}
2019-05-09 23:18:49 -03:00
bool ModeGuided : : is_taking_off ( ) const
2018-04-30 06:50:04 -03:00
{
2021-10-12 06:58:44 -03:00
return guided_mode = = SubMode : : TakeOff & & ! takeoff_complete ;
2018-04-30 06:50:04 -03:00
}
2022-07-27 06:20:29 -03:00
bool ModeGuided : : set_speed_xy ( float speed_xy_cms )
{
// initialise horizontal speed, acceleration
pos_control - > set_max_speed_accel_xy ( speed_xy_cms , wp_nav - > get_wp_acceleration ( ) ) ;
pos_control - > set_correction_speed_accel_xy ( speed_xy_cms , wp_nav - > get_wp_acceleration ( ) ) ;
return true ;
}
bool ModeGuided : : set_speed_up ( float speed_up_cms )
{
// initialize vertical speeds and acceleration
pos_control - > set_max_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , speed_up_cms , wp_nav - > get_accel_z ( ) ) ;
pos_control - > set_correction_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , speed_up_cms , wp_nav - > get_accel_z ( ) ) ;
return true ;
}
bool ModeGuided : : set_speed_down ( float speed_down_cms )
{
// initialize vertical speeds and acceleration
pos_control - > set_max_speed_accel_z ( speed_down_cms , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
pos_control - > set_correction_speed_accel_z ( speed_down_cms , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
return true ;
}
2015-10-08 08:13:53 -03:00
// initialise guided mode's angle controller
2019-05-09 23:18:49 -03:00
void ModeGuided : : angle_control_start ( )
2015-10-08 08:13:53 -03:00
{
// set guided_mode to velocity controller
2021-03-30 00:36:25 -03:00
guided_mode = SubMode : : Angle ;
2015-10-08 08:13:53 -03:00
2021-05-19 11:07:38 -03:00
// set vertical speed and acceleration limits
2021-05-11 01:42:02 -03:00
pos_control - > set_max_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
2021-07-08 01:17:41 -03:00
pos_control - > set_correction_speed_accel_z ( wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) , wp_nav - > get_accel_z ( ) ) ;
2015-10-08 08:13:53 -03:00
2021-05-19 11:07:38 -03:00
// initialise the vertical position controller
2017-01-09 03:31:26 -04:00
if ( ! pos_control - > is_active_z ( ) ) {
2021-05-11 01:42:02 -03:00
pos_control - > init_z_controller ( ) ;
2016-10-14 09:28:32 -03:00
}
2015-10-08 08:13:53 -03:00
// initialise targets
guided_angle_state . update_time_ms = millis ( ) ;
2022-01-18 14:01:02 -04:00
guided_angle_state . attitude_quat . initialise ( ) ;
guided_angle_state . ang_vel . zero ( ) ;
2015-10-08 08:13:53 -03:00
guided_angle_state . climb_rate_cms = 0.0f ;
2016-08-02 14:20:57 -03:00
guided_angle_state . yaw_rate_cds = 0.0f ;
guided_angle_state . use_yaw_rate = false ;
2015-10-08 08:13:53 -03:00
// pilot always controls yaw
2022-09-24 11:12:33 -03:00
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2015-10-08 08:13:53 -03:00
}
2021-05-11 01:33:13 -03:00
// set_destination - sets guided mode's target destination
2016-04-28 04:35:29 -03:00
// Returns true if the fence is enabled and guided waypoint is within the fence
// else return false if the waypoint is outside the fence
2020-02-16 05:42:31 -04:00
bool ModeGuided : : set_destination ( const Vector3f & destination , bool use_yaw , float yaw_cd , bool use_yaw_rate , float yaw_rate_cds , bool relative_yaw , bool terrain_alt )
2014-01-28 09:44:37 -04:00
{
2022-07-19 08:33:13 -03:00
# if AP_FENCE_ENABLED
2016-05-19 05:35:44 -03:00
// reject destination if outside the fence
2021-03-17 18:17:14 -03:00
const Location dest_loc ( destination , terrain_alt ? Location : : AltFrame : : ABOVE_TERRAIN : Location : : AltFrame : : ABOVE_ORIGIN ) ;
2018-02-07 22:21:09 -04:00
if ( ! copter . fence . check_destination_within_fence ( dest_loc ) ) {
2019-03-24 22:31:46 -03:00
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : NAVIGATION , LogErrorCode : : DEST_OUTSIDE_FENCE ) ;
2016-04-28 04:35:29 -03:00
// failure is propagated to GCS with NAK
return false ;
}
2016-05-19 05:35:44 -03:00
# endif
2016-04-28 04:35:29 -03:00
2021-09-07 09:30:25 -03:00
// if configured to use wpnav for position control
if ( use_wpnav_for_position_control ( ) ) {
// ensure we are in position control mode
if ( guided_mode ! = SubMode : : WP ) {
wp_control_start ( ) ;
}
// set yaw state
set_yaw_state ( use_yaw , yaw_cd , use_yaw_rate , yaw_rate_cds , relative_yaw ) ;
// no need to check return status because terrain data is not used
wp_nav - > set_wp_destination ( destination , terrain_alt ) ;
// log target
2022-01-25 12:28:04 -04:00
copter . Log_Write_Guided_Position_Target ( guided_mode , destination , terrain_alt , Vector3f ( ) , Vector3f ( ) ) ;
2021-09-07 09:30:25 -03:00
send_notification = true ;
return true ;
}
// if configured to use position controller for position control
2020-09-08 03:16:14 -03:00
// ensure we are in position control mode
2021-09-07 09:30:25 -03:00
if ( guided_mode ! = SubMode : : Pos ) {
2020-09-08 03:16:14 -03:00
pos_control_start ( ) ;
}
2021-06-25 22:10:03 -03:00
// initialise terrain following if needed
if ( terrain_alt ) {
// get current alt above terrain
float origin_terr_offset ;
if ( ! wp_nav - > get_terrain_offset ( origin_terr_offset ) ) {
// if we don't have terrain altitude then stop
init ( true ) ;
return false ;
}
// convert origin to alt-above-terrain if necessary
if ( ! guided_pos_terrain_alt ) {
// new destination is alt-above-terrain, previous destination was alt-above-ekf-origin
pos_control - > set_pos_offset_z_cm ( origin_terr_offset ) ;
}
} else {
pos_control - > set_pos_offset_z_cm ( 0.0 ) ;
}
2017-06-22 12:20:14 -03:00
// set yaw state
2016-03-21 23:13:34 -03:00
set_yaw_state ( use_yaw , yaw_cd , use_yaw_rate , yaw_rate_cds , relative_yaw ) ;
2017-06-22 12:20:14 -03:00
2021-05-11 01:33:13 -03:00
// set position target and zero velocity and acceleration
guided_pos_target_cm = destination . topostype ( ) ;
2021-06-25 22:10:03 -03:00
guided_pos_terrain_alt = terrain_alt ;
2021-05-11 01:33:13 -03:00
guided_vel_target_cms . zero ( ) ;
guided_accel_target_cmss . zero ( ) ;
update_time_ms = millis ( ) ;
2016-01-10 22:41:28 -04:00
// log target
2022-01-25 12:28:04 -04:00
copter . Log_Write_Guided_Position_Target ( guided_mode , guided_pos_target_cm . tofloat ( ) , guided_pos_terrain_alt , guided_vel_target_cms , guided_accel_target_cmss ) ;
2021-03-05 03:03:56 -04:00
send_notification = true ;
2016-04-28 04:35:29 -03:00
return true ;
2014-01-28 09:44:37 -04:00
}
2021-07-06 18:02:26 -03:00
bool ModeGuided : : get_wp ( Location & destination ) const
2018-05-11 08:59:05 -03:00
{
2021-09-07 09:30:25 -03:00
switch ( guided_mode ) {
case SubMode : : WP :
return wp_nav - > get_oa_wp_destination ( destination ) ;
case SubMode : : Pos :
destination = Location ( guided_pos_target_cm . tofloat ( ) , guided_pos_terrain_alt ? Location : : AltFrame : : ABOVE_TERRAIN : Location : : AltFrame : : ABOVE_ORIGIN ) ;
return true ;
default :
2018-05-11 08:59:05 -03:00
return false ;
}
2021-09-07 09:30:25 -03:00
// should never get here but just in case
return false ;
2018-05-11 08:59:05 -03:00
}
2016-03-11 04:16:26 -04:00
// sets guided mode's target from a Location object
// returns false if destination could not be set (probably caused by missing terrain data)
2016-04-28 04:35:29 -03:00
// or if the fence is enabled and guided waypoint is outside the fence
2019-05-09 23:18:49 -03:00
bool ModeGuided : : set_destination ( const Location & dest_loc , bool use_yaw , float yaw_cd , bool use_yaw_rate , float yaw_rate_cds , bool relative_yaw )
2016-03-11 04:16:26 -04:00
{
2022-07-19 08:33:13 -03:00
# if AP_FENCE_ENABLED
2016-05-19 05:35:44 -03:00
// reject destination outside the fence.
// Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails
2018-02-07 22:21:09 -04:00
if ( ! copter . fence . check_destination_within_fence ( dest_loc ) ) {
2019-03-24 22:31:46 -03:00
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : NAVIGATION , LogErrorCode : : DEST_OUTSIDE_FENCE ) ;
2016-07-02 05:15:05 -03:00
// failure is propagated to GCS with NAK
return false ;
2016-05-19 05:35:44 -03:00
}
2016-04-28 04:35:29 -03:00
# endif
2021-09-07 09:30:25 -03:00
// if using wpnav for position control
if ( use_wpnav_for_position_control ( ) ) {
if ( guided_mode ! = SubMode : : WP ) {
wp_control_start ( ) ;
}
if ( ! wp_nav - > set_wp_destination_loc ( dest_loc ) ) {
// failure to set destination can only be because of missing terrain data
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : NAVIGATION , LogErrorCode : : FAILED_TO_SET_DESTINATION ) ;
// failure is propagated to GCS with NAK
return false ;
}
// set yaw state
set_yaw_state ( use_yaw , yaw_cd , use_yaw_rate , yaw_rate_cds , relative_yaw ) ;
// log target
2022-01-25 12:28:04 -04:00
copter . Log_Write_Guided_Position_Target ( guided_mode , Vector3f ( dest_loc . lat , dest_loc . lng , dest_loc . alt ) , ( dest_loc . get_alt_frame ( ) = = Location : : AltFrame : : ABOVE_TERRAIN ) , Vector3f ( ) , Vector3f ( ) ) ;
2021-09-07 09:30:25 -03:00
send_notification = true ;
return true ;
}
// if configured to use position controller for position control
2020-09-08 03:16:14 -03:00
// ensure we are in position control mode
2021-09-07 09:30:25 -03:00
if ( guided_mode ! = SubMode : : Pos ) {
2020-09-08 03:16:14 -03:00
pos_control_start ( ) ;
}
2017-06-22 12:20:14 -03:00
// set yaw state
2016-03-21 23:13:34 -03:00
set_yaw_state ( use_yaw , yaw_cd , use_yaw_rate , yaw_rate_cds , relative_yaw ) ;
2017-06-22 12:20:14 -03:00
2021-05-11 01:33:13 -03:00
// set position target and zero velocity and acceleration
Vector3f pos_target_f ;
2021-06-25 22:10:03 -03:00
bool terrain_alt ;
if ( ! wp_nav - > get_vector_NEU ( dest_loc , pos_target_f , terrain_alt ) ) {
return false ;
}
// initialise terrain following if needed
if ( terrain_alt ) {
// get current alt above terrain
float origin_terr_offset ;
if ( ! wp_nav - > get_terrain_offset ( origin_terr_offset ) ) {
// if we don't have terrain altitude then stop
init ( true ) ;
return false ;
}
// convert origin to alt-above-terrain if necessary
if ( ! guided_pos_terrain_alt ) {
// new destination is alt-above-terrain, previous destination was alt-above-ekf-origin
pos_control - > set_pos_offset_z_cm ( origin_terr_offset ) ;
}
2021-05-11 01:33:13 -03:00
} else {
2021-06-25 22:10:03 -03:00
pos_control - > set_pos_offset_z_cm ( 0.0 ) ;
2021-05-11 01:33:13 -03:00
}
2021-06-25 22:10:03 -03:00
guided_pos_target_cm = pos_target_f . topostype ( ) ;
guided_pos_terrain_alt = terrain_alt ;
2021-05-11 01:33:13 -03:00
guided_vel_target_cms . zero ( ) ;
guided_accel_target_cmss . zero ( ) ;
2021-09-09 01:05:49 -03:00
update_time_ms = millis ( ) ;
2021-05-11 01:33:13 -03:00
2016-03-11 04:16:26 -04:00
// log target
2022-01-25 12:28:04 -04:00
copter . Log_Write_Guided_Position_Target ( guided_mode , Vector3f ( dest_loc . lat , dest_loc . lng , dest_loc . alt ) , guided_pos_terrain_alt , guided_vel_target_cms , guided_accel_target_cmss ) ;
2021-03-05 03:03:56 -04:00
send_notification = true ;
2016-03-11 04:16:26 -04:00
return true ;
}
2021-05-11 01:33:13 -03:00
// set_velaccel - sets guided mode's target velocity and acceleration
void ModeGuided : : set_accel ( const Vector3f & acceleration , bool use_yaw , float yaw_cd , bool use_yaw_rate , float yaw_rate_cds , bool relative_yaw , bool log_request )
{
// check we are in velocity control mode
if ( guided_mode ! = SubMode : : Accel ) {
accel_control_start ( ) ;
}
// set yaw state
set_yaw_state ( use_yaw , yaw_cd , use_yaw_rate , yaw_rate_cds , relative_yaw ) ;
// set velocity and acceleration targets and zero position
guided_pos_target_cm . zero ( ) ;
2021-06-25 22:10:03 -03:00
guided_pos_terrain_alt = false ;
2021-05-11 01:33:13 -03:00
guided_vel_target_cms . zero ( ) ;
guided_accel_target_cmss = acceleration ;
update_time_ms = millis ( ) ;
// log target
if ( log_request ) {
2022-01-25 12:28:04 -04:00
copter . Log_Write_Guided_Position_Target ( guided_mode , guided_pos_target_cm . tofloat ( ) , guided_pos_terrain_alt , guided_vel_target_cms , guided_accel_target_cmss ) ;
2021-05-11 01:33:13 -03:00
}
}
// set_velocity - sets guided mode's target velocity
2019-05-09 23:18:49 -03:00
void ModeGuided : : set_velocity ( const Vector3f & velocity , bool use_yaw , float yaw_cd , bool use_yaw_rate , float yaw_rate_cds , bool relative_yaw , bool log_request )
2021-05-11 01:33:13 -03:00
{
set_velaccel ( velocity , Vector3f ( ) , use_yaw , yaw_cd , use_yaw_rate , yaw_rate_cds , relative_yaw , log_request ) ;
}
// set_velaccel - sets guided mode's target velocity and acceleration
void ModeGuided : : set_velaccel ( const Vector3f & velocity , const Vector3f & acceleration , bool use_yaw , float yaw_cd , bool use_yaw_rate , float yaw_rate_cds , bool relative_yaw , bool log_request )
2014-06-02 06:06:11 -03:00
{
// check we are in velocity control mode
2021-05-11 01:33:13 -03:00
if ( guided_mode ! = SubMode : : VelAccel ) {
velaccel_control_start ( ) ;
2014-06-02 06:06:11 -03:00
}
2017-06-22 12:20:14 -03:00
// set yaw state
2016-03-21 23:13:34 -03:00
set_yaw_state ( use_yaw , yaw_cd , use_yaw_rate , yaw_rate_cds , relative_yaw ) ;
2017-06-22 12:20:14 -03:00
2021-05-11 01:33:13 -03:00
// set velocity and acceleration targets and zero position
guided_pos_target_cm . zero ( ) ;
2021-06-25 22:10:03 -03:00
guided_pos_terrain_alt = false ;
2016-07-20 08:45:11 -03:00
guided_vel_target_cms = velocity ;
2021-05-11 01:33:13 -03:00
guided_accel_target_cmss = acceleration ;
update_time_ms = millis ( ) ;
2015-08-11 20:36:42 -03:00
2016-01-10 22:41:28 -04:00
// log target
2018-02-06 02:16:09 -04:00
if ( log_request ) {
2022-01-25 12:28:04 -04:00
copter . Log_Write_Guided_Position_Target ( guided_mode , guided_pos_target_cm . tofloat ( ) , guided_pos_terrain_alt , guided_vel_target_cms , guided_accel_target_cmss ) ;
2018-02-06 02:16:09 -04:00
}
2014-06-02 06:06:11 -03:00
}
2021-05-11 01:33:13 -03:00
// set_destination_posvel - set guided mode position and velocity target
2019-05-09 23:18:49 -03:00
bool ModeGuided : : set_destination_posvel ( const Vector3f & destination , const Vector3f & velocity , bool use_yaw , float yaw_cd , bool use_yaw_rate , float yaw_rate_cds , bool relative_yaw )
2021-05-11 01:33:13 -03:00
{
2021-08-11 08:17:09 -03:00
return set_destination_posvelaccel ( destination , velocity , Vector3f ( ) , use_yaw , yaw_cd , use_yaw_rate , yaw_rate_cds , relative_yaw ) ;
2021-05-11 01:33:13 -03:00
}
// set_destination_posvelaccel - set guided mode position, velocity and acceleration target
bool ModeGuided : : set_destination_posvelaccel ( const Vector3f & destination , const Vector3f & velocity , const Vector3f & acceleration , bool use_yaw , float yaw_cd , bool use_yaw_rate , float yaw_rate_cds , bool relative_yaw )
2017-07-11 02:06:18 -03:00
{
2022-07-19 08:33:13 -03:00
# if AP_FENCE_ENABLED
2017-11-27 08:21:44 -04:00
// reject destination if outside the fence
2021-03-17 18:17:14 -03:00
const Location dest_loc ( destination , Location : : AltFrame : : ABOVE_ORIGIN ) ;
2018-02-07 22:21:09 -04:00
if ( ! copter . fence . check_destination_within_fence ( dest_loc ) ) {
2019-03-24 22:31:46 -03:00
AP : : logger ( ) . Write_Error ( LogErrorSubsystem : : NAVIGATION , LogErrorCode : : DEST_OUTSIDE_FENCE ) ;
2017-11-27 08:21:44 -04:00
// failure is propagated to GCS with NAK
return false ;
}
# endif
2020-09-08 03:16:14 -03:00
// check we are in velocity control mode
2021-05-11 01:33:13 -03:00
if ( guided_mode ! = SubMode : : PosVelAccel ) {
posvelaccel_control_start ( ) ;
2020-09-08 03:16:14 -03:00
}
2017-06-22 12:20:14 -03:00
// set yaw state
2016-03-21 23:13:34 -03:00
set_yaw_state ( use_yaw , yaw_cd , use_yaw_rate , yaw_rate_cds , relative_yaw ) ;
2017-06-22 12:20:14 -03:00
2021-05-11 01:33:13 -03:00
update_time_ms = millis ( ) ;
2021-06-17 22:20:26 -03:00
guided_pos_target_cm = destination . topostype ( ) ;
2021-06-25 22:10:03 -03:00
guided_pos_terrain_alt = false ;
2016-07-21 04:14:21 -03:00
guided_vel_target_cms = velocity ;
2021-05-11 01:33:13 -03:00
guided_accel_target_cmss = acceleration ;
2016-01-10 22:41:28 -04:00
// log target
2022-01-25 12:28:04 -04:00
copter . Log_Write_Guided_Position_Target ( guided_mode , guided_pos_target_cm . tofloat ( ) , guided_pos_terrain_alt , guided_vel_target_cms , guided_accel_target_cmss ) ;
2017-11-27 08:21:44 -04:00
return true ;
2014-11-25 16:15:45 -04:00
}
2021-04-15 01:14:12 -03:00
// returns true if GUIDED_OPTIONS param suggests SET_ATTITUDE_TARGET's "thrust" field should be interpreted as thrust instead of climb rate
bool ModeGuided : : set_attitude_target_provides_thrust ( ) const
{
return ( ( copter . g2 . guided_options . get ( ) & uint32_t ( Options : : SetAttitudeTarget_ThrustAsThrust ) ) ! = 0 ) ;
}
2021-09-07 08:44:29 -03:00
// returns true if GUIDED_OPTIONS param specifies position should be controlled (when velocity and/or acceleration control is active)
2021-07-10 01:06:59 -03:00
bool ModeGuided : : stabilizing_pos_xy ( ) const
2021-05-11 01:33:13 -03:00
{
return ! ( ( copter . g2 . guided_options . get ( ) & uint32_t ( Options : : DoNotStabilizePositionXY ) ) ! = 0 ) ;
}
2021-09-07 08:44:29 -03:00
// returns true if GUIDED_OPTIONS param specifies velocity should be controlled (when acceleration control is active)
2021-07-10 01:06:59 -03:00
bool ModeGuided : : stabilizing_vel_xy ( ) const
2021-05-11 01:33:13 -03:00
{
return ! ( ( copter . g2 . guided_options . get ( ) & uint32_t ( Options : : DoNotStabilizeVelocityXY ) ) ! = 0 ) ;
}
2021-09-07 09:30:25 -03:00
// returns true if GUIDED_OPTIONS param specifies waypoint navigation should be used for position control (allow path planning to be used but updates must be slower)
bool ModeGuided : : use_wpnav_for_position_control ( ) const
{
return ( ( copter . g2 . guided_options . get ( ) & uint32_t ( Options : : WPNavUsedForPosControl ) ) ! = 0 ) ;
}
2022-01-18 14:01:02 -04:00
// Sets guided's angular target submode: Using a rotation quaternion, angular velocity, and climbrate or thrust (depends on user option)
// attitude_quat: IF zero: ang_vel (angular velocity) must be provided even if all zeroes
// IF non-zero: attitude_control is performed using both the attitude quaternion and angular velocity
// ang_vel: angular velocity (rad/s)
// climb_rate_cms_or_thrust: represents either the climb_rate (cm/s) or thrust scaled from [0, 1], unitless
// use_thrust: IF true: climb_rate_cms_or_thrust represents thrust
// IF false: climb_rate_cms_or_thrust represents climb_rate (cm/s)
void ModeGuided : : set_angle ( const Quaternion & attitude_quat , const Vector3f & ang_vel , float climb_rate_cms_or_thrust , bool use_thrust )
2015-10-08 08:13:53 -03:00
{
// check we are in velocity control mode
2021-03-30 00:36:25 -03:00
if ( guided_mode ! = SubMode : : Angle ) {
2016-03-21 23:13:34 -03:00
angle_control_start ( ) ;
2015-10-08 08:13:53 -03:00
}
2022-01-18 14:01:02 -04:00
guided_angle_state . attitude_quat = attitude_quat ;
guided_angle_state . ang_vel = ang_vel ;
2015-10-08 08:13:53 -03:00
2020-07-27 06:18:34 -03:00
guided_angle_state . use_thrust = use_thrust ;
if ( use_thrust ) {
guided_angle_state . thrust = climb_rate_cms_or_thrust ;
guided_angle_state . climb_rate_cms = 0.0f ;
} else {
guided_angle_state . thrust = 0.0f ;
guided_angle_state . climb_rate_cms = climb_rate_cms_or_thrust ;
}
2015-10-08 08:13:53 -03:00
guided_angle_state . update_time_ms = millis ( ) ;
2016-01-10 22:41:28 -04:00
2022-01-18 14:01:02 -04:00
// convert quaternion to euler angles
float roll_rad , pitch_rad , yaw_rad ;
attitude_quat . to_euler ( roll_rad , pitch_rad , yaw_rad ) ;
2016-01-10 22:41:28 -04:00
// log target
2022-01-25 12:28:04 -04:00
copter . Log_Write_Guided_Attitude_Target ( guided_mode , roll_rad , pitch_rad , yaw_rad , ang_vel , guided_angle_state . thrust , guided_angle_state . climb_rate_cms * 0.01 ) ;
2015-10-08 08:13:53 -03:00
}
2021-05-11 01:33:13 -03:00
// takeoff_run - takeoff in guided mode
2014-08-04 11:11:23 -03:00
// called by guided_run at 100hz or more
2019-05-09 23:18:49 -03:00
void ModeGuided : : takeoff_run ( )
2018-06-26 00:16:31 -03:00
{
2023-09-28 02:05:51 -03:00
auto_takeoff . run ( ) ;
if ( auto_takeoff . complete & & ! takeoff_complete ) {
2021-09-17 22:33:58 -03:00
takeoff_complete = true ;
2022-10-01 07:21:38 -03:00
# if AP_LANDINGGEAR_ENABLED
2020-02-20 23:08:26 -04:00
// optionally retract landing gear
copter . landinggear . retract_after_takeoff ( ) ;
2021-02-06 23:29:33 -04:00
# endif
2018-07-25 14:17:23 -03:00
}
2018-06-26 00:16:31 -03:00
}
2021-05-11 01:33:13 -03:00
// pos_control_run - runs the guided position controller
2014-06-02 06:06:11 -03:00
// called from guided_run
2019-05-09 23:18:49 -03:00
void ModeGuided : : pos_control_run ( )
2014-06-02 06:06:11 -03:00
{
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2020-10-13 20:19:42 -03:00
// do not spool down tradheli when on the ground with motor interlock enabled
make_safe_ground_handling ( copter . is_tradheli ( ) & & motors - > get_interlock ( ) ) ;
2019-02-28 05:03:23 -04:00
return ;
}
2021-06-25 22:10:03 -03:00
// calculate terrain adjustments
float terr_offset = 0.0f ;
if ( guided_pos_terrain_alt & & ! wp_nav - > get_terrain_offset ( terr_offset ) ) {
2021-07-08 22:50:29 -03:00
// failure to set destination can only be because of missing terrain data
copter . failsafe_terrain_on_event ( ) ;
2021-06-25 22:10:03 -03:00
return ;
}
2016-01-13 03:10:45 -04:00
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-01-13 03:10:45 -04:00
2021-05-11 01:33:13 -03:00
// send position and velocity targets to position controller
guided_accel_target_cmss . zero ( ) ;
guided_vel_target_cms . zero ( ) ;
2021-07-08 05:46:52 -03:00
2021-09-09 01:05:49 -03:00
// stop rotating if no updates received within timeout_ms
if ( millis ( ) - update_time_ms > get_timeout_ms ( ) ) {
2022-09-24 11:12:33 -03:00
if ( ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : RATE ) | | ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : ANGLE_RATE ) ) {
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2021-09-09 01:05:49 -03:00
}
}
2021-07-08 05:46:52 -03:00
float pos_offset_z_buffer = 0.0 ; // Vertical buffer size in m
if ( guided_pos_terrain_alt ) {
2022-02-26 09:50:22 -04:00
pos_offset_z_buffer = MIN ( copter . wp_nav - > get_terrain_margin ( ) * 100.0 , 0.5 * fabsF ( guided_pos_target_cm . z ) ) ;
2021-07-08 05:46:52 -03:00
}
pos_control - > input_pos_xyz ( guided_pos_target_cm , terr_offset , pos_offset_z_buffer ) ;
2014-01-28 09:44:37 -04:00
2021-05-11 01:33:13 -03:00
// run position controllers
pos_control - > update_xy_controller ( ) ;
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2014-01-28 09:44:37 -04:00
2022-09-24 11:12:33 -03:00
// call attitude controller with auto yaw
attitude_control - > input_thrust_vector_heading ( pos_control - > get_thrust_vector ( ) , auto_yaw . get_heading ( ) ) ;
2014-06-02 06:06:11 -03:00
}
2021-05-11 01:33:13 -03:00
// velaccel_control_run - runs the guided velocity controller
2014-06-02 06:06:11 -03:00
// called from guided_run
2021-05-11 01:33:13 -03:00
void ModeGuided : : accel_control_run ( )
2014-06-02 06:06:11 -03:00
{
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2020-10-13 20:19:42 -03:00
// do not spool down tradheli when on the ground with motor interlock enabled
make_safe_ground_handling ( copter . is_tradheli ( ) & & motors - > get_interlock ( ) ) ;
2019-02-28 05:03:23 -04:00
return ;
}
2016-01-13 03:10:45 -04:00
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-01-13 03:10:45 -04:00
2017-07-11 02:39:53 -03:00
// set velocity to zero and stop rotating if no updates received for 3 seconds
2015-08-11 20:36:42 -03:00
uint32_t tnow = millis ( ) ;
2021-07-09 02:02:07 -03:00
if ( tnow - update_time_ms > get_timeout_ms ( ) ) {
2021-07-09 02:25:35 -03:00
guided_vel_target_cms . zero ( ) ;
2021-05-11 01:33:13 -03:00
guided_accel_target_cmss . zero ( ) ;
2022-09-24 11:12:33 -03:00
if ( ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : RATE ) | | ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : ANGLE_RATE ) ) {
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2017-07-11 02:39:53 -03:00
}
2021-08-06 06:41:12 -03:00
pos_control - > input_vel_accel_xy ( guided_vel_target_cms . xy ( ) , guided_accel_target_cmss . xy ( ) , false ) ;
2022-12-15 07:44:58 -04:00
pos_control - > input_vel_accel_z ( guided_vel_target_cms . z , guided_accel_target_cmss . z , false ) ;
2021-07-09 02:25:35 -03:00
} else {
// update position controller with new target
pos_control - > input_accel_xy ( guided_accel_target_cmss ) ;
if ( ! stabilizing_vel_xy ( ) ) {
// set position and velocity errors to zero
pos_control - > stop_vel_xy_stabilisation ( ) ;
} else if ( ! stabilizing_pos_xy ( ) ) {
// set position errors to zero
pos_control - > stop_pos_xy_stabilisation ( ) ;
}
pos_control - > input_accel_z ( guided_accel_target_cmss . z ) ;
2021-05-11 01:33:13 -03:00
}
// call velocity controller which includes z axis controller
pos_control - > update_xy_controller ( ) ;
pos_control - > update_z_controller ( ) ;
2022-09-24 11:12:33 -03:00
// call attitude controller with auto yaw
attitude_control - > input_thrust_vector_heading ( pos_control - > get_thrust_vector ( ) , auto_yaw . get_heading ( ) ) ;
2021-05-11 01:33:13 -03:00
}
// velaccel_control_run - runs the guided velocity and acceleration controller
// called from guided_run
void ModeGuided : : velaccel_control_run ( )
{
// if not armed set throttle to zero and exit immediately
if ( is_disarmed_or_landed ( ) ) {
2020-10-13 20:19:42 -03:00
// do not spool down tradheli when on the ground with motor interlock enabled
make_safe_ground_handling ( copter . is_tradheli ( ) & & motors - > get_interlock ( ) ) ;
2021-05-11 01:33:13 -03:00
return ;
}
// set motors to full range
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
// set velocity to zero and stop rotating if no updates received for 3 seconds
uint32_t tnow = millis ( ) ;
2021-07-09 02:02:07 -03:00
if ( tnow - update_time_ms > get_timeout_ms ( ) ) {
2021-05-11 01:33:13 -03:00
guided_vel_target_cms . zero ( ) ;
guided_accel_target_cmss . zero ( ) ;
2022-09-24 11:12:33 -03:00
if ( ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : RATE ) | | ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : ANGLE_RATE ) ) {
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2021-05-11 01:33:13 -03:00
}
}
bool do_avoid = false ;
# if AC_AVOID_ENABLED
// limit the velocity for obstacle/fence avoidance
copter . avoid . adjust_velocity ( guided_vel_target_cms , pos_control - > get_pos_xy_p ( ) . kP ( ) , pos_control - > get_max_accel_xy_cmss ( ) , pos_control - > get_pos_z_p ( ) . kP ( ) , pos_control - > get_max_accel_z_cmss ( ) , G_Dt ) ;
do_avoid = copter . avoid . limits_active ( ) ;
# endif
// update position controller with new target
if ( ! stabilizing_vel_xy ( ) & & ! do_avoid ) {
// set the current commanded xy vel to the desired vel
guided_vel_target_cms . x = pos_control - > get_vel_desired_cms ( ) . x ;
guided_vel_target_cms . y = pos_control - > get_vel_desired_cms ( ) . y ;
}
2021-08-06 06:41:12 -03:00
pos_control - > input_vel_accel_xy ( guided_vel_target_cms . xy ( ) , guided_accel_target_cmss . xy ( ) , false ) ;
2021-05-11 01:33:13 -03:00
if ( ! stabilizing_vel_xy ( ) & & ! do_avoid ) {
// set position and velocity errors to zero
pos_control - > stop_vel_xy_stabilisation ( ) ;
} else if ( ! stabilizing_pos_xy ( ) & & ! do_avoid ) {
// set position errors to zero
pos_control - > stop_pos_xy_stabilisation ( ) ;
}
2022-12-15 07:44:58 -04:00
pos_control - > input_vel_accel_z ( guided_vel_target_cms . z , guided_accel_target_cmss . z , false ) ;
2021-05-11 01:33:13 -03:00
2015-11-17 02:51:25 -04:00
// call velocity controller which includes z axis controller
2021-05-11 01:42:02 -03:00
pos_control - > update_xy_controller ( ) ;
pos_control - > update_z_controller ( ) ;
2014-06-02 06:06:11 -03:00
2022-09-24 11:12:33 -03:00
// call attitude controller with auto yaw
attitude_control - > input_thrust_vector_heading ( pos_control - > get_thrust_vector ( ) , auto_yaw . get_heading ( ) ) ;
2014-01-28 09:44:37 -04:00
}
2014-10-13 05:41:48 -03:00
2022-01-27 14:36:21 -04:00
// pause_control_run - runs the guided mode pause controller
2022-01-27 05:00:15 -04:00
// called from guided_run
void ModeGuided : : pause_control_run ( )
{
// if not armed set throttle to zero and exit immediately
if ( is_disarmed_or_landed ( ) ) {
// do not spool down tradheli when on the ground with motor interlock enabled
make_safe_ground_handling ( copter . is_tradheli ( ) & & motors - > get_interlock ( ) ) ;
return ;
}
// set motors to full range
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
// set the horizontal velocity and acceleration targets to zero
Vector2f vel_xy , accel_xy ;
pos_control - > input_vel_accel_xy ( vel_xy , accel_xy , false ) ;
// set the vertical velocity and acceleration targets to zero
float vel_z = 0.0 ;
2022-12-15 07:44:58 -04:00
pos_control - > input_vel_accel_z ( vel_z , 0.0 , false ) ;
2022-01-27 05:00:15 -04:00
// call velocity controller which includes z axis controller
pos_control - > update_xy_controller ( ) ;
pos_control - > update_z_controller ( ) ;
// call attitude controller
2022-10-06 21:38:52 -03:00
attitude_control - > input_thrust_vector_rate_heading ( pos_control - > get_thrust_vector ( ) , 0.0 ) ;
2022-01-27 05:00:15 -04:00
}
2021-05-11 01:33:13 -03:00
// posvelaccel_control_run - runs the guided position, velocity and acceleration controller
2014-11-25 16:15:45 -04:00
// called from guided_run
2021-05-11 01:33:13 -03:00
void ModeGuided : : posvelaccel_control_run ( )
2014-11-25 16:15:45 -04:00
{
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2019-04-08 05:15:57 -03:00
if ( is_disarmed_or_landed ( ) ) {
2020-10-13 20:19:42 -03:00
// do not spool down tradheli when on the ground with motor interlock enabled
make_safe_ground_handling ( copter . is_tradheli ( ) & & motors - > get_interlock ( ) ) ;
2019-02-28 05:03:23 -04:00
return ;
}
2016-01-13 03:10:45 -04:00
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-01-13 03:10:45 -04:00
2017-07-11 02:39:53 -03:00
// set velocity to zero and stop rotating if no updates received for 3 seconds
2014-11-25 16:15:45 -04:00
uint32_t tnow = millis ( ) ;
2021-07-09 02:02:07 -03:00
if ( tnow - update_time_ms > get_timeout_ms ( ) ) {
2016-07-21 04:14:21 -03:00
guided_vel_target_cms . zero ( ) ;
2021-05-11 01:33:13 -03:00
guided_accel_target_cmss . zero ( ) ;
2022-09-24 11:12:33 -03:00
if ( ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : RATE ) | | ( auto_yaw . mode ( ) = = AutoYaw : : Mode : : ANGLE_RATE ) ) {
auto_yaw . set_mode ( AutoYaw : : Mode : : HOLD ) ;
2017-07-11 02:39:53 -03:00
}
2014-11-25 16:15:45 -04:00
}
2018-03-08 22:42:17 -04:00
// send position and velocity targets to position controller
2021-05-11 01:33:13 -03:00
if ( ! stabilizing_vel_xy ( ) ) {
// set the current commanded xy pos to the target pos and xy vel to the desired vel
guided_pos_target_cm . x = pos_control - > get_pos_target_cm ( ) . x ;
guided_pos_target_cm . y = pos_control - > get_pos_target_cm ( ) . y ;
guided_vel_target_cms . x = pos_control - > get_vel_desired_cms ( ) . x ;
guided_vel_target_cms . y = pos_control - > get_vel_desired_cms ( ) . y ;
} else if ( ! stabilizing_pos_xy ( ) ) {
// set the current commanded xy pos to the target pos
guided_pos_target_cm . x = pos_control - > get_pos_target_cm ( ) . x ;
guided_pos_target_cm . y = pos_control - > get_pos_target_cm ( ) . y ;
}
2021-08-06 06:41:12 -03:00
pos_control - > input_pos_vel_accel_xy ( guided_pos_target_cm . xy ( ) , guided_vel_target_cms . xy ( ) , guided_accel_target_cmss . xy ( ) , false ) ;
2021-05-11 01:33:13 -03:00
if ( ! stabilizing_vel_xy ( ) ) {
// set position and velocity errors to zero
pos_control - > stop_vel_xy_stabilisation ( ) ;
} else if ( ! stabilizing_pos_xy ( ) ) {
// set position errors to zero
pos_control - > stop_pos_xy_stabilisation ( ) ;
}
2021-06-25 22:10:03 -03:00
// guided_pos_target z-axis should never be a terrain altitude
if ( guided_pos_terrain_alt ) {
INTERNAL_ERROR ( AP_InternalError : : error_t : : flow_of_control ) ;
}
2021-06-17 22:20:26 -03:00
float pz = guided_pos_target_cm . z ;
2021-08-06 06:41:12 -03:00
pos_control - > input_pos_vel_accel_z ( pz , guided_vel_target_cms . z , guided_accel_target_cmss . z , false ) ;
2021-06-17 22:20:26 -03:00
guided_pos_target_cm . z = pz ;
2014-11-25 16:15:45 -04:00
2018-03-08 22:42:17 -04:00
// run position controllers
2018-09-05 03:47:50 -03:00
pos_control - > update_xy_controller ( ) ;
2017-01-09 03:31:26 -04:00
pos_control - > update_z_controller ( ) ;
2015-04-22 16:04:27 -03:00
2022-09-24 11:12:33 -03:00
// call attitude controller with auto yaw
attitude_control - > input_thrust_vector_heading ( pos_control - > get_thrust_vector ( ) , auto_yaw . get_heading ( ) ) ;
2014-11-25 16:15:45 -04:00
}
2014-11-14 17:26:45 -04:00
2021-05-11 01:33:13 -03:00
// angle_control_run - runs the guided angle controller
2015-10-08 08:13:53 -03:00
// called from guided_run
2019-05-09 23:18:49 -03:00
void ModeGuided : : angle_control_run ( )
2015-10-08 08:13:53 -03:00
{
2020-07-27 06:18:34 -03:00
float climb_rate_cms = 0.0f ;
if ( ! guided_angle_state . use_thrust ) {
// constrain climb rate
2021-09-06 23:53:02 -03:00
climb_rate_cms = constrain_float ( guided_angle_state . climb_rate_cms , - wp_nav - > get_default_speed_down ( ) , wp_nav - > get_default_speed_up ( ) ) ;
2015-10-08 08:13:53 -03:00
2020-07-27 06:18:34 -03:00
// get avoidance adjusted climb rate
climb_rate_cms = get_avoidance_adjusted_climbrate ( climb_rate_cms ) ;
}
2017-01-05 02:24:02 -04:00
2015-10-08 08:13:53 -03:00
// check for timeout - set lean angles and climb rate to zero if no updates received for 3 seconds
uint32_t tnow = millis ( ) ;
2021-07-09 02:02:07 -03:00
if ( tnow - guided_angle_state . update_time_ms > get_timeout_ms ( ) ) {
2022-01-18 14:01:02 -04:00
guided_angle_state . attitude_quat . initialise ( ) ;
guided_angle_state . ang_vel . zero ( ) ;
2015-10-08 08:13:53 -03:00
climb_rate_cms = 0.0f ;
2021-07-09 22:25:19 -03:00
if ( guided_angle_state . use_thrust ) {
// initialise vertical velocity controller
pos_control - > init_z_controller ( ) ;
guided_angle_state . use_thrust = false ;
}
2015-10-08 08:13:53 -03:00
}
2020-10-14 02:29:33 -03:00
// interpret positive climb rate or thrust as triggering take-off
2020-10-19 02:49:32 -03:00
const bool positive_thrust_or_climbrate = is_positive ( guided_angle_state . use_thrust ? guided_angle_state . thrust : climb_rate_cms ) ;
if ( motors - > armed ( ) & & positive_thrust_or_climbrate ) {
2020-10-14 02:29:33 -03:00
copter . set_auto_armed ( true ) ;
}
2019-02-28 05:03:23 -04:00
// if not armed set throttle to zero and exit immediately
2020-10-19 02:49:32 -03:00
if ( ! motors - > armed ( ) | | ! copter . ap . auto_armed | | ( copter . ap . land_complete & & ! positive_thrust_or_climbrate ) ) {
2020-10-13 20:19:42 -03:00
// do not spool down tradheli when on the ground with motor interlock enabled
make_safe_ground_handling ( copter . is_tradheli ( ) & & motors - > get_interlock ( ) ) ;
2019-02-28 05:03:23 -04:00
return ;
}
// TODO: use get_alt_hold_state
// landed with positive desired climb rate, takeoff
2019-05-09 23:18:49 -03:00
if ( copter . ap . land_complete & & ( guided_angle_state . climb_rate_cms > 0.0f ) ) {
2019-02-28 05:03:23 -04:00
zero_throttle_and_relax_ac ( ) ;
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
if ( motors - > get_spool_state ( ) = = AP_Motors : : SpoolState : : THROTTLE_UNLIMITED ) {
2019-02-28 05:03:23 -04:00
set_land_complete ( false ) ;
2022-08-24 09:02:44 -03:00
pos_control - > init_z_controller ( ) ;
2019-02-28 05:03:23 -04:00
}
return ;
}
2016-01-13 03:10:45 -04:00
// set motors to full range
2019-04-09 09:16:58 -03:00
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2016-01-13 03:10:45 -04:00
2015-10-08 08:13:53 -03:00
// call attitude controller
2022-01-18 14:01:02 -04:00
if ( guided_angle_state . attitude_quat . is_zero ( ) ) {
attitude_control - > input_rate_bf_roll_pitch_yaw ( ToDeg ( guided_angle_state . ang_vel . x ) * 100.0f , ToDeg ( guided_angle_state . ang_vel . y ) * 100.0f , ToDeg ( guided_angle_state . ang_vel . z ) * 100.0f ) ;
2016-08-02 14:20:57 -03:00
} else {
2022-01-18 14:01:02 -04:00
attitude_control - > input_quaternion ( guided_angle_state . attitude_quat , guided_angle_state . ang_vel ) ;
2016-08-02 14:20:57 -03:00
}
2015-10-08 08:13:53 -03:00
// call position controller
2020-07-27 06:18:34 -03:00
if ( guided_angle_state . use_thrust ) {
attitude_control - > set_throttle_out ( guided_angle_state . thrust , true , copter . g . throttle_filt ) ;
} else {
2021-08-31 01:17:59 -03:00
pos_control - > set_pos_target_z_from_climb_rate_cm ( climb_rate_cms ) ;
2020-07-27 06:18:34 -03:00
pos_control - > update_z_controller ( ) ;
}
2015-10-08 08:13:53 -03:00
}
2017-07-10 09:51:43 -03:00
// helper function to set yaw state and targets
2019-05-09 23:18:49 -03:00
void ModeGuided : : set_yaw_state ( bool use_yaw , float yaw_cd , bool use_yaw_rate , float yaw_rate_cds , bool relative_angle )
2017-06-22 12:20:14 -03:00
{
2021-07-09 05:44:07 -03:00
if ( use_yaw & & relative_angle ) {
2019-04-23 14:26:30 -03:00
auto_yaw . set_fixed_yaw ( yaw_cd * 0.01f , 0.0f , 0 , relative_angle ) ;
2021-07-09 05:44:07 -03:00
} else if ( use_yaw & & use_yaw_rate ) {
auto_yaw . set_yaw_angle_rate ( yaw_cd * 0.01f , yaw_rate_cds * 0.01f ) ;
} else if ( use_yaw & & ! use_yaw_rate ) {
auto_yaw . set_yaw_angle_rate ( yaw_cd * 0.01f , 0.0f ) ;
2017-07-10 09:51:43 -03:00
} else if ( use_yaw_rate ) {
2017-12-25 23:55:42 -04:00
auto_yaw . set_rate ( yaw_rate_cds ) ;
2021-12-22 06:46:49 -04:00
} else {
auto_yaw . set_mode_to_default ( false ) ;
2017-07-10 09:51:43 -03:00
}
2017-06-22 12:20:14 -03:00
}
2020-11-12 20:15:53 -04:00
// returns true if pilot's yaw input should be used to adjust vehicle's heading
bool ModeGuided : : use_pilot_yaw ( void ) const
{
return ( copter . g2 . guided_options . get ( ) & uint32_t ( Options : : IgnorePilotYaw ) ) = = 0 ;
}
2014-10-13 05:41:48 -03:00
// Guided Limit code
2021-05-11 01:33:13 -03:00
// limit_clear - clear/turn off guided limits
2019-05-09 23:18:49 -03:00
void ModeGuided : : limit_clear ( )
2014-10-13 05:41:48 -03:00
{
guided_limit . timeout_ms = 0 ;
guided_limit . alt_min_cm = 0.0f ;
guided_limit . alt_max_cm = 0.0f ;
guided_limit . horiz_max_cm = 0.0f ;
}
2021-05-11 01:33:13 -03:00
// limit_set - set guided timeout and movement limits
2019-05-09 23:18:49 -03:00
void ModeGuided : : limit_set ( uint32_t timeout_ms , float alt_min_cm , float alt_max_cm , float horiz_max_cm )
2014-10-13 05:41:48 -03:00
{
guided_limit . timeout_ms = timeout_ms ;
guided_limit . alt_min_cm = alt_min_cm ;
guided_limit . alt_max_cm = alt_max_cm ;
guided_limit . horiz_max_cm = horiz_max_cm ;
}
2021-05-11 01:33:13 -03:00
// limit_init_time_and_pos - initialise guided start time and position as reference for limit checking
2014-10-13 05:41:48 -03:00
// only called from AUTO mode's auto_nav_guided_start function
2019-05-09 23:18:49 -03:00
void ModeGuided : : limit_init_time_and_pos ( )
2014-10-13 05:41:48 -03:00
{
// initialise start time
2015-11-19 23:04:45 -04:00
guided_limit . start_time = AP_HAL : : millis ( ) ;
2014-10-13 05:41:48 -03:00
// initialise start position from current position
2021-10-20 05:29:57 -03:00
guided_limit . start_pos = inertial_nav . get_position_neu_cm ( ) ;
2014-10-13 05:41:48 -03:00
}
2021-05-11 01:33:13 -03:00
// limit_check - returns true if guided mode has breached a limit
2014-10-13 05:41:48 -03:00
// used when guided is invoked from the NAV_GUIDED_ENABLE mission command
2019-05-09 23:18:49 -03:00
bool ModeGuided : : limit_check ( )
2014-10-13 05:41:48 -03:00
{
// check if we have passed the timeout
if ( ( guided_limit . timeout_ms > 0 ) & & ( millis ( ) - guided_limit . start_time > = guided_limit . timeout_ms ) ) {
return true ;
}
// get current location
2021-10-20 05:29:57 -03:00
const Vector3f & curr_pos = inertial_nav . get_position_neu_cm ( ) ;
2014-10-13 05:41:48 -03:00
// check if we have gone below min alt
2015-05-04 23:34:21 -03:00
if ( ! is_zero ( guided_limit . alt_min_cm ) & & ( curr_pos . z < guided_limit . alt_min_cm ) ) {
2014-10-13 05:41:48 -03:00
return true ;
}
// check if we have gone above max alt
2015-05-04 23:34:21 -03:00
if ( ! is_zero ( guided_limit . alt_max_cm ) & & ( curr_pos . z > guided_limit . alt_max_cm ) ) {
2014-10-13 05:41:48 -03:00
return true ;
}
// check if we have gone beyond horizontal limit
if ( guided_limit . horiz_max_cm > 0.0f ) {
2021-09-11 00:44:02 -03:00
const float horiz_move = get_horizontal_distance_cm ( guided_limit . start_pos . xy ( ) , curr_pos . xy ( ) ) ;
2014-10-13 05:41:48 -03:00
if ( horiz_move > guided_limit . horiz_max_cm ) {
return true ;
}
}
// if we got this far we must be within limits
return false ;
}
2017-12-05 21:28:32 -04:00
2021-05-11 01:33:13 -03:00
const Vector3p & ModeGuided : : get_target_pos ( ) const
{
return guided_pos_target_cm ;
}
const Vector3f & ModeGuided : : get_target_vel ( ) const
{
return guided_vel_target_cms ;
}
const Vector3f & ModeGuided : : get_target_accel ( ) const
{
return guided_accel_target_cmss ;
}
2017-12-05 21:28:32 -04:00
2019-05-09 23:18:49 -03:00
uint32_t ModeGuided : : wp_distance ( ) const
2017-12-05 21:28:32 -04:00
{
2021-03-30 00:36:25 -03:00
switch ( guided_mode ) {
case SubMode : : WP :
2021-09-07 09:30:25 -03:00
return wp_nav - > get_wp_distance_to_destination ( ) ;
case SubMode : : Pos :
2021-10-20 05:29:57 -03:00
return get_horizontal_distance_cm ( inertial_nav . get_position_xy_cm ( ) , guided_pos_target_cm . tofloat ( ) . xy ( ) ) ;
2021-05-11 01:33:13 -03:00
case SubMode : : PosVelAccel :
2021-05-11 01:42:02 -03:00
return pos_control - > get_pos_error_xy_cm ( ) ;
2017-12-05 21:28:32 -04:00
default :
return 0 ;
}
}
2019-05-09 23:18:49 -03:00
int32_t ModeGuided : : wp_bearing ( ) const
2017-12-05 21:28:32 -04:00
{
2021-03-30 00:36:25 -03:00
switch ( guided_mode ) {
case SubMode : : WP :
2021-09-07 09:30:25 -03:00
return wp_nav - > get_wp_bearing_to_destination ( ) ;
case SubMode : : Pos :
2021-10-20 05:29:57 -03:00
return get_bearing_cd ( inertial_nav . get_position_xy_cm ( ) , guided_pos_target_cm . tofloat ( ) . xy ( ) ) ;
2021-05-11 01:33:13 -03:00
case SubMode : : PosVelAccel :
2021-05-11 01:42:02 -03:00
return pos_control - > get_bearing_to_target_cd ( ) ;
2021-03-30 00:36:25 -03:00
case SubMode : : TakeOff :
2021-05-11 01:33:13 -03:00
case SubMode : : Accel :
case SubMode : : VelAccel :
2021-03-30 00:36:25 -03:00
case SubMode : : Angle :
// these do not have bearings
2017-12-05 21:28:32 -04:00
return 0 ;
}
2021-03-30 00:36:25 -03:00
// compiler guarantees we don't get here
return 0.0 ;
2017-12-05 21:28:32 -04:00
}
2018-05-23 12:34:24 -03:00
2019-05-09 23:18:49 -03:00
float ModeGuided : : crosstrack_error ( ) const
2018-05-23 12:34:24 -03:00
{
2021-03-30 00:36:25 -03:00
switch ( guided_mode ) {
case SubMode : : WP :
2021-09-07 09:30:25 -03:00
return wp_nav - > crosstrack_error ( ) ;
case SubMode : : Pos :
2021-03-30 00:36:25 -03:00
case SubMode : : TakeOff :
2021-05-11 01:33:13 -03:00
case SubMode : : Accel :
case SubMode : : VelAccel :
case SubMode : : PosVelAccel :
2021-07-20 21:38:05 -03:00
return pos_control - > crosstrack_error ( ) ;
2021-03-30 00:36:25 -03:00
case SubMode : : Angle :
// no track to have a crosstrack to
2018-05-23 12:34:24 -03:00
return 0 ;
}
2021-03-30 00:36:25 -03:00
// compiler guarantees we don't get here
return 0 ;
2018-05-23 12:34:24 -03:00
}
2019-02-25 10:32:52 -04:00
2021-09-09 01:05:49 -03:00
// return guided mode timeout in milliseconds. Only used for velocity, acceleration, angle control, and angular rates
2021-07-09 02:02:07 -03:00
uint32_t ModeGuided : : get_timeout_ms ( ) const
{
return MAX ( copter . g2 . guided_timeout , 0.1 ) * 1000 ;
}
2022-01-27 14:36:21 -04:00
// pause guide mode
bool ModeGuided : : pause ( )
{
_paused = true ;
return true ;
}
// resume guided mode
bool ModeGuided : : resume ( )
{
_paused = false ;
return true ;
}
2019-02-25 10:32:52 -04:00
# endif