2016-01-14 15:30:56 -04:00
# include "Sub.h"
2015-12-30 18:57:56 -04:00
// get_pilot_desired_angle - transform pilot's roll or pitch input into a desired lean angle
// returns desired angle in centi-degrees
2016-01-14 15:30:56 -04:00
void Sub : : get_pilot_desired_lean_angles ( float roll_in , float pitch_in , float & roll_out , float & pitch_out , float angle_max )
2015-12-30 18:57:56 -04:00
{
// sanity check angle max parameter
2022-07-05 00:08:57 -03:00
aparm . angle_max . set ( constrain_int16 ( aparm . angle_max , 1000 , 8000 ) ) ;
2015-12-30 18:57:56 -04:00
// limit max lean angle
angle_max = constrain_float ( angle_max , 1000 , aparm . angle_max ) ;
// scale roll_in, pitch_in to ANGLE_MAX parameter range
float scaler = aparm . angle_max / ( float ) ROLL_PITCH_INPUT_MAX ;
roll_in * = scaler ;
pitch_in * = scaler ;
// do circular limit
2017-02-03 00:18:27 -04:00
float total_in = norm ( pitch_in , roll_in ) ;
2015-12-30 18:57:56 -04:00
if ( total_in > angle_max ) {
float ratio = angle_max / total_in ;
roll_in * = ratio ;
pitch_in * = ratio ;
}
// do lateral tilt to euler roll conversion
2016-02-27 15:35:34 -04:00
roll_in = ( 18000 / M_PI ) * atanf ( cosf ( pitch_in * ( M_PI / 18000 ) ) * tanf ( roll_in * ( M_PI / 18000 ) ) ) ;
2015-12-30 18:57:56 -04:00
// return
roll_out = roll_in ;
pitch_out = pitch_in ;
}
// get_pilot_desired_heading - transform pilot's yaw input into a
// desired yaw rate
// returns desired yaw rate in centi-degrees per second
2021-02-01 12:26:24 -04:00
float Sub : : get_pilot_desired_yaw_rate ( int16_t stick_angle ) const
2015-12-30 18:57:56 -04:00
{
// convert pilot input to the desired yaw rate
return stick_angle * g . acro_yaw_p ;
}
// check for ekf yaw reset and adjust target heading
2016-01-14 15:30:56 -04:00
void Sub : : check_ekf_yaw_reset ( )
2015-12-30 18:57:56 -04:00
{
2018-01-26 23:45:07 -04:00
float yaw_angle_change_rad ;
2015-12-30 18:57:56 -04:00
uint32_t new_ekfYawReset_ms = ahrs . getLastYawResetAngle ( yaw_angle_change_rad ) ;
if ( new_ekfYawReset_ms ! = ekfYawReset_ms ) {
2018-01-26 23:45:07 -04:00
attitude_control . inertial_frame_reset ( ) ;
2015-12-30 18:57:56 -04:00
ekfYawReset_ms = new_ekfYawReset_ms ;
}
}
/*************************************************************
* yaw controllers
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
// get_roi_yaw - returns heading towards location held in roi_WP
// should be called at 100hz
2016-01-14 15:30:56 -04:00
float Sub : : get_roi_yaw ( )
2015-12-30 18:57:56 -04:00
{
static uint8_t roi_yaw_counter = 0 ; // used to reduce update rate to 100hz
roi_yaw_counter + + ;
if ( roi_yaw_counter > = 4 ) {
roi_yaw_counter = 0 ;
2021-10-20 05:30:56 -03:00
yaw_look_at_WP_bearing = get_bearing_cd ( inertial_nav . get_position_xy_cm ( ) , roi_WP . xy ( ) ) ;
2015-12-30 18:57:56 -04:00
}
return yaw_look_at_WP_bearing ;
}
2016-01-14 15:30:56 -04:00
float Sub : : get_look_ahead_yaw ( )
2015-12-30 18:57:56 -04:00
{
2021-10-20 05:30:56 -03:00
const Vector3f & vel = inertial_nav . get_velocity_neu_cms ( ) ;
const float speed_sq = vel . xy ( ) . length_squared ( ) ;
2015-12-30 18:57:56 -04:00
// Commanded Yaw to automatically look ahead.
2021-10-20 05:30:56 -03:00
if ( position_ok ( ) & & ( speed_sq > ( YAW_LOOK_AHEAD_MIN_SPEED * YAW_LOOK_AHEAD_MIN_SPEED ) ) ) {
2015-12-30 18:57:56 -04:00
yaw_look_ahead_bearing = degrees ( atan2f ( vel . y , vel . x ) ) * 100.0f ;
}
return yaw_look_ahead_bearing ;
}
/*************************************************************
* throttle control
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
2016-04-05 00:17:39 -03:00
// get_pilot_desired_climb_rate - transform pilot's throttle input to climb rate in cm/s
2015-12-30 18:57:56 -04:00
// without any deadzone at the bottom
2016-01-14 15:30:56 -04:00
float Sub : : get_pilot_desired_climb_rate ( float throttle_control )
2015-12-30 18:57:56 -04:00
{
// throttle failsafe check
2017-04-14 16:58:54 -03:00
if ( failsafe . pilot_input ) {
2015-12-30 18:57:56 -04:00
return 0.0f ;
}
float desired_rate = 0.0f ;
float mid_stick = channel_throttle - > get_control_mid ( ) ;
2023-10-31 17:59:34 -03:00
float deadband_top = mid_stick + g . throttle_deadzone * gain ;
float deadband_bottom = mid_stick - g . throttle_deadzone * gain ;
2015-12-30 18:57:56 -04:00
// ensure a reasonable throttle value
2016-04-05 00:17:39 -03:00
throttle_control = constrain_float ( throttle_control , 0.0f , 1000.0f ) ;
2015-12-30 18:57:56 -04:00
// ensure a reasonable deadzone
2022-07-05 00:08:57 -03:00
g . throttle_deadzone . set ( constrain_int16 ( g . throttle_deadzone , 0 , 400 ) ) ;
2015-12-30 18:57:56 -04:00
// check throttle is above, below or in the deadband
if ( throttle_control < deadband_bottom ) {
// below the deadband
2017-11-19 08:29:09 -04:00
desired_rate = get_pilot_speed_dn ( ) * ( throttle_control - deadband_bottom ) / deadband_bottom ;
2017-02-03 17:33:27 -04:00
} else if ( throttle_control > deadband_top ) {
2015-12-30 18:57:56 -04:00
// above the deadband
2017-11-19 08:29:09 -04:00
desired_rate = g . pilot_speed_up * ( throttle_control - deadband_top ) / ( 1000.0f - deadband_top ) ;
2017-02-03 17:33:27 -04:00
} else {
2015-12-30 18:57:56 -04:00
// must be in the deadband
desired_rate = 0.0f ;
}
// desired climb rate for logging
desired_climb_rate = desired_rate ;
return desired_rate ;
}
2017-02-10 13:46:54 -04:00
// get_surface_tracking_climb_rate - hold vehicle at the desired distance above the ground
2015-12-30 18:57:56 -04:00
// returns climb rate (in cm/s) which should be passed to the position controller
2016-01-14 15:30:56 -04:00
float Sub : : get_surface_tracking_climb_rate ( int16_t target_rate , float current_alt_target , float dt )
2015-12-30 18:57:56 -04:00
{
2016-05-22 21:50:44 -03:00
# if RANGEFINDER_ENABLED == ENABLED
2015-12-30 18:57:56 -04:00
static uint32_t last_call_ms = 0 ;
float distance_error ;
float velocity_correction ;
2021-10-20 05:30:56 -03:00
float current_alt = inertial_nav . get_position_z_up_cm ( ) ;
2015-12-30 18:57:56 -04:00
2018-04-13 20:05:16 -03:00
uint32_t now = AP_HAL : : millis ( ) ;
2015-12-30 18:57:56 -04:00
// reset target altitude if this controller has just been engaged
2016-05-22 21:50:44 -03:00
if ( now - last_call_ms > RANGEFINDER_TIMEOUT_MS ) {
2017-02-03 17:33:27 -04:00
target_rangefinder_alt = rangefinder_state . alt_cm + current_alt_target - current_alt ;
2015-12-30 18:57:56 -04:00
}
last_call_ms = now ;
2016-05-22 21:50:44 -03:00
// adjust rangefinder target alt if motors have not hit their limits
2015-12-30 18:57:56 -04:00
if ( ( target_rate < 0 & & ! motors . limit . throttle_lower ) | | ( target_rate > 0 & & ! motors . limit . throttle_upper ) ) {
2016-05-22 21:50:44 -03:00
target_rangefinder_alt + = target_rate * dt ;
2015-12-30 18:57:56 -04:00
}
// do not let target altitude get too far from current altitude above ground
2021-04-27 03:50:06 -03:00
target_rangefinder_alt = constrain_float ( target_rangefinder_alt ,
2021-05-19 11:08:30 -03:00
rangefinder_state . alt_cm - pos_control . get_pos_error_z_down_cm ( ) ,
rangefinder_state . alt_cm + pos_control . get_pos_error_z_up_cm ( ) ) ;
2015-12-30 18:57:56 -04:00
2016-05-22 21:50:44 -03:00
// calc desired velocity correction from target rangefinder alt vs actual rangefinder alt (remove the error already passed to Altitude controller to avoid oscillations)
distance_error = ( target_rangefinder_alt - rangefinder_state . alt_cm ) - ( current_alt_target - current_alt ) ;
velocity_correction = distance_error * g . rangefinder_gain ;
2015-12-30 18:57:56 -04:00
velocity_correction = constrain_float ( velocity_correction , - THR_SURFACE_TRACKING_VELZ_MAX , THR_SURFACE_TRACKING_VELZ_MAX ) ;
2016-05-22 21:50:44 -03:00
// return combined pilot climb rate + rate to correct rangefinder alt error
2015-12-30 18:57:56 -04:00
return ( target_rate + velocity_correction ) ;
2016-05-22 21:50:44 -03:00
# else
return ( float ) target_rate ;
# endif
2015-12-30 18:57:56 -04:00
}
// rotate vector from vehicle's perspective to North-East frame
2016-01-14 15:30:56 -04:00
void Sub : : rotate_body_frame_to_NE ( float & x , float & y )
2015-12-30 18:57:56 -04:00
{
float ne_x = x * ahrs . cos_yaw ( ) - y * ahrs . sin_yaw ( ) ;
float ne_y = x * ahrs . sin_yaw ( ) + y * ahrs . cos_yaw ( ) ;
x = ne_x ;
y = ne_y ;
}
2017-11-19 08:29:09 -04:00
// It will return the PILOT_SPEED_DN value if non zero, otherwise if zero it returns the PILOT_SPEED_UP value.
2021-02-01 12:26:24 -04:00
uint16_t Sub : : get_pilot_speed_dn ( ) const
2017-11-19 08:29:09 -04:00
{
if ( g . pilot_speed_dn = = 0 ) {
return abs ( g . pilot_speed_up ) ;
}
2018-06-28 12:18:49 -03:00
return abs ( g . pilot_speed_dn ) ;
2017-11-19 08:29:09 -04:00
}