CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_InputManager/AC_InputManager_Heli.cpp
Views: 1798
1
#include "AC_InputManager_Heli.h"
2
#include <AP_Math/AP_Math.h>
3
#include <AP_HAL/AP_HAL.h>
4
#include <GCS_MAVLink/GCS.h>
5
6
extern const AP_HAL::HAL& hal;
7
8
const AP_Param::GroupInfo AC_InputManager_Heli::var_info[] = {
9
10
// parameters from parent vehicle
11
AP_NESTEDGROUPINFO(AC_InputManager, 0),
12
13
// Indicies 1-4 (STAB_COL_1 thru STAB_COL_4) have been replaced.
14
15
// @Param: ACRO_COL_EXP
16
// @DisplayName: Acro Mode Collective Expo
17
// @Description: Used to soften collective pitch inputs near center point in Acro mode.
18
// @Values: 0:Disabled,0.1:Very Low,0.2:Low,0.3:Medium,0.4:High,0.5:Very High
19
// @User: Advanced
20
AP_GROUPINFO("ACRO_COL_EXP", 5, AC_InputManager_Heli, _acro_col_expo, 0),
21
22
// @Param: STB_COL_1
23
// @DisplayName: Stabilize Collective Low
24
// @Description: Helicopter's minimum collective pitch setting at zero collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
25
// @Range: 0 100
26
// @Units: %
27
// @Increment: 1
28
// @User: Standard
29
AP_GROUPINFO("STB_COL_1", 6, AC_InputManager_Heli, _heli_stab_col_min, AC_ATTITUDE_HELI_STAB_COLLECTIVE_MIN_DEFAULT),
30
31
// @Param: STB_COL_2
32
// @DisplayName: Stabilize Collective Mid-Low
33
// @Description: Helicopter's collective pitch setting at mid-low (40%) collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
34
// @Range: 0 100
35
// @Units: %
36
// @Increment: 1
37
// @User: Standard
38
AP_GROUPINFO("STB_COL_2", 7, AC_InputManager_Heli, _heli_stab_col_low, AC_ATTITUDE_HELI_STAB_COLLECTIVE_LOW_DEFAULT),
39
40
// @Param: STB_COL_3
41
// @DisplayName: Stabilize Collective Mid-High
42
// @Description: Helicopter's collective pitch setting at mid-high (60%) collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
43
// @Range: 0 100
44
// @Units: %
45
// @Increment: 1
46
// @User: Standard
47
AP_GROUPINFO("STB_COL_3", 8, AC_InputManager_Heli, _heli_stab_col_high, AC_ATTITUDE_HELI_STAB_COLLECTIVE_HIGH_DEFAULT),
48
49
// @Param: STB_COL_4
50
// @DisplayName: Stabilize Collective High
51
// @Description: Helicopter's maximum collective pitch setting at full collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
52
// @Range: 0 100
53
// @Units: %
54
// @Increment: 1
55
// @User: Standard
56
AP_GROUPINFO("STB_COL_4", 9, AC_InputManager_Heli, _heli_stab_col_max, AC_ATTITUDE_HELI_STAB_COLLECTIVE_MAX_DEFAULT),
57
58
AP_GROUPEND
59
};
60
61
// get_pilot_desired_collective - rescale's pilot collective pitch input in Stabilize and Acro modes
62
float AC_InputManager_Heli::get_pilot_desired_collective(int16_t control_in)
63
{
64
float slope_low, slope_high, slope_range, slope_run, scalar;
65
float stab_col_out, acro_col_out;
66
67
// calculate stabilize collective value which scales pilot input to reduced collective range
68
// code implements a 3-segment curve with knee points at 40% and 60% throttle input
69
if (control_in < 400){ // control_in ranges from 0 to 1000
70
slope_low = _heli_stab_col_min * 0.01f;
71
slope_high = _heli_stab_col_low * 0.01f;
72
slope_range = 0.4f;
73
slope_run = control_in * 0.001f;
74
} else if(control_in <600){ // control_in ranges from 0 to 1000
75
slope_low = _heli_stab_col_low * 0.01f;
76
slope_high = _heli_stab_col_high * 0.01f;
77
slope_range = 0.2f;
78
slope_run = (control_in - 400) * 0.001f; // control_in ranges from 0 to 1000
79
} else {
80
slope_low = _heli_stab_col_high * 0.01f;
81
slope_high = _heli_stab_col_max * 0.01f;
82
slope_range = 0.4f;
83
slope_run = (control_in - 600) * 0.001f; // control_in ranges from 0 to 1000
84
}
85
86
scalar = (slope_high - slope_low)/slope_range;
87
stab_col_out = slope_low + slope_run * scalar;
88
stab_col_out = constrain_float(stab_col_out, 0.0f, 1.0f);
89
90
//
91
// calculate expo-scaled acro collective
92
// range check expo
93
if (_acro_col_expo > 1.0f) {
94
_acro_col_expo.set(1.0f);
95
}
96
97
if (_acro_col_expo <= 0.0f) {
98
acro_col_out = control_in * 0.001f; // control_in ranges from 0 to 1000
99
} else {
100
// expo variables
101
float col_in, col_in3, col_out;
102
col_in = (float)(control_in-500)/500.0f; // control_in ranges from 0 to 1000
103
col_in3 = col_in*col_in*col_in;
104
col_out = (_acro_col_expo * col_in3) + ((1.0f-_acro_col_expo)*col_in);
105
acro_col_out = 0.5f + col_out*0.5f;
106
}
107
acro_col_out = constrain_float(acro_col_out, 0.0f, 1.0f);
108
109
// ramp to and from stab col over 1/2 second
110
if (_im_flags_heli.use_stab_col && (_stab_col_ramp < 1.0f)){
111
_stab_col_ramp += 2.0f/(float)_loop_rate;
112
} else if(!_im_flags_heli.use_stab_col && (_stab_col_ramp > 0.0f)){
113
_stab_col_ramp -= 2.0f/(float)_loop_rate;
114
}
115
_stab_col_ramp = constrain_float(_stab_col_ramp, 0.0f, 1.0f);
116
117
// scale collective output smoothly between acro and stab col
118
float collective_out;
119
collective_out = (float)((1.0f-_stab_col_ramp)*acro_col_out + _stab_col_ramp*stab_col_out);
120
collective_out = constrain_float(collective_out, 0.0f, 1.0f);
121
122
return collective_out;
123
}
124
125
// parameter_check - check if input manager specific parameters are sensible
126
bool AC_InputManager_Heli::parameter_check(char* fail_msg, uint8_t fail_msg_len) const
127
{
128
129
const struct StabCheck {
130
const char *name;
131
int16_t value;
132
} stab_checks[] = {
133
{"IM_STB_COL_1", _heli_stab_col_min },
134
{"IM_STB_COL_2", _heli_stab_col_low },
135
{"IM_STB_COL_3", _heli_stab_col_high },
136
{"IM_STB_COL_4", _heli_stab_col_max },
137
};
138
139
// check values are within valid range
140
for (uint8_t i=0; i<ARRAY_SIZE(stab_checks); i++) {
141
const StabCheck check = stab_checks[i];
142
if ((check.value < 0) || (check.value > 100)){
143
hal.util->snprintf(fail_msg, fail_msg_len, "%s out of range", check.name);
144
return false;
145
}
146
}
147
// check values are in correct order
148
for (uint8_t i=1; i<ARRAY_SIZE(stab_checks); i++) {
149
if ((stab_checks[i-1].value >= stab_checks[i].value)){
150
hal.util->snprintf(fail_msg, fail_msg_len, "%s must be < %s", stab_checks[i-1].name, stab_checks[i].name);
151
return false;
152
}
153
}
154
// all other cases parameters are OK
155
return true;
156
}
157
158
159