2016-01-14 15:30:56 -04:00
# include "Sub.h"
2015-12-30 18:57:56 -04:00
2023-04-03 09:11:21 -03:00
bool ModeAlthold : : init ( bool ignore_checks ) {
if ( ! sub . control_check_barometer ( ) ) {
2017-02-03 17:33:27 -04:00
return false ;
}
2016-08-24 18:50:20 -03:00
2021-04-27 03:50:06 -03:00
// initialize vertical maximum speeds and acceleration
2016-01-20 23:29:51 -04:00
// sets the maximum speed up and down returned by position controller
2023-04-03 09:11:21 -03:00
position_control - > set_max_speed_accel_z ( - sub . get_pilot_speed_dn ( ) , g . pilot_speed_up , g . pilot_accel_z ) ;
position_control - > set_correction_speed_accel_z ( - sub . get_pilot_speed_dn ( ) , g . pilot_speed_up , g . pilot_accel_z ) ;
2015-12-30 18:57:56 -04:00
// initialise position and desired velocity
2023-04-03 09:11:21 -03:00
position_control - > init_z_controller ( ) ;
2015-12-30 18:57:56 -04:00
2023-04-03 09:11:21 -03:00
sub . last_pilot_heading = ahrs . yaw_sensor ;
2015-12-30 18:57:56 -04:00
return true ;
}
// althold_run - runs the althold controller
// should be called at 100hz or more
2023-04-03 09:11:21 -03:00
void ModeAlthold : : run ( )
2024-02-21 16:12:34 -04:00
{
run_pre ( ) ;
control_depth ( ) ;
run_post ( ) ;
}
void ModeAlthold : : run_pre ( )
2015-12-30 18:57:56 -04:00
{
2017-02-03 17:33:27 -04:00
uint32_t tnow = AP_HAL : : millis ( ) ;
2015-12-30 18:57:56 -04:00
// initialize vertical speeds and acceleration
2023-04-03 09:11:21 -03:00
position_control - > set_max_speed_accel_z ( - sub . get_pilot_speed_dn ( ) , g . pilot_speed_up , g . pilot_accel_z ) ;
2015-12-30 18:57:56 -04:00
2017-04-11 13:45:16 -03:00
if ( ! motors . armed ( ) ) {
2019-04-09 20:09:55 -03:00
motors . set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : GROUND_IDLE ) ;
2017-02-10 13:46:54 -04:00
// Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
2023-04-03 09:11:21 -03:00
attitude_control - > set_throttle_out ( 0.5 , true , g . throttle_filt ) ;
attitude_control - > relax_attitude_controllers ( ) ;
position_control - > relax_z_controller ( motors . get_throttle_hover ( ) ) ;
sub . last_pilot_heading = ahrs . yaw_sensor ;
2017-02-03 00:18:27 -04:00
return ;
}
2019-04-09 20:09:55 -03:00
motors . set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : THROTTLE_UNLIMITED ) ;
2017-02-03 00:18:27 -04:00
2015-12-30 18:57:56 -04:00
// get pilot desired lean angles
float target_roll , target_pitch ;
2018-04-14 00:15:15 -03:00
// Check if set_attitude_target_no_gps is valid
if ( tnow - sub . set_attitude_target_no_gps . last_message_ms < 5000 ) {
float target_yaw ;
Quaternion (
2023-04-03 09:11:21 -03:00
sub . set_attitude_target_no_gps . packet . q
2018-04-14 00:15:15 -03:00
) . to_euler (
target_roll ,
target_pitch ,
target_yaw
) ;
target_roll = degrees ( target_roll ) ;
target_pitch = degrees ( target_pitch ) ;
target_yaw = degrees ( target_yaw ) ;
2023-04-03 09:11:21 -03:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( target_roll * 1e2 f , target_pitch * 1e2 f , target_yaw * 1e2 f , true ) ;
2018-04-14 00:15:15 -03:00
return ;
}
2015-12-30 18:57:56 -04:00
2023-04-03 09:11:21 -03:00
sub . get_pilot_desired_lean_angles ( channel_roll - > get_control_in ( ) , channel_pitch - > get_control_in ( ) , target_roll , target_pitch , attitude_control - > get_althold_lean_angle_max_cd ( ) ) ;
2018-06-28 12:18:49 -03:00
2015-12-30 18:57:56 -04:00
// get pilot's desired yaw rate
2023-10-31 16:49:06 -03:00
float yaw_input = channel_yaw - > pwm_to_angle_dz_trim ( channel_yaw - > get_dead_zone ( ) * sub . gain , channel_yaw - > get_radio_trim ( ) ) ;
float target_yaw_rate = sub . get_pilot_desired_yaw_rate ( yaw_input ) ;
2015-12-30 18:57:56 -04:00
2017-02-03 17:33:27 -04:00
// call attitude controller
if ( ! is_zero ( target_yaw_rate ) ) { // call attitude controller with rate yaw determined by pilot input
2023-04-03 09:11:21 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( target_roll , target_pitch , target_yaw_rate ) ;
sub . last_pilot_heading = ahrs . yaw_sensor ;
sub . last_pilot_yaw_input_ms = tnow ; // time when pilot last changed heading
2017-02-03 17:33:27 -04:00
} else { // hold current heading
// this check is required to prevent bounce back after very fast yaw maneuvers
// the inertia of the vehicle causes the heading to move slightly past the point when pilot input actually stopped
2023-04-03 09:11:21 -03:00
if ( tnow < sub . last_pilot_yaw_input_ms + 250 ) { // give 250ms to slow down, then set target heading
2017-02-03 17:33:27 -04:00
target_yaw_rate = 0 ; // Stop rotation on yaw axis
// call attitude controller with target yaw rate = 0 to decelerate on yaw axis
2023-04-03 09:11:21 -03:00
attitude_control - > input_euler_angle_roll_pitch_euler_rate_yaw ( target_roll , target_pitch , target_yaw_rate ) ;
sub . last_pilot_heading = ahrs . yaw_sensor ; // update heading to hold
2017-02-03 17:33:27 -04:00
2024-02-21 16:12:34 -04:00
} else { // call attitude controller holding absolute bearing
2023-04-03 09:11:21 -03:00
attitude_control - > input_euler_angle_roll_pitch_yaw ( target_roll , target_pitch , sub . last_pilot_heading , true ) ;
2017-02-03 17:33:27 -04:00
}
}
2024-02-21 16:12:34 -04:00
}
2017-02-03 17:33:27 -04:00
2024-02-21 16:12:34 -04:00
void ModeAlthold : : run_post ( )
{
2020-08-03 00:31:50 -03:00
motors . set_forward ( channel_forward - > norm_input ( ) ) ;
motors . set_lateral ( channel_lateral - > norm_input ( ) ) ;
}
2023-04-03 09:11:21 -03:00
void ModeAlthold : : control_depth ( ) {
float target_climb_rate_cm_s = sub . get_pilot_desired_climb_rate ( channel_throttle - > get_control_in ( ) ) ;
target_climb_rate_cm_s = constrain_float ( target_climb_rate_cm_s , - sub . get_pilot_speed_dn ( ) , g . pilot_speed_up ) ;
2020-09-04 00:31:33 -03:00
// desired_climb_rate returns 0 when within the deadzone.
//we allow full control to the pilot, but as soon as there's no input, we handle being at surface/bottom
if ( fabsf ( target_climb_rate_cm_s ) < 0.05f ) {
2023-04-03 09:11:21 -03:00
if ( sub . ap . at_surface ) {
2024-09-17 01:49:43 -03:00
position_control - > set_pos_desired_z_cm ( MIN ( position_control - > get_pos_desired_z_cm ( ) , g . surface_depth - 5.0f ) ) ; // set target to 5 cm below surface level
2023-04-03 09:11:21 -03:00
} else if ( sub . ap . at_bottom ) {
2024-09-17 01:49:43 -03:00
position_control - > set_pos_desired_z_cm ( MAX ( inertial_nav . get_position_z_up_cm ( ) + 10.0f , position_control - > get_pos_desired_z_cm ( ) ) ) ; // set target to 10 cm above bottom
2017-02-27 14:06:55 -04:00
}
2020-09-04 00:31:33 -03:00
}
2019-03-06 14:47:35 -04:00
2023-04-03 09:11:21 -03:00
position_control - > set_pos_target_z_from_climb_rate_cm ( target_climb_rate_cm_s ) ;
position_control - > update_z_controller ( ) ;
2015-12-30 18:57:56 -04:00
}