Path: blob/master/libraries/AP_Camera/AP_Camera_SoloGimbal.h
9676 views
#pragma once12#include "AP_Camera_config.h"34#if AP_CAMERA_SOLOGIMBAL_ENABLED56#include "AP_Camera_Backend.h"7#include <GCS_MAVLink/GCS_MAVLink.h>89class AP_Camera_SoloGimbal : public AP_Camera_Backend10{11public:1213// Constructor14using AP_Camera_Backend::AP_Camera_Backend;1516/* Do not allow copies */17CLASS_NO_COPY(AP_Camera_SoloGimbal);1819// entry point to actually take a picture. returns true on success20bool trigger_pic() override;2122// momentary switch to change camera between picture and video modes23void cam_mode_toggle() override;2425// handle MAVLink messages from the camera26void handle_message(mavlink_channel_t chan, const mavlink_message_t &msg) override;2728private:2930GOPRO_CAPTURE_MODE gopro_capture_mode;31GOPRO_HEARTBEAT_STATUS gopro_status;32bool gopro_is_recording;33mavlink_channel_t heartbeat_channel;34};3536#endif // AP_CAMERA_SOLOGIMBAL_ENABLED373839