#include "Sub.h"
#if POSHOLD_ENABLED
bool ModePoshold::init(bool ignore_checks)
{
if (!sub.position_ok()) {
return false;
}
position_control->NE_set_max_speed_accel_cm(g.pilot_speed, g.pilot_accel_z);
position_control->NE_set_correction_speed_accel_cm(g.pilot_speed, g.pilot_accel_z);
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->NE_init_controller_stopping_point();
position_control->D_init_controller();
attitude_control->set_throttle_out(NEUTRAL_THROTTLE ,true, g.throttle_filt);
attitude_control->relax_attitude_controllers();
position_control->D_relax_controller(0.5f);
sub.last_pilot_heading_rad = ahrs.get_yaw_rad();
return true;
}
void ModePoshold::run()
{
uint32_t tnow = AP_HAL::millis();
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->NE_init_controller_stopping_point();
position_control->D_relax_controller(0.5f);
sub.last_pilot_heading_rad = ahrs.get_yaw_rad();
return;
}
motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
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);
float target_roll, target_pitch;
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());
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);
}
}
control_depth();
control_horizontal();
}
void ModePoshold::control_horizontal() {
float lateral_out = 0;
float forward_out = 0;
Vector2f body_rates_cms = {
sub.get_pilot_desired_horizontal_rate(channel_forward),
sub.get_pilot_desired_horizontal_rate(channel_lateral)
};
if (sub.position_ok()) {
if (!position_control->NE_is_active()) {
position_control->NE_init_controller_stopping_point();
}
auto earth_rates_cms = ahrs.body_to_earth2D(body_rates_cms);
position_control->input_vel_accel_NE_cm(earth_rates_cms, {0, 0});
sub.translate_pos_control_rp(lateral_out, forward_out);
position_control->NE_update_controller();
} else if (g.pilot_speed > 0) {
forward_out = body_rates_cms.x / (float)g.pilot_speed;
lateral_out = body_rates_cms.y / (float)g.pilot_speed;
}
motors.set_forward(forward_out);
motors.set_lateral(lateral_out);
}
#endif