mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
Plane: re-enable geofencing on APM2
it only just fits ...
This commit is contained in:
parent
85179edf58
commit
be747afd0b
@ -420,11 +420,7 @@
|
|||||||
|
|
||||||
// use this to disable geo-fencing
|
// use this to disable geo-fencing
|
||||||
#ifndef GEOFENCE_ENABLED
|
#ifndef GEOFENCE_ENABLED
|
||||||
#if HAL_CPU_CLASS > HAL_CPU_CLASS_16
|
|
||||||
# define GEOFENCE_ENABLED ENABLED
|
# define GEOFENCE_ENABLED ENABLED
|
||||||
#else
|
|
||||||
# define GEOFENCE_ENABLED DISABLE
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// pwm value on FENCE_CHANNEL to use to enable fenced mode
|
// pwm value on FENCE_CHANNEL to use to enable fenced mode
|
||||||
|
@ -94,7 +94,8 @@ void Plane::geofence_load(void)
|
|||||||
uint8_t i;
|
uint8_t i;
|
||||||
|
|
||||||
if (geofence_state == NULL) {
|
if (geofence_state == NULL) {
|
||||||
if (hal.util->available_memory() < 512 + sizeof(struct GeofenceState)) {
|
uint16_t boundary_size = sizeof(Vector2l) * max_fencepoints();
|
||||||
|
if (hal.util->available_memory() < 100 + boundary_size + sizeof(struct GeofenceState)) {
|
||||||
// too risky to enable as we could run out of stack
|
// too risky to enable as we could run out of stack
|
||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
@ -104,7 +105,7 @@ void Plane::geofence_load(void)
|
|||||||
goto failed;
|
goto failed;
|
||||||
}
|
}
|
||||||
|
|
||||||
geofence_state->boundary = (Vector2l *)calloc(sizeof(Vector2l), max_fencepoints());
|
geofence_state->boundary = (Vector2l *)calloc(1, boundary_size);
|
||||||
if (geofence_state->boundary == NULL) {
|
if (geofence_state->boundary == NULL) {
|
||||||
free(geofence_state);
|
free(geofence_state);
|
||||||
geofence_state = NULL;
|
geofence_state = NULL;
|
||||||
|
Loading…
Reference in New Issue
Block a user