3 #if FRAME_CONFIG == HELI_FRAME
5 * Init and run calls for stabilize flight mode for trad heli
8 // stabilize_init - initialise stabilize controller
9 bool ModeStabilize_Heli::init(bool ignore_checks
)
11 // be aware that when adding code to this function that it is *NOT
12 // RUN* at vehicle startup!
14 // set stab collective true to use stabilize scaled collective pitch range
15 copter
.input_manager
.set_use_stab_col(true);
20 // stabilize_run - runs the main stabilize controller
21 // should be called at 100hz or more
22 void ModeStabilize_Heli::run()
24 float target_roll
, target_pitch
;
25 float pilot_throttle_scaled
;
27 // apply SIMPLE mode transform to pilot inputs
30 // convert pilot input to lean angles
31 get_pilot_desired_lean_angles(target_roll
, target_pitch
, copter
.aparm
.angle_max
, copter
.aparm
.angle_max
);
33 // get pilot's desired yaw rate
34 float target_yaw_rate
= get_pilot_desired_yaw_rate();
36 // get pilot's desired throttle
37 pilot_throttle_scaled
= copter
.input_manager
.get_pilot_desired_collective(channel_throttle
->get_control_in());
39 // Tradheli should not reset roll, pitch, yaw targets when motors are not runup while flying, because
40 // we may be in autorotation flight. This is so that the servos move in a realistic fashion while disarmed
41 // for operational checks. Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero
42 // so the swash servos move.
44 if (!motors
->armed()) {
45 // Motors should be Stopped
46 motors
->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN
);
48 // heli will not let the spool state progress to THROTTLE_UNLIMITED until motor interlock is enabled
49 motors
->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED
);
52 switch (motors
->get_spool_state()) {
53 case AP_Motors::SpoolState::SHUT_DOWN
:
55 attitude_control
->reset_yaw_target_and_rate(false);
56 attitude_control
->reset_rate_controller_I_terms();
58 case AP_Motors::SpoolState::GROUND_IDLE
:
59 // If aircraft is landed, set target heading to current and reset the integrator
60 // Otherwise motors could be at ground idle for practice autorotation
61 if ((motors
->init_targets_on_arming() && motors
->using_leaky_integrator()) || (copter
.ap
.land_complete
&& !motors
->using_leaky_integrator())) {
62 attitude_control
->reset_yaw_target_and_rate(false);
63 attitude_control
->reset_rate_controller_I_terms_smoothly();
66 case AP_Motors::SpoolState::THROTTLE_UNLIMITED
:
67 if (copter
.ap
.land_complete
&& !motors
->using_leaky_integrator()) {
68 attitude_control
->reset_rate_controller_I_terms_smoothly();
71 case AP_Motors::SpoolState::SPOOLING_UP
:
72 case AP_Motors::SpoolState::SPOOLING_DOWN
:
77 // call attitude controller
78 attitude_control
->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll
, target_pitch
, target_yaw_rate
);
80 // output pilot's throttle
81 attitude_control
->set_throttle_out(pilot_throttle_scaled
, true, g
.throttle_filt
);