Copter: allow terrain to be excluded from build
This commit is contained in:
parent
2b111c2bd6
commit
731c44d053
@ -26,7 +26,8 @@
|
|||||||
//#define CAMERA DISABLED // disable camera trigger to save 1k 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 CONFIG_SONAR DISABLED // disable sonar to save 1k of flash
|
||||||
//#define POSHOLD_ENABLED DISABLED // disable PosHold flight mode to save 4.5k of flash
|
//#define POSHOLD_ENABLED DISABLED // disable PosHold flight mode to save 4.5k of flash
|
||||||
//#define AC_RALLY DISABLED // disable rally points to save 2k of flash, and also frees rally point EEPROM for more mission commands
|
//#define AC_RALLY DISABLED // disable rally points library (must also disable terrain which relies on rally)
|
||||||
|
//#define AC_TERRAIN DISABLED // disable terrain library
|
||||||
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
|
//#define PARACHUTE DISABLED // disable parachute release to save 1k of flash
|
||||||
//#define EPM_ENABLED DISABLED // disable epm cargo gripper to save 500bytes of flash
|
//#define EPM_ENABLED DISABLED // disable epm cargo gripper to save 500bytes of flash
|
||||||
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
|
//#define CLI_ENABLED DISABLED // disable the CLI (command-line-interface) to save 21K of flash space
|
||||||
|
@ -502,7 +502,7 @@ void Copter::one_hz_loop()
|
|||||||
|
|
||||||
check_usb_mux();
|
check_usb_mux();
|
||||||
|
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
terrain.update();
|
terrain.update();
|
||||||
|
|
||||||
// tell the rangefinder our height, so it can go into power saving
|
// tell the rangefinder our height, so it can go into power saving
|
||||||
|
@ -120,7 +120,7 @@ Copter::Copter(void) :
|
|||||||
#if PARACHUTE == ENABLED
|
#if PARACHUTE == ENABLED
|
||||||
parachute(relay),
|
parachute(relay),
|
||||||
#endif
|
#endif
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
terrain(ahrs, mission, rally),
|
terrain(ahrs, mission, rally),
|
||||||
#endif
|
#endif
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if PRECISION_LANDING == ENABLED
|
||||||
|
@ -500,7 +500,7 @@ private:
|
|||||||
AP_LandingGear landinggear;
|
AP_LandingGear landinggear;
|
||||||
|
|
||||||
// terrain handling
|
// terrain handling
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
AP_Terrain terrain;
|
AP_Terrain terrain;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -219,7 +219,7 @@ NOINLINE void Copter::send_extended_status1(mavlink_channel_t chan)
|
|||||||
battery_current = battery.current_amps() * 100;
|
battery_current = battery.current_amps() * 100;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
switch (terrain.status()) {
|
switch (terrain.status()) {
|
||||||
case AP_Terrain::TerrainStatusDisabled:
|
case AP_Terrain::TerrainStatusDisabled:
|
||||||
break;
|
break;
|
||||||
@ -642,7 +642,7 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_TERRAIN:
|
case MSG_TERRAIN:
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
|
CHECK_PAYLOAD_SIZE(TERRAIN_REQUEST);
|
||||||
copter.terrain.send_request(chan);
|
copter.terrain.send_request(chan);
|
||||||
#endif
|
#endif
|
||||||
@ -961,7 +961,7 @@ GCS_MAVLINK::data_stream_send(void)
|
|||||||
send_message(MSG_HWSTATUS);
|
send_message(MSG_HWSTATUS);
|
||||||
send_message(MSG_SYSTEM_TIME);
|
send_message(MSG_SYSTEM_TIME);
|
||||||
send_message(MSG_RANGEFINDER);
|
send_message(MSG_RANGEFINDER);
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
send_message(MSG_TERRAIN);
|
send_message(MSG_TERRAIN);
|
||||||
#endif
|
#endif
|
||||||
send_message(MSG_BATTERY2);
|
send_message(MSG_BATTERY2);
|
||||||
@ -1828,7 +1828,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
|
|
||||||
case MAVLINK_MSG_ID_TERRAIN_DATA:
|
case MAVLINK_MSG_ID_TERRAIN_DATA:
|
||||||
case MAVLINK_MSG_ID_TERRAIN_CHECK:
|
case MAVLINK_MSG_ID_TERRAIN_CHECK:
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
copter.terrain.handle_data(chan, msg);
|
copter.terrain.handle_data(chan, msg);
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
@ -1056,7 +1056,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
GOBJECT(sonar, "RNGFND", RangeFinder),
|
GOBJECT(sonar, "RNGFND", RangeFinder),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_TERRAIN_AVAILABLE
|
#if AP_TERRAIN_AVAILABLE && AC_TERRAIN
|
||||||
// @Group: TERRAIN_
|
// @Group: TERRAIN_
|
||||||
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
|
// @Path: ../libraries/AP_Terrain/AP_Terrain.cpp
|
||||||
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
|
GOBJECT(terrain, "TERRAIN_", AP_Terrain),
|
||||||
|
@ -738,6 +738,13 @@
|
|||||||
#define AC_RALLY ENABLED
|
#define AC_RALLY ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AC_TERRAIN
|
||||||
|
#define AC_TERRAIN ENABLED
|
||||||
|
#if !AC_RALLY
|
||||||
|
#error Terrain relies on Rally which is disabled
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Developer Items
|
// Developer Items
|
||||||
//
|
//
|
||||||
|
Loading…
Reference in New Issue
Block a user