Browse Source

Plane: fix for HAL_GPIO_*

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
1e2b644b1b
  1. 3
      ArduPlane/compat.h
  2. 6
      ArduPlane/geofence.pde
  3. 4
      ArduPlane/system.pde

3
ArduPlane/compat.h

@ -2,9 +2,6 @@ @@ -2,9 +2,6 @@
#ifndef __COMPAT_H__
#define __COMPAT_H__
#define OUTPUT GPIO_OUTPUT
#define INPUT GPIO_INPUT
#define HIGH 1
#define LOW 0

6
ArduPlane/geofence.pde

@ -302,7 +302,8 @@ static void geofence_check(bool altitude_check_only) @@ -302,7 +302,8 @@ static void geofence_check(bool altitude_check_only)
geofence_state->fence_triggered = false;
gcs_send_text_P(SEVERITY_LOW,PSTR("geo-fence OK"));
#if FENCE_TRIGGERED_PIN > 0
digitalWrite(FENCE_TRIGGERED_PIN, LOW);
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
hal.gpio->write(FENCE_TRIGGERED_PIN, 0);
#endif
gcs_send_message(MSG_FENCE_STATUS);
}
@ -325,7 +326,8 @@ static void geofence_check(bool altitude_check_only) @@ -325,7 +326,8 @@ static void geofence_check(bool altitude_check_only)
geofence_state->breach_type = breach_type;
#if FENCE_TRIGGERED_PIN > 0
digitalWrite(FENCE_TRIGGERED_PIN, HIGH);
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
hal.gpio->write(FENCE_TRIGGERED_PIN, 1);
#endif
gcs_send_text_P(SEVERITY_LOW,PSTR("geo-fence triggered"));

4
ArduPlane/system.pde

@ -174,8 +174,8 @@ static void init_ardupilot() @@ -174,8 +174,8 @@ static void init_ardupilot()
relay.init();
#if FENCE_TRIGGERED_PIN > 0
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, OUTPUT);
digitalWrite(FENCE_TRIGGERED_PIN, LOW);
hal.gpio->pinMode(FENCE_TRIGGERED_PIN, HAL_GPIO_OUTPUT);
hal.gpio->write(FENCE_TRIGGERED_PIN, 0);
#endif
/*

Loading…
Cancel
Save