3 #include <AP_Logger/LogStructure.h>
4 #include "AP_VisualOdom_config.h"
6 #define LOG_IDS_FROM_VISUALODOM \
11 // @LoggerMessage: VISO
12 // @Description: Visual Odometry
13 // @Field: TimeUS: System time
14 // @Field: dt: Time period this data covers
15 // @Field: AngDX: Angular change for body-frame roll axis
16 // @Field: AngDY: Angular change for body-frame pitch axis
17 // @Field: AngDZ: Angular change for body-frame z axis
18 // @Field: PosDX: Position change for body-frame X axis (Forward-Back)
19 // @Field: PosDY: Position change for body-frame Y axis (Right-Left)
20 // @Field: PosDZ: Position change for body-frame Z axis (Down-Up)
21 // @Field: conf: Confidence
22 struct PACKED log_VisualOdom
{
29 float position_delta_x
;
30 float position_delta_y
;
31 float position_delta_z
;
35 // @LoggerMessage: VISP
36 // @Description: Vision Position
37 // @Field: TimeUS: System time
38 // @Field: RTimeUS: Remote system time
39 // @Field: CTimeMS: Corrected system time
40 // @Field: PX: Position X-axis (North-South)
41 // @Field: PY: Position Y-axis (East-West)
42 // @Field: PZ: Position Z-axis (Down-Up)
43 // @Field: R: Roll lean angle
44 // @Field: P: Pitch lean angle
45 // @Field: Y: Yaw angle
46 // @Field: PErr: Position estimate error
47 // @Field: AErr: Attitude estimate error
48 // @Field: Rst: Position reset counter
49 // @Field: Ign: Ignored
51 struct PACKED log_VisualPosition
{
54 uint64_t remote_time_us
;
59 float roll
; // degrees
60 float pitch
; // degrees
62 float pos_err
; // meters
63 float ang_err
; // radians
64 uint8_t reset_counter
;
69 // @LoggerMessage: VISV
70 // @Description: Vision Velocity
71 // @Field: TimeUS: System time
72 // @Field: RTimeUS: Remote system time
73 // @Field: CTimeMS: Corrected system time
74 // @Field: VX: Velocity X-axis (North-South)
75 // @Field: VY: Velocity Y-axis (East-West)
76 // @Field: VZ: Velocity Z-axis (Down-Up)
77 // @Field: VErr: Velocity estimate error
78 // @Field: Rst: Velocity reset counter
79 // @Field: Ign: Ignored
81 struct PACKED log_VisualVelocity
{
84 uint64_t remote_time_us
;
90 uint8_t reset_counter
;
95 #if HAL_VISUALODOM_ENABLED
96 #define LOG_STRUCTURE_FROM_VISUALODOM \
97 { LOG_VISUALODOM_MSG, sizeof(log_VisualOdom), \
98 "VISO", "Qffffffff", "TimeUS,dt,AngDX,AngDY,AngDZ,PosDX,PosDY,PosDZ,conf", "ssrrrmmm-", "FF000000-" }, \
99 { LOG_VISUALPOS_MSG, sizeof(log_VisualPosition), \
100 "VISP", "QQIffffffffBBb", "TimeUS,RTimeUS,CTimeMS,PX,PY,PZ,R,P,Y,PErr,AErr,Rst,Ign,Q", "sssmmmddhmd--%", "FFC00000000--0" }, \
101 { LOG_VISUALVEL_MSG, sizeof(log_VisualVelocity), \
102 "VISV", "QQIffffBBb", "TimeUS,RTimeUS,CTimeMS,VX,VY,VZ,VErr,Rst,Ign,Q", "sssnnnn--%", "FFC0000--0" },
104 #define LOG_STRUCTURE_FROM_VISUALODOM