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_SoloGimbal.cpp
Views: 1798
#include "AP_Camera_SoloGimbal.h"12#if AP_CAMERA_SOLOGIMBAL_ENABLED34#include <GCS_MAVLink/GCS.h>56// Toggle the shutter on the GoPro7// This is so ArduPilot can toggle the shutter directly, either for mission/GCS commands, or when the8// Solo's gimbal is installed on a vehicle other than a Solo. The usual GoPro controls through the9// Solo app and Solo controller do not use this, as it is done offboard on the companion computer.10// entry point to actually take a picture. returns true on success11bool AP_Camera_SoloGimbal::trigger_pic()12{13if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) {14GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Not Available");15return false;16}1718const uint8_t gopro_shutter_start[4] = { 1, 0, 0, 0};19const uint8_t gopro_shutter_stop[4] = { 0, 0, 0, 0};2021if (gopro_capture_mode == GOPRO_CAPTURE_MODE_PHOTO) {22// Trigger shutter start to take a photo23GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Photo Trigger");24mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_start);2526} else if (gopro_capture_mode == GOPRO_CAPTURE_MODE_VIDEO) {27if (gopro_is_recording) {28// GoPro is recording, so stop recording29GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Recording Stop");30mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_stop);31} else {32// GoPro is not recording, so start recording33GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro Recording Start");34mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_SHUTTER,gopro_shutter_start);35}36} else {37GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Unsupported Capture Mode");38return false;39}4041return true;42}4344// Cycle the GoPro capture mode45// This is so ArduPilot can cycle through the capture modes of the GoPro directly, probably with an RC Aux function.46// This is primarily for Solo's gimbal being installed on a vehicle other than a Solo. The usual GoPro controls47// through the Solo app and Solo controller do not use this, as it is done offboard on the companion computer.48// momentary switch to change camera between picture and video modes49void AP_Camera_SoloGimbal::cam_mode_toggle()50{51uint8_t gopro_capture_mode_values[4] = { };5253if (gopro_status != GOPRO_HEARTBEAT_STATUS_CONNECTED) {54GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "GoPro Not Available");55return;56}5758switch(gopro_capture_mode) {59case GOPRO_CAPTURE_MODE_VIDEO:60if (gopro_is_recording) {61// GoPro is recording, cannot change modes62GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro recording, can't change modes");63} else {64// Change to camera mode65gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_PHOTO;66mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_CAPTURE_MODE,gopro_capture_mode_values);67GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro changing to mode photo");68}69break;7071case GOPRO_CAPTURE_MODE_PHOTO:72default:73// Change to video mode74gopro_capture_mode_values[0] = GOPRO_CAPTURE_MODE_VIDEO;75mavlink_msg_gopro_set_request_send(heartbeat_channel, mavlink_system.sysid, MAV_COMP_ID_GIMBAL,GOPRO_COMMAND_CAPTURE_MODE,gopro_capture_mode_values);76GCS_SEND_TEXT(MAV_SEVERITY_INFO, "GoPro changing to mode video");77break;78}79}8081// handle incoming heartbeat from the Solo gimbal GoPro82void AP_Camera_SoloGimbal::handle_message(mavlink_channel_t chan, const mavlink_message_t &msg)83{84mavlink_gopro_heartbeat_t report_msg;85mavlink_msg_gopro_heartbeat_decode(&msg, &report_msg);86gopro_is_recording = report_msg.flags & GOPRO_FLAG_RECORDING;87heartbeat_channel = chan;8889switch((GOPRO_HEARTBEAT_STATUS)report_msg.status) {90case GOPRO_HEARTBEAT_STATUS_DISCONNECTED:91case GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE:92case GOPRO_HEARTBEAT_STATUS_ERROR:93case GOPRO_HEARTBEAT_STATUS_CONNECTED:94gopro_status = (GOPRO_HEARTBEAT_STATUS)report_msg.status;95break;96case GOPRO_HEARTBEAT_STATUS_ENUM_END:97break;98}99100switch((GOPRO_CAPTURE_MODE)report_msg.capture_mode){101case GOPRO_CAPTURE_MODE_VIDEO:102case GOPRO_CAPTURE_MODE_PHOTO:103case GOPRO_CAPTURE_MODE_BURST:104case GOPRO_CAPTURE_MODE_TIME_LAPSE:105case GOPRO_CAPTURE_MODE_MULTI_SHOT:106case GOPRO_CAPTURE_MODE_PLAYBACK:107case GOPRO_CAPTURE_MODE_SETUP:108case GOPRO_CAPTURE_MODE_UNKNOWN:109gopro_capture_mode = (GOPRO_CAPTURE_MODE)report_msg.capture_mode;110break;111case GOPRO_CAPTURE_MODE_ENUM_END:112break;113}114}115116#endif // AP_CAMERA_SOLOGIMBAL_ENABLED117118119