APM:Libraries
AC_InputManager_Heli.cpp
Go to the documentation of this file.
1 #include "AC_InputManager_Heli.h"
2 #include <AP_Math/AP_Math.h>
3 #include <AP_HAL/AP_HAL.h>
4 
5 extern const AP_HAL::HAL& hal;
6 
8 
9  // parameters from parent vehicle
11 
12  // @Param: STAB_COL_1
13  // @DisplayName: Stabilize Mode Collective Point 1
14  // @Description: Helicopter's minimum collective pitch setting at zero throttle input in Stabilize mode
15  // @Range: 0 500
16  // @Units: d%
17  // @Increment: 1
18  // @User: Standard
20 
21  // @Param: STAB_COL_2
22  // @DisplayName: Stabilize Mode Collective Point 2
23  // @Description: Helicopter's collective pitch setting at mid-low throttle input in Stabilize mode
24  // @Range: 0 500
25  // @Units: d%
26  // @Increment: 1
27  // @User: Standard
29 
30  // @Param: STAB_COL_3
31  // @DisplayName: Stabilize Mode Collective Point 3
32  // @Description: Helicopter's collective pitch setting at mid-high throttle input in Stabilize mode
33  // @Range: 500 1000
34  // @Units: d%
35  // @Increment: 1
36  // @User: Standard
38 
39  // @Param: STAB_COL_4
40  // @DisplayName: Stabilize Mode Collective Point 4
41  // @Description: Helicopter's maximum collective pitch setting at full throttle input in Stabilize mode
42  // @Range: 500 1000
43  // @Units: d%
44  // @Increment: 1
45  // @User: Standard
47 
48  // @Param: ACRO_COL_EXP
49  // @DisplayName: Acro Mode Collective Expo
50  // @Description: Used to soften collective pitch inputs near center point in Acro mode.
51  // @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
52  // @User: Advanced
53  AP_GROUPINFO("ACRO_COL_EXP", 5, AC_InputManager_Heli, _acro_col_expo, 0),
54 
56 };
57 
58 // get_pilot_desired_collective - rescale's pilot collective pitch input in Stabilize and Acro modes
60 {
61  float slope_low, slope_high, slope_range, slope_run, scalar;
62  float stab_col_out, acro_col_out;
63 
64  // calculate stabilize collective value which scales pilot input to reduced collective range
65  // code implements a 3-segment curve with knee points at 40% and 60% throttle input
66  if (control_in < 400){
67  slope_low = _heli_stab_col_min / 1000.0f;
68  slope_high = _heli_stab_col_low / 1000.0f;
69  slope_range = 0.4f;
70  slope_run = control_in / 1000.0f;
71  } else if(control_in <600){
72  slope_low = _heli_stab_col_low / 1000.0f;
73  slope_high = _heli_stab_col_high / 1000.0f;
74  slope_range = 0.2f;
75  slope_run = (control_in - 400) / 1000.0f;
76  } else {
77  slope_low = _heli_stab_col_high / 1000.0f;
78  slope_high = _heli_stab_col_max / 1000.0f;
79  slope_range = 0.4f;
80  slope_run = (control_in - 600) / 1000.0f;
81  }
82 
83  scalar = (slope_high - slope_low)/slope_range;
84  stab_col_out = slope_low + slope_run * scalar;
85  stab_col_out = constrain_float(stab_col_out, 0.0f, 1.0f);
86 
87  //
88  // calculate expo-scaled acro collective
89  // range check expo
90  if (_acro_col_expo > 1.0f) {
91  _acro_col_expo = 1.0f;
92  }
93 
94  if (_acro_col_expo <= 0.0f) {
95  acro_col_out = control_in / 1000.0f;
96  } else {
97  // expo variables
98  float col_in, col_in3, col_out;
99  col_in = (float)(control_in-500)/500.0f;
100  col_in3 = col_in*col_in*col_in;
101  col_out = (_acro_col_expo * col_in3) + ((1.0f-_acro_col_expo)*col_in);
102  acro_col_out = 0.5f + col_out*0.5f;
103  }
104  acro_col_out = constrain_float(acro_col_out, 0.0f, 1.0f);
105 
106  // ramp to and from stab col over 1/2 second
107  if (_im_flags_heli.use_stab_col && (_stab_col_ramp < 1.0f)){
108  _stab_col_ramp += 2.0f/(float)_loop_rate;
109  } else if(!_im_flags_heli.use_stab_col && (_stab_col_ramp > 0.0f)){
110  _stab_col_ramp -= 2.0f/(float)_loop_rate;
111  }
113 
114  // scale collective output smoothly between acro and stab col
115  float collective_out;
116  collective_out = (float)((1.0f-_stab_col_ramp)*acro_col_out + _stab_col_ramp*stab_col_out);
117  collective_out = constrain_float(collective_out, 0.0f, 1.0f);
118 
119  return collective_out;
120 }
121 
122 
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
struct AC_InputManager_Heli::InputManagerHeliFlags _im_flags_heli
#define AC_ATTITUDE_HELI_STAB_COLLECTIVE_MAX_DEFAULT
float get_pilot_desired_collective(int16_t control_in)
#define AC_ATTITUDE_HELI_STAB_COLLECTIVE_MIN_DEFAULT
static const struct AP_Param::GroupInfo var_info[]
Pilot manual control input library for Conventional Helicopter.
#define f(i)
#define AC_ATTITUDE_HELI_STAB_COLLECTIVE_HIGH_DEFAULT
#define AC_ATTITUDE_HELI_STAB_COLLECTIVE_LOW_DEFAULT
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
#define AP_NESTEDGROUPINFO(clazz, idx)
Definition: AP_Param.h:105
Class managing the pilot&#39;s control inputs.
#define AP_GROUPEND
Definition: AP_Param.h:121