Files
ardupilot/ArduCopter/mode_althold.cpp
2025-12-17 08:03:10 +09:00

106 lines
3.8 KiB
C++

#include "Copter.h"
/*
* Init and run calls for althold, flight mode
*/
// althold_init - initialise althold controller
bool ModeAltHold::init(bool ignore_checks)
{
// initialise the vertical position controller
if (!pos_control->D_is_active()) {
pos_control->D_init_controller();
}
// set vertical speed and acceleration limits
pos_control->D_set_max_speed_accel_m(get_pilot_speed_dn_ms(), get_pilot_speed_up_ms(), get_pilot_accel_D_mss());
pos_control->D_set_correction_speed_accel_m(get_pilot_speed_dn_ms(), get_pilot_speed_up_ms(), get_pilot_accel_D_mss());
return true;
}
// althold_run - runs the althold controller
// should be called at 100hz or more
void ModeAltHold::run()
{
// set vertical speed and acceleration limits
pos_control->D_set_max_speed_accel_m(get_pilot_speed_dn_ms(), get_pilot_speed_up_ms(), get_pilot_accel_D_mss());
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();
// get pilot desired lean angles
float target_roll_rad, target_pitch_rad;
get_pilot_desired_lean_angles_rad(target_roll_rad, target_pitch_rad, attitude_control->lean_angle_max_rad(), attitude_control->get_althold_lean_angle_max_rad());
// get pilot's desired yaw rate
float target_yaw_rate_rads = get_pilot_desired_yaw_rate_rads();
// get pilot desired climb rate
float target_climb_rate_ms = get_pilot_desired_climb_rate_ms();
target_climb_rate_ms = constrain_float(target_climb_rate_ms, -get_pilot_speed_dn_ms(), get_pilot_speed_up_ms());
// Alt Hold State Machine Determination
AltHoldModeState althold_state = get_alt_hold_state_D_ms(target_climb_rate_ms);
// Alt Hold State Machine
switch (althold_state) {
case AltHoldModeState::MotorStopped:
attitude_control->reset_rate_controller_I_terms();
attitude_control->reset_yaw_target_and_rate(false);
pos_control->D_relax_controller(0.0f); // forces throttle output to decay to zero
break;
case AltHoldModeState::Landed_Ground_Idle:
attitude_control->reset_yaw_target_and_rate();
FALLTHROUGH;
case AltHoldModeState::Landed_Pre_Takeoff:
attitude_control->reset_rate_controller_I_terms_smoothly();
pos_control->D_relax_controller(0.0f); // forces throttle output to decay to zero
break;
case AltHoldModeState::Takeoff:
// initiate take-off
if (!takeoff.running()) {
takeoff.start_m(constrain_float(g.pilot_takeoff_alt_cm * 0.01, 0.0, 10.0));
}
// get avoidance adjusted climb rate
target_climb_rate_ms = get_avoidance_adjusted_climbrate_ms(target_climb_rate_ms);
// set position controller targets adjusted for pilot input
takeoff.do_pilot_takeoff_ms(target_climb_rate_ms);
break;
case AltHoldModeState::Flying:
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
#if AP_AVOIDANCE_ENABLED
// apply avoidance
copter.avoid.adjust_roll_pitch_rad(target_roll_rad, target_pitch_rad, attitude_control->lean_angle_max_rad());
#endif
// get avoidance adjusted climb rate
target_climb_rate_ms = get_avoidance_adjusted_climbrate_ms(target_climb_rate_ms);
#if AP_RANGEFINDER_ENABLED
// update the vertical offset based on the surface measurement
copter.surface_tracking.update_surface_offset();
#endif
// Send the commanded climb rate to the position controller
pos_control->D_set_pos_target_from_climb_rate_ms(target_climb_rate_ms);
break;
}
// call attitude controller
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw_rad(target_roll_rad, target_pitch_rad, target_yaw_rate_rads);
// run the vertical position controller and set output throttle
pos_control->D_update_controller();
}