APM:Copter
heli.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // Traditional helicopter variables and functions
4 
5 #if FRAME_CONFIG == HELI_FRAME
6 
7 #ifndef HELI_DYNAMIC_FLIGHT_SPEED_MIN
8  #define HELI_DYNAMIC_FLIGHT_SPEED_MIN 500 // we are in "dynamic flight" when the speed is over 5m/s for 2 seconds
9 #endif
10 
11 // counter to control dynamic flight profile
12 static int8_t heli_dynamic_flight_counter;
13 
14 // heli_init - perform any special initialisation required for the tradheli
15 void Copter::heli_init()
16 {
17  // pre-load stab col values as mode is initialized as Stabilize, but stabilize_init() function is not run on start-up.
18  input_manager.set_use_stab_col(true);
19  input_manager.set_stab_col_ramp(1.0);
20 }
21 
22 // heli_check_dynamic_flight - updates the dynamic_flight flag based on our horizontal velocity
23 // should be called at 50hz
25 {
26  if (!motors->armed() || !motors->rotor_runup_complete() ||
28  heli_dynamic_flight_counter = 0;
29  heli_flags.dynamic_flight = false;
30  return;
31  }
32 
33  bool moving = false;
34 
35  // with GPS lock use inertial nav to determine if we are moving
36  if (position_ok()) {
37  // get horizontal velocity
38  float velocity = inertial_nav.get_velocity_xy();
39  moving = (velocity >= HELI_DYNAMIC_FLIGHT_SPEED_MIN);
40  }else{
41  // with no GPS lock base it on throttle and forward lean angle
42  moving = (motors->get_throttle() > 0.8f || ahrs.pitch_sensor < -1500);
43  }
44 
45  if (!moving && rangefinder_state.enabled && rangefinder.status_orient(ROTATION_PITCH_270) == RangeFinder::RangeFinder_Good) {
46  // when we are more than 2m from the ground with good
47  // rangefinder lock consider it to be dynamic flight
48  moving = (rangefinder.distance_cm_orient(ROTATION_PITCH_270) > 200);
49  }
50 
51  if (moving) {
52  // if moving for 2 seconds, set the dynamic flight flag
53  if (!heli_flags.dynamic_flight) {
54  heli_dynamic_flight_counter++;
55  if (heli_dynamic_flight_counter >= 100) {
56  heli_flags.dynamic_flight = true;
57  heli_dynamic_flight_counter = 100;
58  }
59  }
60  }else{
61  // if not moving for 2 seconds, clear the dynamic flight flag
62  if (heli_flags.dynamic_flight) {
63  if (heli_dynamic_flight_counter > 0) {
64  heli_dynamic_flight_counter--;
65  }else{
66  heli_flags.dynamic_flight = false;
67  }
68  }
69  }
70 }
71 
72 // update_heli_control_dynamics - pushes several important factors up into AP_MotorsHeli.
73 // should be run between the rate controller and the servo updates.
75 {
76  // Use Leaky_I if we are not moving fast
77  attitude_control->use_leaky_i(!heli_flags.dynamic_flight);
78 
79  if (ap.land_complete || (is_zero(motors->get_desired_rotor_speed()))){
80  // if we are landed or there is no rotor power demanded, decrement slew scalar
81  hover_roll_trim_scalar_slew--;
82  } else {
83  // if we are not landed and motor power is demanded, increment slew scalar
84  hover_roll_trim_scalar_slew++;
85  }
86  hover_roll_trim_scalar_slew = constrain_int16(hover_roll_trim_scalar_slew, 0, scheduler.get_loop_rate_hz());
87 
88  // set hover roll trim scalar, will ramp from 0 to 1 over 1 second after we think helicopter has taken off
89  attitude_control->set_hover_roll_trim_scalar((float)(hover_roll_trim_scalar_slew/scheduler.get_loop_rate_hz()));
90 }
91 
92 // heli_update_landing_swash - sets swash plate flag so higher minimum is used when landed or landing
93 // should be called soon after update_land_detector in main code
95 {
96  switch(control_mode) {
97  case ACRO:
98  case STABILIZE:
99  case DRIFT:
100  case SPORT:
101  // manual modes always uses full swash range
102  motors->set_collective_for_landing(false);
103  break;
104 
105  case LAND:
106  // landing always uses limit swash range
107  motors->set_collective_for_landing(true);
108  break;
109 
110  case RTL:
111  case SMART_RTL:
112  if (mode_rtl.state() == RTL_Land) {
113  motors->set_collective_for_landing(true);
114  }else{
115  motors->set_collective_for_landing(!heli_flags.dynamic_flight || ap.land_complete || !ap.auto_armed);
116  }
117  break;
118 
119  case AUTO:
120  if (mode_auto.mode() == Auto_Land) {
121  motors->set_collective_for_landing(true);
122  }else{
123  motors->set_collective_for_landing(!heli_flags.dynamic_flight || ap.land_complete || !ap.auto_armed);
124  }
125  break;
126 
127  default:
128  // auto and hold use limited swash when landed
129  motors->set_collective_for_landing(!heli_flags.dynamic_flight || ap.land_complete || !ap.auto_armed);
130  break;
131  }
132 }
133 
134 // heli_update_rotor_speed_targets - reads pilot input and passes new rotor speed targets to heli motors object
136 {
137 
138  static bool rotor_runup_complete_last = false;
139 
140  // get rotor control method
141  uint8_t rsc_control_mode = motors->get_rsc_mode();
142 
143  float rsc_control_deglitched = rotor_speed_deglitch_filter.apply((float)RC_Channels::rc_channel(CH_8)->get_control_in()) * 0.001f;
144 
145  switch (rsc_control_mode) {
147  // pass through pilot desired rotor speed if control input is higher than 10, creating a deadband at the bottom
148  if (rsc_control_deglitched > 0.01f) {
149  ap.motor_interlock_switch = true;
150  motors->set_desired_rotor_speed(rsc_control_deglitched);
151  } else {
152  ap.motor_interlock_switch = false;
153  motors->set_desired_rotor_speed(0.0f);
154  }
155  break;
159  // pass setpoint through as desired rotor speed, this is almost pointless as the Setpoint serves no function in this mode
160  // other than being used to create a crude estimate of rotor speed
161  if (rsc_control_deglitched > 0.0f) {
162  ap.motor_interlock_switch = true;
163  motors->set_desired_rotor_speed(motors->get_rsc_setpoint());
164  }else{
165  ap.motor_interlock_switch = false;
166  motors->set_desired_rotor_speed(0.0f);
167  }
168  break;
169  }
170 
171  // when rotor_runup_complete changes to true, log event
172  if (!rotor_runup_complete_last && motors->rotor_runup_complete()){
174  } else if (rotor_runup_complete_last && !motors->rotor_runup_complete()){
176  }
177  rotor_runup_complete_last = motors->rotor_runup_complete();
178 }
179 
180 #endif // FRAME_CONFIG == HELI_FRAME
#define DATA_ROTOR_SPEED_BELOW_CRITICAL
Definition: defines.h:379
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
AC_AttitudeControl_t * attitude_control
Definition: Copter.h:492
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
static RC_Channel * rc_channel(uint8_t chan)
uint16_t get_loop_rate_hz(void)
RangeFinder rangefinder
Definition: Copter.h:238
ModeAuto mode_auto
Definition: Copter.h:965
Definition: defines.h:95
#define DATA_ROTOR_RUNUP_COMPLETE
Definition: defines.h:378
struct Copter::@0 rangefinder_state
Definition: defines.h:100
ROTOR_CONTROL_MODE_SPEED_SETPOINT
void check_dynamic_flight(void)
void heli_update_landing_swash()
Definition: defines.h:101
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
Definition: defines.h:102
ROTOR_CONTROL_MODE_CLOSED_LOOP_POWER_OUTPUT
MOTOR_CLASS * motors
Definition: Copter.h:422
void heli_init()
AutoMode mode() const
Definition: Copter.h:250
Definition: defines.h:93
int32_t pitch_sensor
bool is_zero(const T fVal1)
void Log_Write_Event(uint8_t id)
Definition: Log.cpp:200
RTLState state()
Definition: Copter.h:945
uint16_t distance_cm_orient(enum Rotation orientation) const
ModeRTL mode_rtl
Definition: Copter.h:994
AP_Scheduler scheduler
Definition: Copter.h:212
RangeFinder_Status status_orient(enum Rotation orientation) const
void update_heli_control_dynamics(void)
bool position_ok()
Definition: system.cpp:312
void heli_update_rotor_speed_targets()
ROTOR_CONTROL_MODE_SPEED_PASSTHROUGH
float get_velocity_xy() const
control_mode_t control_mode
Definition: Copter.h:345
ROTOR_CONTROL_MODE_OPEN_LOOP_POWER_OUTPUT
Definition: defines.h:98