mirror of https://github.com/ArduPilot/ardupilot
Copter: added FLTMODE_CH parameter
this allows for the flight mode to be on any RC channel, or no channel at all to disable RC flight modes
This commit is contained in:
parent
692e6518cc
commit
89674482a7
|
@ -336,6 +336,13 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @User: Standard
|
||||
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),
|
||||
|
||||
// @Param: FLTMODE_CH
|
||||
// @DisplayName: Flightmode channel
|
||||
// @Description: RC Channel to use for flight mode control
|
||||
// @Values: 0:Disabled,5:Channel5,6:Channel6,7:Channel7,8:Channel8
|
||||
// @User: Advanced
|
||||
GSCALAR(flight_mode_chan, "FLTMODE_CH", CH_MODE_DEFAULT),
|
||||
|
||||
// @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)
|
||||
|
|
|
@ -313,6 +313,7 @@ public:
|
|||
k_param_flight_mode5,
|
||||
k_param_flight_mode6,
|
||||
k_param_simple_modes,
|
||||
k_param_flight_mode_chan,
|
||||
|
||||
//
|
||||
// 210: Waypoint data
|
||||
|
@ -432,6 +433,7 @@ public:
|
|||
AP_Int8 flight_mode5;
|
||||
AP_Int8 flight_mode6;
|
||||
AP_Int8 simple_modes;
|
||||
AP_Int8 flight_mode_chan;
|
||||
|
||||
// Misc
|
||||
//
|
||||
|
|
|
@ -586,3 +586,7 @@
|
|||
#ifndef ADVANCED_FAILSAFE
|
||||
# define ADVANCED_FAILSAFE DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef CH_MODE_DEFAULT
|
||||
#define CH_MODE_DEFAULT CH_5
|
||||
#endif
|
||||
|
|
|
@ -15,16 +15,21 @@ struct {
|
|||
|
||||
void Copter::read_control_switch()
|
||||
{
|
||||
if (g.flight_mode_chan <= 0) {
|
||||
// no flight mode channel
|
||||
return;
|
||||
}
|
||||
|
||||
uint32_t tnow_ms = millis();
|
||||
|
||||
// calculate position of flight mode switch
|
||||
int8_t switch_position;
|
||||
uint16_t rc5_in = RC_Channels::rc_channel(CH_5)->get_radio_in();
|
||||
if (rc5_in < 1231) switch_position = 0;
|
||||
else if (rc5_in < 1361) switch_position = 1;
|
||||
else if (rc5_in < 1491) switch_position = 2;
|
||||
else if (rc5_in < 1621) switch_position = 3;
|
||||
else if (rc5_in < 1750) switch_position = 4;
|
||||
uint16_t mode_in = RC_Channels::rc_channel(g.flight_mode_chan-1)->get_radio_in();
|
||||
if (mode_in < 1231) switch_position = 0;
|
||||
else if (mode_in < 1361) switch_position = 1;
|
||||
else if (mode_in < 1491) switch_position = 2;
|
||||
else if (mode_in < 1621) switch_position = 3;
|
||||
else if (mode_in < 1750) switch_position = 4;
|
||||
else switch_position = 5;
|
||||
|
||||
// store time that switch last moved
|
||||
|
|
Loading…
Reference in New Issue