Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Camera/AP_Camera_Mount.cpp
Views: 1798
#include "AP_Camera_Mount.h"12#if AP_CAMERA_MOUNT_ENABLED3#include <AP_Mount/AP_Mount.h>45extern const AP_HAL::HAL& hal;67// entry point to actually take a picture. returns true on success8bool AP_Camera_Mount::trigger_pic()9{10AP_Mount* mount = AP::mount();11if (mount != nullptr) {12return mount->take_picture(get_mount_instance());13}14return false;15}1617// start/stop recording video. returns true on success18// start_recording should be true to start recording, false to stop recording19bool AP_Camera_Mount::record_video(bool start_recording)20{21AP_Mount* mount = AP::mount();22if (mount != nullptr) {23return mount->record_video(get_mount_instance(), start_recording);24}25return false;26}2728// set zoom specified as a rate or percentage29bool AP_Camera_Mount::set_zoom(ZoomType zoom_type, float zoom_value)30{31AP_Mount* mount = AP::mount();32if (mount != nullptr) {33return mount->set_zoom(get_mount_instance(), zoom_type, zoom_value);34}35return false;36}3738// set focus specified as rate, percentage or auto39// focus in = -1, focus hold = 0, focus out = 140SetFocusResult AP_Camera_Mount::set_focus(FocusType focus_type, float focus_value)41{42AP_Mount* mount = AP::mount();43if (mount != nullptr) {44return mount->set_focus(get_mount_instance(), focus_type, focus_value);45}46return SetFocusResult::FAILED;47}4849// set tracking to none, point or rectangle (see TrackingType enum)50// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right51// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom52bool AP_Camera_Mount::set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)53{54AP_Mount* mount = AP::mount();55if (mount != nullptr) {56return mount->set_tracking(get_mount_instance(), tracking_type, p1, p2);57}58return false;59}606162// set camera lens as a value from 0 to 563bool AP_Camera_Mount::set_lens(uint8_t lens)64{65AP_Mount* mount = AP::mount();66if (mount != nullptr) {67return mount->set_lens(get_mount_instance(), lens);68}69return false;70}7172#if HAL_MOUNT_SET_CAMERA_SOURCE_ENABLED73// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type74bool AP_Camera_Mount::set_camera_source(AP_Camera::CameraSource primary_source, AP_Camera::CameraSource secondary_source)75{76AP_Mount* mount = AP::mount();77if (mount != nullptr) {78return mount->set_camera_source(get_mount_instance(), (uint8_t)primary_source, (uint8_t)secondary_source);79}80return false;81}82#endif8384// send camera information message to GCS85void AP_Camera_Mount::send_camera_information(mavlink_channel_t chan) const86{87AP_Mount* mount = AP::mount();88if (mount != nullptr) {89return mount->send_camera_information(get_mount_instance(), chan);90}91}9293// send camera settings message to GCS94void AP_Camera_Mount::send_camera_settings(mavlink_channel_t chan) const95{96AP_Mount* mount = AP::mount();97if (mount != nullptr) {98return mount->send_camera_settings(get_mount_instance(), chan);99}100}101102// send camera capture status message to GCS103void AP_Camera_Mount::send_camera_capture_status(mavlink_channel_t chan) const104{105AP_Mount* mount = AP::mount();106if (mount != nullptr) {107return mount->send_camera_capture_status(get_mount_instance(), chan);108}109}110111#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED112// send camera thermal range message to GCS113void AP_Camera_Mount::send_camera_thermal_range(mavlink_channel_t chan) const114{115#if AP_MOUNT_SEND_THERMAL_RANGE_ENABLED116AP_Mount* mount = AP::mount();117if (mount != nullptr) {118mount->send_camera_thermal_range(get_mount_instance(), chan);119}120#endif121}122#endif // AP_CAMERA_SEND_THERMAL_RANGE_ENABLED123124#if AP_CAMERA_SCRIPTING_ENABLED125// change camera settings not normally used by autopilot126bool AP_Camera_Mount::change_setting(CameraSetting setting, float value)127{128AP_Mount* mount = AP::mount();129if (mount != nullptr) {130return mount->change_setting(get_mount_instance(), setting, value);131}132return false;133}134#endif135136#endif // AP_CAMERA_MOUNT_ENABLED137138139