Browse Source

Copter: integrate skeleton Hybrid mode

master
Randy Mackay 11 years ago
parent
commit
b5ed23f592
  1. 2
      ArduCopter/GCS_Mavlink.pde
  2. 12
      ArduCopter/Parameters.pde
  3. 3
      ArduCopter/defines.h
  4. 2
      ArduCopter/events.pde
  5. 12
      ArduCopter/flight_mode.pde

2
ArduCopter/GCS_Mavlink.pde

@ -68,6 +68,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan) @@ -68,6 +68,7 @@ static NOINLINE void send_heartbeat(mavlink_channel_t chan)
case LOITER:
case GUIDED:
case CIRCLE:
case HYBRID:
base_mode |= MAV_MODE_FLAG_GUIDED_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
@ -175,6 +176,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan) @@ -175,6 +176,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan)
case CIRCLE:
case LAND:
case OF_LOITER:
case HYBRID:
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL;
break;

12
ArduCopter/Parameters.pde

@ -285,42 +285,42 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -285,42 +285,42 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Param: FLTMODE1
// @DisplayName: Flight Mode 1
// @Description: Flight mode when Channel 5 pwm is <= 1230
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,17:Hybrid
// @User: Standard
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1),
// @Param: FLTMODE2
// @DisplayName: Flight Mode 2
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,17:Hybrid
// @User: Standard
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2),
// @Param: FLTMODE3
// @DisplayName: Flight Mode 3
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,17:Hybrid
// @User: Standard
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3),
// @Param: FLTMODE4
// @DisplayName: Flight Mode 4
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,17:Hybrid
// @User: Standard
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4),
// @Param: FLTMODE5
// @DisplayName: Flight Mode 5
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,17:Hybrid
// @User: Standard
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5),
// @Param: FLTMODE6
// @DisplayName: Flight Mode 6
// @Description: Flight mode when Channel 5 pwm is >=1750
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,17:Hybrid
// @User: Standard
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6),

3
ArduCopter/defines.h

@ -100,7 +100,8 @@ @@ -100,7 +100,8 @@
#define SPORT 13 // earth frame rate control
#define FLIP 14 // flip the vehicle on the roll axis
#define AUTOTUNE 15 // autotune the vehicle's roll and pitch gains
#define NUM_MODES 16
#define HYBRID 16 // hybrid - position hold with manual override
#define NUM_MODES 17
// CH_6 Tuning

2
ArduCopter/events.pde

@ -50,6 +50,7 @@ static void failsafe_radio_on_event() @@ -50,6 +50,7 @@ static void failsafe_radio_on_event()
break;
case LOITER:
case ALT_HOLD:
case HYBRID:
// if landed with throttle at zero disarm, otherwise do the regular thing
if (g.rc_3.control_in == 0 && ap.land_complete) {
init_disarm_motors();
@ -139,6 +140,7 @@ static void failsafe_battery_event(void) @@ -139,6 +140,7 @@ static void failsafe_battery_event(void)
break;
case LOITER:
case ALT_HOLD:
case HYBRID:
// if landed with throttle at zero disarm, otherwise fall through to default handling
if (g.rc_3.control_in == 0 && ap.land_complete) {
init_disarm_motors();

12
ArduCopter/flight_mode.pde

@ -87,6 +87,10 @@ static bool set_mode(uint8_t mode) @@ -87,6 +87,10 @@ static bool set_mode(uint8_t mode)
break;
#endif
case HYBRID:
success = hybrid_init(ignore_checks);
break;
default:
success = false;
break;
@ -177,6 +181,10 @@ static void update_flight_mode() @@ -177,6 +181,10 @@ static void update_flight_mode()
autotune_run();
break;
#endif
case HYBRID:
hybrid_run();
break;
}
}
@ -205,6 +213,7 @@ static bool mode_requires_GPS(uint8_t mode) { @@ -205,6 +213,7 @@ static bool mode_requires_GPS(uint8_t mode) {
case RTL:
case CIRCLE:
case DRIFT:
case HYBRID:
return true;
default:
return false;
@ -277,6 +286,9 @@ print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode) @@ -277,6 +286,9 @@ print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
case AUTOTUNE:
port->print_P(PSTR("AUTOTUNE"));
break;
case HYBRID:
port->print_P(PSTR("HYBRID"));
break;
default:
port->printf_P(PSTR("Mode(%u)"), (unsigned)mode);
break;

Loading…
Cancel
Save