Path: blob/master/libraries/AP_Camera/AP_Camera_MAVLinkCamV2.cpp
9441 views
#include "AP_Camera_MAVLinkCamV2.h"12#if AP_CAMERA_MAVLINKCAMV2_ENABLED3#include <GCS_MAVLink/GCS.h>45extern const AP_HAL::HAL& hal;67#define AP_CAMERA_MAVLINKCAMV2_SEARCH_MS 60000 // search for camera for 60 seconds after startup89// update - should be called at 50hz10void AP_Camera_MAVLinkCamV2::update()11{12// exit immediately if not initialised13if (!_initialised) {14find_camera();15}1617// call parent update18AP_Camera_Backend::update();19}2021// entry point to actually take a picture. returns true on success22bool AP_Camera_MAVLinkCamV2::trigger_pic()23{24// exit immediately if have not found camera or does not support taking pictures25if (_link == nullptr || !(_cam_info.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE)) {26return false;27}2829// prepare and send message30mavlink_command_long_t pkt {};31pkt.target_system = _sysid;32pkt.target_component = _compid;33pkt.command = MAV_CMD_IMAGE_START_CAPTURE;34pkt.param3 = 1; // number of images to take35pkt.param4 = image_index+1; // starting sequence number3637_link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt);3839return true;40}4142// start or stop video recording. returns true on success43// set start_recording = true to start record, false to stop recording44bool AP_Camera_MAVLinkCamV2::record_video(bool start_recording)45{46// exit immediately if have not found camera or does not support recording video47if (_link == nullptr || !(_cam_info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO)) {48return false;49}5051// prepare and send message52mavlink_command_long_t pkt {};53pkt.target_system = _sysid;54pkt.target_component = _compid;5556if (start_recording) {57pkt.command = MAV_CMD_VIDEO_START_CAPTURE;58// param1 = 0, video stream id. 0 for all streams59// param2 = 0, status frequency. frequency that CAMERA_CAPTURE_STATUS messages should be sent while recording. 0 for no messages60} else {61pkt.command = MAV_CMD_VIDEO_STOP_CAPTURE;62// param1 = 0, video stream id. 0 for all streams63}6465_link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt);6667return true;68}6970// set zoom specified as a rate or percentage71bool AP_Camera_MAVLinkCamV2::set_zoom(ZoomType zoom_type, float zoom_value)72{73// exit immediately if have not found camera or does not support zoom74if (_link == nullptr || !(_cam_info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM)) {75return false;76}7778// prepare and send message79mavlink_command_long_t pkt {};80pkt.target_system = _sysid;81pkt.target_component = _compid;82pkt.command = MAV_CMD_SET_CAMERA_ZOOM;83switch (zoom_type) {84case ZoomType::RATE:85pkt.param1 = ZOOM_TYPE_CONTINUOUS;86break;87case ZoomType::PCT:88pkt.param1 = ZOOM_TYPE_RANGE;89break;90}91pkt.param2 = zoom_value; // Zoom Value9293_link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt);9495return true;96}9798// set focus specified as rate, percentage or auto99// focus in = -1, focus hold = 0, focus out = 1100SetFocusResult AP_Camera_MAVLinkCamV2::set_focus(FocusType focus_type, float focus_value)101{102// exit immediately if have not found camera or does not support focus103if (_link == nullptr || !(_cam_info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS)) {104return SetFocusResult::FAILED;105}106107// prepare and send message108mavlink_command_long_t pkt {};109pkt.target_system = _sysid;110pkt.target_component = _compid;111pkt.command = MAV_CMD_SET_CAMERA_FOCUS;112switch (focus_type) {113case FocusType::RATE:114// focus in, out or hold (focus in = -1, hold = 0, focus out = 1). Same as FOCUS_TYPE_CONTINUOUS115pkt.param1 = FOCUS_TYPE_CONTINUOUS;116break;117case FocusType::PCT:118// focus to a percentage (from 0 to 100) of the full range. Same as FOCUS_TYPE_RANGE119pkt.param1 = FOCUS_TYPE_RANGE;120break;121case FocusType::AUTO:122// focus automatically. Same as FOCUS_TYPE_AUTO123pkt.param1 = FOCUS_TYPE_AUTO;124break;125}126pkt.param2 = focus_value;127128_link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt);129130return SetFocusResult::ACCEPTED;131}132133// handle incoming mavlink message including CAMERA_INFORMATION134void AP_Camera_MAVLinkCamV2::handle_message(mavlink_channel_t chan, const mavlink_message_t &msg)135{136// exit immediately if this is not our message137if (msg.sysid != _sysid || msg.compid != _compid) {138return;139}140141// handle CAMERA_INFORMATION142if (msg.msgid == MAVLINK_MSG_ID_CAMERA_INFORMATION) {143mavlink_msg_camera_information_decode(&msg, &_cam_info);144145const uint8_t fw_ver_major = _cam_info.firmware_version & 0x000000FF;146const uint8_t fw_ver_minor = (_cam_info.firmware_version & 0x0000FF00) >> 8;147const uint8_t fw_ver_revision = (_cam_info.firmware_version & 0x00FF0000) >> 16;148const uint8_t fw_ver_build = (_cam_info.firmware_version & 0xFF000000) >> 24;149150// display camera info to user151GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Camera: %.32s %.32s fw:%u.%u.%u.%u",152_cam_info.vendor_name,153_cam_info.model_name,154(unsigned)fw_ver_major,155(unsigned)fw_ver_minor,156(unsigned)fw_ver_revision,157(unsigned)fw_ver_build);158159_got_camera_info = true;160}161}162163// send camera information message to GCS164void AP_Camera_MAVLinkCamV2::send_camera_information(mavlink_channel_t chan) const165{166// exit immediately if we have not yet received cam info167if (!_got_camera_info) {168return;169}170171// send CAMERA_INFORMATION message172mavlink_msg_camera_information_send(173chan,174AP_HAL::millis(), // time_boot_ms175_cam_info.vendor_name, // vendor_name uint8_t[32]176_cam_info.model_name, // model_name uint8_t[32]177_cam_info.firmware_version, // firmware version uint32_t178_cam_info.focal_length, // focal_length float (mm)179_cam_info.sensor_size_h, // sensor_size_h float (mm)180_cam_info.sensor_size_v, // sensor_size_v float (mm)181_cam_info.resolution_h, // resolution_h uint16_t (pix)182_cam_info.resolution_v, // resolution_v uint16_t (pix)183_cam_info.lens_id, // lens_id, uint8_t184_cam_info.flags, // flags uint32_t (CAMERA_CAP_FLAGS)185_cam_info.cam_definition_version, // cam_definition_version uint16_t186_cam_info.cam_definition_uri, // cam_definition_uri char[140]187get_gimbal_device_id()); // gimbal_device_id uint8_t188}189190// search for camera in GCS_MAVLink routing table191void AP_Camera_MAVLinkCamV2::find_camera()192{193// do not look for camera for first 10 seconds so user may see banner194uint32_t now_ms = AP_HAL::millis();195if (now_ms < 10000) {196return;197}198199// search for camera for 60 seconds or until armed200if ((now_ms > AP_CAMERA_MAVLINKCAMV2_SEARCH_MS) && hal.util->get_soft_armed()) {201return;202}203204// search for a mavlink enabled camera205if (_link == nullptr) {206// we expect that instance 0 has compid = MAV_COMP_ID_CAMERA, instance 1 has compid = MAV_COMP_ID_CAMERA2, etc207uint8_t compid = MIN(MAV_COMP_ID_CAMERA + _instance, MAV_COMP_ID_CAMERA6);208_link = GCS_MAVLINK::find_by_mavtype_and_compid(MAV_TYPE_CAMERA, compid, _sysid);209if (_link == nullptr) {210// have not yet found a camera so return211return;212}213_compid = compid;214}215216// request CAMERA_INFORMATION217if (!_got_camera_info) {218if (now_ms - _last_caminfo_req_ms > 1000) {219_last_caminfo_req_ms = now_ms;220request_camera_information();221}222return;223}224225_initialised = true;226}227228// request CAMERA_INFORMATION (holds vendor and model name)229void AP_Camera_MAVLinkCamV2::request_camera_information() const230{231if (_link == nullptr) {232return;233}234235const mavlink_command_long_t pkt {236MAVLINK_MSG_ID_CAMERA_INFORMATION, // param12370, // param22380, // param32390, // param42400, // param52410, // param62420, // param7243MAV_CMD_REQUEST_MESSAGE,244_sysid,245_compid,2460 // confirmation247};248249_link->send_message(MAVLINK_MSG_ID_COMMAND_LONG, (const char*)&pkt);250}251252#endif // AP_CAMERA_MAVLINKCAMV2_ENABLED253254255