ardupilot/libraries/AP_Camera/LogStructure.h

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

46 lines
1.4 KiB
C
Raw Permalink Normal View History

2021-01-22 15:50:46 -04:00
#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: I: Instance number
2023-02-22 07:38:36 -04:00
// @Field: Img: Image number
2021-01-22 15:50:46 -04:00
// @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
2023-02-22 07:38:36 -04:00
// @Field: R: current vehicle roll
// @Field: P: current vehicle pitch
// @Field: Y: current vehicle yaw
2021-01-22 15:50:46 -04:00
struct PACKED log_Camera {
LOG_PACKET_HEADER;
uint64_t time_us;
uint8_t instance;
2023-02-22 07:38:36 -04:00
uint16_t image_number;
2021-01-22 15:50:46 -04:00
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), \
2023-02-22 07:38:36 -04:00
"CAM", "QBHIHLLeeeccC","TimeUS,I,Img,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,GPSAlt,R,P,Y", "s#---DUmmmddd", "F----GGBBBBBB" }, \
2021-01-22 15:50:46 -04:00
{ LOG_TRIGGER_MSG, sizeof(log_Camera), \
2023-02-22 07:38:36 -04:00
"TRIG", "QBHIHLLeeeccC","TimeUS,I,Img,GPSTime,GPSWeek,Lat,Lng,Alt,RelAlt,GPSAlt,R,P,Y", "s#---DUmmmddd", "F----GGBBBBBB" },