Browse Source

Copter: integrate parachute lib

mission-4.1.18
Randy Mackay 11 years ago
parent
commit
ff32b27272
  1. 1
      ArduCopter/APM_Config.h
  2. 10
      ArduCopter/ArduCopter.pde
  3. 3
      ArduCopter/Parameters.h
  4. 6
      ArduCopter/Parameters.pde
  5. 6
      ArduCopter/config.h

1
ArduCopter/APM_Config.h

@ -29,6 +29,7 @@ @@ -29,6 +29,7 @@
//#define AC_FENCE DISABLED // disable fence to save 2k of flash
//#define CAMERA DISABLED // disable camera trigger to save 1k of flash
//#define CONFIG_SONAR DISABLED // disable sonar to save 1k of flash
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
// features below are disabled by default
//#define SPRAYER ENABLED // enable the crop sprayer feature (two ESC controlled pumps the speed of which depends upon the vehicle's horizontal velocity)

10
ArduCopter/ArduCopter.pde

@ -143,6 +143,9 @@ @@ -143,6 +143,9 @@
#if EPM_ENABLED == ENABLED
#include <AP_EPM.h> // EPM cargo gripper stuff
#endif
#if PARACHUTE == ENABLED
#include <AP_Parachute.h> // Parachute release library
#endif
// AP_HAL to Arduino compatibility layer
#include "compat.h"
@ -712,6 +715,13 @@ static AC_Sprayer sprayer(&inertial_nav); @@ -712,6 +715,13 @@ static AC_Sprayer sprayer(&inertial_nav);
static AP_EPM epm;
#endif
////////////////////////////////////////////////////////////////////////////////
// Parachute release
////////////////////////////////////////////////////////////////////////////////
#if PARACHUTE == ENABLED
static AP_Parachute parachute(relay);
#endif
////////////////////////////////////////////////////////////////////////////////
// function definitions to keep compiler from complaining about undeclared functions
////////////////////////////////////////////////////////////////////////////////

3
ArduCopter/Parameters.h

@ -76,6 +76,9 @@ public: @@ -76,6 +76,9 @@ public:
// GPS object
k_param_gps,
// Parachute object
k_param_parachute, // 17
// Misc
//
k_param_log_bitmask = 20,

6
ArduCopter/Parameters.pde

@ -864,6 +864,12 @@ const AP_Param::Info var_info[] PROGMEM = { @@ -864,6 +864,12 @@ const AP_Param::Info var_info[] PROGMEM = {
GOBJECT(epm, "EPM_", AP_EPM),
#endif
#if PARACHUTE == ENABLED
// @Group: CHUTE_
// @Path: ../libraries/AP_Parachute/AP_Parachute.cpp
GOBJECT(parachute, "CHUTE_", AP_Parachute),
#endif
// @Group: COMPASS_
// @Path: ../libraries/AP_Compass/Compass.cpp
GOBJECT(compass, "COMPASS_", Compass),

6
ArduCopter/config.h

@ -404,6 +404,12 @@ @@ -404,6 +404,12 @@
# define EPM_ENABLED DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Parachute release
#ifndef PARACHUTE
# define PARACHUTE ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION
//////////////////////////////////////////////////////////////////////////////

Loading…
Cancel
Save