#include "Sub.h"
bool ModeAlthold::init(bool ignore_checks) {
if(!sub.control_check_barometer()) {
return false;
}
position_control->D_set_max_speed_accel_cm(sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
position_control->D_set_correction_speed_accel_cm(sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
position_control->D_init_controller();
sub.last_pilot_heading_rad = ahrs.get_yaw_rad();
return true;
}
void ModeAlthold::run()
{
run_pre();
control_depth();
run_post();
}
void ModeAlthold::run_pre()
{
uint32_t tnow = AP_HAL::millis();
position_control->D_set_max_speed_accel_cm(sub.get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z);
if (!motors.armed()) {
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
attitude_control->set_throttle_out(NEUTRAL_THROTTLE,true,g.throttle_filt);
attitude_control->relax_attitude_controllers();
position_control->D_relax_controller(motors.get_throttle_hover());
sub.last_pilot_heading_rad = ahrs.get_yaw_rad();
return;
}
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
float target_roll, target_pitch;
if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
float target_yaw;
Quaternion(
sub.set_attitude_target_no_gps.packet.q
).to_euler(
target_roll,
target_pitch,
target_yaw
);
target_roll = degrees(target_roll);
target_pitch = degrees(target_pitch);
target_yaw = degrees(target_yaw);
attitude_control->input_euler_angle_roll_pitch_yaw_cd(target_roll * 1e2f, target_pitch * 1e2f, target_yaw * 1e2f, true);
return;
}
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());
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);
if (!is_zero(target_yaw_rate)) {
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(target_roll, target_pitch, target_yaw_rate);
sub.last_pilot_heading_rad = ahrs.get_yaw_rad();
sub.last_pilot_yaw_input_ms = tnow;
} else {
if (tnow < sub.last_pilot_yaw_input_ms + 250) {
target_yaw_rate = 0;
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(target_roll, target_pitch, target_yaw_rate);
sub.last_pilot_heading_rad = ahrs.get_yaw_rad();
} else {
attitude_control->input_euler_angle_roll_pitch_yaw_cd(target_roll, target_pitch, rad_to_cd(sub.last_pilot_heading_rad), true);
}
}
}
void ModeAlthold::run_post()
{
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
}
void ModeAlthold::control_depth() {
float distance_to_surface = (g.surface_depth - inertial_nav.get_position_z_up_cm()) * 0.01f;
distance_to_surface = constrain_float(distance_to_surface, 0.0f, 1.0f);
motors.set_max_throttle(g.surface_max_throttle + (1.0f - g.surface_max_throttle) * distance_to_surface);
float target_climb_rate_cms = sub.get_pilot_desired_climb_rate(channel_throttle->get_control_in());
target_climb_rate_cms = constrain_float(target_climb_rate_cms, -sub.get_pilot_speed_dn(), g.pilot_speed_up);
if (fabsf(target_climb_rate_cms) < 0.05f) {
if (sub.ap.at_surface) {
position_control->set_pos_desired_U_cm(MIN(position_control->get_pos_desired_U_cm(), g.surface_depth));
} else if (sub.ap.at_bottom) {
position_control->set_pos_desired_U_cm(MAX(inertial_nav.get_position_z_up_cm() + 10.0f, position_control->get_pos_desired_U_cm()));
}
}
position_control->D_set_pos_target_from_climb_rate_cms(target_climb_rate_cms);
position_control->D_update_controller();
}