mirror of https://github.com/ArduPilot/ardupilot
Changed software ID from 0 to 20 for ArduRover V2 Divergence.
Also changed definition of flight mode 2 from Stabilize to Learning.
This commit is contained in:
parent
1920bcbe1d
commit
a03642df52
|
@ -263,9 +263,9 @@
|
|||
// Name | Description
|
||||
// -----------------+--------------------------------------------
|
||||
// |
|
||||
// MANUAL | Full manual control via the hardware multiplexer.
|
||||
// MANUAL | Full manual control via software.
|
||||
// |
|
||||
// STABILIZE | Tries to maintain level flight, but can be overridden with radio control inputs.
|
||||
// LEARNING | Full manual control, used for live waypoint definition via Ch7 toggle.
|
||||
// |
|
||||
// FLY_BY_WIRE_A | Autopilot style control via user input, with manual throttle.
|
||||
// |
|
||||
|
@ -298,8 +298,8 @@
|
|||
//
|
||||
//#define FLIGHT_MODE_1 RTL
|
||||
//#define FLIGHT_MODE_2 RTL
|
||||
//#define FLIGHT_MODE_3 STABILIZE
|
||||
//#define FLIGHT_MODE_4 STABILIZE
|
||||
//#define FLIGHT_MODE_3 LEARNING
|
||||
//#define FLIGHT_MODE_4 LEARNING
|
||||
//#define FLIGHT_MODE_5 MANUAL
|
||||
//#define FLIGHT_MODE_6 MANUAL
|
||||
//
|
||||
|
|
|
@ -22,8 +22,8 @@
|
|||
|
||||
#define FLIGHT_MODE_1 AUTO // pos 0 ---
|
||||
#define FLIGHT_MODE_2 AUTO // pos 1
|
||||
#define FLIGHT_MODE_3 STABILIZE // pos 2
|
||||
#define FLIGHT_MODE_4 STABILIZE // pos 3 ---
|
||||
#define FLIGHT_MODE_3 LEARNING // pos 2
|
||||
#define FLIGHT_MODE_4 LEARNING // pos 3 ---
|
||||
#define FLIGHT_MODE_5 MANUAL // pos 4
|
||||
#define FLIGHT_MODE_6 MANUAL // pos 5 ---
|
||||
|
||||
|
@ -39,8 +39,8 @@
|
|||
|
||||
#define FLIGHT_MODE_1 AUTO // pos 0 ---
|
||||
#define FLIGHT_MODE_2 AUTO // pos 1
|
||||
#define FLIGHT_MODE_3 STABILIZE // pos 2
|
||||
#define FLIGHT_MODE_4 STABILIZE // pos 3 ---
|
||||
#define FLIGHT_MODE_3 LEARNING // pos 2
|
||||
#define FLIGHT_MODE_4 LEARNING // pos 3 ---
|
||||
#define FLIGHT_MODE_5 MANUAL // pos 4
|
||||
#define FLIGHT_MODE_6 MANUAL // pos 5 ---
|
||||
|
||||
|
|
|
@ -37,8 +37,8 @@
|
|||
|
||||
#define FLIGHT_MODE_1 AUTO // pos 0 ---
|
||||
#define FLIGHT_MODE_2 AUTO // pos 1
|
||||
#define FLIGHT_MODE_3 STABILIZE // pos 2
|
||||
#define FLIGHT_MODE_4 STABILIZE // pos 3 ---
|
||||
#define FLIGHT_MODE_3 LEARNING // pos 2
|
||||
#define FLIGHT_MODE_4 LEARNING // pos 3 ---
|
||||
#define FLIGHT_MODE_5 MANUAL // pos 4
|
||||
#define FLIGHT_MODE_6 MANUAL // pos 5 ---
|
||||
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
#define FLIGHT_MODE_2 RTL
|
||||
#define FLIGHT_MODE_3 FLY_BY_WIRE_A
|
||||
#define FLIGHT_MODE_4 FLY_BY_WIRE_B
|
||||
#define FLIGHT_MODE_5 STABILIZE
|
||||
#define FLIGHT_MODE_5 LEARNING
|
||||
#define FLIGHT_MODE_6 MANUAL
|
||||
|
||||
// HIL_MODE SELECTION
|
||||
|
|
|
@ -336,7 +336,7 @@ static const char *comma = ",";
|
|||
static const char* flight_mode_strings[] = {
|
||||
"Manual",
|
||||
"Circle",
|
||||
"Stabilize",
|
||||
"Learning",
|
||||
"",
|
||||
"",
|
||||
"FBW_A",
|
||||
|
@ -846,8 +846,8 @@ static void fast_loop()
|
|||
|
||||
// apply desired roll, pitch and yaw to the plane
|
||||
// ----------------------------------------------
|
||||
if (control_mode > STABILIZE)
|
||||
stabilize();
|
||||
if (control_mode > LEARNING)
|
||||
learning();
|
||||
|
||||
// write out the servo PWM values
|
||||
// ------------------------------
|
||||
|
@ -1133,7 +1133,7 @@ static void update_current_flight_mode(void)
|
|||
case FLY_BY_WIRE_B:
|
||||
break;
|
||||
|
||||
case STABILIZE:
|
||||
case LEARNING:
|
||||
nav_roll = 0;
|
||||
nav_pitch = 0;
|
||||
#if X_PLANE == ENABLED
|
||||
|
|
|
@ -4,7 +4,7 @@
|
|||
// Function that controls aileron/rudder, elevator, rudder (if 4 channel control) and throttle to produce desired attitude and airspeed.
|
||||
//****************************************************************
|
||||
|
||||
static void stabilize()
|
||||
static void learning()
|
||||
{
|
||||
// Calculate desired servo output for the turn // Wheels Direction
|
||||
// ---------------------------------------------
|
||||
|
@ -111,7 +111,7 @@ static void set_servos(void)
|
|||
rc_array[CH_7] = &g.rc_7;
|
||||
rc_array[CH_8] = &g.rc_8;
|
||||
|
||||
if((control_mode == MANUAL) || (control_mode == STABILIZE)){
|
||||
if((control_mode == MANUAL) || (control_mode == LEARNING)){
|
||||
// do a direct pass through of radio values
|
||||
g.channel_roll.radio_out = g.channel_roll.radio_in;
|
||||
g.channel_pitch.radio_out = g.channel_pitch.radio_in;
|
||||
|
|
|
@ -44,11 +44,11 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
|||
case MANUAL:
|
||||
base_mode = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
||||
break;
|
||||
case STABILIZE:
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A:
|
||||
case FLY_BY_WIRE_B:
|
||||
case FLY_BY_WIRE_C:
|
||||
base_mode = MAV_MODE_FLAG_STABILIZE_ENABLED;
|
||||
base_mode = MAV_MODE_FLAG_LEARNING_ENABLED;
|
||||
break;
|
||||
case AUTO:
|
||||
case RTL:
|
||||
|
@ -56,7 +56,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
|||
case GUIDED:
|
||||
case CIRCLE:
|
||||
base_mode = MAV_MODE_FLAG_GUIDED_ENABLED |
|
||||
MAV_MODE_FLAG_STABILIZE_ENABLED;
|
||||
MAV_MODE_FLAG_LEARNING_ENABLED;
|
||||
// note that MAV_MODE_FLAG_AUTO_ENABLED does not match what
|
||||
// APM does in any mode, as that is defined as "system finds its own goal
|
||||
// positions", which APM does not currently do
|
||||
|
@ -68,7 +68,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
|
|||
|
||||
if (control_mode != MANUAL && control_mode != INITIALISING) {
|
||||
// stabiliser of some form is enabled
|
||||
base_mode |= MAV_MODE_FLAG_STABILIZE_ENABLED;
|
||||
base_mode |= MAV_MODE_FLAG_LEARNING_ENABLED;
|
||||
}
|
||||
|
||||
#if ENABLE_STICK_MIXING==ENABLED
|
||||
|
@ -165,7 +165,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
|||
case MANUAL:
|
||||
break;
|
||||
|
||||
case STABILIZE:
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A:
|
||||
control_sensors_enabled |= (1<<10); // 3D angular rate control
|
||||
control_sensors_enabled |= (1<<11); // attitude stabilisation
|
||||
|
@ -242,7 +242,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack
|
|||
case MANUAL:
|
||||
mode = MAV_MODE_MANUAL;
|
||||
break;
|
||||
case STABILIZE:
|
||||
case LEARNING:
|
||||
mode = MAV_MODE_TEST1;
|
||||
break;
|
||||
case FLY_BY_WIRE_A:
|
||||
|
@ -1315,7 +1315,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
switch (packet.custom_mode) {
|
||||
case MANUAL:
|
||||
case CIRCLE:
|
||||
case STABILIZE:
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A:
|
||||
case FLY_BY_WIRE_B:
|
||||
case FLY_BY_WIRE_C:
|
||||
|
@ -1346,7 +1346,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||
break;
|
||||
|
||||
case MAV_MODE_TEST1:
|
||||
set_mode(STABILIZE);
|
||||
set_mode(LEARNING);
|
||||
break;
|
||||
|
||||
case MAV_MODE_TEST2:
|
||||
|
|
|
@ -24,7 +24,7 @@ public:
|
|||
// GCS will interpret values 0-9 as ArduPilotMega. Developers may use
|
||||
// values within that range to identify different branches.
|
||||
//
|
||||
static const uint16_t k_software_type = 0; // 0 for APM trunk
|
||||
static const uint16_t k_software_type = 20; // 0 for APM trunk
|
||||
|
||||
enum {
|
||||
// Layout version number, always key zero.
|
||||
|
|
|
@ -382,19 +382,19 @@
|
|||
#endif
|
||||
|
||||
#if !defined(FLIGHT_MODE_1)
|
||||
# define FLIGHT_MODE_1 STABILIZE
|
||||
# define FLIGHT_MODE_1 LEARNING
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_2)
|
||||
# define FLIGHT_MODE_2 STABILIZE
|
||||
# define FLIGHT_MODE_2 LEARNING
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_3)
|
||||
# define FLIGHT_MODE_3 STABILIZE
|
||||
# define FLIGHT_MODE_3 LEARNING
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_4)
|
||||
# define FLIGHT_MODE_4 STABILIZE
|
||||
# define FLIGHT_MODE_4 LEARNING
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_5)
|
||||
# define FLIGHT_MODE_5 STABILIZE
|
||||
# define FLIGHT_MODE_5 LEARNING
|
||||
#endif
|
||||
#if !defined(FLIGHT_MODE_6)
|
||||
# define FLIGHT_MODE_6 MANUAL
|
||||
|
|
|
@ -77,7 +77,7 @@ if (g.ch7_option == CH7_SAVE_WP){ // set to 1
|
|||
#endif
|
||||
CH7_wp_index = 1;
|
||||
return;
|
||||
} else if (control_mode == STABILIZE) { // if SW7 is ON in STABILIZE = record the Wp
|
||||
} else if (control_mode == LEARNING) { // if SW7 is ON in LEARNING = record the Wp
|
||||
// set the next_WP (home is stored at 0)
|
||||
// max out at 100 since I think we need to stay under the EEPROM limit
|
||||
CH7_wp_index = constrain(CH7_wp_index, 1, 100);
|
||||
|
@ -113,7 +113,7 @@ if (g.ch7_option == CH7_SAVE_WP){ // set to 1
|
|||
}else{ // switch is disengaged
|
||||
if(trim_flag){
|
||||
trim_flag = false;
|
||||
if (control_mode == STABILIZE) {
|
||||
if (control_mode == LEARNING) {
|
||||
set_mode(RTL);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -94,7 +94,7 @@
|
|||
// ----------------
|
||||
#define MANUAL 0
|
||||
#define CIRCLE 1 // When flying sans GPS, and we loose the radio, just circle
|
||||
#define STABILIZE 2
|
||||
#define LEARNING 2
|
||||
|
||||
#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical = manual throttle
|
||||
#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical => desired airspeed
|
||||
|
|
|
@ -10,7 +10,7 @@ static void failsafe_short_on_event(int fstype)
|
|||
switch(control_mode)
|
||||
{
|
||||
case MANUAL:
|
||||
case STABILIZE:
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A: // middle position
|
||||
case FLY_BY_WIRE_B: // middle position
|
||||
set_mode(CIRCLE);
|
||||
|
@ -41,7 +41,7 @@ static void failsafe_long_on_event(int fstype)
|
|||
switch(control_mode)
|
||||
{
|
||||
case MANUAL:
|
||||
case STABILIZE:
|
||||
case LEARNING:
|
||||
case FLY_BY_WIRE_A: // middle position
|
||||
case FLY_BY_WIRE_B: // middle position
|
||||
case CIRCLE:
|
||||
|
|
|
@ -275,7 +275,7 @@ static void geofence_check(bool altitude_check_only)
|
|||
|
||||
if (control_mode == MANUAL && g.auto_trim) {
|
||||
// make sure we don't auto trim the surfaces on this change
|
||||
control_mode = STABILIZE;
|
||||
control_mode = LEARNING;
|
||||
}
|
||||
|
||||
set_mode(GUIDED);
|
||||
|
|
|
@ -224,7 +224,7 @@ setup_flightmodes(uint8_t argc, const Menu::arg *argv)
|
|||
while (
|
||||
mode != MANUAL &&
|
||||
mode != CIRCLE &&
|
||||
mode != STABILIZE &&
|
||||
mode != LEARNING &&
|
||||
mode != FLY_BY_WIRE_A &&
|
||||
mode != FLY_BY_WIRE_B &&
|
||||
mode != AUTO &&
|
||||
|
|
|
@ -355,7 +355,7 @@ static void set_mode(byte mode)
|
|||
switch(control_mode)
|
||||
{
|
||||
case MANUAL:
|
||||
case STABILIZE:
|
||||
case LEARNING:
|
||||
case CIRCLE:
|
||||
case FLY_BY_WIRE_A:
|
||||
case FLY_BY_WIRE_B:
|
||||
|
|
Loading…
Reference in New Issue