mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
Plane: added INITIAL_MODE which is the mode we boot up into.
This is useful when flying without a RX or if you have a RX that outputs zeros without a detected Txmtr
This commit is contained in:
parent
472a50f9c2
commit
420e9e0d2e
@ -272,6 +272,7 @@ public:
|
|||||||
k_param_flight_mode4,
|
k_param_flight_mode4,
|
||||||
k_param_flight_mode5,
|
k_param_flight_mode5,
|
||||||
k_param_flight_mode6,
|
k_param_flight_mode6,
|
||||||
|
k_param_initial_mode,
|
||||||
|
|
||||||
//
|
//
|
||||||
// 220: Waypoint data
|
// 220: Waypoint data
|
||||||
@ -407,6 +408,7 @@ public:
|
|||||||
AP_Int8 flight_mode4;
|
AP_Int8 flight_mode4;
|
||||||
AP_Int8 flight_mode5;
|
AP_Int8 flight_mode5;
|
||||||
AP_Int8 flight_mode6;
|
AP_Int8 flight_mode6;
|
||||||
|
AP_Int8 initial_mode;
|
||||||
|
|
||||||
// Navigational maneuvering limits
|
// Navigational maneuvering limits
|
||||||
//
|
//
|
||||||
|
@ -605,6 +605,13 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
||||||
|
|
||||||
|
// @Param: INITIAL_MODE
|
||||||
|
// @DisplayName: Initial flight mode
|
||||||
|
// @Description: This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver.
|
||||||
|
// @Values: 0:Manual,1:CIRCLE,2:STABILIZE,3:TRAINING,4:ACRO,5:FBWA,6:FBWB,7:CRUISE,8:AUTOTUNE,10:Auto,11:RTL,12:Loiter,15:Guided
|
||||||
|
// @User: Advanced
|
||||||
|
GSCALAR(initial_mode, "INITIAL_MODE", MANUAL),
|
||||||
|
|
||||||
// @Param: LIM_ROLL_CD
|
// @Param: LIM_ROLL_CD
|
||||||
// @DisplayName: Maximum Bank Angle
|
// @DisplayName: Maximum Bank Angle
|
||||||
// @Description: The maximum commanded bank angle in either direction
|
// @Description: The maximum commanded bank angle in either direction
|
||||||
|
@ -220,7 +220,7 @@ static void init_ardupilot()
|
|||||||
// choose the nav controller
|
// choose the nav controller
|
||||||
set_nav_controller();
|
set_nav_controller();
|
||||||
|
|
||||||
set_mode(MANUAL);
|
set_mode((FlightMode)g.initial_mode.get());
|
||||||
|
|
||||||
// set the correct flight mode
|
// set the correct flight mode
|
||||||
// ---------------------------
|
// ---------------------------
|
||||||
|
Loading…
Reference in New Issue
Block a user