Path: blob/master/libraries/AP_Camera/AP_Camera_Logging.cpp
9373 views
#include "AP_Camera_Backend.h"1#include <AP_Mount/AP_Mount.h>2#include <AP_Logger/AP_Logger_config.h>34#if AP_CAMERA_ENABLED && HAL_LOGGING_ENABLED56#include <AP_Logger/AP_Logger.h>7#include <AP_GPS/AP_GPS.h>8#include <AP_AHRS/AP_AHRS.h>910// Write a Camera packet. Also writes a Mount packet if available11void AP_Camera_Backend::Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us)12{13// exit immediately if no logger14AP_Logger *logger = AP_Logger::get_singleton();15if (logger == nullptr) {16return;17}1819// exit immediately if should not log camera messages20if (!logger->should_log(_frontend.get_log_camera_bit())) {21return;22}2324const AP_AHRS &ahrs = AP::ahrs();2526Location current_loc;27if (!ahrs.get_location(current_loc)) {28// completely ignore this failure! AHRS will provide its best guess.29}3031int32_t altitude_cm = 0;32int32_t altitude_rel_cm = 0;33if (current_loc.initialised()) {34// ignore failures to get altitude35IGNORE_RETURN(current_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, altitude_cm));36IGNORE_RETURN(current_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, altitude_rel_cm));37}3839int32_t altitude_gps_cm = 0;40const AP_GPS &gps = AP::gps();41if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {42if (!gps.location().get_alt_cm(Location::AltFrame::ABSOLUTE, altitude_gps_cm)) {43// ignore this problem...44}45}4647// if timestamp is zero set to current system time48if (timestamp_us == 0) {49timestamp_us = AP_HAL::micros64();50}5152const struct log_Camera pkt{53LOG_PACKET_HEADER_INIT(static_cast<uint8_t>(msg)),54time_us : timestamp_us,55instance : _instance,56image_number: image_index,57gps_time : gps.time_week_ms(),58gps_week : gps.time_week(),59latitude : current_loc.lat,60longitude : current_loc.lng,61altitude : altitude_cm,62altitude_rel: altitude_rel_cm,63altitude_gps: altitude_gps_cm,64roll : ahrs.get_roll_deg(),65pitch : ahrs.get_pitch_deg(),66yaw : ahrs.get_yaw_deg()67};68AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));6970#if HAL_MOUNT_ENABLED71auto *mount = AP_Mount::get_singleton();72if (mount!= nullptr) {73mount->write_log(get_mount_instance(), timestamp_us);74}75#endif76}7778// Write a Camera packet79void AP_Camera_Backend::Write_Camera(uint64_t timestamp_us)80{81Write_CameraInfo(LOG_CAMERA_MSG, timestamp_us);82}8384// Write a Trigger packet85void AP_Camera_Backend::Write_Trigger()86{87Write_CameraInfo(LOG_TRIGGER_MSG, 0);88}8990#endif // AP_CAMERA_ENABLED && HAL_LOGGING_ENABLED919293