AP_Camera: ported to AP_HAL

This commit is contained in:
Pat Hickey 2012-12-12 11:48:01 -08:00 committed by Andrew Tridgell
parent f935f1ae31
commit 054f35e33d
2 changed files with 7 additions and 3 deletions

View File

@ -2,8 +2,11 @@
#include <AP_Camera.h>
#include <AP_Relay.h>
#include <../RC_Channel/RC_Channel_aux.h>
#include <AP_Math.h>
#include <RC_Channel.h>
#include <AP_HAL.h>
extern const AP_HAL::HAL& hal;
extern int32_t wp_distance; // Note: unfortunately this variable is in meter for ArduPlane and cm for ArduCopter
extern AP_Relay relay;
@ -91,7 +94,7 @@ void
AP_Camera::transistor_pic()
{
// TODO: Assign pin spare pin for output
digitalWrite(AP_CAMERA_TRANSISTOR_PIN, HIGH);
hal.gpio->write(AP_CAMERA_TRANSISTOR_PIN,1);
// leave a message that it should be active for two event loop cycles
_trigger_counter = 1;
@ -139,7 +142,7 @@ AP_Camera::trigger_pic_cleanup()
relay.off();
break;
case AP_CAMERA_TRIGGER_TYPE_TRANSISTOR:
digitalWrite(AP_CAMERA_TRANSISTOR_PIN, LOW);
hal.gpio->write(AP_CAMERA_TRANSISTOR_PIN, 0);
break;
}
}

View File

@ -7,6 +7,7 @@
#ifndef AP_CAMERA_H
#define AP_CAMERA_H
#include <AP_Param.h>
#include <AP_Common.h>
#include <GCS_MAVLink.h>