Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_AHRS/AP_AHRS_Logging.cpp
9507 views
1
#include <AP_Logger/AP_Logger_config.h>
2
3
#if HAL_LOGGING_ENABLED
4
5
#include "AP_AHRS.h"
6
#include <AP_Logger/AP_Logger.h>
7
8
#include <AC_AttitudeControl/AC_AttitudeControl.h>
9
#include <AC_AttitudeControl/AC_PosControl.h>
10
11
12
// Write an AHRS2 packet
13
void AP_AHRS::Write_AHRS2() const
14
{
15
Vector3f euler;
16
Location loc;
17
Quaternion quat;
18
if (!get_secondary_attitude(euler) || !get_secondary_position(loc) || !get_secondary_quaternion(quat)) {
19
return;
20
}
21
float alt;
22
if (!loc.initialised() || !loc.get_alt_m(Location::AltFrame::ABSOLUTE, alt)) {
23
alt = AP_Logger::quiet_nanf();
24
}
25
const struct log_AHRS pkt{
26
LOG_PACKET_HEADER_INIT(LOG_AHR2_MSG),
27
time_us : AP_HAL::micros64(),
28
roll : (int16_t)(degrees(euler.x)*100),
29
pitch : (int16_t)(degrees(euler.y)*100),
30
yaw : (uint16_t)(wrap_360_cd(degrees(euler.z)*100)),
31
alt : alt,
32
lat : loc.lat,
33
lng : loc.lng,
34
q1 : quat.q1,
35
q2 : quat.q2,
36
q3 : quat.q3,
37
q4 : quat.q4,
38
};
39
AP::logger().WriteBlock(&pkt, sizeof(pkt));
40
}
41
42
// Write AOA and SSA
43
void AP_AHRS::Write_AOA_SSA(void) const
44
{
45
const struct log_AOA_SSA aoa_ssa{
46
LOG_PACKET_HEADER_INIT(LOG_AOA_SSA_MSG),
47
time_us : AP_HAL::micros64(),
48
AOA : getAOA(),
49
SSA : getSSA()
50
};
51
52
AP::logger().WriteBlock(&aoa_ssa, sizeof(aoa_ssa));
53
}
54
55
// Write an attitude packet, targets in degrees
56
void AP_AHRS::Write_Attitude(const Vector3f &targets) const
57
{
58
const struct log_Attitude pkt{
59
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
60
time_us : AP_HAL::micros64(),
61
control_roll : targets.x,
62
roll : degrees(roll),
63
control_pitch : targets.y,
64
pitch : degrees(pitch),
65
control_yaw : wrap_360(targets.z),
66
yaw : wrap_360(degrees(yaw)),
67
active : uint8_t(active_EKF_type()),
68
};
69
AP::logger().WriteBlock(&pkt, sizeof(pkt));
70
}
71
72
void AP_AHRS::Write_Origin(LogOriginType origin_type, const Location &loc) const
73
{
74
int32_t alt_cm;
75
if (!loc.initialised() || !loc.get_alt_cm(Location::AltFrame::ABSOLUTE, alt_cm)) {
76
alt_cm = 0;
77
}
78
const struct log_ORGN pkt{
79
LOG_PACKET_HEADER_INIT(LOG_ORGN_MSG),
80
time_us : AP_HAL::micros64(),
81
origin_type : (uint8_t)origin_type,
82
latitude : loc.lat,
83
longitude : loc.lng,
84
altitude : alt_cm
85
};
86
AP::logger().WriteBlock(&pkt, sizeof(pkt));
87
}
88
89
// Write a POS packet
90
void AP_AHRS::Write_POS() const
91
{
92
Location loc;
93
if (!get_location(loc)) {
94
return;
95
}
96
float home;
97
AP::ahrs().get_relative_position_D_home(home);
98
99
const auto nanf = AP_Logger::quiet_nanf();
100
float origin_pos_up;
101
if (get_relative_position_D_origin_float(origin_pos_up)) {
102
origin_pos_up *= -1; // down -> up
103
} else {
104
origin_pos_up = nanf;
105
}
106
float alt;
107
if (!loc.get_alt_m(Location::AltFrame::ABSOLUTE, alt)) {
108
alt = nanf;
109
}
110
const struct log_POS pkt{
111
LOG_PACKET_HEADER_INIT(LOG_POS_MSG),
112
time_us : AP_HAL::micros64(),
113
lat : loc.lat,
114
lng : loc.lng,
115
alt : alt,
116
rel_home_alt : -home,
117
rel_origin_alt : origin_pos_up,
118
};
119
AP::logger().WriteBlock(&pkt, sizeof(pkt));
120
}
121
122
// Write a packet for video stabilisation
123
void AP_AHRS::write_video_stabilisation() const
124
{
125
Quaternion current_attitude;
126
get_quat_body_to_ned(current_attitude);
127
Vector3f accel = get_accel() - get_accel_bias();
128
const struct log_Video_Stabilisation pkt {
129
LOG_PACKET_HEADER_INIT(LOG_VIDEO_STABILISATION_MSG),
130
time_us : AP_HAL::micros64(),
131
gyro_x : state.gyro_estimate.x,
132
gyro_y : state.gyro_estimate.y,
133
gyro_z : state.gyro_estimate.z,
134
accel_x : accel.x,
135
accel_y : accel.y,
136
accel_z : accel.z,
137
Q1 : current_attitude.q1,
138
Q2 : current_attitude.q2,
139
Q3 : current_attitude.q3,
140
Q4 : current_attitude.q4,
141
};
142
AP::logger().WriteBlock(&pkt, sizeof(pkt));
143
}
144
145
// Write an attitude view packet, targets in degrees
146
void AP_AHRS_View::Write_AttitudeView(const Vector3f &targets) const
147
{
148
const struct log_Attitude pkt{
149
LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
150
time_us : AP_HAL::micros64(),
151
control_roll : targets.x,
152
roll : degrees(roll),
153
control_pitch : targets.y,
154
pitch : degrees(pitch),
155
control_yaw : wrap_360(targets.z),
156
yaw : wrap_360(degrees(yaw)),
157
active : uint8_t(AP::ahrs().active_EKF_type()),
158
};
159
AP::logger().WriteBlock(&pkt, sizeof(pkt));
160
}
161
162
#endif // HAL_LOGGING_ENABLED
163
164