CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Rover/Log.cpp
Views: 1798
1
#include "Rover.h"
2
3
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
4
5
#if HAL_LOGGING_ENABLED
6
7
// Write an attitude packet
8
void Rover::Log_Write_Attitude()
9
{
10
float desired_pitch = degrees(g2.attitude_control.get_desired_pitch());
11
const Vector3f targets(0.0f, desired_pitch, 0.0f);
12
13
ahrs.Write_Attitude(targets);
14
15
AP::ahrs().Log_Write();
16
17
// log steering rate controller
18
logger.Write_PID(LOG_PIDS_MSG, g2.attitude_control.get_steering_rate_pid().get_pid_info());
19
logger.Write_PID(LOG_PIDA_MSG, g2.attitude_control.get_throttle_speed_pid_info());
20
21
// log pitch control for balance bots
22
if (is_balancebot()) {
23
logger.Write_PID(LOG_PIDP_MSG, g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info());
24
}
25
26
// log heel to sail control for sailboats
27
if (g2.sailboat.sail_enabled()) {
28
logger.Write_PID(LOG_PIDR_MSG, g2.attitude_control.get_sailboat_heel_pid().get_pid_info());
29
}
30
}
31
32
#if AP_RANGEFINDER_ENABLED
33
// Write a range finder depth message
34
void Rover::Log_Write_Depth()
35
{
36
// only log depth on boats
37
if (!rover.is_boat() || !rangefinder.has_orientation(ROTATION_PITCH_270)) {
38
return;
39
}
40
41
// get position
42
Location loc;
43
IGNORE_RETURN(ahrs.get_location(loc));
44
45
for (uint8_t i=0; i<rangefinder.num_sensors(); i++) {
46
const AP_RangeFinder_Backend *s = rangefinder.get_backend(i);
47
48
if (s == nullptr || s->orientation() != ROTATION_PITCH_270 || !s->has_data()) {
49
continue;
50
}
51
52
// check if new sensor reading has arrived
53
const uint32_t reading_ms = s->last_reading_ms();
54
if (reading_ms == rangefinder_last_reading_ms[i]) {
55
continue;
56
}
57
rangefinder_last_reading_ms[i] = reading_ms;
58
59
float temp_C;
60
if (!s->get_temp(temp_C)) {
61
temp_C = 0.0f;
62
}
63
64
// @LoggerMessage: DPTH
65
// @Description: Depth messages on boats with downwards facing range finder
66
// @Field: TimeUS: Time since system startup
67
// @Field: Inst: Instance
68
// @Field: Lat: Latitude
69
// @Field: Lng: Longitude
70
// @Field: Depth: Depth as detected by the sensor
71
// @Field: Temp: Temperature
72
73
logger.Write("DPTH", "TimeUS,Inst,Lat,Lng,Depth,Temp",
74
"s#DUmO", "F-GG00", "QBLLff",
75
AP_HAL::micros64(),
76
i,
77
loc.lat,
78
loc.lng,
79
(double)(s->distance()),
80
temp_C);
81
}
82
}
83
#endif
84
85
// guided mode logging
86
struct PACKED log_GuidedTarget {
87
LOG_PACKET_HEADER;
88
uint64_t time_us;
89
uint8_t type;
90
float pos_target_x;
91
float pos_target_y;
92
float pos_target_z;
93
float vel_target_x;
94
float vel_target_y;
95
float vel_target_z;
96
};
97
98
// Write a Guided mode target
99
void Rover::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target)
100
{
101
struct log_GuidedTarget pkt = {
102
LOG_PACKET_HEADER_INIT(LOG_GUIDEDTARGET_MSG),
103
time_us : AP_HAL::micros64(),
104
type : target_type,
105
pos_target_x : pos_target.x,
106
pos_target_y : pos_target.y,
107
pos_target_z : pos_target.z,
108
vel_target_x : vel_target.x,
109
vel_target_y : vel_target.y,
110
vel_target_z : vel_target.z
111
};
112
logger.WriteBlock(&pkt, sizeof(pkt));
113
}
114
115
struct PACKED log_Nav_Tuning {
116
LOG_PACKET_HEADER;
117
uint64_t time_us;
118
float wp_distance;
119
float wp_bearing;
120
float nav_bearing;
121
uint16_t yaw;
122
float xtrack_error;
123
};
124
125
// Write a navigation tuning packet
126
void Rover::Log_Write_Nav_Tuning()
127
{
128
struct log_Nav_Tuning pkt = {
129
LOG_PACKET_HEADER_INIT(LOG_NTUN_MSG),
130
time_us : AP_HAL::micros64(),
131
wp_distance : control_mode->get_distance_to_destination(),
132
wp_bearing : control_mode->wp_bearing(),
133
nav_bearing : control_mode->nav_bearing(),
134
yaw : (uint16_t)ahrs.yaw_sensor,
135
xtrack_error : control_mode->crosstrack_error()
136
};
137
logger.WriteBlock(&pkt, sizeof(pkt));
138
}
139
140
void Rover::Log_Write_Sail()
141
{
142
// only log sail if present
143
if (!g2.sailboat.sail_enabled()) {
144
return;
145
}
146
147
float wind_dir_tack = logger.quiet_nanf();
148
uint8_t current_tack = 0;
149
if (g2.windvane.enabled()) {
150
wind_dir_tack = degrees(g2.windvane.get_tack_threshold_wind_dir_rad());
151
current_tack = uint8_t(g2.windvane.get_current_tack());
152
}
153
154
// @LoggerMessage: SAIL
155
// @Description: Sailboat information
156
// @Field: TimeUS: Time since system startup
157
// @Field: Tack: Current tack, 0 = port, 1 = starboard
158
// @Field: TackThr: Apparent wind angle used for tack threshold
159
// @Field: MainOut: Normalized mainsail output
160
// @Field: WingOut: Normalized wingsail output
161
// @Field: MastRotOut: Normalized direct-rotation mast output
162
// @Field: VMG: Velocity made good (speed at which vehicle is making progress directly towards destination)
163
164
logger.Write("SAIL", "TimeUS,Tack,TackThr,MainOut,WingOut,MastRotOut,VMG",
165
"s-d%%%n", "F000000", "QBfffff",
166
AP_HAL::micros64(),
167
current_tack,
168
(double)wind_dir_tack,
169
(double)g2.motors.get_mainsail(),
170
(double)g2.motors.get_wingsail(),
171
(double)g2.motors.get_mast_rotation(),
172
(double)g2.sailboat.get_VMG());
173
}
174
175
struct PACKED log_Steering {
176
LOG_PACKET_HEADER;
177
uint64_t time_us;
178
int16_t steering_in;
179
float steering_out;
180
float desired_lat_accel;
181
float lat_accel;
182
float desired_turn_rate;
183
float turn_rate;
184
};
185
186
// Write a steering packet
187
void Rover::Log_Write_Steering()
188
{
189
float lat_accel = logger.quiet_nanf();
190
g2.attitude_control.get_lat_accel(lat_accel);
191
struct log_Steering pkt = {
192
LOG_PACKET_HEADER_INIT(LOG_STEERING_MSG),
193
time_us : AP_HAL::micros64(),
194
steering_in : channel_steer->get_control_in(),
195
steering_out : g2.motors.get_steering(),
196
desired_lat_accel : control_mode->get_desired_lat_accel(),
197
lat_accel : lat_accel,
198
desired_turn_rate : degrees(g2.attitude_control.get_desired_turn_rate()),
199
turn_rate : degrees(ahrs.get_yaw_rate_earth())
200
};
201
logger.WriteBlock(&pkt, sizeof(pkt));
202
}
203
204
struct PACKED log_Throttle {
205
LOG_PACKET_HEADER;
206
uint64_t time_us;
207
int16_t throttle_in;
208
float throttle_out;
209
float desired_speed;
210
float speed;
211
float accel_x;
212
};
213
214
// Write a throttle control packet
215
void Rover::Log_Write_Throttle()
216
{
217
const Vector3f accel = ins.get_accel();
218
float speed = logger.quiet_nanf();
219
g2.attitude_control.get_forward_speed(speed);
220
struct log_Throttle pkt = {
221
LOG_PACKET_HEADER_INIT(LOG_THR_MSG),
222
time_us : AP_HAL::micros64(),
223
throttle_in : channel_throttle->get_control_in(),
224
throttle_out : g2.motors.get_throttle(),
225
desired_speed : g2.attitude_control.get_desired_speed(),
226
speed : speed,
227
accel_x : accel.x
228
};
229
logger.WriteBlock(&pkt, sizeof(pkt));
230
}
231
232
void Rover::Log_Write_RC(void)
233
{
234
logger.Write_RCIN();
235
logger.Write_RCOUT();
236
#if AP_RSSI_ENABLED
237
if (rssi.enabled()) {
238
logger.Write_RSSI();
239
}
240
#endif
241
}
242
243
void Rover::Log_Write_Vehicle_Startup_Messages()
244
{
245
// only 200(?) bytes are guaranteed by AP_Logger
246
logger.Write_Mode((uint8_t)control_mode->mode_number(), control_mode_reason);
247
ahrs.Log_Write_Home_And_Origin();
248
gps.Write_AP_Logger_Log_Startup_messages();
249
}
250
251
// type and unit information can be found in
252
// libraries/AP_Logger/Logstructure.h; search for "log_Units" for
253
// units and "Format characters" for field type information
254
255
const LogStructure Rover::log_structure[] = {
256
LOG_COMMON_STRUCTURES,
257
258
// @LoggerMessage: THR
259
// @Description: Throttle related messages
260
// @Field: TimeUS: Time since system startup
261
// @Field: ThrIn: Throttle Input
262
// @Field: ThrOut: Throttle Output
263
// @Field: DesSpeed: Desired speed
264
// @Field: Speed: Actual speed
265
// @Field: AccX: Acceleration
266
267
{ LOG_THR_MSG, sizeof(log_Throttle),
268
"THR", "Qhffff", "TimeUS,ThrIn,ThrOut,DesSpeed,Speed,AccX", "s--nno", "F--000" },
269
270
// @LoggerMessage: NTUN
271
// @Description: Navigation Tuning information - e.g. vehicle destination
272
// @URL: http://ardupilot.org/rover/docs/navigation.html
273
// @Field: TimeUS: Time since system startup
274
// @Field: WpDist: distance to the current navigation waypoint
275
// @Field: WpBrg: bearing to the current navigation waypoint
276
// @Field: DesYaw: the vehicle's desired heading
277
// @Field: Yaw: the vehicle's current heading
278
// @Field: XTrack: the vehicle's current distance from the current travel segment
279
280
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
281
"NTUN", "QfffHf", "TimeUS,WpDist,WpBrg,DesYaw,Yaw,XTrack", "smhhhm", "F000B0" },
282
283
// @LoggerMessage: STER
284
// @Description: Steering related messages
285
// @Field: TimeUS: Time since system startup
286
// @Field: SteerIn: Steering input
287
// @Field: SteerOut: Normalized steering output
288
// @Field: DesLatAcc: Desired lateral acceleration
289
// @Field: LatAcc: Actual lateral acceleration
290
// @Field: DesTurnRate: Desired turn rate
291
// @Field: TurnRate: Actual turn rate
292
293
{ LOG_STEERING_MSG, sizeof(log_Steering),
294
"STER", "Qhfffff", "TimeUS,SteerIn,SteerOut,DesLatAcc,LatAcc,DesTurnRate,TurnRate", "s--ookk", "F--0000" },
295
296
// @LoggerMessage: GUIP
297
// @Description: Guided mode target information
298
// @Field: TimeUS: Time since system startup
299
// @Field: Type: Type of guided mode
300
// @Field: pX: Target position, X-Axis
301
// @Field: pY: Target position, Y-Axis
302
// @Field: pZ: Target position, Z-Axis
303
// @Field: vX: Target velocity, X-Axis
304
// @Field: vY: Target velocity, Y-Axis
305
// @Field: vZ: Target velocity, Z-Axis
306
307
{ LOG_GUIDEDTARGET_MSG, sizeof(log_GuidedTarget),
308
"GUIP", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" },
309
};
310
311
uint8_t Rover::get_num_log_structures() const
312
{
313
return ARRAY_SIZE(log_structure);
314
}
315
316
#endif // LOGGING_ENABLED
317
318