APM:Copter
mode_stabilize_heli.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if FRAME_CONFIG == HELI_FRAME
4 /*
5  * Init and run calls for stabilize flight mode for trad heli
6  */
7 
8 // stabilize_init - initialise stabilize controller
9 bool Copter::ModeStabilize_Heli::init(bool ignore_checks)
10 {
11  // set target altitude to zero for reporting
12  // To-Do: make pos controller aware when it's active/inactive so it can always report the altitude error?
13  pos_control->set_alt_target(0);
14 
15  // set stab collective true to use stabilize scaled collective pitch range
16  copter.input_manager.set_use_stab_col(true);
17 
18  return true;
19 }
20 
21 // stabilize_run - runs the main stabilize controller
22 // should be called at 100hz or more
23 void Copter::ModeStabilize_Heli::run()
24 {
25  float target_roll, target_pitch;
26  float target_yaw_rate;
27  float pilot_throttle_scaled;
28 
29  // Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because
30  // we may be in autorotation flight. These should be reset only when transitioning from disarmed
31  // to armed, because the pilot will have placed the helicopter down on the landing pad. This is so
32  // that the servos move in a realistic fashion while disarmed for operational checks.
33  // Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
34 
35  if(!motors->armed()) {
36  copter.heli_flags.init_targets_on_arming = true;
37  attitude_control->set_yaw_target_to_current_heading();
38  attitude_control->reset_rate_controller_I_terms();
39  }
40 
41  if(motors->armed() && copter.heli_flags.init_targets_on_arming) {
42  attitude_control->set_yaw_target_to_current_heading();
43  attitude_control->reset_rate_controller_I_terms();
44  if (motors->get_interlock()) {
45  copter.heli_flags.init_targets_on_arming=false;
46  }
47  }
48 
49  // clear landing flag above zero throttle
50  if (motors->armed() && motors->get_interlock() && motors->rotor_runup_complete() && !ap.throttle_zero) {
51  set_land_complete(false);
52  }
53 
54  // apply SIMPLE mode transform to pilot inputs
55  update_simple_mode();
56 
57  // convert pilot input to lean angles
58  get_pilot_desired_lean_angles(target_roll, target_pitch, copter.aparm.angle_max, copter.aparm.angle_max);
59 
60  // get pilot's desired yaw rate
61  target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
62 
63  // get pilot's desired throttle
64  pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());
65 
66  // call attitude controller
67  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(target_roll, target_pitch, target_yaw_rate);
68 
69  // output pilot's throttle - note that TradHeli does not used angle-boost
70  attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
71 }
72 
73 #endif //HELI_FRAME
AP_MotorsMatrix motors(400)
bool armed() const
bool get_interlock() const
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581