#include "Sub.h"
bool ModeSurface::init(bool ignore_checks)
{
nobaro_mode = !sub.control_check_barometer();
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();
return true;
}
void ModeSurface::run()
{
float target_roll, target_pitch;
if (!motors.armed()) {
motors.output_min();
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_init_controller();
return;
}
if (nobaro_mode) {
float thrust_output = 0.5f + g2.surface_nobaro_thrust * 0.005f;
attitude_control->set_throttle_out(thrust_output, true, g.throttle_filt);
} else {
if (sub.ap.at_surface) {
set_mode(Mode::Number::ALT_HOLD, ModeReason::SURFACE_COMPLETE);
}
sub.get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control->lean_angle_max_cd());
float target_yaw_rate = sub.get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_cd(target_roll, target_pitch, target_yaw_rate);
float cmb_rate_cms = constrain_float(fabsf(sub.wp_nav.get_default_speed_up_cms()), 1, position_control->get_max_speed_up_cms());
position_control->D_set_pos_target_from_climb_rate_cms(cmb_rate_cms);
position_control->D_update_controller();
}
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
}