mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Sub: Remove simple mode parameters, and disable simple modes
This commit is contained in:
parent
9aa05e1195
commit
19afd7a3dd
@ -232,13 +232,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @User: Standard
|
||||
GSCALAR(compass_enabled, "MAG_ENABLE", MAGNETOMETER),
|
||||
|
||||
// @Param: SUPER_SIMPLE
|
||||
// @DisplayName: Super Simple Mode
|
||||
// @Description: Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode
|
||||
// @Values: 0:Disabled,1:Mode1,2:Mode2,3:Mode1+2,4:Mode3,5:Mode1+3,6:Mode2+3,7:Mode1+2+3,8:Mode4,9:Mode1+4,10:Mode2+4,11:Mode1+2+4,12:Mode3+4,13:Mode1+3+4,14:Mode2+3+4,15:Mode1+2+3+4,16:Mode5,17:Mode1+5,18:Mode2+5,19:Mode1+2+5,20:Mode3+5,21:Mode1+3+5,22:Mode2+3+5,23:Mode1+2+3+5,24:Mode4+5,25:Mode1+4+5,26:Mode2+4+5,27:Mode1+2+4+5,28:Mode3+4+5,29:Mode1+3+4+5,30:Mode2+3+4+5,31:Mode1+2+3+4+5,32:Mode6,33:Mode1+6,34:Mode2+6,35:Mode1+2+6,36:Mode3+6,37:Mode1+3+6,38:Mode2+3+6,39:Mode1+2+3+6,40:Mode4+6,41:Mode1+4+6,42:Mode2+4+6,43:Mode1+2+4+6,44:Mode3+4+6,45:Mode1+3+4+6,46:Mode2+3+4+6,47:Mode1+2+3+4+6,48:Mode5+6,49:Mode1+5+6,50:Mode2+5+6,51:Mode1+2+5+6,52:Mode3+5+6,53:Mode1+3+5+6,54:Mode2+3+5+6,55:Mode1+2+3+5+6,56:Mode4+5+6,57:Mode1+4+5+6,58:Mode2+4+5+6,59:Mode1+2+4+5+6,60:Mode3+4+5+6,61:Mode1+3+4+5+6,62:Mode2+3+4+5+6,63:Mode1+2+3+4+5+6
|
||||
// @User: Standard
|
||||
GSCALAR(super_simple, "SUPER_SIMPLE", 0),
|
||||
|
||||
// @Param: RTL_ALT_FINAL
|
||||
// @DisplayName: RTL Final Altitude
|
||||
// @Description: This is the altitude the vehicle will move to as the final stage of Returning to Launch or after completing a mission. Set to zero to land.
|
||||
@ -376,12 +369,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||
// @User: Standard
|
||||
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
||||
|
||||
// @Param: SIMPLE
|
||||
// @DisplayName: Simple mode bitmask
|
||||
// @Description: Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode)
|
||||
// @User: Advanced
|
||||
GSCALAR(simple_modes, "SIMPLE", 0),
|
||||
|
||||
// @Param: LOG_BITMASK
|
||||
// @DisplayName: Log bitmask
|
||||
// @Description: 4 byte bitmap of log types to enable
|
||||
|
@ -159,7 +159,6 @@ public:
|
||||
k_param_compass,
|
||||
k_param_fs_batt_voltage,
|
||||
k_param_ch7_option,
|
||||
k_param_super_simple = 155,
|
||||
k_param_ahrs, // AHRS group // 159
|
||||
|
||||
//
|
||||
@ -210,7 +209,6 @@ public:
|
||||
k_param_flight_mode4,
|
||||
k_param_flight_mode5,
|
||||
k_param_flight_mode6,
|
||||
k_param_simple_modes,
|
||||
|
||||
//
|
||||
// 210: Waypoint data
|
||||
@ -321,7 +319,6 @@ public:
|
||||
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
|
||||
|
||||
AP_Int8 compass_enabled;
|
||||
AP_Int8 super_simple;
|
||||
AP_Int16 rtl_alt_final;
|
||||
AP_Int16 rtl_climb_min; // rtl minimum climb in cm
|
||||
|
||||
@ -350,7 +347,6 @@ public:
|
||||
AP_Int8 flight_mode4;
|
||||
AP_Int8 flight_mode5;
|
||||
AP_Int8 flight_mode6;
|
||||
AP_Int8 simple_modes;
|
||||
|
||||
// Misc
|
||||
//
|
||||
|
@ -359,7 +359,8 @@ void Sub::report_flight_modes()
|
||||
print_divider();
|
||||
|
||||
for(int16_t i = 0; i < 6; i++ ) {
|
||||
print_switch(i, (control_mode_t)flight_modes[i].get(), BIT_IS_SET(g.simple_modes, i));
|
||||
// print_switch(i, (control_mode_t)flight_modes[i].get(), BIT_IS_SET(g.simple_modes, i));
|
||||
print_switch(i, (control_mode_t)flight_modes[i].get(), BIT_IS_SET(0, i));
|
||||
}
|
||||
print_blanks(2);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user