Navigation Menu

Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Privatizes AP_Camera logging #16458

Merged
merged 2 commits into from Feb 1, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
6 changes: 3 additions & 3 deletions libraries/AP_Camera/AP_Camera.cpp
Expand Up @@ -461,9 +461,9 @@ void AP_Camera::log_picture()
}

if (!using_feedback_pin()) {
logger->Write_Camera(current_loc);
Write_Camera();
} else {
logger->Write_Trigger(current_loc);
Write_Trigger();
}
}

Expand Down Expand Up @@ -499,7 +499,7 @@ void AP_Camera::update_trigger()
if (logger->should_log(log_camera_bit)) {
uint32_t tdiff = AP_HAL::micros() - timestamp32;
uint64_t timestamp = AP_HAL::micros64();
logger->Write_Camera(current_loc, timestamp - tdiff);
Write_Camera(timestamp - tdiff);
}
}
}
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_Camera/AP_Camera.h
Expand Up @@ -4,6 +4,7 @@

#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_Logger/AP_Logger.h>

#define AP_CAMERA_TRIGGER_DEFAULT_DURATION 10 // default duration servo or relay is held open in 10ths of a second (i.e. 10 = 1 second)

Expand Down Expand Up @@ -123,6 +124,11 @@ class AP_Camera {

void log_picture();

// Logging Function
void Write_Camera(uint64_t timestamp_us=0);
void Write_Trigger(void);
void Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us=0);

uint32_t log_camera_bit;
const struct Location &current_loc;

Expand Down
51 changes: 51 additions & 0 deletions libraries/AP_Camera/AP_Camera_Logging.cpp
@@ -0,0 +1,51 @@
#include "AP_Camera.h"
#include <AP_Logger/AP_Logger.h>

// Write a Camera packet
void AP_Camera::Write_CameraInfo(enum LogMessages msg, uint64_t timestamp_us)
{
const AP_AHRS &ahrs = AP::ahrs();

int32_t altitude, altitude_rel, altitude_gps;
if (current_loc.relative_alt) {
altitude = current_loc.alt+ahrs.get_home().alt;
altitude_rel = current_loc.alt;
} else {
altitude = current_loc.alt;
altitude_rel = current_loc.alt - ahrs.get_home().alt;
}
const AP_GPS &gps = AP::gps();
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
altitude_gps = gps.location().alt;
} else {
altitude_gps = 0;
}

const struct log_Camera pkt{
LOG_PACKET_HEADER_INIT(static_cast<uint8_t>(msg)),
time_us : timestamp_us?timestamp_us:AP_HAL::micros64(),
gps_time : gps.time_week_ms(),
gps_week : gps.time_week(),
latitude : current_loc.lat,
longitude : current_loc.lng,
altitude : altitude,
altitude_rel: altitude_rel,
altitude_gps: altitude_gps,
roll : (int16_t)ahrs.roll_sensor,
pitch : (int16_t)ahrs.pitch_sensor,
yaw : (uint16_t)ahrs.yaw_sensor
};
AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
}

// Write a Camera packet
void AP_Camera::Write_Camera(uint64_t timestamp_us)
{
Write_CameraInfo(LOG_CAMERA_MSG, timestamp_us);
}

// Write a Trigger packet
void AP_Camera::Write_Trigger(void)
{
Write_CameraInfo(LOG_TRIGGER_MSG, 0);
}
41 changes: 41 additions & 0 deletions libraries/AP_Camera/LogStructure.h
@@ -0,0 +1,41 @@
#pragma once

#include <AP_Logger/LogStructure.h>

#define LOG_IDS_FROM_CAMERA \
LOG_CAMERA_MSG, \
LOG_TRIGGER_MSG

// @LoggerMessage: CAM,TRIG
// @Description: Camera shutter information
// @Field: TimeUS: Time since system startup
// @Field: GPSTime: milliseconds since start of GPS week
// @Field: GPSWeek: weeks since 5 Jan 1980
// @Field: Lat: current latitude
// @Field: Lng: current longitude
// @Field: Alt: current altitude
// @Field: RelAlt: current altitude relative to home
// @Field: GPSAlt: altitude as reported by GPS
// @Field: Roll: current vehicle roll
// @Field: Pitch: current vehicle pitch
// @Field: Yaw: current vehicle yaw
struct PACKED log_Camera {
LOG_PACKET_HEADER;
uint64_t time_us;
uint32_t gps_time;
uint16_t gps_week;
int32_t latitude;
int32_t longitude;
int32_t altitude;
int32_t altitude_rel;
int32_t altitude_gps;
int16_t roll;
int16_t pitch;
uint16_t yaw;
};

#define LOG_STRUCTURE_FROM_CAMERA \
{ LOG_CAMERA_MSG, sizeof(log_Camera), \
"CAM", "QIHLLeeeccC","TimeUS,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,GPSAlt,Roll,Pitch,Yaw", "s--DUmmmddd", "F--GGBBBBBB" }, \
{ LOG_TRIGGER_MSG, sizeof(log_Camera), \
"TRIG", "QIHLLeeeccC","TimeUS,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,GPSAlt,Roll,Pitch,Yaw", "s--DUmmmddd", "F--GGBBBBBB" },
3 changes: 0 additions & 3 deletions libraries/AP_Logger/AP_Logger.h
Expand Up @@ -314,9 +314,6 @@ class AP_Logger
void Write_Radio(const mavlink_radio_t &packet);
void Write_Message(const char *message);
void Write_MessageF(const char *fmt, ...);
void Write_CameraInfo(enum LogMessages msg, const Location &current_loc, uint64_t timestamp_us=0);
void Write_Camera(const Location &current_loc, uint64_t timestamp_us=0);
void Write_Trigger(const Location &current_loc);
void Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t esc_temp, uint16_t current_tot, int16_t motor_temp, float error_rate = 0.0f);
void Write_ServoStatus(uint64_t time_us, uint8_t id, float position, float force, float speed, uint8_t power_pct);
void Write_ESCStatus(uint64_t time_us, uint8_t id, uint32_t error_count, float voltage, float current, float temperature, int32_t rpm, uint8_t power_pct);
Expand Down
49 changes: 0 additions & 49 deletions libraries/AP_Logger/LogFile.cpp
Expand Up @@ -459,55 +459,6 @@ void AP_Logger::Write_Radio(const mavlink_radio_t &packet)
WriteBlock(&pkt, sizeof(pkt));
}

// Write a Camera packet
void AP_Logger::Write_CameraInfo(enum LogMessages msg, const Location &current_loc, uint64_t timestamp_us)
{
const AP_AHRS &ahrs = AP::ahrs();

int32_t altitude, altitude_rel, altitude_gps;
if (current_loc.relative_alt) {
altitude = current_loc.alt+ahrs.get_home().alt;
altitude_rel = current_loc.alt;
} else {
altitude = current_loc.alt;
altitude_rel = current_loc.alt - ahrs.get_home().alt;
}
const AP_GPS &gps = AP::gps();
if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
altitude_gps = gps.location().alt;
} else {
altitude_gps = 0;
}

const struct log_Camera pkt{
LOG_PACKET_HEADER_INIT(static_cast<uint8_t>(msg)),
time_us : timestamp_us?timestamp_us:AP_HAL::micros64(),
gps_time : gps.time_week_ms(),
gps_week : gps.time_week(),
latitude : current_loc.lat,
longitude : current_loc.lng,
altitude : altitude,
altitude_rel: altitude_rel,
altitude_gps: altitude_gps,
roll : (int16_t)ahrs.roll_sensor,
pitch : (int16_t)ahrs.pitch_sensor,
yaw : (uint16_t)ahrs.yaw_sensor
};
WriteCriticalBlock(&pkt, sizeof(pkt));
}

// Write a Camera packet
void AP_Logger::Write_Camera(const Location &current_loc, uint64_t timestamp_us)
{
Write_CameraInfo(LOG_CAMERA_MSG, current_loc, timestamp_us);
}

// Write a Trigger packet
void AP_Logger::Write_Trigger(const Location &current_loc)
{
Write_CameraInfo(LOG_TRIGGER_MSG, current_loc, 0);
}

void AP_Logger::Write_Compass_instance(const uint64_t time_us, const uint8_t mag_instance)
{
const Compass &compass = AP::compass();
Expand Down
38 changes: 3 additions & 35 deletions libraries/AP_Logger/LogStructure.h
Expand Up @@ -123,6 +123,7 @@ const struct MultiplierStructure log_Multipliers[] = {
#include <AP_BattMonitor/LogStructure.h>

#include <AP_AHRS/LogStructure.h>
#include <AP_Camera/LogStructure.h>

// structure used to define logging format
struct LogStructure {
Expand Down Expand Up @@ -480,21 +481,6 @@ struct PACKED log_Radio {
uint16_t fixed;
};

struct PACKED log_Camera {
LOG_PACKET_HEADER;
uint64_t time_us;
uint32_t gps_time;
uint16_t gps_week;
int32_t latitude;
int32_t longitude;
int32_t altitude;
int32_t altitude_rel;
int32_t altitude_gps;
int16_t roll;
int16_t pitch;
uint16_t yaw;
};

struct PACKED log_PID {
LOG_PACKET_HEADER;
uint64_t time_us;
Expand Down Expand Up @@ -1058,20 +1044,6 @@ struct PACKED log_PSC {
// @Field: PosY: Calculated beacon position, y-axis
// @Field: PosZ: Calculated beacon position, z-axis

// @LoggerMessage: CAM,TRIG
// @Description: Camera shutter information
// @Field: TimeUS: Time since system startup
// @Field: GPSTime: milliseconds since start of GPS week
// @Field: GPSWeek: weeks since 5 Jan 1980
// @Field: Lat: current latitude
// @Field: Lng: current longitude
// @Field: Alt: current altitude
// @Field: RelAlt: current altitude relative to home
// @Field: GPSAlt: altitude as reported by GPS
// @Field: Roll: current vehicle roll
// @Field: Pitch: current vehicle pitch
// @Field: Yaw: current vehicle yaw

// @LoggerMessage: CESC
// @Description: CAN ESC data
// @Field: TimeUS: Time since system startup
Expand Down Expand Up @@ -1748,10 +1720,7 @@ struct PACKED log_PSC {
"MAVC", "QBBBHBBffffiifBB","TimeUS,TS,TC,Fr,Cmd,Cur,AC,P1,P2,P3,P4,X,Y,Z,Res,WL", "s---------------", "F---------------" }, \
{ LOG_RADIO_MSG, sizeof(log_Radio), \
"RAD", "QBBBBBHH", "TimeUS,RSSI,RemRSSI,TxBuf,Noise,RemNoise,RxErrors,Fixed", "s-------", "F-------" }, \
{ LOG_CAMERA_MSG, sizeof(log_Camera), \
"CAM", "QIHLLeeeccC","TimeUS,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,GPSAlt,Roll,Pitch,Yaw", "s--DUmmmddd", "F--GGBBBBBB" }, \
{ LOG_TRIGGER_MSG, sizeof(log_Camera), \
"TRIG", "QIHLLeeeccC","TimeUS,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,GPSAlt,Roll,Pitch,Yaw", "s--DUmmmddd", "F--GGBBBBBB" }, \
LOG_STRUCTURE_FROM_CAMERA \
{ LOG_ARSP_MSG, sizeof(log_ARSP), "ARSP", "QBffcffBBfB", "TimeUS,I,Airspeed,DiffPress,Temp,RawPress,Offset,U,H,Hfp,Pri", "s#nPOPP----", "F-00B00----" }, \
LOG_STRUCTURE_FROM_BATTMONITOR \
{ LOG_MAG_MSG, sizeof(log_MAG), \
Expand Down Expand Up @@ -1905,7 +1874,7 @@ enum LogMessages : uint8_t {
LOG_MAVLINK_COMMAND_MSG,
LOG_RADIO_MSG,
LOG_ATRP_MSG,
LOG_CAMERA_MSG,
LOG_IDS_FROM_CAMERA,
LOG_TERRAIN_MSG,
LOG_GPS_UBX1_MSG,
LOG_GPS_UBX2_MSG,
Expand Down Expand Up @@ -1951,7 +1920,6 @@ enum LogMessages : uint8_t {
LOG_MSG_SBPRAWH,
LOG_MSG_SBPRAWM,
LOG_MSG_SBPEVENT,
LOG_TRIGGER_MSG,

LOG_RALLY_MSG,
LOG_VISUALODOM_MSG,
Expand Down