#include "Sub.h"
bool ModeStabilize::init(bool ignore_checks) {
position_control->set_pos_desired_U_cm(0);
sub.last_pilot_heading_rad = ahrs.get_yaw_rad();
return true;
return true;
}
void ModeStabilize::run()
{
uint32_t tnow = AP_HAL::millis();
float target_roll, target_pitch;
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();
sub.last_pilot_heading_rad = ahrs.get_yaw_rad();
return;
}
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
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 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);
}
}
attitude_control->set_throttle_out((channel_throttle->norm_input() + 1.0f) / 2.0f, false, g.throttle_filt);
motors.set_forward(channel_forward->norm_input());
motors.set_lateral(channel_lateral->norm_input());
}