forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmode_stabilize_heli.cpp
84 lines (69 loc) · 3.29 KB
/
mode_stabilize_heli.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
#include "Copter.h"
#if FRAME_CONFIG == HELI_FRAME
/*
* Init and run calls for stabilize flight mode for trad heli
*/
// stabilize_init - initialise stabilize controller
bool ModeStabilize_Heli::init(bool ignore_checks)
{
// be aware that when adding code to this function that it is *NOT
// RUN* at vehicle startup!
// set stab collective true to use stabilize scaled collective pitch range
copter.input_manager.set_use_stab_col(true);
return true;
}
// stabilize_run - runs the main stabilize controller
// should be called at 100hz or more
void ModeStabilize_Heli::run()
{
float target_roll, target_pitch;
float pilot_throttle_scaled;
// apply SIMPLE mode transform to pilot inputs
update_simple_mode();
// convert pilot input to lean angles
get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
// get pilot's desired yaw rate
float target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->norm_input_dz());
// get pilot's desired throttle
pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());
// Tradheli should not reset roll, pitch, yaw targets when motors are not runup while flying, because
// we may be in autorotation flight. This is so that the servos move in a realistic fashion while disarmed
// for operational checks. Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero
// so the swash servos move.
if (!motors->armed()) {
// Motors should be Stopped
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::SHUT_DOWN);
} else {
// heli will not let the spool state progress to THROTTLE_UNLIMITED until motor interlock is enabled
motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
}
switch (motors->get_spool_state()) {
case AP_Motors::SpoolState::SHUT_DOWN:
// Motors Stopped
attitude_control->reset_yaw_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms();
break;
case AP_Motors::SpoolState::GROUND_IDLE:
// If aircraft is landed, set target heading to current and reset the integrator
// Otherwise motors could be at ground idle for practice autorotation
if ((motors->init_targets_on_arming() && motors->using_leaky_integrator()) || (copter.ap.land_complete && !motors->using_leaky_integrator())) {
attitude_control->reset_yaw_target_and_rate(false);
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;
case AP_Motors::SpoolState::THROTTLE_UNLIMITED:
if (copter.ap.land_complete && !motors->using_leaky_integrator()) {
attitude_control->reset_rate_controller_I_terms_smoothly();
}
break;
case AP_Motors::SpoolState::SPOOLING_UP:
case AP_Motors::SpoolState::SPOOLING_DOWN:
// do nothing
break;
}
// call attitude controller
attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
// output pilot's throttle - note that TradHeli does not used angle-boost
attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
}
#endif //HELI_FRAME