APM:Copter
mode_acro_heli.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 #if MODE_ACRO_ENABLED == ENABLED
4 
5 #if FRAME_CONFIG == HELI_FRAME
6 /*
7  * Init and run calls for acro flight mode for trad heli
8  */
9 
10 // heli_acro_init - initialise acro controller
11 bool Copter::ModeAcro_Heli::init(bool ignore_checks)
12 {
13  // if heli is equipped with a flybar, then tell the attitude controller to pass through controls directly to servos
14  attitude_control->use_flybar_passthrough(motors->has_flybar(), motors->supports_yaw_passthrough());
15 
16  motors->set_acro_tail(true);
17 
18  // set stab collective false to use full collective pitch range
19  copter.input_manager.set_use_stab_col(false);
20 
21  // always successfully enter acro
22  return true;
23 }
24 
25 // heli_acro_run - runs the acro controller
26 // should be called at 100hz or more
27 void Copter::ModeAcro_Heli::run()
28 {
29  float target_roll, target_pitch, target_yaw;
30  float pilot_throttle_scaled;
31 
32  // Tradheli should not reset roll, pitch, yaw targets when motors are not runup, because
33  // we may be in autorotation flight. These should be reset only when transitioning from disarmed
34  // to armed, because the pilot will have placed the helicopter down on the landing pad. This is so
35  // that the servos move in a realistic fashion while disarmed for operational checks.
36  // Also, unlike multicopters we do not set throttle (i.e. collective pitch) to zero so the swash servos move
37 
38  if(!motors->armed()) {
39  copter.heli_flags.init_targets_on_arming=true;
40  attitude_control->set_attitude_target_to_current_attitude();
41  attitude_control->reset_rate_controller_I_terms();
42  }
43 
44  if(motors->armed() && copter.heli_flags.init_targets_on_arming) {
45  attitude_control->set_attitude_target_to_current_attitude();
46  attitude_control->reset_rate_controller_I_terms();
47  if (motors->get_interlock()) {
48  copter.heli_flags.init_targets_on_arming=false;
49  }
50  }
51 
52  // clear landing flag above zero throttle
53  if (motors->armed() && motors->get_interlock() && motors->rotor_runup_complete() && !ap.throttle_zero) {
54  set_land_complete(false);
55  }
56 
57  if (!motors->has_flybar()){
58  // convert the input to the desired body frame rate
59  get_pilot_desired_angle_rates(channel_roll->get_control_in(), channel_pitch->get_control_in(), channel_yaw->get_control_in(), target_roll, target_pitch, target_yaw);
60 
61  if (motors->supports_yaw_passthrough()) {
62  // if the tail on a flybar heli has an external gyro then
63  // also use no deadzone for the yaw control and
64  // pass-through the input direct to output.
65  target_yaw = channel_yaw->get_control_in_zero_dz();
66  }
67 
68  // run attitude controller
69  attitude_control->input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
70  }else{
71  /*
72  for fly-bar passthrough use control_in values with no
73  deadzone. This gives true pass-through.
74  */
75  float roll_in = channel_roll->get_control_in_zero_dz();
76  float pitch_in = channel_pitch->get_control_in_zero_dz();
77  float yaw_in;
78 
79  if (motors->supports_yaw_passthrough()) {
80  // if the tail on a flybar heli has an external gyro then
81  // also use no deadzone for the yaw control and
82  // pass-through the input direct to output.
83  yaw_in = channel_yaw->get_control_in_zero_dz();
84  } else {
85  // if there is no external gyro then run the usual
86  // ACRO_YAW_P gain on the input control, including
87  // deadzone
88  yaw_in = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
89  }
90 
91  // run attitude controller
92  attitude_control->passthrough_bf_roll_pitch_rate_yaw(roll_in, pitch_in, yaw_in);
93  }
94 
95  // get pilot's desired throttle
96  pilot_throttle_scaled = copter.input_manager.get_pilot_desired_collective(channel_throttle->get_control_in());
97 
98  // output pilot's throttle without angle boost
99  attitude_control->set_throttle_out(pilot_throttle_scaled, false, g.throttle_filt);
100 }
101 
102 #endif //HELI_FRAME
103 #endif //MODE_ACRO_ENABLED == ENABLED
AP_MotorsMatrix motors(400)
bool armed() const
bool get_interlock() const
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581