2023-02-10 20:27:39 -04:00
|
|
|
#include "AP_Camera_Mount.h"
|
|
|
|
|
2023-03-06 18:15:58 -04:00
|
|
|
#if AP_CAMERA_MOUNT_ENABLED
|
2023-02-10 20:27:39 -04:00
|
|
|
#include <AP_Mount/AP_Mount.h>
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
// entry point to actually take a picture. returns true on success
|
|
|
|
bool AP_Camera_Mount::trigger_pic()
|
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
2023-09-20 04:55:03 -03:00
|
|
|
return mount->take_picture(get_mount_instance());
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// start/stop recording video. returns true on success
|
|
|
|
// start_recording should be true to start recording, false to stop recording
|
|
|
|
bool AP_Camera_Mount::record_video(bool start_recording)
|
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
2023-08-01 15:45:51 -03:00
|
|
|
return mount->record_video(get_mount_instance(), start_recording);
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2023-04-06 21:49:46 -03:00
|
|
|
// set zoom specified as a rate or percentage
|
2023-04-18 22:06:16 -03:00
|
|
|
bool AP_Camera_Mount::set_zoom(ZoomType zoom_type, float zoom_value)
|
2023-02-10 20:27:39 -04:00
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
2023-08-01 15:45:51 -03:00
|
|
|
return mount->set_zoom(get_mount_instance(), zoom_type, zoom_value);
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2023-04-24 09:23:07 -03:00
|
|
|
// set focus specified as rate, percentage or auto
|
2023-02-10 20:27:39 -04:00
|
|
|
// focus in = -1, focus hold = 0, focus out = 1
|
2023-06-21 03:03:39 -03:00
|
|
|
SetFocusResult AP_Camera_Mount::set_focus(FocusType focus_type, float focus_value)
|
2023-02-10 20:27:39 -04:00
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
2023-08-01 15:45:51 -03:00
|
|
|
return mount->set_focus(get_mount_instance(), focus_type, focus_value);
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
2023-06-21 03:03:39 -03:00
|
|
|
return SetFocusResult::FAILED;
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
|
|
|
|
2023-07-06 01:57:20 -03:00
|
|
|
// set tracking to none, point or rectangle (see TrackingType enum)
|
|
|
|
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
|
|
|
|
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
|
|
|
|
bool AP_Camera_Mount::set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)
|
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
2023-08-01 15:45:51 -03:00
|
|
|
return mount->set_tracking(get_mount_instance(), tracking_type, p1, p2);
|
2023-07-06 01:57:20 -03:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2023-07-14 08:21:02 -03:00
|
|
|
|
|
|
|
// set camera lens as a value from 0 to 5
|
|
|
|
bool AP_Camera_Mount::set_lens(uint8_t lens)
|
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
2023-08-01 15:45:51 -03:00
|
|
|
return mount->set_lens(get_mount_instance(), lens);
|
2023-07-14 08:21:02 -03:00
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2024-04-11 21:50:27 -03:00
|
|
|
#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED
|
2024-02-08 04:29:29 -04:00
|
|
|
// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type
|
|
|
|
bool AP_Camera_Mount::set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source)
|
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
|
|
|
return mount->set_camera_source(get_mount_instance(), (uint8_t)primary_source, (uint8_t)secondary_source);
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2024-04-11 21:50:27 -03:00
|
|
|
#endif
|
2024-02-08 04:29:29 -04:00
|
|
|
|
2023-06-09 23:17:12 -03:00
|
|
|
// send camera information message to GCS
|
|
|
|
void AP_Camera_Mount::send_camera_information(mavlink_channel_t chan) const
|
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
2023-08-01 15:45:51 -03:00
|
|
|
return mount->send_camera_information(get_mount_instance(), chan);
|
2023-06-09 23:17:12 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// send camera settings message to GCS
|
|
|
|
void AP_Camera_Mount::send_camera_settings(mavlink_channel_t chan) const
|
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
2023-08-01 15:45:51 -03:00
|
|
|
return mount->send_camera_settings(get_mount_instance(), chan);
|
2023-06-09 23:17:12 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-09-11 23:23:53 -03:00
|
|
|
// send camera capture status message to GCS
|
|
|
|
void AP_Camera_Mount::send_camera_capture_status(mavlink_channel_t chan) const
|
|
|
|
{
|
|
|
|
AP_Mount* mount = AP::mount();
|
|
|
|
if (mount != nullptr) {
|
|
|
|
return mount->send_camera_capture_status(get_mount_instance(), chan);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-03-06 18:15:58 -04:00
|
|
|
#endif // AP_CAMERA_MOUNT_ENABLED
|