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.cpp
Views: 1798
#include "AP_Camera.h"12#if AP_CAMERA_ENABLED34#include <GCS_MAVLink/GCS.h>5#include <AP_Math/AP_Math.h>6#include <AP_HAL/AP_HAL.h>7#include <SRV_Channel/SRV_Channel.h>8#include <AP_Vehicle/AP_Vehicle.h>9#include "AP_Camera_Backend.h"10#include "AP_Camera_Servo.h"11#include "AP_Camera_Relay.h"12#include "AP_Camera_SoloGimbal.h"13#include "AP_Camera_Mount.h"14#include "AP_Camera_MAVLink.h"15#include "AP_Camera_MAVLinkCamV2.h"16#include "AP_Camera_Scripting.h"17#include "AP_RunCam.h"1819const AP_Param::GroupInfo AP_Camera::var_info[] = {2021// @Param: _MAX_ROLL22// @DisplayName: Maximum photo roll angle.23// @Description: Postpone shooting if roll is greater than limit. (0=Disable, will shoot regardless of roll).24// @User: Standard25// @Units: deg26// @Range: 0 18027AP_GROUPINFO("_MAX_ROLL", 7, AP_Camera, _max_roll, 0),2829// @Param: _AUTO_ONLY30// @DisplayName: Distance-trigging in AUTO mode only31// @Description: When enabled, trigging by distance is done in AUTO mode only.32// @Values: 0:Always,1:Only when in AUTO33// @User: Standard34AP_GROUPINFO("_AUTO_ONLY", 10, AP_Camera, _auto_mode_only, 0),3536// @Group: 137// @Path: AP_Camera_Params.cpp38AP_SUBGROUPINFO(_params[0], "1", 12, AP_Camera, AP_Camera_Params),3940#if AP_CAMERA_MAX_INSTANCES > 141// @Group: 242// @Path: AP_Camera_Params.cpp43AP_SUBGROUPINFO(_params[1], "2", 13, AP_Camera, AP_Camera_Params),44#endif45#if AP_CAMERA_RUNCAM_ENABLED46// @Group: 1_RC_47// @Path: AP_RunCam.cpp48AP_SUBGROUPVARPTR(_backends[0], "1_RC_", 14, AP_Camera, _backend_var_info[0]),4950#if AP_CAMERA_MAX_INSTANCES > 151// @Group: 2_RC_52// @Path: AP_RunCam.cpp53AP_SUBGROUPVARPTR(_backends[1], "2_RC_", 15, AP_Camera, _backend_var_info[1]),54#endif55#endif56AP_GROUPEND57};5859#if AP_CAMERA_RUNCAM_ENABLED60const AP_Param::GroupInfo *AP_Camera::_backend_var_info[AP_CAMERA_MAX_INSTANCES];61#endif6263extern const AP_HAL::HAL& hal;6465AP_Camera::AP_Camera(uint32_t _log_camera_bit) :66log_camera_bit(_log_camera_bit)67{68AP_Param::setup_object_defaults(this, var_info);69_singleton = this;70}7172// set camera trigger distance in a mission73void AP_Camera::set_trigger_distance(float distance_m)74{75WITH_SEMAPHORE(_rsem);7677if (primary == nullptr) {78return;79}80primary->set_trigger_distance(distance_m);81}8283// momentary switch to change camera between picture and video modes84void AP_Camera::cam_mode_toggle()85{86WITH_SEMAPHORE(_rsem);8788if (primary == nullptr) {89return;90}91primary->cam_mode_toggle();92}9394// take a picture95bool AP_Camera::take_picture()96{97WITH_SEMAPHORE(_rsem);9899// call for each instance100bool success = false;101for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {102if (_backends[i] != nullptr) {103success |= _backends[i]->take_picture();104}105}106107// return true if at least once pic taken108return success;109}110111bool AP_Camera::take_picture(uint8_t instance)112{113WITH_SEMAPHORE(_rsem);114115auto *backend = get_instance(instance);116if (backend == nullptr) {117return false;118}119return backend->take_picture();120}121122// take multiple pictures, time_interval between two consecutive pictures is in miliseconds123// if instance is not provided, all available cameras affected124// time_interval_ms must be positive125// total_num is number of pictures to be taken, -1 means capture forever126// returns true if at least one camera is successful127bool AP_Camera::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num)128{129WITH_SEMAPHORE(_rsem);130131// sanity check time interval132if (time_interval_ms == 0) {133return false;134}135136// call for all instances137bool success = false;138for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {139if (_backends[i] != nullptr) {140_backends[i]->take_multiple_pictures(time_interval_ms, total_num);141success = true;142}143}144145// return true if at least once backend was successful146return success;147}148149bool AP_Camera::take_multiple_pictures(uint8_t instance, uint32_t time_interval_ms, int16_t total_num)150{151WITH_SEMAPHORE(_rsem);152153// sanity check time interval154if (time_interval_ms == 0) {155return false;156}157158auto *backend = get_instance(instance);159if (backend == nullptr) {160return false;161}162backend->take_multiple_pictures(time_interval_ms, total_num);163return true;164}165166// stop capturing multiple image sequence167void AP_Camera::stop_capture()168{169WITH_SEMAPHORE(_rsem);170171// call for each instance172for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {173if (_backends[i] != nullptr) {174_backends[i]->stop_capture();175}176}177}178179bool AP_Camera::stop_capture(uint8_t instance)180{181WITH_SEMAPHORE(_rsem);182183auto *backend = get_instance(instance);184if (backend == nullptr) {185return false;186}187backend->stop_capture();188return true;189}190191// start/stop recording video192// start_recording should be true to start recording, false to stop recording193bool AP_Camera::record_video(bool start_recording)194{195WITH_SEMAPHORE(_rsem);196197if (primary == nullptr) {198return false;199}200return primary->record_video(start_recording);201}202203// detect and initialise backends204void AP_Camera::init()205{206// check init has not been called before207if (primary != nullptr) {208return;209}210211// perform any required parameter conversion212convert_params();213214// create each instance215for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {216switch ((CameraType)_params[instance].type.get()) {217#if AP_CAMERA_SERVO_ENABLED218case CameraType::SERVO:219_backends[instance] = NEW_NOTHROW AP_Camera_Servo(*this, _params[instance], instance);220break;221#endif222#if AP_CAMERA_RELAY_ENABLED223case CameraType::RELAY:224_backends[instance] = NEW_NOTHROW AP_Camera_Relay(*this, _params[instance], instance);225break;226#endif227#if AP_CAMERA_SOLOGIMBAL_ENABLED228// check for GoPro in Solo camera229case CameraType::SOLOGIMBAL:230_backends[instance] = NEW_NOTHROW AP_Camera_SoloGimbal(*this, _params[instance], instance);231break;232#endif233#if AP_CAMERA_MOUNT_ENABLED234// check for Mount camera235case CameraType::MOUNT:236_backends[instance] = NEW_NOTHROW AP_Camera_Mount(*this, _params[instance], instance);237break;238#endif239#if AP_CAMERA_MAVLINK_ENABLED240// check for MAVLink enabled camera driver241case CameraType::MAVLINK:242_backends[instance] = NEW_NOTHROW AP_Camera_MAVLink(*this, _params[instance], instance);243break;244#endif245#if AP_CAMERA_MAVLINKCAMV2_ENABLED246// check for MAVLink Camv2 driver247case CameraType::MAVLINK_CAMV2:248_backends[instance] = NEW_NOTHROW AP_Camera_MAVLinkCamV2(*this, _params[instance], instance);249break;250#endif251#if AP_CAMERA_SCRIPTING_ENABLED252// check for Scripting driver253case CameraType::SCRIPTING:254_backends[instance] = NEW_NOTHROW AP_Camera_Scripting(*this, _params[instance], instance);255break;256#endif257#if AP_CAMERA_RUNCAM_ENABLED258// check for RunCam driver259case CameraType::RUNCAM:260if (_backends[instance] == nullptr) { // may have already been created by the conversion code261_backends[instance] = NEW_NOTHROW AP_RunCam(*this, _params[instance], instance, _runcam_instances);262_backend_var_info[instance] = AP_RunCam::var_info;263AP_Param::load_object_from_eeprom(_backends[instance], _backend_var_info[instance]);264_runcam_instances++;265}266break;267#endif268case CameraType::NONE:269break;270}271272// set primary to first non-null instance273if (primary == nullptr) {274primary = _backends[instance];275}276}277278// init each instance, do it after all instances were created, so that they all know things279for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {280if (_backends[instance] != nullptr) {281_backends[instance]->init();282}283}284}285286// handle incoming mavlink messages287void AP_Camera::handle_message(mavlink_channel_t chan, const mavlink_message_t &msg)288{289WITH_SEMAPHORE(_rsem);290291if (msg.msgid == MAVLINK_MSG_ID_DIGICAM_CONTROL) {292// decode deprecated MavLink message that controls camera.293__mavlink_digicam_control_t packet;294mavlink_msg_digicam_control_decode(&msg, &packet);295control(packet.session, packet.zoom_pos, packet.zoom_step, packet.focus_lock, packet.shot, packet.command_id);296return;297}298299// call each instance300for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {301if (_backends[instance] != nullptr) {302_backends[instance]->handle_message(chan, msg);303}304}305}306307// handle command_long mavlink messages308MAV_RESULT AP_Camera::handle_command(const mavlink_command_int_t &packet)309{310switch (packet.command) {311case MAV_CMD_DO_DIGICAM_CONFIGURE:312configure(packet.param1, packet.param2, packet.param3, packet.param4, packet.x, packet.y, packet.z);313return MAV_RESULT_ACCEPTED;314case MAV_CMD_DO_DIGICAM_CONTROL:315control(packet.param1, packet.param2, packet.param3, packet.param4, packet.x, packet.y);316return MAV_RESULT_ACCEPTED;317case MAV_CMD_DO_SET_CAM_TRIGG_DIST:318set_trigger_distance(packet.param1);319if (is_equal(packet.param3, 1.0f)) {320take_picture();321}322return MAV_RESULT_ACCEPTED;323case MAV_CMD_SET_CAMERA_ZOOM:324if (is_equal(packet.param1, (float)ZOOM_TYPE_CONTINUOUS) &&325set_zoom(ZoomType::RATE, packet.param2)) {326return MAV_RESULT_ACCEPTED;327}328if (is_equal(packet.param1, (float)ZOOM_TYPE_RANGE) &&329set_zoom(ZoomType::PCT, packet.param2)) {330return MAV_RESULT_ACCEPTED;331}332return MAV_RESULT_UNSUPPORTED;333case MAV_CMD_SET_CAMERA_FOCUS:334// accept any of the auto focus types335switch ((SET_FOCUS_TYPE)packet.param1) {336case FOCUS_TYPE_AUTO:337case FOCUS_TYPE_AUTO_SINGLE:338case FOCUS_TYPE_AUTO_CONTINUOUS:339return (MAV_RESULT)set_focus(FocusType::AUTO, 0);340case FOCUS_TYPE_CONTINUOUS:341// accept continuous manual focus342return (MAV_RESULT)set_focus(FocusType::RATE, packet.param2);343// accept focus as percentage344case FOCUS_TYPE_RANGE:345return (MAV_RESULT)set_focus(FocusType::PCT, packet.param2);346case SET_FOCUS_TYPE_ENUM_END:347case FOCUS_TYPE_STEP:348case FOCUS_TYPE_METERS:349// unsupported focus (bad parameter)350break;351}352return MAV_RESULT_DENIED;353354#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED355case MAV_CMD_SET_CAMERA_SOURCE:356// sanity check instance357if (is_negative(packet.param1) || packet.param1 > AP_CAMERA_MAX_INSTANCES) {358return MAV_RESULT_DENIED;359}360if (is_zero(packet.param1)) {361// set camera source for all backends362bool accepted = false;363for (uint8_t i = 0; i < ARRAY_SIZE(_backends); i++) {364if (_backends[i] != nullptr) {365accepted |= set_camera_source(i, (AP_Camera::CameraSource)packet.param2, (AP_Camera::CameraSource)packet.param3);366}367}368return accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED;369}370if (set_camera_source(packet.param1-1, (AP_Camera::CameraSource)packet.param2, (AP_Camera::CameraSource)packet.param3)) {371return MAV_RESULT_ACCEPTED;372}373return MAV_RESULT_DENIED;374#endif375376case MAV_CMD_IMAGE_START_CAPTURE:377// param1 : camera id378// param2 : interval (in seconds)379// param3 : total num images380// sanity check instance381if (is_negative(packet.param1)) {382return MAV_RESULT_UNSUPPORTED;383}384// check if this is a single picture request (e.g. total images is 1 or interval and total images are zero)385if (is_equal(packet.param3, 1.0f) ||386(is_zero(packet.param2) && is_zero(packet.param3))) {387if (is_zero(packet.param1)) {388// take pictures for every backend389return take_picture() ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;390}391// take picture for specified instance392return take_picture(packet.param1-1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;393} else if (is_zero(packet.param3)) {394// multiple picture request, take pictures forever395if (is_zero(packet.param1)) {396// take pictures for every backend397return take_multiple_pictures(packet.param2*1000, -1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;398}399return take_multiple_pictures(packet.param1-1, packet.param2*1000, -1) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;400} else {401// take multiple pictures equal to the number specified in param3402if (is_zero(packet.param1)) {403// take pictures for every backend404return take_multiple_pictures(packet.param2*1000, packet.param3) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;405}406return take_multiple_pictures(packet.param1-1, packet.param2*1000, packet.param3) ? MAV_RESULT_ACCEPTED : MAV_RESULT_FAILED;407}408case MAV_CMD_IMAGE_STOP_CAPTURE:409// param1 : camera id410if (is_negative(packet.param1)) {411return MAV_RESULT_UNSUPPORTED;412}413if (is_zero(packet.param1)) {414// stop capture for every backend415stop_capture();416return MAV_RESULT_ACCEPTED;417}418if (stop_capture(packet.param1-1)) {419return MAV_RESULT_ACCEPTED;420}421return MAV_RESULT_UNSUPPORTED;422case MAV_CMD_CAMERA_TRACK_POINT:423if (set_tracking(TrackingType::TRK_POINT, Vector2f{packet.param1, packet.param2}, Vector2f{})) {424return MAV_RESULT_ACCEPTED;425}426return MAV_RESULT_UNSUPPORTED;427case MAV_CMD_CAMERA_TRACK_RECTANGLE:428if (set_tracking(TrackingType::TRK_RECTANGLE, Vector2f{packet.param1, packet.param2}, Vector2f{packet.param3, packet.param4})) {429return MAV_RESULT_ACCEPTED;430}431return MAV_RESULT_UNSUPPORTED;432case MAV_CMD_CAMERA_STOP_TRACKING:433if (set_tracking(TrackingType::TRK_NONE, Vector2f{}, Vector2f{})) {434return MAV_RESULT_ACCEPTED;435}436return MAV_RESULT_UNSUPPORTED;437case MAV_CMD_VIDEO_START_CAPTURE:438case MAV_CMD_VIDEO_STOP_CAPTURE:439{440bool success = false;441const bool start_recording = (packet.command == MAV_CMD_VIDEO_START_CAPTURE);442const uint8_t stream_id = packet.param1; // Stream ID443if (stream_id == 0) {444// stream id of 0 interpreted as primary camera445success = record_video(start_recording);446} else {447// convert stream id to instance id448success = record_video(stream_id - 1, start_recording);449}450if (success) {451return MAV_RESULT_ACCEPTED;452} else {453return MAV_RESULT_FAILED;454}455}456default:457return MAV_RESULT_UNSUPPORTED;458}459}460461// send a mavlink message; returns false if there was not space to462// send the message, true otherwise463bool AP_Camera::send_mavlink_message(GCS_MAVLINK &link, const enum ap_message msg_id)464{465const auto chan = link.get_chan();466467switch (msg_id) {468case MSG_CAMERA_FEEDBACK:469CHECK_PAYLOAD_SIZE2(CAMERA_FEEDBACK);470send_feedback(chan);471break;472case MSG_CAMERA_INFORMATION:473CHECK_PAYLOAD_SIZE2(CAMERA_INFORMATION);474send_camera_information(chan);475break;476case MSG_CAMERA_SETTINGS:477CHECK_PAYLOAD_SIZE2(CAMERA_SETTINGS);478send_camera_settings(chan);479break;480#if AP_CAMERA_SEND_FOV_STATUS_ENABLED481case MSG_CAMERA_FOV_STATUS:482CHECK_PAYLOAD_SIZE2(CAMERA_FOV_STATUS);483send_camera_fov_status(chan);484break;485#endif486case MSG_CAMERA_CAPTURE_STATUS:487CHECK_PAYLOAD_SIZE2(CAMERA_CAPTURE_STATUS);488send_camera_capture_status(chan);489break;490#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED491case MSG_CAMERA_THERMAL_RANGE:492CHECK_PAYLOAD_SIZE2(CAMERA_THERMAL_RANGE);493send_camera_thermal_range(chan);494break;495#endif496#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED497case MSG_VIDEO_STREAM_INFORMATION:498CHECK_PAYLOAD_SIZE2(VIDEO_STREAM_INFORMATION);499send_video_stream_information(chan);500break;501#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED502503default:504// should not reach this; should only be called for specific IDs505break;506}507508return true;509}510511// set camera trigger distance in a mission512void AP_Camera::set_trigger_distance(uint8_t instance, float distance_m)513{514WITH_SEMAPHORE(_rsem);515516auto *backend = get_instance(instance);517if (backend == nullptr) {518return;519}520521// call backend522backend->set_trigger_distance(distance_m);523}524525// momentary switch to change camera between picture and video modes526void AP_Camera::cam_mode_toggle(uint8_t instance)527{528WITH_SEMAPHORE(_rsem);529530auto *backend = get_instance(instance);531if (backend == nullptr) {532return;533}534535// call backend536backend->cam_mode_toggle();537}538539// configure camera540void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)541{542WITH_SEMAPHORE(_rsem);543544if (primary == nullptr) {545return;546}547primary->configure(shooting_mode, shutter_speed, aperture, ISO, exposure_type, cmd_id, engine_cutoff_time);548}549550void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)551{552WITH_SEMAPHORE(_rsem);553554auto *backend = get_instance(instance);555if (backend == nullptr) {556return;557}558559// call backend560backend->configure(shooting_mode, shutter_speed, aperture, ISO, exposure_type, cmd_id, engine_cutoff_time);561}562563// handle camera control564void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)565{566WITH_SEMAPHORE(_rsem);567568if (primary == nullptr) {569return;570}571primary->control(session, zoom_pos, zoom_step, focus_lock, shooting_cmd, cmd_id);572}573574void AP_Camera::control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)575{576WITH_SEMAPHORE(_rsem);577578auto *backend = get_instance(instance);579if (backend == nullptr) {580return;581}582583// call backend584backend->control(session, zoom_pos, zoom_step, focus_lock, shooting_cmd, cmd_id);585}586587/*588Send camera feedback to the GCS589*/590void AP_Camera::send_feedback(mavlink_channel_t chan)591{592WITH_SEMAPHORE(_rsem);593594// call each instance595for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {596if (_backends[instance] != nullptr) {597_backends[instance]->send_camera_feedback(chan);598}599}600}601602// send camera information message to GCS603void AP_Camera::send_camera_information(mavlink_channel_t chan)604{605WITH_SEMAPHORE(_rsem);606607// call each instance608for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {609if (_backends[instance] != nullptr) {610_backends[instance]->send_camera_information(chan);611}612}613}614615#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED616// send video stream information message to GCS617void AP_Camera::send_video_stream_information(mavlink_channel_t chan)618{619WITH_SEMAPHORE(_rsem);620621// call each instance622for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {623if (_backends[instance] != nullptr) {624_backends[instance]->send_video_stream_information(chan);625}626}627}628#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED629630// send camera settings message to GCS631void AP_Camera::send_camera_settings(mavlink_channel_t chan)632{633WITH_SEMAPHORE(_rsem);634635// call each instance636for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {637if (_backends[instance] != nullptr) {638_backends[instance]->send_camera_settings(chan);639}640}641}642643#if AP_CAMERA_SEND_FOV_STATUS_ENABLED644// send camera field of view status645void AP_Camera::send_camera_fov_status(mavlink_channel_t chan)646{647WITH_SEMAPHORE(_rsem);648649// call each instance650for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {651if (_backends[instance] != nullptr) {652_backends[instance]->send_camera_fov_status(chan);653}654}655}656#endif657658// send camera capture status message to GCS659void AP_Camera::send_camera_capture_status(mavlink_channel_t chan)660{661WITH_SEMAPHORE(_rsem);662663// call each instance664for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {665if (_backends[instance] != nullptr) {666_backends[instance]->send_camera_capture_status(chan);667}668}669}670671#if AP_CAMERA_SEND_THERMAL_RANGE_ENABLED672// send camera thermal range message to GCS673void AP_Camera::send_camera_thermal_range(mavlink_channel_t chan)674{675WITH_SEMAPHORE(_rsem);676677// call each instance678for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {679if (_backends[instance] != nullptr) {680_backends[instance]->send_camera_thermal_range(chan);681}682}683}684#endif685686/*687update; triggers by distance moved and camera trigger688*/689void AP_Camera::update()690{691WITH_SEMAPHORE(_rsem);692693// call each instance694for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {695if (_backends[instance] != nullptr) {696_backends[instance]->update();697}698}699}700701// start/stop recording video. returns true on success702// start_recording should be true to start recording, false to stop recording703bool AP_Camera::record_video(uint8_t instance, bool start_recording)704{705WITH_SEMAPHORE(_rsem);706707auto *backend = get_instance(instance);708if (backend == nullptr) {709return false;710}711712// call backend713return backend->record_video(start_recording);714}715716// zoom specified as a rate or percentage717bool AP_Camera::set_zoom(ZoomType zoom_type, float zoom_value)718{719WITH_SEMAPHORE(_rsem);720721if (primary == nullptr) {722return false;723}724return primary->set_zoom(zoom_type, zoom_value);725}726727// zoom specified as a rate or percentage728bool AP_Camera::set_zoom(uint8_t instance, ZoomType zoom_type, float zoom_value)729{730WITH_SEMAPHORE(_rsem);731732auto *backend = get_instance(instance);733if (backend == nullptr) {734return false;735}736737// call each instance738return backend->set_zoom(zoom_type, zoom_value);739}740741742// set focus specified as rate, percentage or auto743// focus in = -1, focus hold = 0, focus out = 1744SetFocusResult AP_Camera::set_focus(FocusType focus_type, float focus_value)745{746WITH_SEMAPHORE(_rsem);747748if (primary == nullptr) {749return SetFocusResult::FAILED;750}751return primary->set_focus(focus_type, focus_value);752}753754// set focus specified as rate, percentage or auto755// focus in = -1, focus hold = 0, focus out = 1756SetFocusResult AP_Camera::set_focus(uint8_t instance, FocusType focus_type, float focus_value)757{758WITH_SEMAPHORE(_rsem);759760auto *backend = get_instance(instance);761if (backend == nullptr) {762return SetFocusResult::FAILED;763}764765// call each instance766return backend->set_focus(focus_type, focus_value);767}768769// set tracking to none, point or rectangle (see TrackingType enum)770// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right771// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom772bool AP_Camera::set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)773{774WITH_SEMAPHORE(_rsem);775776if (primary == nullptr) {777return false;778}779return primary->set_tracking(tracking_type, p1, p2);780}781782// set tracking to none, point or rectangle (see TrackingType enum)783// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right784// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom785bool AP_Camera::set_tracking(uint8_t instance, TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)786{787WITH_SEMAPHORE(_rsem);788789auto *backend = get_instance(instance);790if (backend == nullptr) {791return false;792}793794// call each instance795return backend->set_tracking(tracking_type, p1, p2);796}797798#if AP_CAMERA_SET_CAMERA_SOURCE_ENABLED799// set camera lens as a value from 0 to 5800bool AP_Camera::set_lens(uint8_t lens)801{802WITH_SEMAPHORE(_rsem);803804if (primary == nullptr) {805return false;806}807return primary->set_lens(lens);808}809810bool AP_Camera::set_lens(uint8_t instance, uint8_t lens)811{812WITH_SEMAPHORE(_rsem);813814auto *backend = get_instance(instance);815if (backend == nullptr) {816return false;817}818819// call instance820return backend->set_lens(lens);821}822823// set_camera_source is functionally the same as set_lens except primary and secondary lenses are specified by type824bool AP_Camera::set_camera_source(uint8_t instance, CameraSource primary_source, CameraSource secondary_source)825{826WITH_SEMAPHORE(_rsem);827828auto *backend = get_instance(instance);829if (backend == nullptr) {830return false;831}832833// call instance834return backend->set_camera_source(primary_source, secondary_source);835}836#endif // AP_CAMERA_SET_CAMERA_SOURCE_ENABLED837838#if AP_CAMERA_SCRIPTING_ENABLED839// accessor to allow scripting backend to retrieve state840// returns true on success and cam_state is filled in841bool AP_Camera::get_state(uint8_t instance, camera_state_t& cam_state)842{843WITH_SEMAPHORE(_rsem);844845auto *backend = get_instance(instance);846if (backend == nullptr) {847return false;848}849return backend->get_state(cam_state);850}851852// change camera settings not normally used by autopilot853bool AP_Camera::change_setting(uint8_t instance, CameraSetting setting, float value)854{855WITH_SEMAPHORE(_rsem);856857auto *backend = get_instance(instance);858if (backend == nullptr) {859return false;860}861return backend->change_setting(setting, value);862}863864#endif // #if AP_CAMERA_SCRIPTING_ENABLED865866867#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED868void AP_Camera::set_camera_information(mavlink_camera_information_t camera_info)869{870WITH_SEMAPHORE(_rsem);871872if (primary == nullptr) {873return;874}875return primary->set_camera_information(camera_info);876}877878void AP_Camera::set_camera_information(uint8_t instance, mavlink_camera_information_t camera_info)879{880WITH_SEMAPHORE(_rsem);881882auto *backend = get_instance(instance);883if (backend == nullptr) {884return;885}886887// call instance888backend->set_camera_information(camera_info);889}890891void AP_Camera::set_stream_information(mavlink_video_stream_information_t stream_info)892{893WITH_SEMAPHORE(_rsem);894895if (primary == nullptr) {896return;897}898return primary->set_stream_information(stream_info);899}900901void AP_Camera::set_stream_information(uint8_t instance, mavlink_video_stream_information_t stream_info)902{903WITH_SEMAPHORE(_rsem);904905auto *backend = get_instance(instance);906if (backend == nullptr) {907return;908}909910// call instance911backend->set_stream_information(stream_info);912}913#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED914915// return backend for instance number916AP_Camera_Backend *AP_Camera::get_instance(uint8_t instance) const917{918if (instance >= ARRAY_SIZE(_backends)) {919return nullptr;920}921return _backends[instance];922}923924// perform any required parameter conversion925void AP_Camera::convert_params()926{927// exit immediately if CAM1_TYPE has already been configured928if (_params[0].type.configured()929#if AP_CAMERA_RUNCAM_ENABLED930&& _params[1].type.configured()931#endif932) {933return;934}935936// PARAMETER_CONVERSION - Added: Feb-2023 ahead of 4.4 release937938// convert CAM_TRIGG_TYPE to CAM1_TYPE939int8_t cam_trigg_type = 0;940int8_t cam1_type = 0;941IGNORE_RETURN(AP_Param::get_param_by_index(this, 0, AP_PARAM_INT8, &cam_trigg_type));942if ((cam_trigg_type == 0) && SRV_Channels::function_assigned(SRV_Channel::k_cam_trigger)) {943// CAM_TRIGG_TYPE was 0 (Servo) and camera trigger servo function was assigned so set CAM1_TYPE = 1 (Servo)944cam1_type = 1;945}946if ((cam_trigg_type >= 1) && (cam_trigg_type <= 3)) {947// CAM_TRIGG_TYPE was set to Relay, GoPro or Mount948cam1_type = cam_trigg_type + 1;949}950_params[0].type.set_and_save(cam1_type);951952#if AP_CAMERA_RUNCAM_ENABLED953// RunCam PARAMETER_CONVERSION - Added: Nov-2024 ahead of 4.7 release954955// Since slot 1 is essentially used by the trigger type, we will use slot 2 for runcam956int8_t rc_type = 0;957// find vehicle's top level key958uint16_t k_param_vehicle_key;959if (!AP_Param::find_top_level_key_by_pointer(AP::vehicle(), k_param_vehicle_key)) {960return;961}962963// RunCam protocol configured so set cam type to RunCam964bool rc_protocol_configured = false;965AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();966if (serial_manager && serial_manager->find_serial(AP_SerialManager::SerialProtocol_RunCam, 0)) {967rc_protocol_configured = true;968}969970const AP_Param::ConversionInfo rc_type_info = {971k_param_vehicle_key, AP_GROUP_ELEM_IDX(1, 1), AP_PARAM_INT8, "CAM_RC_TYPE"972};973AP_Int8 rc_type_old;974const bool found_rc_type = AP_Param::find_old_parameter(&rc_type_info, &rc_type_old);975976if (rc_protocol_configured || (found_rc_type && rc_type_old.get() > 0)) {977rc_type = int8_t(CameraType::RUNCAM);978_backends[1] = NEW_NOTHROW AP_RunCam(*this, _params[1], 1, _runcam_instances);979_backend_var_info[1] = AP_RunCam::var_info;980AP_Param::convert_class(k_param_vehicle_key, &_backends[1], _backend_var_info[1], 1, false);981AP_Param::invalidate_count();982_runcam_instances++;983}984985_params[1].type.set_and_save(rc_type);986#endif // AP_CAMERA_RUNCAM_ENABLED987988// convert CAM_DURATION (in deci-seconds) to CAM1_DURATION (in seconds)989int8_t cam_duration = 0;990if (AP_Param::get_param_by_index(this, 1, AP_PARAM_INT8, &cam_duration) && (cam_duration > 0)) {991_params[0].trigger_duration.set_and_save(cam_duration * 0.1);992}993994// convert CAM_MIN_INTERVAL (in milliseconds) to CAM1__INTRVAL_MIN (in seconds)995int16_t cam_min_interval = 0;996if (AP_Param::get_param_by_index(this, 6, AP_PARAM_INT16, &cam_min_interval) && (cam_min_interval > 0)) {997_params[0].interval_min.set_and_save(cam_min_interval * 0.001f);998}9991000// find Camera's top level key1001uint16_t k_param_camera_key;1002if (!AP_Param::find_top_level_key_by_pointer(this, k_param_camera_key)) {1003return;1004}10051006// table parameters to convert without scaling1007static const AP_Param::ConversionInfo camera_param_conversion_info[] {1008{ k_param_camera_key, 2, AP_PARAM_INT16, "CAM1_SERVO_ON" },1009{ k_param_camera_key, 3, AP_PARAM_INT16, "CAM1_SERVO_OFF" },1010{ k_param_camera_key, 4, AP_PARAM_FLOAT, "CAM1_TRIGG_DIST" },1011{ k_param_camera_key, 5, AP_PARAM_INT8, "CAM1_RELAY_ON" },1012{ k_param_camera_key, 8, AP_PARAM_INT8, "CAM1_FEEDBAK_PIN" },1013{ k_param_camera_key, 9, AP_PARAM_INT8, "CAM1_FEEDBAK_POL" },1014};1015uint8_t table_size = ARRAY_SIZE(camera_param_conversion_info);1016for (uint8_t i=0; i<table_size; i++) {1017AP_Param::convert_old_parameter(&camera_param_conversion_info[i], 1.0f);1018}1019}10201021#if AP_RELAY_ENABLED1022// Return true and the relay index if relay camera backend is selected, used for conversion to relay functions1023bool AP_Camera::get_legacy_relay_index(int8_t &index) const1024{1025// PARAMETER_CONVERSION - Added: Dec-202310261027// Note that this assumes that the camera param conversion has already been done1028// Copter, Plane, Sub and Rover all have both relay and camera and all init relay first1029// This will only be a issue if the relay and camera conversion were done at once, if the user skipped 4.41030for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) {1031#if AP_CAMERA_RELAY_ENABLED1032if ((CameraType)_params[i].type.get() == CameraType::RELAY) {1033// Camera was hard coded to relay 01034index = 0;1035return true;1036}1037#endif1038}1039return false;1040}1041#endif10421043// singleton instance1044AP_Camera *AP_Camera::_singleton;10451046namespace AP {10471048AP_Camera *camera()1049{1050return AP_Camera::get_singleton();1051}10521053}10541055#endif105610571058