mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Camera: add and use AP_CAMERA_MOUNT_ENABLED
This commit is contained in:
parent
a7eeb35150
commit
a0d4706643
@ -102,10 +102,12 @@ void AP_Camera::init()
|
||||
_num_instances++;
|
||||
#endif
|
||||
|
||||
#if AP_CAMERA_MOUNT_ENABLED
|
||||
// check for Mount camera
|
||||
} else if (camera_type == CameraType::MOUNT) {
|
||||
_backends[instance] = new AP_Camera_Mount(*this, _params[instance], instance);
|
||||
_num_instances++;
|
||||
#endif
|
||||
|
||||
// check for MAVLink enabled camera driver
|
||||
} else if (camera_type == CameraType::MAVLINK) {
|
||||
|
@ -50,7 +50,9 @@ public:
|
||||
SERVO = 1, // Servo/PWM controlled camera
|
||||
RELAY = 2, // Relay controlled camera
|
||||
SOLOGIMBAL = 3, // GoPro in Solo gimbal
|
||||
#if AP_CAMERA_MOUNT_ENABLED
|
||||
MOUNT = 4, // Mount library implements camera
|
||||
#endif
|
||||
MAVLINK = 5, // MAVLink enabled camera
|
||||
};
|
||||
|
||||
|
@ -1,6 +1,6 @@
|
||||
#include "AP_Camera_Mount.h"
|
||||
|
||||
#if AP_CAMERA_ENABLED
|
||||
#if AP_CAMERA_MOUNT_ENABLED
|
||||
#include <AP_Mount/AP_Mount.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
@ -8,13 +8,11 @@ extern const AP_HAL::HAL& hal;
|
||||
// entry point to actually take a picture. returns true on success
|
||||
bool AP_Camera_Mount::trigger_pic()
|
||||
{
|
||||
#if HAL_MOUNT_ENABLED
|
||||
AP_Mount* mount = AP::mount();
|
||||
if (mount != nullptr) {
|
||||
mount->take_picture(0);
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -22,12 +20,10 @@ bool AP_Camera_Mount::trigger_pic()
|
||||
// start_recording should be true to start recording, false to stop recording
|
||||
bool AP_Camera_Mount::record_video(bool start_recording)
|
||||
{
|
||||
#if HAL_MOUNT_ENABLED
|
||||
AP_Mount* mount = AP::mount();
|
||||
if (mount != nullptr) {
|
||||
return mount->record_video(0, start_recording);
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -35,12 +31,10 @@ bool AP_Camera_Mount::record_video(bool start_recording)
|
||||
// zoom out = -1, hold = 0, zoom in = 1
|
||||
bool AP_Camera_Mount::set_zoom_step(int8_t zoom_step)
|
||||
{
|
||||
#if HAL_MOUNT_ENABLED
|
||||
AP_Mount* mount = AP::mount();
|
||||
if (mount != nullptr) {
|
||||
return mount->set_zoom_step(0, zoom_step);
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -48,25 +42,21 @@ bool AP_Camera_Mount::set_zoom_step(int8_t zoom_step)
|
||||
// focus in = -1, focus hold = 0, focus out = 1
|
||||
bool AP_Camera_Mount::set_manual_focus_step(int8_t focus_step)
|
||||
{
|
||||
#if HAL_MOUNT_ENABLED
|
||||
AP_Mount* mount = AP::mount();
|
||||
if (mount != nullptr) {
|
||||
return mount->set_manual_focus_step(0, focus_step);
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
// auto focus. returns true on success
|
||||
bool AP_Camera_Mount::set_auto_focus()
|
||||
{
|
||||
#if HAL_MOUNT_ENABLED
|
||||
AP_Mount* mount = AP::mount();
|
||||
if (mount != nullptr) {
|
||||
return mount->set_auto_focus(0);
|
||||
}
|
||||
#endif
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif // AP_CAMERA_ENABLED
|
||||
#endif // AP_CAMERA_MOUNT_ENABLED
|
||||
|
@ -20,7 +20,7 @@
|
||||
|
||||
#include "AP_Camera_Backend.h"
|
||||
|
||||
#if AP_CAMERA_ENABLED
|
||||
#if AP_CAMERA_MOUNT_ENABLED
|
||||
|
||||
class AP_Camera_Mount : public AP_Camera_Backend
|
||||
{
|
||||
@ -51,4 +51,4 @@ public:
|
||||
bool set_auto_focus() override;
|
||||
};
|
||||
|
||||
#endif // AP_CAMERA_ENABLED
|
||||
#endif // AP_CAMERA_MOUNT_ENABLED
|
||||
|
@ -1,7 +1,16 @@
|
||||
#pragma once
|
||||
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include <AP_Mount/AP_Mount_config.h>
|
||||
|
||||
#ifndef AP_CAMERA_ENABLED
|
||||
#define AP_CAMERA_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef AP_CAMERA_BACKEND_DEFAULT_ENABLED
|
||||
#define AP_CAMERA_BACKEND_DEFAULT_ENABLED AP_CAMERA_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_CAMERA_MOUNT_ENABLED
|
||||
#define AP_CAMERA_MOUNT_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_MOUNT_ENABLED
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user