mirror of https://github.com/ArduPilot/ardupilot
AP_Camera: add and use AP_CAMERA_RELAY_ENABLED
This commit is contained in:
parent
5afbaea30b
commit
dea34086ac
|
@ -90,10 +90,12 @@ void AP_Camera::init()
|
||||||
_backends[instance] = new AP_Camera_Servo(*this, _params[instance], instance);
|
_backends[instance] = new AP_Camera_Servo(*this, _params[instance], instance);
|
||||||
_num_instances++;
|
_num_instances++;
|
||||||
|
|
||||||
|
#if AP_CAMERA_RELAY_ENABLED
|
||||||
// check for relay camera
|
// check for relay camera
|
||||||
} else if (camera_type == CameraType::RELAY) {
|
} else if (camera_type == CameraType::RELAY) {
|
||||||
_backends[instance] = new AP_Camera_Relay(*this, _params[instance], instance);
|
_backends[instance] = new AP_Camera_Relay(*this, _params[instance], instance);
|
||||||
_num_instances++;
|
_num_instances++;
|
||||||
|
#endif
|
||||||
|
|
||||||
#if AP_CAMERA_SOLOGIMBAL_ENABLED
|
#if AP_CAMERA_SOLOGIMBAL_ENABLED
|
||||||
// check for GoPro in Solo camera
|
// check for GoPro in Solo camera
|
||||||
|
|
|
@ -48,7 +48,9 @@ public:
|
||||||
enum class CameraType {
|
enum class CameraType {
|
||||||
NONE = 0, // None
|
NONE = 0, // None
|
||||||
SERVO = 1, // Servo/PWM controlled camera
|
SERVO = 1, // Servo/PWM controlled camera
|
||||||
|
#if AP_CAMERA_RELAY_ENABLED
|
||||||
RELAY = 2, // Relay controlled camera
|
RELAY = 2, // Relay controlled camera
|
||||||
|
#endif
|
||||||
#if AP_CAMERA_SOLOGIMBAL_ENABLED
|
#if AP_CAMERA_SOLOGIMBAL_ENABLED
|
||||||
SOLOGIMBAL = 3, // GoPro in Solo gimbal
|
SOLOGIMBAL = 3, // GoPro in Solo gimbal
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -1,11 +1,9 @@
|
||||||
#include "AP_Camera_Relay.h"
|
#include "AP_Camera_Relay.h"
|
||||||
|
|
||||||
#if AP_CAMERA_ENABLED
|
#if AP_CAMERA_RELAY_ENABLED
|
||||||
|
|
||||||
#include <AP_Relay/AP_Relay.h>
|
#include <AP_Relay/AP_Relay.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
|
||||||
|
|
||||||
// update - should be called at 50hz
|
// update - should be called at 50hz
|
||||||
void AP_Camera_Relay::update()
|
void AP_Camera_Relay::update()
|
||||||
{
|
{
|
||||||
|
@ -53,5 +51,4 @@ bool AP_Camera_Relay::trigger_pic()
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AP_CAMERA_RELAY_ENABLED
|
||||||
#endif // AP_CAMERA_ENABLED
|
|
||||||
|
|
|
@ -20,7 +20,7 @@
|
||||||
|
|
||||||
#include "AP_Camera_Backend.h"
|
#include "AP_Camera_Backend.h"
|
||||||
|
|
||||||
#if AP_CAMERA_ENABLED
|
#if AP_CAMERA_RELAY_ENABLED
|
||||||
|
|
||||||
class AP_Camera_Relay : public AP_Camera_Backend
|
class AP_Camera_Relay : public AP_Camera_Backend
|
||||||
{
|
{
|
||||||
|
@ -43,4 +43,4 @@ private:
|
||||||
uint16_t trigger_counter; // count of number of cycles shutter should be held open
|
uint16_t trigger_counter; // count of number of cycles shutter should be held open
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_CAMERA_ENABLED
|
#endif // AP_CAMERA_RELAY_ENABLED
|
||||||
|
|
|
@ -19,6 +19,10 @@
|
||||||
#define AP_CAMERA_MOUNT_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_MOUNT_ENABLED
|
#define AP_CAMERA_MOUNT_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_MOUNT_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifndef AP_CAMERA_RELAY_ENABLED
|
||||||
|
#define AP_CAMERA_RELAY_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef AP_CAMERA_SOLOGIMBAL_ENABLED
|
#ifndef AP_CAMERA_SOLOGIMBAL_ENABLED
|
||||||
#define AP_CAMERA_SOLOGIMBAL_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_SOLO_GIMBAL_ENABLED
|
#define AP_CAMERA_SOLOGIMBAL_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_SOLO_GIMBAL_ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue