ArduCopter: bug fix so AP_Limits does not use up memory if it is disabled
This commit is contained in:
parent
d8e3d5c10c
commit
6da68c53a5
@ -873,7 +873,7 @@ AP_Mount camera_mount2(¤t_loc, g_gps, &ahrs, 1);
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Experimental AP_Limits library - set constraints, limits, fences, minima, maxima on various parameters
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#ifdef AP_LIMITS
|
||||
#if AP_LIMITS == ENABLED
|
||||
AP_Limits limits;
|
||||
AP_Limit_GPSLock gpslock_limit(g_gps);
|
||||
AP_Limit_Geofence geofence_limit(FENCE_START_BYTE, FENCE_WP_SIZE, MAX_FENCEPOINTS, g_gps, &home, ¤t_loc);
|
||||
|
@ -1929,7 +1929,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
break;
|
||||
}
|
||||
|
||||
#ifdef AP_LIMITS
|
||||
#if AP_LIMITS == ENABLED
|
||||
|
||||
// receive an AP_Limits fence point from GCS and store in EEPROM
|
||||
// receive a fence point from GCS and store in EEPROM
|
||||
|
@ -583,12 +583,14 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
|
||||
GOBJECT(barometer, "GND_", AP_Baro),
|
||||
|
||||
#if AP_LIMITS == ENABLED
|
||||
//@Group: LIM_
|
||||
//@Path: ../libraries/AP_Limits/AP_Limits.cpp,../libraries/AP_Limits/AP_Limit_GPSLock.cpp, ../libraries/AP_Limits/AP_Limit_Geofence.cpp, ../libraries/AP_Limits/AP_Limit_Altitude.cpp, ../libraries/AP_Limits/AP_Limit_Module.cpp
|
||||
GOBJECT(limits, "LIM_", AP_Limits),
|
||||
GOBJECT(gpslock_limit, "LIM_", AP_Limit_GPSLock),
|
||||
GOBJECT(geofence_limit, "LIM_", AP_Limit_Geofence),
|
||||
GOBJECT(altitude_limit, "LIM_", AP_Limit_Altitude),
|
||||
#endif
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// @Group: H_
|
||||
|
@ -43,7 +43,7 @@ static void arm_motors()
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Experimental AP_Limits library - set constraints, limits, fences, minima, maxima on various parameters
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#ifdef AP_LIMITS
|
||||
#if AP_LIMITS == ENABLED
|
||||
if (limits.enabled() && limits.required()) {
|
||||
gcs_send_text_P(SEVERITY_LOW, PSTR("Limits - Running pre-arm checks"));
|
||||
|
||||
|
@ -294,11 +294,7 @@ init_rate_controllers();
|
||||
// Experimental AP_Limits library - set constraints, limits, fences, minima,
|
||||
// maxima on various parameters
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
static void init_ap_limits() {
|
||||
#ifdef AP_LIMITS
|
||||
// AP_Limits modules are stored as a _linked list_. That allows us to
|
||||
// define an infinite number of modules and also to allocate no space until
|
||||
// we actually need to.
|
||||
#if AP_LIMITS == ENABLED
|
||||
|
||||
// The linked list looks (logically) like this [limits module] -> [first
|
||||
// limit module] -> [second limit module] -> [third limit module] -> NULL
|
||||
|
Loading…
Reference in New Issue
Block a user