AP_Camera: make solo gimbal inclusion configurable per-board

This commit is contained in:
Andy Piper 2020-07-24 18:31:42 +01:00 committed by Andrew Tridgell
parent 07df203d19
commit cd60238e3d
3 changed files with 17 additions and 0 deletions

View File

@ -153,9 +153,13 @@ void AP_Camera::trigger_pic()
case CamTrigType::relay: case CamTrigType::relay:
relay_pic(); // basic relay activation relay_pic(); // basic relay activation
break; break;
#if HAL_SOLO_GIMBAL_ENABLED
case CamTrigType::gopro: // gopro in Solo Gimbal case CamTrigType::gopro: // gopro in Solo Gimbal
AP_Camera_SoloGimbal::gopro_shutter_toggle(); AP_Camera_SoloGimbal::gopro_shutter_toggle();
break; break;
#endif
default:
break;
} }
log_picture(); log_picture();
@ -208,6 +212,7 @@ void AP_Camera::handle_message(mavlink_channel_t chan, const mavlink_message_t &
case MAVLINK_MSG_ID_DIGICAM_CONTROL: case MAVLINK_MSG_ID_DIGICAM_CONTROL:
control_msg(msg); control_msg(msg);
break; break;
#if HAL_SOLO_GIMBAL_ENABLED
case MAVLINK_MSG_ID_GOPRO_HEARTBEAT: case MAVLINK_MSG_ID_GOPRO_HEARTBEAT:
// heartbeat from the Solo gimbal with a GoPro // heartbeat from the Solo gimbal with a GoPro
if (get_trigger_type() == CamTrigType::gopro) { if (get_trigger_type() == CamTrigType::gopro) {
@ -215,6 +220,7 @@ void AP_Camera::handle_message(mavlink_channel_t chan, const mavlink_message_t &
break; break;
} }
break; break;
#endif
} }
} }
@ -222,9 +228,11 @@ void AP_Camera::handle_message(mavlink_channel_t chan, const mavlink_message_t &
void AP_Camera::cam_mode_toggle() void AP_Camera::cam_mode_toggle()
{ {
switch (get_trigger_type()) { switch (get_trigger_type()) {
#if HAL_SOLO_GIMBAL_ENABLED
case CamTrigType::gopro: case CamTrigType::gopro:
AP_Camera_SoloGimbal::gopro_capture_mode_toggle(); AP_Camera_SoloGimbal::gopro_capture_mode_toggle();
break; break;
#endif
default: default:
// no other cameras use this yet // no other cameras use this yet
break; break;

View File

@ -1,6 +1,8 @@
#include "AP_Camera_SoloGimbal.h" #include "AP_Camera_SoloGimbal.h"
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
#if HAL_SOLO_GIMBAL_ENABLED
GOPRO_CAPTURE_MODE AP_Camera_SoloGimbal::gopro_capture_mode; GOPRO_CAPTURE_MODE AP_Camera_SoloGimbal::gopro_capture_mode;
GOPRO_HEARTBEAT_STATUS AP_Camera_SoloGimbal::gopro_status; GOPRO_HEARTBEAT_STATUS AP_Camera_SoloGimbal::gopro_status;
bool AP_Camera_SoloGimbal::gopro_is_recording; bool AP_Camera_SoloGimbal::gopro_is_recording;
@ -110,3 +112,5 @@ void AP_Camera_SoloGimbal::handle_gopro_heartbeat(mavlink_channel_t chan, const
break; break;
} }
} }
#endif // HAL_SOLO_GIMBAL_ENABLED

View File

@ -1,6 +1,9 @@
#pragma once #pragma once
#include <GCS_MAVLink/GCS_MAVLink.h> #include <GCS_MAVLink/GCS_MAVLink.h>
#include <AP_Mount/AP_Mount.h>
#if HAL_SOLO_GIMBAL_ENABLED
class AP_Camera_SoloGimbal { class AP_Camera_SoloGimbal {
public: public:
@ -16,3 +19,5 @@ private:
static bool gopro_is_recording; static bool gopro_is_recording;
static mavlink_channel_t heartbeat_channel; static mavlink_channel_t heartbeat_channel;
}; };
#endif // HAL_SOLO_GIMBAL_ENABLED