2017-02-26 19:13:46 -04:00
# include "AP_Soaring.h"
2022-11-06 19:20:59 -04:00
# if HAL_SOARING_ENABLED
2019-06-27 00:05:06 -03:00
# include <AP_Logger/AP_Logger.h>
2022-11-06 19:20:59 -04:00
# include <AP_TECS/AP_TECS.h>
2017-02-26 19:13:46 -04:00
# include <GCS_MAVLink/GCS.h>
# include <stdint.h>
// ArduSoar parameters
const AP_Param : : GroupInfo SoaringController : : var_info [ ] = {
// @Param: ENABLE
// @DisplayName: Is the soaring mode enabled or not
// @Description: Toggles the soaring mode on and off
// @Values: 0:Disable,1:Enable
// @User: Advanced
AP_GROUPINFO_FLAGS ( " ENABLE " , 1 , SoaringController , soar_active , 0 , AP_PARAM_FLAG_ENABLE ) ,
// @Param: VSPEED
// @DisplayName: Vertical v-speed
// @Description: Rate of climb to trigger themalling speed
// @Units: m/s
// @Range: 0 10
// @User: Advanced
AP_GROUPINFO ( " VSPEED " , 2 , SoaringController , thermal_vspeed , 0.7f ) ,
// @Param: Q1
// @DisplayName: Process noise
// @Description: Standard deviation of noise in process for strength
2020-06-02 08:03:02 -03:00
// @Range: 0.0001 0.01
2017-02-26 19:13:46 -04:00
// @User: Advanced
AP_GROUPINFO ( " Q1 " , 3 , SoaringController , thermal_q1 , 0.001f ) ,
// @Param: Q2
// @DisplayName: Process noise
// @Description: Standard deviation of noise in process for position and radius
2020-06-02 08:03:02 -03:00
// @Range: 0.01 1
2017-02-26 19:13:46 -04:00
// @User: Advanced
AP_GROUPINFO ( " Q2 " , 4 , SoaringController , thermal_q2 , 0.03f ) ,
// @Param: R
// @DisplayName: Measurement noise
// @Description: Standard deviation of noise in measurement
2020-06-02 08:03:02 -03:00
// @Range: 0.01 1
2017-02-26 19:13:46 -04:00
// @User: Advanced
AP_GROUPINFO ( " R " , 5 , SoaringController , thermal_r , 0.45f ) ,
// @Param: DIST_AHEAD
// @DisplayName: Distance to thermal center
// @Description: Initial guess of the distance to the thermal center
2017-05-02 10:48:16 -03:00
// @Units: m
2017-02-26 19:13:46 -04:00
// @Range: 0 100
// @User: Advanced
AP_GROUPINFO ( " DIST_AHEAD " , 6 , SoaringController , thermal_distance_ahead , 5.0f ) ,
// @Param: MIN_THML_S
// @DisplayName: Minimum thermalling time
// @Description: Minimum number of seconds to spend thermalling
2017-05-02 10:48:16 -03:00
// @Units: s
2020-06-02 08:03:02 -03:00
// @Range: 0 600
2017-02-26 19:13:46 -04:00
// @User: Advanced
AP_GROUPINFO ( " MIN_THML_S " , 7 , SoaringController , min_thermal_s , 20 ) ,
// @Param: MIN_CRSE_S
// @DisplayName: Minimum cruising time
// @Description: Minimum number of seconds to spend cruising
2017-05-02 10:48:16 -03:00
// @Units: s
2020-06-02 08:03:02 -03:00
// @Range: 0 600
2017-02-26 19:13:46 -04:00
// @User: Advanced
2020-08-19 06:42:56 -03:00
AP_GROUPINFO ( " MIN_CRSE_S " , 8 , SoaringController , min_cruise_s , 10 ) ,
2017-02-26 19:13:46 -04:00
// @Param: POLAR_CD0
// @DisplayName: Zero lift drag coef.
// @Description: Zero lift drag coefficient
2020-06-02 08:03:02 -03:00
// @Range: 0.005 0.5
2017-02-26 19:13:46 -04:00
// @User: Advanced
2020-04-20 08:11:22 -03:00
AP_GROUPINFO ( " POLAR_CD0 " , 9 , SoaringController , _polarParams . CD0 , 0.027 ) ,
2017-02-26 19:13:46 -04:00
// @Param: POLAR_B
// @DisplayName: Induced drag coeffient
// @Description: Induced drag coeffient
2020-06-02 08:03:02 -03:00
// @Range: 0.005 0.05
2017-02-26 19:13:46 -04:00
// @User: Advanced
2020-04-20 08:11:22 -03:00
AP_GROUPINFO ( " POLAR_B " , 10 , SoaringController , _polarParams . B , 0.031 ) ,
2017-02-26 19:13:46 -04:00
// @Param: POLAR_K
// @DisplayName: Cl factor
// @Description: Cl factor 2*m*g/(rho*S)
2017-05-02 10:48:16 -03:00
// @Units: m.m/s/s
2020-06-02 08:03:02 -03:00
// @Range: 20 400
2017-02-26 19:13:46 -04:00
// @User: Advanced
2020-04-20 08:11:22 -03:00
AP_GROUPINFO ( " POLAR_K " , 11 , SoaringController , _polarParams . K , 25.6 ) ,
2017-02-26 19:13:46 -04:00
// @Param: ALT_MAX
// @DisplayName: Maximum soaring altitude, relative to the home location
// @Description: Don't thermal any higher than this.
2017-05-02 10:48:16 -03:00
// @Units: m
2020-06-02 08:03:02 -03:00
// @Range: 0 5000.0
2017-02-26 19:13:46 -04:00
// @User: Advanced
AP_GROUPINFO ( " ALT_MAX " , 12 , SoaringController , alt_max , 350.0 ) ,
// @Param: ALT_MIN
// @DisplayName: Minimum soaring altitude, relative to the home location
// @Description: Don't get any lower than this.
2017-05-02 10:48:16 -03:00
// @Units: m
2017-02-26 19:13:46 -04:00
// @Range: 0 1000.0
// @User: Advanced
AP_GROUPINFO ( " ALT_MIN " , 13 , SoaringController , alt_min , 50.0 ) ,
// @Param: ALT_CUTOFF
// @DisplayName: Maximum power altitude, relative to the home location
// @Description: Cut off throttle at this alt.
2017-05-02 10:48:16 -03:00
// @Units: m
2020-06-02 08:03:02 -03:00
// @Range: 0 5000.0
2017-02-26 19:13:46 -04:00
// @User: Advanced
AP_GROUPINFO ( " ALT_CUTOFF " , 14 , SoaringController , alt_cutoff , 250.0 ) ,
2017-03-01 00:00:02 -04:00
2020-07-13 05:46:51 -03:00
// 15 was SOAR_ENABLE_CH, now RCX_OPTION
2017-02-26 19:13:46 -04:00
2019-06-09 07:01:16 -03:00
// @Param: MAX_DRIFT
2019-06-08 22:10:35 -03:00
// @DisplayName: (Optional) Maximum drift distance to allow when thermalling.
2020-07-31 08:06:57 -03:00
// @Description: The previous mode will be restored if the horizontal distance to the thermalling start location exceeds this value. -1 to disable.
2019-06-08 22:10:35 -03:00
// @Range: 0 1000
// @User: Advanced
2019-06-22 14:51:17 -03:00
AP_GROUPINFO ( " MAX_DRIFT " , 16 , SoaringController , max_drift , - 1 ) ,
2019-06-08 22:10:35 -03:00
2019-06-17 09:15:53 -03:00
// @Param: MAX_RADIUS
// @DisplayName: (Optional) Maximum distance from home
// @Description: RTL will be entered when a thermal is exited and the plane is more than this distance from home. -1 to disable.
// @Range: 0 1000
// @User: Advanced
AP_GROUPINFO ( " MAX_RADIUS " , 17 , SoaringController , max_radius , - 1 ) ,
2021-01-20 17:07:31 -04:00
// @Param: THML_BANK
// @DisplayName: Thermalling bank angle
// @Description: This parameter sets the bank angle to use when thermalling. Typically 30 - 45 degrees works well.
// @Range: 20 50
// @User: Advanced
2021-01-29 14:16:33 -04:00
// @Units: deg
2021-01-20 17:07:31 -04:00
AP_GROUPINFO ( " THML_BANK " , 18 , SoaringController , thermal_bank , 30.0 ) ,
2020-07-10 11:14:23 -03:00
// 19 reserved for POLAR_LEARN.
// @Param: THML_ARSPD
2022-10-17 21:51:09 -03:00
// @DisplayName: Specific setting for airspeed when soaring in THERMAL mode.
// @Description: If non-zero this airspeed will be used when thermalling. A value of 0 will use TRIM_ARSPD_CM.
// @Range: 0 50
2020-07-10 11:14:23 -03:00
// @User: Advanced
AP_GROUPINFO ( " THML_ARSPD " , 20 , SoaringController , soar_thermal_airspeed , 0 ) ,
// @Param: CRSE_ARSPD
2022-10-17 21:51:09 -03:00
// @DisplayName: Specific setting for airspeed when soaring in AUTO mode.
// @Description: If non-zero this airspeed will be used when cruising between thermals in AUTO. If set to -1, airspeed will be selected based on speed-to-fly theory. If set to 0, then TRIM_ARSPD_CM will be used while cruising between thermals.
// @Range: -1 50
2020-07-10 11:14:23 -03:00
// @User: Advanced
AP_GROUPINFO ( " CRSE_ARSPD " , 21 , SoaringController , soar_cruise_airspeed , 0 ) ,
// @Param: THML_FLAP
// @DisplayName: Flap percent to be used during thermalling flight.
// @Description: This sets the flap when in LOITER with soaring active. Overrides the usual auto flap behaviour.
// @Range: 0 100
// @User: Advanced
AP_GROUPINFO ( " THML_FLAP " , 22 , SoaringController , soar_thermal_flap , 0 ) ,
2017-02-26 19:13:46 -04:00
AP_GROUPEND
} ;
2022-09-29 20:10:41 -03:00
SoaringController : : SoaringController ( AP_TECS & tecs , const AP_FixedWing & parms ) :
2021-11-12 13:55:01 -04:00
_tecs ( tecs ) ,
2020-04-20 08:11:22 -03:00
_vario ( parms , _polarParams ) ,
2021-02-28 08:54:34 -04:00
_speedToFly ( _polarParams ) ,
2019-05-16 07:39:56 -03:00
_aparm ( parms ) ,
2017-04-29 07:40:24 -03:00
_throttle_suppressed ( true )
2017-02-26 19:13:46 -04:00
{
AP_Param : : setup_object_defaults ( this , var_info ) ;
}
void SoaringController : : get_target ( Location & wp )
{
2020-05-05 01:41:17 -03:00
wp = AP : : ahrs ( ) . get_home ( ) ;
2020-01-11 11:14:28 -04:00
wp . offset ( _position_x_filter . get ( ) , _position_y_filter . get ( ) ) ;
2017-02-26 19:13:46 -04:00
}
bool SoaringController : : suppress_throttle ( )
{
2019-04-24 09:35:43 -03:00
float alt = _vario . alt ;
2017-02-26 19:13:46 -04:00
if ( _throttle_suppressed & & ( alt < alt_min ) ) {
// Time to throttle up
2018-10-18 09:51:21 -03:00
set_throttle_suppressed ( false ) ;
2017-02-26 19:13:46 -04:00
} else if ( ( ! _throttle_suppressed ) & & ( alt > alt_cutoff ) ) {
// Start glide
2018-10-18 09:51:21 -03:00
set_throttle_suppressed ( true ) ;
2017-02-26 19:13:46 -04:00
// Zero the pitch integrator - the nose is currently raised to climb, we need to go back to glide.
2021-11-12 13:55:01 -04:00
_tecs . reset_pitch_I ( ) ;
2018-10-18 09:51:21 -03:00
2017-02-26 19:13:46 -04:00
_cruise_start_time_us = AP_HAL : : micros64 ( ) ;
2021-04-04 09:17:05 -03:00
2017-02-26 19:13:46 -04:00
// Reset the filtered vario rate - it is currently elevated due to the climb rate and would otherwise take a while to fall again,
// leading to false positives.
2021-04-04 09:17:05 -03:00
_vario . reset_trigger_filter ( 0.0f ) ;
2017-02-26 19:13:46 -04:00
}
return _throttle_suppressed ;
}
bool SoaringController : : check_thermal_criteria ( )
{
2021-08-03 08:08:14 -03:00
return ( _last_update_status = = ActiveStatus : : AUTO_MODE_CHANGE
2017-02-26 19:13:46 -04:00
& & ( ( AP_HAL : : micros64 ( ) - _cruise_start_time_us ) > ( ( unsigned ) min_cruise_s * 1e6 ) )
2021-04-04 09:17:05 -03:00
& & ( _vario . get_trigger_value ( ) - _vario . get_exp_thermalling_sink ( ) ) > thermal_vspeed
2017-04-27 18:44:03 -03:00
& & _vario . alt < alt_max
2019-08-18 12:02:15 -03:00
& & _vario . alt > alt_min ) ;
2017-02-26 19:13:46 -04:00
}
2019-06-05 15:23:29 -03:00
2019-06-22 14:51:17 -03:00
SoaringController : : LoiterStatus SoaringController : : check_cruise_criteria ( Vector2f prev_wp , Vector2f next_wp )
2017-02-26 19:13:46 -04:00
{
2021-06-03 07:34:57 -03:00
// Check conditions for re-entering cruise. Note that the aircraft needs to also be aligned with the appropriate
// heading before some of these conditions will actually trigger.
// The GCS messages are emitted in mode_thermal.cpp. Update these if the logic here is changed.
2021-08-03 08:08:14 -03:00
if ( _last_update_status = = ActiveStatus : : SOARING_DISABLED ) {
2020-04-05 08:38:19 -03:00
return LoiterStatus : : DISABLED ;
2019-06-05 15:23:29 -03:00
}
2017-02-26 19:13:46 -04:00
2020-04-05 08:38:19 -03:00
LoiterStatus result = LoiterStatus : : GOOD_TO_KEEP_LOITERING ;
2019-06-05 15:23:29 -03:00
const float alt = _vario . alt ;
2020-09-07 08:59:47 -03:00
if ( _exit_commanded ) {
result = LoiterStatus : : EXIT_COMMANDED ;
} else if ( alt > alt_max ) {
2020-04-05 08:38:19 -03:00
result = LoiterStatus : : ALT_TOO_HIGH ;
2019-06-05 15:23:29 -03:00
} else if ( alt < alt_min ) {
2020-04-05 08:38:19 -03:00
result = LoiterStatus : : ALT_TOO_LOW ;
2019-06-05 15:23:29 -03:00
} else if ( ( AP_HAL : : micros64 ( ) - _thermal_start_time_us ) > ( ( unsigned ) min_thermal_s * 1e6 ) ) {
const float mcCreadyAlt = McCready ( alt ) ;
2019-06-22 13:02:35 -03:00
if ( _thermalability < mcCreadyAlt ) {
2020-04-05 08:38:19 -03:00
result = LoiterStatus : : THERMAL_WEAK ;
2021-04-04 09:17:05 -03:00
} else if ( alt < ( - _thermal_start_pos . z ) | | _vario . get_filtered_climb ( ) < 0.0 ) {
2020-04-05 08:38:19 -03:00
result = LoiterStatus : : ALT_LOST ;
2019-06-22 14:51:17 -03:00
} else if ( check_drift ( prev_wp , next_wp ) ) {
2020-04-05 08:38:19 -03:00
result = LoiterStatus : : DRIFT_EXCEEDED ;
2019-06-05 15:23:29 -03:00
}
2017-02-26 19:13:46 -04:00
}
2019-06-07 12:07:06 -03:00
return result ;
2017-02-26 19:13:46 -04:00
}
void SoaringController : : init_thermalling ( )
{
// Calc filter matrices - so that changes to parameters can be updated by switching in and out of thermal mode
2019-04-24 09:35:43 -03:00
float r = powf ( thermal_r , 2 ) ; // Measurement noise
float cov_q1 = powf ( thermal_q1 , 2 ) ; // Process noise for strength
float cov_q2 = powf ( thermal_q2 , 2 ) ; // Process noise for position and radius
const float init_q [ 4 ] = { cov_q1 ,
cov_q2 ,
cov_q2 ,
cov_q2 } ;
2017-03-01 00:12:12 -04:00
const MatrixN < float , 4 > q { init_q } ;
2019-04-24 09:35:43 -03:00
const float init_p [ 4 ] = { INITIAL_STRENGTH_COVARIANCE ,
INITIAL_RADIUS_COVARIANCE ,
INITIAL_POSITION_COVARIANCE ,
INITIAL_POSITION_COVARIANCE } ;
2017-03-01 00:12:12 -04:00
const MatrixN < float , 4 > p { init_p } ;
2017-02-26 19:13:46 -04:00
2019-03-29 11:10:11 -03:00
Vector3f position ;
2020-05-05 01:41:17 -03:00
const AP_AHRS & _ahrs = AP : : ahrs ( ) ;
2019-03-29 11:10:11 -03:00
if ( ! _ahrs . get_relative_position_NED_home ( position ) ) {
return ;
}
2017-02-26 19:13:46 -04:00
// New state vector filter will be reset. Thermal location is placed in front of a/c
2021-04-14 19:22:14 -03:00
const float init_xr [ 4 ] = { _vario . get_trigger_value ( ) ,
2017-02-26 19:13:46 -04:00
INITIAL_THERMAL_RADIUS ,
2024-01-12 08:40:23 -04:00
position . x + thermal_distance_ahead * cosf ( _ahrs . get_yaw ( ) ) ,
position . y + thermal_distance_ahead * sinf ( _ahrs . get_yaw ( ) ) } ;
2019-04-24 09:35:43 -03:00
2017-02-26 19:13:46 -04:00
const VectorN < float , 4 > xr { init_xr } ;
// Also reset covariance matrix p so filter is not affected by previous data
_ekf . reset ( xr , p , q , r ) ;
_prev_update_time = AP_HAL : : micros64 ( ) ;
_thermal_start_time_us = AP_HAL : : micros64 ( ) ;
2019-06-08 22:10:35 -03:00
_thermal_start_pos = position ;
2019-06-08 09:51:00 -03:00
2021-04-04 09:17:05 -03:00
_vario . reset_climb_filter ( 0.0 ) ;
2020-01-11 11:14:28 -04:00
_position_x_filter . reset ( _ekf . X [ 2 ] ) ;
_position_y_filter . reset ( _ekf . X [ 3 ] ) ;
2020-09-07 08:59:47 -03:00
_exit_commanded = false ;
2017-02-26 19:13:46 -04:00
}
void SoaringController : : init_cruising ( )
{
2021-08-03 08:08:14 -03:00
if ( _last_update_status > = ActiveStatus : : MANUAL_MODE_CHANGE ) {
2017-02-26 19:13:46 -04:00
_cruise_start_time_us = AP_HAL : : micros64 ( ) ;
// Start glide. Will be updated on the next loop.
2018-10-18 09:51:21 -03:00
set_throttle_suppressed ( true ) ;
2017-02-26 19:13:46 -04:00
}
}
void SoaringController : : update_thermalling ( )
{
2019-04-24 09:35:43 -03:00
float deltaT = ( AP_HAL : : micros64 ( ) - _prev_update_time ) * 1e-6 ;
2019-03-29 11:10:11 -03:00
Vector3f current_position ;
2020-05-05 01:41:17 -03:00
const AP_AHRS & _ahrs = AP : : ahrs ( ) ;
2019-03-29 11:10:11 -03:00
if ( ! _ahrs . get_relative_position_NED_home ( current_position ) ) {
return ;
}
2017-02-26 19:13:46 -04:00
2021-04-04 09:17:05 -03:00
Vector3f wind_drift = _ahrs . wind_estimate ( ) * deltaT * _vario . get_filtered_climb ( ) / _ekf . X [ 0 ] ;
2019-03-29 11:08:52 -03:00
2019-06-22 13:02:35 -03:00
// update the filter
_ekf . update ( _vario . reading , current_position . x , current_position . y , wind_drift . x , wind_drift . y ) ;
2021-01-20 17:07:31 -04:00
_thermalability = ( _ekf . X [ 0 ] * expf ( - powf ( get_thermalling_radius ( ) / _ekf . X [ 1 ] , 2 ) ) ) - _vario . get_exp_thermalling_sink ( ) ;
2019-06-22 13:02:35 -03:00
_prev_update_time = AP_HAL : : micros64 ( ) ;
2020-01-11 11:14:28 -04:00
// Compute smoothed estimate of position
_position_x_filter . set_cutoff_frequency ( 1 / ( 3 * _vario . tau ) ) ;
_position_y_filter . set_cutoff_frequency ( 1 / ( 3 * _vario . tau ) ) ;
_position_x_filter . apply ( _ekf . X [ 2 ] , deltaT ) ;
_position_y_filter . apply ( _ekf . X [ 3 ] , deltaT ) ;
2019-03-29 11:08:52 -03:00
// write log - save the data.
2020-04-05 21:44:21 -03:00
// @LoggerMessage: SOAR
// @Vehicles: Plane
// @Description: Logged data from soaring feature
// @URL: https://ardupilot.org/plane/docs/soaring.html
// @Field: TimeUS: microseconds since system startup
// @Field: nettorate: Estimate of vertical speed of surrounding airmass
// @Field: x0: Thermal strength estimate
// @Field: x1: Thermal radius estimate
// @Field: x2: Thermal position estimate north from home
// @Field: x3: Thermal position estimate east from home
// @Field: north: Aircraft position north from home
// @Field: east: Aircraft position east from home
// @Field: alt: Aircraft altitude
// @Field: dx_w: Wind speed north
// @Field: dy_w: Wind speed east
// @Field: th: Estimate of achievable climbrate in thermal
2021-08-17 06:57:41 -03:00
AP : : logger ( ) . WriteStreaming ( " SOAR " , " TimeUS,nettorate,x0,x1,x2,x3,north,east,alt,dx_w,dy_w,th " , " Qfffffffffff " ,
2019-03-29 11:08:52 -03:00
AP_HAL : : micros64 ( ) ,
( double ) _vario . reading ,
( double ) _ekf . X [ 0 ] ,
( double ) _ekf . X [ 1 ] ,
( double ) _ekf . X [ 2 ] ,
( double ) _ekf . X [ 3 ] ,
2019-04-24 09:35:43 -03:00
current_position . x ,
current_position . y ,
2019-03-29 11:08:52 -03:00
( double ) _vario . alt ,
2019-04-24 09:35:43 -03:00
( double ) wind_drift . x ,
2019-06-22 13:02:35 -03:00
( double ) wind_drift . y ,
( double ) _thermalability ) ;
2017-02-26 19:13:46 -04:00
}
void SoaringController : : update_cruising ( )
{
2021-02-28 08:54:34 -04:00
// Calculate the optimal airspeed for the current conditions of wind along current direction,
// expected lift in next thermal and filtered sink rate.
Vector3f wind = AP : : ahrs ( ) . wind_estimate ( ) ;
Vector3f wind_bf = AP : : ahrs ( ) . earth_to_body ( wind ) ;
const float wx = wind_bf . x ;
const float wz = _vario . get_stf_value ( ) ;
// Constraints on the airspeed calculation.
const float CLmin = _polarParams . K / ( _aparm . airspeed_max * _aparm . airspeed_max ) ;
const float CLmax = _polarParams . K / ( _aparm . airspeed_min * _aparm . airspeed_min ) ;
// Update the calculation.
_speedToFly . update ( wx , wz , thermal_vspeed , CLmin , CLmax ) ;
AP : : logger ( ) . WriteStreaming ( " SORC " , " TimeUS,wx,wz,wexp,CLmin,CLmax,Vopt " , " Qffffff " ,
AP_HAL : : micros64 ( ) ,
( double ) wx ,
( double ) wz ,
( double ) thermal_vspeed ,
( double ) CLmin ,
( double ) CLmax ,
( double ) _speedToFly . speed_to_fly ( ) ) ;
2017-02-26 19:13:46 -04:00
}
void SoaringController : : update_vario ( )
{
2020-04-20 08:11:22 -03:00
_vario . update ( thermal_bank ) ;
2017-02-26 19:13:46 -04:00
}
float SoaringController : : McCready ( float alt )
{
// A method shell to be filled in later
return thermal_vspeed ;
}
2021-08-03 08:08:14 -03:00
SoaringController : : ActiveStatus SoaringController : : active_state ( bool override_disable ) const
2017-02-26 19:13:46 -04:00
{
2021-08-03 08:08:14 -03:00
if ( override_disable | | ! soar_active ) {
2020-07-13 05:46:51 -03:00
return ActiveStatus : : SOARING_DISABLED ;
2019-08-18 12:02:15 -03:00
}
2020-07-13 05:46:51 -03:00
return _pilot_desired_state ;
2017-02-26 19:13:46 -04:00
}
2018-10-18 09:51:21 -03:00
2021-08-03 08:08:14 -03:00
void SoaringController : : update_active_state ( bool override_disable )
2019-07-15 07:27:29 -03:00
{
2021-08-03 08:08:14 -03:00
ActiveStatus status = active_state ( override_disable ) ;
2019-08-18 12:02:15 -03:00
bool state_changed = ! ( status = = _last_update_status ) ;
2019-07-15 07:27:29 -03:00
if ( state_changed ) {
2019-08-18 12:19:15 -03:00
switch ( status ) {
2020-07-13 05:46:51 -03:00
case ActiveStatus : : SOARING_DISABLED :
2019-08-18 12:19:15 -03:00
// It's not enabled, but was enabled on the last loop.
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Soaring: Disabled. " ) ;
set_throttle_suppressed ( false ) ;
break ;
2020-04-05 08:38:19 -03:00
case ActiveStatus : : MANUAL_MODE_CHANGE :
2019-08-18 12:19:15 -03:00
// It's enabled, but wasn't on the last loop.
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Soaring: Enabled, manual mode changes. " ) ;
break ;
2020-04-05 08:38:19 -03:00
case ActiveStatus : : AUTO_MODE_CHANGE :
2019-08-18 12:19:15 -03:00
gcs ( ) . send_text ( MAV_SEVERITY_INFO , " Soaring: Enabled, automatic mode changes. " ) ;
break ;
2019-07-15 07:27:29 -03:00
}
2021-03-21 06:46:11 -03:00
if ( _last_update_status = = ActiveStatus : : SOARING_DISABLED ) {
// We have switched from disabled into an active mode, start cruising.
init_cruising ( ) ;
} else if ( status ! = ActiveStatus : : SOARING_DISABLED ) {
// We switched between active modes. If we're in THERMAL this means we should exit gracefully.
// This has no effect if we're cruising as it is reset on thermal entry.
_exit_commanded = true ;
}
2019-07-15 07:27:29 -03:00
}
2019-08-18 12:02:15 -03:00
_last_update_status = status ;
2019-07-15 07:27:29 -03:00
}
2018-10-18 09:51:21 -03:00
void SoaringController : : set_throttle_suppressed ( bool suppressed )
{
_throttle_suppressed = suppressed ;
// Let the TECS know.
2021-11-12 13:55:01 -04:00
_tecs . set_gliding_requested_flag ( suppressed ) ;
2019-06-22 14:51:17 -03:00
}
bool SoaringController : : check_drift ( Vector2f prev_wp , Vector2f next_wp )
{
// Check for -1 (disabled)
if ( max_drift < 0 ) {
return false ;
}
// Check against the estimated thermal.
Vector2f position ( _ekf . X [ 2 ] , _ekf . X [ 3 ] ) ;
Vector2f start_pos ( _thermal_start_pos . x , _thermal_start_pos . y ) ;
Vector2f mission_leg = next_wp - prev_wp ;
if ( prev_wp . is_zero ( ) | | mission_leg . length ( ) < 0.1 ) {
// Simple check of distance from initial start point.
return ( position - start_pos ) . length ( ) > max_drift ;
} else {
// Regard the effective start point as projected onto mission leg.
// Calculate drift parallel and perpendicular to mission leg.
// Drift parallel and in direction of mission leg is acceptable.
Vector2f effective_start , vec1 , vec2 ;
// Calculate effective start point (on mission leg).
vec1 = ( start_pos - prev_wp ) . projected ( mission_leg ) ;
effective_start = prev_wp + vec1 ;
// Calculate parallel and perpendicular offsets.
vec2 = position - effective_start ;
float parallel = vec2 * mission_leg . normalized ( ) ;
float perpendicular = ( vec2 - mission_leg . normalized ( ) * parallel ) . length ( ) ;
// Check if we've drifted beyond the next wp.
if ( parallel > ( next_wp - effective_start ) . length ( ) ) {
return true ;
}
// Check if we've drifted too far laterally or backwards. We don't count positive parallel offsets
// as these are favourable (towards next wp)
parallel = parallel > 0 ? 0 : parallel ;
2022-02-05 08:19:37 -04:00
return ( powf ( parallel , 2 ) + powf ( perpendicular , 2 ) ) > powf ( max_drift , 2 ) ;
2019-06-22 14:51:17 -03:00
}
2019-08-19 11:18:25 -03:00
}
2020-09-23 05:20:07 -03:00
2021-01-20 17:07:31 -04:00
float SoaringController : : get_thermalling_radius ( ) const
{
// Thermalling radius is controlled by parameter SOAR_THML_BANK and true target airspeed.
2021-11-12 13:55:01 -04:00
const float target_aspd = _tecs . get_target_airspeed ( ) * AP : : ahrs ( ) . get_EAS2TAS ( ) ;
2021-01-20 17:07:31 -04:00
const float radius = ( target_aspd * target_aspd ) / ( GRAVITY_MSS * tanf ( thermal_bank * DEG_TO_RAD ) ) ;
return radius ;
}
2020-07-10 11:14:23 -03:00
float SoaringController : : get_thermalling_target_airspeed ( )
{
return soar_thermal_airspeed ;
}
float SoaringController : : get_cruising_target_airspeed ( )
{
2021-02-28 08:54:34 -04:00
if ( soar_cruise_airspeed < 0 ) {
return _speedToFly . speed_to_fly ( ) ;
}
2020-07-10 11:14:23 -03:00
return soar_cruise_airspeed ;
}
2020-09-23 05:20:07 -03:00
# endif // HAL_SOARING_ENABLED