Browse Source

Copter: add option to disable BRAKE flight mode

master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
86b162e32f
  1. 1
      ArduCopter/APM_Config.h
  2. 2
      ArduCopter/Copter.h
  3. 4
      ArduCopter/GCS_Mavlink.cpp
  4. 6
      ArduCopter/config.h
  5. 2
      ArduCopter/mode.cpp

1
ArduCopter/APM_Config.h

@ -24,6 +24,7 @@
//#define SPRAYER DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity) //#define SPRAYER DISABLED // disable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)
//#define WINCH_ENABLED DISABLED // disable winch support //#define WINCH_ENABLED DISABLED // disable winch support
//#define MODE_AUTO_ENABLED DISABLED // disable auto mode support //#define MODE_AUTO_ENABLED DISABLED // disable auto mode support
//#define MODE_BRAKE_ENABLED DISABLED // disable brake mode support
//#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support //#define MODE_DRIFT_ENABLED DISABLED // disable drift mode support
//#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support //#define MODE_GUIDED_ENABLED DISABLED // disable guided mode support
//#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support //#define MODE_LOITER_ENABLED DISABLED // disable loiter mode support

2
ArduCopter/Copter.h

@ -962,7 +962,9 @@ private:
#if AUTOTUNE_ENABLED == ENABLED #if AUTOTUNE_ENABLED == ENABLED
ModeAutoTune mode_autotune; ModeAutoTune mode_autotune;
#endif #endif
#if MODE_BRAKE_ENABLED == ENABLED
ModeBrake mode_brake; ModeBrake mode_brake;
#endif
ModeCircle mode_circle; ModeCircle mode_circle;
#if MODE_DRIFT_ENABLED == ENABLED #if MODE_DRIFT_ENABLED == ENABLED
ModeDrift mode_drift; ModeDrift mode_drift;

4
ArduCopter/GCS_Mavlink.cpp

@ -1303,11 +1303,15 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
bool shot_mode = (!is_zero(packet.param1) && (copter.control_mode == GUIDED || copter.control_mode == GUIDED_NOGPS)); bool shot_mode = (!is_zero(packet.param1) && (copter.control_mode == GUIDED || copter.control_mode == GUIDED_NOGPS));
if (!shot_mode) { if (!shot_mode) {
#if MODE_BRAKE_ENABLED == ENABLED
if (copter.set_mode(BRAKE, MODE_REASON_GCS_COMMAND)) { if (copter.set_mode(BRAKE, MODE_REASON_GCS_COMMAND)) {
copter.mode_brake.timeout_to_loiter_ms(2500); copter.mode_brake.timeout_to_loiter_ms(2500);
} else { } else {
copter.set_mode(ALT_HOLD, MODE_REASON_GCS_COMMAND); copter.set_mode(ALT_HOLD, MODE_REASON_GCS_COMMAND);
} }
#else
copter.set_mode(ALT_HOLD, MODE_REASON_GCS_COMMAND);
#endif
} else { } else {
// SoloLink is expected to handle pause in shots // SoloLink is expected to handle pause in shots
} }

6
ArduCopter/config.h

@ -273,6 +273,12 @@
# define MODE_AUTO_ENABLED ENABLED # define MODE_AUTO_ENABLED ENABLED
#endif #endif
//////////////////////////////////////////////////////////////////////////////
// Brake mode - bring vehicle to stop
#ifndef MODE_BRAKE_ENABLED
# define MODE_BRAKE_ENABLED ENABLED
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Drift - fly vehicle in altitude-held, coordinated-turn mode // Drift - fly vehicle in altitude-held, coordinated-turn mode
#ifndef MODE_DRIFT_ENABLED #ifndef MODE_DRIFT_ENABLED

2
ArduCopter/mode.cpp

@ -110,9 +110,11 @@ Copter::Mode *Copter::mode_from_mode_num(const uint8_t mode)
break; break;
#endif #endif
#if MODE_BRAKE_ENABLED == ENABLED
case BRAKE: case BRAKE:
ret = &mode_brake; ret = &mode_brake;
break; break;
#endif
case THROW: case THROW:
ret = &mode_throw; ret = &mode_throw;

Loading…
Cancel
Save