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_Backend.cpp
Views: 1798
#include "AP_Camera_config.h"12#if AP_CAMERA_ENABLED34#include "AP_Camera_Backend.h"56#include <GCS_MAVLink/GCS.h>7#include <AP_GPS/AP_GPS.h>8#include <AP_Mount/AP_Mount.h>9#include <AP_AHRS/AP_AHRS.h>1011extern const AP_HAL::HAL& hal;1213// Constructor14AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params ¶ms, uint8_t instance) :15_frontend(frontend),16_params(params),17_instance(instance)18{}1920void AP_Camera_Backend::init()21{22#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED23_camera_info.focal_length = NaNf;24_camera_info.sensor_size_h = NaNf;25_camera_info.sensor_size_v = NaNf;2627_camera_info.flags = CAMERA_CAP_FLAGS_CAPTURE_IMAGE;28#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED29}3031// update - should be called at 50hz32void AP_Camera_Backend::update()33{34// Check camera options and start/stop recording based on arm/disarm35if (option_is_enabled(Option::RecordWhileArmed)) {36if (hal.util->get_soft_armed() != last_is_armed) {37last_is_armed = hal.util->get_soft_armed();38if (!record_video(last_is_armed)) {39GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Camera: failed to %s recording", last_is_armed ? "start" : "stop");40}41}42}4344// try to take picture if pending45if (trigger_pending) {46take_picture();47}4849// check feedback pin50check_feedback();5152// time based triggering53// if time and distance triggering both are enabled then we only do time based triggering54if (time_interval_settings.num_remaining != 0) {55uint32_t delta_ms = AP_HAL::millis() - last_picture_time_ms;56if (delta_ms > time_interval_settings.time_interval_ms) {57if (take_picture()) {58// decrease num_remaining except when its -1 i.e. capture forever59if (time_interval_settings.num_remaining > 0) {60time_interval_settings.num_remaining--;61}62}63}64return;65}6667// implement trigger distance68if (!is_positive(_params.trigg_dist)) {69last_location.lat = 0;70last_location.lng = 0;71return;72}7374const AP_AHRS &ahrs = AP::ahrs();7576Location current_loc;77if (!ahrs.get_location(current_loc)) {78return;79}8081// check vehicle flight mode supports trigg dist82if (!_frontend.vehicle_mode_ok_for_trigg_dist()) {83return;84}8586// check vehicle roll angle is less than configured maximum87if ((_frontend.get_roll_max() > 0) && (fabsf(ahrs.roll_sensor * 1e-2f) > _frontend.get_roll_max())) {88return;89}9091// initialise last location to current location92if (last_location.lat == 0 && last_location.lng == 0) {93last_location = current_loc;94return;95}96if (last_location.lat == current_loc.lat && last_location.lng == current_loc.lng) {97// we haven't moved - this can happen as update() may98// be called without a new GPS fix99return;100}101102// check vehicle has moved at least trigg_dist meters103if (current_loc.get_distance(last_location) < _params.trigg_dist) {104return;105}106107take_picture();108}109110// get corresponding mount instance for the camera111uint8_t AP_Camera_Backend::get_mount_instance() const112{113// instance 0 means default114if (_params.mount_instance.get() == 0) {115return _instance;116}117return _params.mount_instance.get() - 1;118}119120// get mavlink gimbal device id which is normally mount_instance+1121uint8_t AP_Camera_Backend::get_gimbal_device_id() const122{123#if HAL_MOUNT_ENABLED124const uint8_t mount_instance = get_mount_instance();125AP_Mount* mount = AP::mount();126if (mount != nullptr) {127if (mount->get_mount_type(mount_instance) != AP_Mount::Type::None) {128return (mount_instance + 1);129}130}131#endif132return 0;133}134135136// take a picture. returns true on success137bool AP_Camera_Backend::take_picture()138{139// setup feedback pin interrupt or timer140setup_feedback_callback();141142// check minimum time interval since last picture taken143uint32_t now_ms = AP_HAL::millis();144if (now_ms - last_picture_time_ms < (uint32_t)(_params.interval_min * 1000)) {145trigger_pending = true;146return false;147}148149trigger_pending = false;150151// trigger actually taking picture and update image count152if (trigger_pic()) {153image_index++;154last_picture_time_ms = now_ms;155IGNORE_RETURN(AP::ahrs().get_location(last_location));156#if HAL_LOGGING_ENABLED157log_picture();158#endif159return true;160}161162return false;163}164165// take multiple pictures, time_interval between two consecutive pictures is in miliseconds166// total_num is number of pictures to be taken, -1 means capture forever167void AP_Camera_Backend::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num)168{169time_interval_settings = {time_interval_ms, total_num};170}171172// stop capturing multiple image sequence173void AP_Camera_Backend::stop_capture()174{175time_interval_settings = {0, 0};176}177178// handle camera control179void AP_Camera_Backend::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)180{181// take picture182if (shooting_cmd == 1) {183take_picture();184}185}186187// send camera feedback message to GCS188void AP_Camera_Backend::send_camera_feedback(mavlink_channel_t chan)189{190int32_t altitude = 0;191if (camera_feedback.location.initialised() && !camera_feedback.location.get_alt_cm(Location::AltFrame::ABSOLUTE, altitude)) {192// completely ignore this failure! this is a shouldn't-happen193// as current_loc should never be in an altitude we can't194// convert.195}196int32_t altitude_rel = 0;197if (camera_feedback.location.initialised() && !camera_feedback.location.get_alt_cm(Location::AltFrame::ABOVE_HOME, altitude_rel)) {198// completely ignore this failure! this is a shouldn't-happen199// as current_loc should never be in an altitude we can't200// convert.201}202203// send camera feedback message204mavlink_msg_camera_feedback_send(205chan,206camera_feedback.timestamp_us, // image timestamp2070, // target system id208_instance, // camera id209image_index, // image index210camera_feedback.location.lat, // latitude211camera_feedback.location.lng, // longitude212altitude*1e-2f, // alt MSL213altitude_rel*1e-2f, // alt relative to home214camera_feedback.roll_sensor*1e-2f, // roll angle (deg)215camera_feedback.pitch_sensor*1e-2f, // pitch angle (deg)216camera_feedback.yaw_sensor*1e-2f, // yaw angle (deg)2170.0f, // focal length218CAMERA_FEEDBACK_PHOTO, // flags219camera_feedback.feedback_trigger_logged_count); // completed image captures220}221222// send camera information message to GCS223void AP_Camera_Backend::send_camera_information(mavlink_channel_t chan) const224{225mavlink_camera_information_t camera_info;226#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED227228camera_info = _camera_info;229230#else231232memset(&camera_info, 0, sizeof(camera_info));233234camera_info.focal_length = NaNf;235camera_info.sensor_size_h = NaNf;236camera_info.sensor_size_v = NaNf;237238camera_info.flags = CAMERA_CAP_FLAGS_CAPTURE_IMAGE;239240#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED241242// Set fixed fields243// lens_id is populated with the instance number, to disambiguate multiple cameras244camera_info.lens_id = _instance;245camera_info.gimbal_device_id = get_gimbal_device_id();246camera_info.time_boot_ms = AP_HAL::millis();247248// Send CAMERA_INFORMATION message249mavlink_msg_camera_information_send_struct(chan, &camera_info);250}251252#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED253void AP_Camera_Backend::set_camera_information(mavlink_camera_information_t camera_info)254{255GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Camera %u CAMERA_INFORMATION (%s %s) set from script", _instance, camera_info.vendor_name, camera_info.model_name);256_camera_info = camera_info;257};258#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED259260#if AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED261// send video stream information message to GCS262void AP_Camera_Backend::send_video_stream_information(mavlink_channel_t chan) const263{264#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED265266// Send VIDEO_STREAM_INFORMATION message267mavlink_msg_video_stream_information_send_struct(chan, &_stream_info);268269#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED270}271#endif // AP_MAVLINK_MSG_VIDEO_STREAM_INFORMATION_ENABLED272273#if AP_CAMERA_INFO_FROM_SCRIPT_ENABLED274void AP_Camera_Backend::set_stream_information(mavlink_video_stream_information_t stream_info)275{276_stream_info = stream_info;277};278#endif // AP_CAMERA_INFO_FROM_SCRIPT_ENABLED279280// send camera settings message to GCS281void AP_Camera_Backend::send_camera_settings(mavlink_channel_t chan) const282{283// send CAMERA_SETTINGS message284mavlink_msg_camera_settings_send(285chan,286AP_HAL::millis(), // time_boot_ms287CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey)288NaNf, // zoomLevel float, percentage from 0 to 100, NaN if unknown289NaNf); // focusLevel float, percentage from 0 to 100, NaN if unknown290}291292#if AP_CAMERA_SEND_FOV_STATUS_ENABLED293// send camera field of view status294void AP_Camera_Backend::send_camera_fov_status(mavlink_channel_t chan) const295{296// getting corresponding mount instance for camera297AP_Mount* mount = AP::mount();298if (mount == nullptr) {299return;300}301302// get latest POI from mount303Quaternion quat;304Location camera_loc;305Location poi_loc;306const bool have_poi_loc = mount->get_poi(get_mount_instance(), quat, camera_loc, poi_loc);307308// if failed to get POI, get camera location directly from AHRS309// and attitude directly from mount310bool have_camera_loc = have_poi_loc;311if (!have_camera_loc) {312have_camera_loc = AP::ahrs().get_location(camera_loc);313mount->get_attitude_quaternion(get_mount_instance(), quat);314}315316// calculate attitude quaternion in earth frame using AHRS yaw317Quaternion quat_ef;318quat_ef.from_euler(0, 0, AP::ahrs().get_yaw());319quat_ef *= quat;320321// send camera fov status message only if the last calculated values aren't stale322const float quat_array[4] = {323quat_ef.q1,324quat_ef.q2,325quat_ef.q3,326quat_ef.q4327};328mavlink_msg_camera_fov_status_send(329chan,330AP_HAL::millis(),331have_camera_loc ? camera_loc.lat : INT32_MAX,332have_camera_loc ? camera_loc.lng : INT32_MAX,333have_camera_loc ? camera_loc.alt * 10 : INT32_MAX,334have_poi_loc ? poi_loc.lat : INT32_MAX,335have_poi_loc ? poi_loc.lng : INT32_MAX,336have_poi_loc ? poi_loc.alt * 10 : INT32_MAX,337quat_array,338horizontal_fov() > 0 ? horizontal_fov() : NaNf,339vertical_fov() > 0 ? vertical_fov() : NaNf340);341}342#endif343344// send camera capture status message to GCS345void AP_Camera_Backend::send_camera_capture_status(mavlink_channel_t chan) const346{347// Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)348const uint8_t image_status = (time_interval_settings.num_remaining > 0) ? 2 : 0;349350// send CAMERA_CAPTURE_STATUS message351mavlink_msg_camera_capture_status_send(352chan,353AP_HAL::millis(),354image_status,3550, // current status of video capturing (0: idle, 1: capture in progress)356static_cast<float>(time_interval_settings.time_interval_ms) / 1000.0, // image capture interval (s)3570, // elapsed time since recording started (ms)358NaNf, // available storage capacity (ms)359image_index); // total number of images captured360}361362// setup a callback for a feedback pin. When on PX4 with the right FMU363// mode we can use the microsecond timer.364void AP_Camera_Backend::setup_feedback_callback()365{366if (_params.feedback_pin <= 0 || timer_installed || isr_installed) {367// invalid or already installed368return;369}370371// ensure we are in input mode372hal.gpio->pinMode(_params.feedback_pin, HAL_GPIO_INPUT);373374// enable pullup/pulldown375uint8_t trigger_polarity = _params.feedback_polarity == 0 ? 0 : 1;376hal.gpio->write(_params.feedback_pin, !trigger_polarity);377378if (hal.gpio->attach_interrupt(_params.feedback_pin, FUNCTOR_BIND_MEMBER(&AP_Camera_Backend::feedback_pin_isr, void, uint8_t, bool, uint32_t),379trigger_polarity?AP_HAL::GPIO::INTERRUPT_RISING:AP_HAL::GPIO::INTERRUPT_FALLING)) {380isr_installed = true;381} else {382// install a 1kHz timer to check feedback pin383hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Camera_Backend::feedback_pin_timer, void));384385timer_installed = true;386}387}388389// interrupt handler for interrupt based feedback trigger390void AP_Camera_Backend::feedback_pin_isr(uint8_t pin, bool high, uint32_t timestamp_us)391{392feedback_trigger_timestamp_us = timestamp_us;393feedback_trigger_count++;394}395396// check if feedback pin is high for timer based feedback trigger, when397// attach_interrupt fails398void AP_Camera_Backend::feedback_pin_timer()399{400uint8_t pin_state = hal.gpio->read(_params.feedback_pin);401uint8_t trigger_polarity = _params.feedback_polarity == 0 ? 0 : 1;402if (pin_state == trigger_polarity &&403last_pin_state != trigger_polarity) {404feedback_trigger_timestamp_us = AP_HAL::micros();405feedback_trigger_count++;406}407last_pin_state = pin_state;408}409410// check for feedback pin update and log if necessary411void AP_Camera_Backend::check_feedback()412{413if (feedback_trigger_logged_count != feedback_trigger_count) {414#if HAL_LOGGING_ENABLED415const uint32_t timestamp32 = feedback_trigger_timestamp_us;416#endif417feedback_trigger_logged_count = feedback_trigger_count;418419// we should consider doing this inside the ISR and pin_timer420prep_mavlink_msg_camera_feedback(feedback_trigger_timestamp_us);421422#if HAL_LOGGING_ENABLED423// log camera message424uint32_t tdiff = AP_HAL::micros() - timestamp32;425uint64_t timestamp = AP_HAL::micros64();426Write_Camera(timestamp - tdiff);427#endif428}429}430431void AP_Camera_Backend::prep_mavlink_msg_camera_feedback(uint64_t timestamp_us)432{433const AP_AHRS &ahrs = AP::ahrs();434if (!ahrs.get_location(camera_feedback.location)) {435// completely ignore this failure! AHRS will provide its best guess.436}437camera_feedback.timestamp_us = timestamp_us;438camera_feedback.roll_sensor = ahrs.roll_sensor;439camera_feedback.pitch_sensor = ahrs.pitch_sensor;440camera_feedback.yaw_sensor = ahrs.yaw_sensor;441camera_feedback.feedback_trigger_logged_count = feedback_trigger_logged_count;442443GCS_SEND_MESSAGE(MSG_CAMERA_FEEDBACK);444}445446#if HAL_LOGGING_ENABLED447// log picture448void AP_Camera_Backend::log_picture()449{450const bool using_feedback_pin = _params.feedback_pin > 0;451452if (!using_feedback_pin) {453// if we're using a feedback pin then when the event occurs we454// stash the feedback data. Since we're not using a feedback455// pin, we just use "now".456prep_mavlink_msg_camera_feedback(AP::gps().time_epoch_usec());457}458459if (!using_feedback_pin) {460Write_Camera();461} else {462Write_Trigger();463}464}465#endif466467#endif // AP_CAMERA_ENABLED468469470