APM:Libraries
LogFile.cpp
Go to the documentation of this file.
1 #include <stdlib.h>
2 
3 #include <AP_AHRS/AP_AHRS.h>
4 #include <AP_Baro/AP_Baro.h>
7 #include <AP_HAL/AP_HAL.h>
8 #include <AP_Math/AP_Math.h>
9 #include <AP_Param/AP_Param.h>
10 #include <AP_Motors/AP_Motors.h>
14 
15 #include "DataFlash.h"
16 #include "DataFlash_File.h"
17 #include "DataFlash_File_sd.h"
18 #include "DataFlash_MAVLink.h"
19 #include "DataFlash_Revo.h"
20 #include "DataFlash_File_sd.h"
21 #include "DFMessageWriter.h"
22 
23 extern const AP_HAL::HAL& hal;
24 
25 
26 /*
27  write a structure format to the log - should be in frontend
28  */
30 {
31  memset(&pkt, 0, sizeof(pkt));
32  pkt.head1 = HEAD_BYTE1;
33  pkt.head2 = HEAD_BYTE2;
34  pkt.msgid = LOG_FORMAT_MSG;
35  pkt.type = s->msg_type;
36  pkt.length = s->msg_len;
37  strncpy(pkt.name, s->name, sizeof(pkt.name));
38  strncpy(pkt.format, s->format, sizeof(pkt.format));
39  strncpy(pkt.labels, s->labels, sizeof(pkt.labels));
40 }
41 
42 /*
43  Pack a LogStructure packet into a structure suitable to go to the logfile:
44  */
46 {
47  memset(&pkt, 0, sizeof(pkt));
48  pkt.head1 = HEAD_BYTE1;
49  pkt.head2 = HEAD_BYTE2;
50  pkt.msgid = LOG_FORMAT_UNITS_MSG;
51  pkt.time_us = AP_HAL::micros64();
52  pkt.format_type = s->msg_type;
53  strncpy(pkt.units, s->units, sizeof(pkt.units));
54  strncpy(pkt.multipliers, s->multipliers, sizeof(pkt.multipliers));
55 }
56 
57 /*
58  write a structure format to the log
59  */
61 {
62  struct log_Format pkt;
63  Log_Fill_Format(s, pkt);
64  return WriteCriticalBlock(&pkt, sizeof(pkt));
65 }
66 
67 /*
68  write a unit definition
69  */
71 {
72  struct log_Unit pkt = {
75  type : s->ID,
76  unit : { }
77  };
78  strncpy(pkt.unit, s->unit, sizeof(pkt.unit));
79 
80  return WriteCriticalBlock(&pkt, sizeof(pkt));
81 }
82 
83 /*
84  write a unit-multiplier definition
85  */
87 {
88  struct log_Format_Multiplier pkt = {
91  type : s->ID,
93  };
94 
95  return WriteCriticalBlock(&pkt, sizeof(pkt));
96 }
97 
98 /*
99  write the units for a format to the log
100  */
102 {
103  struct log_Format_Units pkt;
104  Log_Fill_Format_Units(s, pkt);
105  return WriteCriticalBlock(&pkt, sizeof(pkt));
106 }
107 
108 /*
109  write a parameter to the log
110  */
112 {
113  struct log_Parameter pkt = {
116  name : {},
117  value : value
118  };
119  strncpy(pkt.name, name, sizeof(pkt.name));
120  return WriteCriticalBlock(&pkt, sizeof(pkt));
121 }
122 
123 /*
124  write a parameter to the log
125  */
127  const AP_Param::ParamToken &token,
128  enum ap_var_type type)
129 {
130  char name[16];
131  ap->copy_name_token(token, &name[0], sizeof(name), true);
132  return Log_Write_Parameter(name, ap->cast_to_float(type));
133 }
134 
135 // Write an GPS packet
136 void DataFlash_Class::Log_Write_GPS(uint8_t i, uint64_t time_us)
137 {
138  const AP_GPS &gps = AP::gps();
139  if (time_us == 0) {
140  time_us = AP_HAL::micros64();
141  }
142  const struct Location &loc = gps.location(i);
143  struct log_GPS pkt = {
144  LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GPS_MSG+i)),
145  time_us : time_us,
146  status : (uint8_t)gps.status(i),
147  gps_week_ms : gps.time_week_ms(i),
148  gps_week : gps.time_week(i),
149  num_sats : gps.num_sats(i),
150  hdop : gps.get_hdop(i),
151  latitude : loc.lat,
152  longitude : loc.lng,
153  altitude : loc.alt,
154  ground_speed : gps.ground_speed(i),
155  ground_course : gps.ground_course(i),
156  vel_z : gps.velocity(i).z,
157  used : (uint8_t)(gps.primary_sensor() == i)
158  };
159  WriteBlock(&pkt, sizeof(pkt));
160 
161  /* write auxiliary accuracy information as well */
162  float hacc = 0, vacc = 0, sacc = 0;
163  gps.horizontal_accuracy(i, hacc);
164  gps.vertical_accuracy(i, vacc);
165  gps.speed_accuracy(i, sacc);
166  struct log_GPA pkt2 = {
167  LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GPA_MSG+i)),
168  time_us : time_us,
169  vdop : gps.get_vdop(i),
170  hacc : (uint16_t)MIN((hacc*100), UINT16_MAX),
171  vacc : (uint16_t)MIN((vacc*100), UINT16_MAX),
172  sacc : (uint16_t)MIN((sacc*100), UINT16_MAX),
173  have_vv : (uint8_t)gps.have_vertical_velocity(i),
176  };
177  WriteBlock(&pkt2, sizeof(pkt2));
178 }
179 
180 
181 // Write an RFND (rangefinder) packet
183 {
184  AP_RangeFinder_Backend *s0 = rangefinder.get_backend(0);
185  AP_RangeFinder_Backend *s1 = rangefinder.get_backend(1);
186 
187  struct log_RFND pkt = {
190  dist1 : s0 ? s0->distance_cm() : (uint16_t)0,
191  orient1 : s0 ? s0->orientation() : ROTATION_NONE,
192  dist2 : s1 ? s1->distance_cm() : (uint16_t)0,
193  orient2 : s1 ? s1->orientation() : ROTATION_NONE,
194  };
195  WriteBlock(&pkt, sizeof(pkt));
196 }
197 
198 // Write an RCIN packet
200 {
201  struct log_RCIN pkt = {
218  };
219  WriteBlock(&pkt, sizeof(pkt));
220 }
221 
222 // Write an SERVO packet
224 {
225  struct log_RCOUT pkt = {
228  chan1 : hal.rcout->read(0),
229  chan2 : hal.rcout->read(1),
230  chan3 : hal.rcout->read(2),
231  chan4 : hal.rcout->read(3),
232  chan5 : hal.rcout->read(4),
233  chan6 : hal.rcout->read(5),
234  chan7 : hal.rcout->read(6),
235  chan8 : hal.rcout->read(7),
236  chan9 : hal.rcout->read(8),
237  chan10 : hal.rcout->read(9),
238  chan11 : hal.rcout->read(10),
239  chan12 : hal.rcout->read(11),
240  chan13 : hal.rcout->read(12),
241  chan14 : hal.rcout->read(13)
242  };
243  WriteBlock(&pkt, sizeof(pkt));
244  Log_Write_ESC();
245 }
246 
247 // Write an RSSI packet
249 {
250  struct log_RSSI pkt = {
253  RXRSSI : rssi.read_receiver_rssi()
254  };
255  WriteBlock(&pkt, sizeof(pkt));
256 }
257 
258 void DataFlash_Class::Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
259 {
260  AP_Baro &baro = AP::baro();
261  float climbrate = baro.get_climb_rate();
262  float drift_offset = baro.get_baro_drift_offset();
263  float ground_temp = baro.get_ground_temperature();
264  struct log_BARO pkt = {
266  time_us : time_us,
267  altitude : baro.get_altitude(baro_instance),
268  pressure : baro.get_pressure(baro_instance),
269  temperature : (int16_t)(baro.get_temperature(baro_instance) * 100 + 0.5f),
270  climbrate : climbrate,
271  sample_time_ms: baro.get_last_update(baro_instance),
274  };
275  WriteBlock(&pkt, sizeof(pkt));
276 }
277 
278 // Write a BARO packet
280 {
281  if (time_us == 0) {
282  time_us = AP_HAL::micros64();
283  }
284  const AP_Baro &baro = AP::baro();
285  Log_Write_Baro_instance(time_us, 0, LOG_BARO_MSG);
286  if (baro.num_instances() > 1 && baro.healthy(1)) {
287  Log_Write_Baro_instance(time_us, 1, LOG_BAR2_MSG);
288  }
289  if (baro.num_instances() > 2 && baro.healthy(2)) {
290  Log_Write_Baro_instance(time_us, 2, LOG_BAR3_MSG);
291  }
292 }
293 
294 void DataFlash_Class::Log_Write_IMU_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type)
295 {
296  const AP_InertialSensor &ins = AP::ins();
297  const Vector3f &gyro = ins.get_gyro(imu_instance);
298  const Vector3f &accel = ins.get_accel(imu_instance);
299  struct log_IMU pkt = {
301  time_us : time_us,
302  gyro_x : gyro.x,
303  gyro_y : gyro.y,
304  gyro_z : gyro.z,
305  accel_x : accel.x,
306  accel_y : accel.y,
307  accel_z : accel.z,
308  gyro_error : ins.get_gyro_error_count(imu_instance),
309  accel_error : ins.get_accel_error_count(imu_instance),
310  temperature : ins.get_temperature(imu_instance),
311  gyro_health : (uint8_t)ins.get_gyro_health(imu_instance),
312  accel_health : (uint8_t)ins.get_accel_health(imu_instance),
313  gyro_rate : ins.get_gyro_rate_hz(imu_instance),
314  accel_rate : ins.get_accel_rate_hz(imu_instance),
315  };
316  WriteBlock(&pkt, sizeof(pkt));
317 }
318 
319 // Write an raw accel/gyro data packet
321 {
322  uint64_t time_us = AP_HAL::micros64();
323 
324  const AP_InertialSensor &ins = AP::ins();
325 
326  Log_Write_IMU_instance(time_us, 0, LOG_IMU_MSG);
327  if (ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) {
328  return;
329  }
330 
331  Log_Write_IMU_instance(time_us, 1, LOG_IMU2_MSG);
332 
333  if (ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) {
334  return;
335  }
336 
337  Log_Write_IMU_instance(time_us, 2, LOG_IMU3_MSG);
338 }
339 
340 // Write an accel/gyro delta time data packet
341 void DataFlash_Class::Log_Write_IMUDT_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type)
342 {
343  const AP_InertialSensor &ins = AP::ins();
344  float delta_t = ins.get_delta_time();
345  float delta_vel_t = ins.get_delta_velocity_dt(imu_instance);
346  float delta_ang_t = ins.get_delta_angle_dt(imu_instance);
347  Vector3f delta_angle, delta_velocity;
348  ins.get_delta_angle(imu_instance, delta_angle);
349  ins.get_delta_velocity(imu_instance, delta_velocity);
350 
351  struct log_IMUDT pkt = {
353  time_us : time_us,
354  delta_time : delta_t,
355  delta_vel_dt : delta_vel_t,
356  delta_ang_dt : delta_ang_t,
357  delta_ang_x : delta_angle.x,
358  delta_ang_y : delta_angle.y,
359  delta_ang_z : delta_angle.z,
360  delta_vel_x : delta_velocity.x,
361  delta_vel_y : delta_velocity.y,
362  delta_vel_z : delta_velocity.z
363  };
364  WriteBlock(&pkt, sizeof(pkt));
365 }
366 
367 void DataFlash_Class::Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
368 {
369  const AP_InertialSensor &ins = AP::ins();
370  if (imu_mask & 1) {
371  Log_Write_IMUDT_instance(time_us, 0, LOG_IMUDT_MSG);
372  }
373  if ((ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) || !ins.use_gyro(1)) {
374  return;
375  }
376 
377  if (imu_mask & 2) {
378  Log_Write_IMUDT_instance(time_us, 1, LOG_IMUDT2_MSG);
379  }
380 
381  if ((ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) || !ins.use_gyro(2)) {
382  return;
383  }
384 
385  if (imu_mask & 4) {
386  Log_Write_IMUDT_instance(time_us, 2, LOG_IMUDT3_MSG);
387  }
388 }
389 
391 {
392  uint64_t time_us = AP_HAL::micros64();
393  const AP_InertialSensor &ins = AP::ins();
394  const Vector3f vibration = ins.get_vibration_levels();
395  struct log_Vibe pkt = {
397  time_us : time_us,
398  vibe_x : vibration.x,
399  vibe_y : vibration.y,
400  vibe_z : vibration.z,
404  };
405  WriteBlock(&pkt, sizeof(pkt));
406 }
407 
408 // Write a mission command. Total length : 36 bytes
410  const AP_Mission::Mission_Command &cmd)
411 {
412  mavlink_mission_item_t mav_cmd = {};
414  return Log_Write_MavCmd(mission.num_commands(),mav_cmd);
415 }
416 
418 {
420  writer.set_dataflash_backend(this);
421  writer.set_mission(&mission);
422  writer.process();
423 }
424 
425 // Write a text message to the log
426 bool DataFlash_Backend::Log_Write_Message(const char *message)
427 {
428  struct log_Message pkt = {
431  msg : {}
432  };
433  strncpy(pkt.msg, message, sizeof(pkt.msg));
434  return WriteCriticalBlock(&pkt, sizeof(pkt));
435 }
436 
438 {
439 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
440  uint8_t safety_and_armed = uint8_t(hal.util->safety_switch_state());
441  if (hal.util->get_soft_armed()) {
442  // encode armed state in bit 3
443  safety_and_armed |= 1U<<2;
444  }
445  struct log_POWR pkt = {
448  Vcc : hal.analogin->board_voltage(),
451  safety_and_arm : safety_and_armed
452  };
453  WriteBlock(&pkt, sizeof(pkt));
454 #endif
455 }
456 
457 // Write an AHRS2 packet
459 {
460  Vector3f euler;
461  struct Location loc;
462  Quaternion quat;
463  if (!ahrs.get_secondary_attitude(euler) || !ahrs.get_secondary_position(loc)) {
464  return;
465  }
466  ahrs.get_secondary_quaternion(quat);
467  struct log_AHRS pkt = {
470  roll : (int16_t)(degrees(euler.x)*100),
471  pitch : (int16_t)(degrees(euler.y)*100),
472  yaw : (uint16_t)(wrap_360_cd(degrees(euler.z)*100)),
473  alt : loc.alt*1.0e-2f,
474  lat : loc.lat,
475  lng : loc.lng,
476  q1 : quat.q1,
477  q2 : quat.q2,
478  q3 : quat.q3,
479  q4 : quat.q4,
480  };
481  WriteBlock(&pkt, sizeof(pkt));
482 }
483 
484 // Write a POS packet
486 {
487  Location loc;
488  if (!ahrs.get_position(loc)) {
489  return;
490  }
491  float home, origin;
492  ahrs.get_relative_position_D_home(home);
493  struct log_POS pkt = {
496  lat : loc.lat,
497  lng : loc.lng,
498  alt : loc.alt*1.0e-2f,
499  rel_home_alt : -home,
500  rel_origin_alt : ahrs.get_relative_position_D_origin(origin) ? -origin : quiet_nanf(),
501  };
502  WriteBlock(&pkt, sizeof(pkt));
503 }
504 
505 #if AP_AHRS_NAVEKF_AVAILABLE
506 void DataFlash_Class::Log_Write_EKF(AP_AHRS_NavEKF &ahrs)
507 {
508  // only log EKF2 if enabled
509  if (ahrs.get_NavEKF2().activeCores() > 0) {
510  Log_Write_EKF2(ahrs);
511  }
512  // only log EKF3 if enabled
513  if (ahrs.get_NavEKF3().activeCores() > 0) {
514  Log_Write_EKF3(ahrs);
515  }
516 }
517 
518 
519 /*
520  write an EKF timing message
521  */
522 void DataFlash_Class::Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
523 {
524  Log_Write(name,
525  "TimeUS,Cnt,IMUMin,IMUMax,EKFMin,EKFMax,AngMin,AngMax,VMin,VMax",
526  "QIffffffff",
527  time_us,
528  timing.count,
529  (double)timing.dtIMUavg_min,
530  (double)timing.dtIMUavg_max,
531  (double)timing.dtEKFavg_min,
532  (double)timing.dtEKFavg_max,
533  (double)timing.delAngDT_min,
534  (double)timing.delAngDT_max,
535  (double)timing.delVelDT_min,
536  (double)timing.delVelDT_max);
537 }
538 
539 void DataFlash_Class::Log_Write_EKF2(AP_AHRS_NavEKF &ahrs)
540 {
541  uint64_t time_us = AP_HAL::micros64();
542  // Write first EKF packet
543  Vector3f euler;
544  Vector2f posNE;
545  float posD;
546  Vector3f velNED;
547  Vector3f gyroBias;
548  float posDownDeriv;
549  Location originLLH;
550  ahrs.get_NavEKF2().getEulerAngles(0,euler);
551  ahrs.get_NavEKF2().getVelNED(0,velNED);
552  ahrs.get_NavEKF2().getPosNE(0,posNE);
553  ahrs.get_NavEKF2().getPosD(0,posD);
554  ahrs.get_NavEKF2().getGyroBias(0,gyroBias);
555  posDownDeriv = ahrs.get_NavEKF2().getPosDownDerivative(0);
556  if (!ahrs.get_NavEKF2().getOriginLLH(0,originLLH)) {
557  originLLH.alt = 0;
558  }
559  struct log_EKF1 pkt = {
561  time_us : time_us,
562  roll : (int16_t)(100*degrees(euler.x)), // roll angle (centi-deg, displayed as deg due to format string)
563  pitch : (int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg, displayed as deg due to format string)
564  yaw : (uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg, displayed as deg due to format string)
565  velN : (float)(velNED.x), // velocity North (m/s)
566  velE : (float)(velNED.y), // velocity East (m/s)
567  velD : (float)(velNED.z), // velocity Down (m/s)
568  posD_dot : (float)(posDownDeriv), // first derivative of down position
569  posN : (float)(posNE.x), // metres North
570  posE : (float)(posNE.y), // metres East
571  posD : (float)(posD), // metres Down
572  gyrX : (int16_t)(100*degrees(gyroBias.x)), // cd/sec, displayed as deg/sec due to format string
573  gyrY : (int16_t)(100*degrees(gyroBias.y)), // cd/sec, displayed as deg/sec due to format string
574  gyrZ : (int16_t)(100*degrees(gyroBias.z)), // cd/sec, displayed as deg/sec due to format string
575  originHgt : originLLH.alt // WGS-84 altitude of EKF origin in cm
576  };
577  WriteBlock(&pkt, sizeof(pkt));
578 
579  // Write second EKF packet
580  float azbias = 0;
581  Vector3f wind;
582  Vector3f magNED;
583  Vector3f magXYZ;
584  Vector3f gyroScaleFactor;
585  uint8_t magIndex = ahrs.get_NavEKF2().getActiveMag(0);
586  ahrs.get_NavEKF2().getAccelZBias(0,azbias);
587  ahrs.get_NavEKF2().getWind(0,wind);
588  ahrs.get_NavEKF2().getMagNED(0,magNED);
589  ahrs.get_NavEKF2().getMagXYZ(0,magXYZ);
590  ahrs.get_NavEKF2().getGyroScaleErrorPercentage(0,gyroScaleFactor);
591  struct log_NKF2 pkt2 = {
593  time_us : time_us,
594  AZbias : (int8_t)(100*azbias),
595  scaleX : (int16_t)(100*gyroScaleFactor.x),
596  scaleY : (int16_t)(100*gyroScaleFactor.y),
597  scaleZ : (int16_t)(100*gyroScaleFactor.z),
598  windN : (int16_t)(100*wind.x),
599  windE : (int16_t)(100*wind.y),
600  magN : (int16_t)(magNED.x),
601  magE : (int16_t)(magNED.y),
602  magD : (int16_t)(magNED.z),
603  magX : (int16_t)(magXYZ.x),
604  magY : (int16_t)(magXYZ.y),
605  magZ : (int16_t)(magXYZ.z),
606  index : (uint8_t)(magIndex)
607  };
608  WriteBlock(&pkt2, sizeof(pkt2));
609 
610  // Write third EKF packet
611  Vector3f velInnov;
612  Vector3f posInnov;
613  Vector3f magInnov;
614  float tasInnov = 0;
615  float yawInnov = 0;
616  ahrs.get_NavEKF2().getInnovations(0,velInnov, posInnov, magInnov, tasInnov, yawInnov);
617  struct log_NKF3 pkt3 = {
619  time_us : time_us,
620  innovVN : (int16_t)(100*velInnov.x),
621  innovVE : (int16_t)(100*velInnov.y),
622  innovVD : (int16_t)(100*velInnov.z),
623  innovPN : (int16_t)(100*posInnov.x),
624  innovPE : (int16_t)(100*posInnov.y),
625  innovPD : (int16_t)(100*posInnov.z),
626  innovMX : (int16_t)(magInnov.x),
627  innovMY : (int16_t)(magInnov.y),
628  innovMZ : (int16_t)(magInnov.z),
629  innovYaw : (int16_t)(100*degrees(yawInnov)),
630  innovVT : (int16_t)(100*tasInnov)
631  };
632  WriteBlock(&pkt3, sizeof(pkt3));
633 
634  // Write fourth EKF packet
635  float velVar = 0;
636  float posVar = 0;
637  float hgtVar = 0;
638  Vector3f magVar;
639  float tasVar = 0;
640  Vector2f offset;
641  uint16_t faultStatus=0;
642  uint8_t timeoutStatus=0;
643  nav_filter_status solutionStatus {};
644  nav_gps_status gpsStatus {};
645  ahrs.get_NavEKF2().getVariances(0,velVar, posVar, hgtVar, magVar, tasVar, offset);
646  float tempVar = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z);
647  ahrs.get_NavEKF2().getFilterFaults(0,faultStatus);
648  ahrs.get_NavEKF2().getFilterTimeouts(0,timeoutStatus);
649  ahrs.get_NavEKF2().getFilterStatus(0,solutionStatus);
650  ahrs.get_NavEKF2().getFilterGpsStatus(0,gpsStatus);
651  float tiltError;
652  ahrs.get_NavEKF2().getTiltError(0,tiltError);
653  int8_t primaryIndex = ahrs.get_NavEKF2().getPrimaryCoreIndex();
654  struct log_NKF4 pkt4 = {
656  time_us : time_us,
657  sqrtvarV : (int16_t)(100*velVar),
658  sqrtvarP : (int16_t)(100*posVar),
659  sqrtvarH : (int16_t)(100*hgtVar),
660  sqrtvarM : (int16_t)(100*tempVar),
661  sqrtvarVT : (int16_t)(100*tasVar),
662  tiltErr : (float)tiltError,
663  offsetNorth : (int8_t)(offset.x),
664  offsetEast : (int8_t)(offset.y),
665  faults : (uint16_t)(faultStatus),
666  timeouts : (uint8_t)(timeoutStatus),
667  solution : (uint16_t)(solutionStatus.value),
668  gps : (uint16_t)(gpsStatus.value),
669  primary : (int8_t)primaryIndex
670  };
671  WriteBlock(&pkt4, sizeof(pkt4));
672 
673  // Write fifth EKF packet - take data from the primary instance
674  float normInnov=0; // normalised innovation variance ratio for optical flow observations fused by the main nav filter
675  float gndOffset=0; // estimated vertical position of the terrain relative to the nav filter zero datum
676  float flowInnovX=0, flowInnovY=0; // optical flow LOS rate vector innovations from the main nav filter
677  float auxFlowInnov=0; // optical flow LOS rate innovation from terrain offset estimator
678  float HAGL=0; // height above ground level
679  float rngInnov=0; // range finder innovations
680  float range=0; // measured range
681  float gndOffsetErr=0; // filter ground offset state error
682  Vector3f predictorErrors; // output predictor angle, velocity and position tracking error
683  ahrs.get_NavEKF2().getFlowDebug(-1,normInnov, gndOffset, flowInnovX, flowInnovY, auxFlowInnov, HAGL, rngInnov, range, gndOffsetErr);
684  ahrs.get_NavEKF2().getOutputTrackingError(-1,predictorErrors);
685  struct log_NKF5 pkt5 = {
687  time_us : time_us,
688  normInnov : (uint8_t)(MIN(100*normInnov,255)),
689  FIX : (int16_t)(1000*flowInnovX),
690  FIY : (int16_t)(1000*flowInnovY),
691  AFI : (int16_t)(1000*auxFlowInnov),
692  HAGL : (int16_t)(100*HAGL),
693  offset : (int16_t)(100*gndOffset),
694  RI : (int16_t)(100*rngInnov),
695  meaRng : (uint16_t)(100*range),
696  errHAGL : (uint16_t)(100*gndOffsetErr),
697  angErr : (float)predictorErrors.x,
698  velErr : (float)predictorErrors.y,
699  posErr : (float)predictorErrors.z
700  };
701  WriteBlock(&pkt5, sizeof(pkt5));
702 
703  // log quaternion
704  Quaternion quat;
705  ahrs.get_NavEKF2().getQuaternion(0, quat);
706  struct log_Quaternion pktq1 = {
708  time_us : time_us,
709  q1 : quat.q1,
710  q2 : quat.q2,
711  q3 : quat.q3,
712  q4 : quat.q4
713  };
714  WriteBlock(&pktq1, sizeof(pktq1));
715 
716  // log innovations for the second IMU if enabled
717  if (ahrs.get_NavEKF2().activeCores() >= 2) {
718  // Write 6th EKF packet
719  ahrs.get_NavEKF2().getEulerAngles(1,euler);
720  ahrs.get_NavEKF2().getVelNED(1,velNED);
721  ahrs.get_NavEKF2().getPosNE(1,posNE);
722  ahrs.get_NavEKF2().getPosD(1,posD);
723  ahrs.get_NavEKF2().getGyroBias(1,gyroBias);
724  posDownDeriv = ahrs.get_NavEKF2().getPosDownDerivative(1);
725  if (!ahrs.get_NavEKF2().getOriginLLH(1,originLLH)) {
726  originLLH.alt = 0;
727  }
728  struct log_EKF1 pkt6 = {
730  time_us : time_us,
731  roll : (int16_t)(100*degrees(euler.x)), // roll angle (centi-deg, displayed as deg due to format string)
732  pitch : (int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg, displayed as deg due to format string)
733  yaw : (uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg, displayed as deg due to format string)
734  velN : (float)(velNED.x), // velocity North (m/s)
735  velE : (float)(velNED.y), // velocity East (m/s)
736  velD : (float)(velNED.z), // velocity Down (m/s)
737  posD_dot : (float)(posDownDeriv), // first derivative of down position
738  posN : (float)(posNE.x), // metres North
739  posE : (float)(posNE.y), // metres East
740  posD : (float)(posD), // metres Down
741  gyrX : (int16_t)(100*degrees(gyroBias.x)), // cd/sec, displayed as deg/sec due to format string
742  gyrY : (int16_t)(100*degrees(gyroBias.y)), // cd/sec, displayed as deg/sec due to format string
743  gyrZ : (int16_t)(100*degrees(gyroBias.z)), // cd/sec, displayed as deg/sec due to format string
744  originHgt : originLLH.alt // WGS-84 altitude of EKF origin in cm
745  };
746  WriteBlock(&pkt6, sizeof(pkt6));
747 
748  // Write 7th EKF packet
749  ahrs.get_NavEKF2().getAccelZBias(1,azbias);
750  ahrs.get_NavEKF2().getWind(1,wind);
751  ahrs.get_NavEKF2().getMagNED(1,magNED);
752  ahrs.get_NavEKF2().getMagXYZ(1,magXYZ);
753  ahrs.get_NavEKF2().getGyroScaleErrorPercentage(1,gyroScaleFactor);
754  magIndex = ahrs.get_NavEKF2().getActiveMag(1);
755  struct log_NKF2 pkt7 = {
757  time_us : time_us,
758  AZbias : (int8_t)(100*azbias),
759  scaleX : (int16_t)(100*gyroScaleFactor.x),
760  scaleY : (int16_t)(100*gyroScaleFactor.y),
761  scaleZ : (int16_t)(100*gyroScaleFactor.z),
762  windN : (int16_t)(100*wind.x),
763  windE : (int16_t)(100*wind.y),
764  magN : (int16_t)(magNED.x),
765  magE : (int16_t)(magNED.y),
766  magD : (int16_t)(magNED.z),
767  magX : (int16_t)(magXYZ.x),
768  magY : (int16_t)(magXYZ.y),
769  magZ : (int16_t)(magXYZ.z),
770  index : (uint8_t)(magIndex)
771  };
772  WriteBlock(&pkt7, sizeof(pkt7));
773 
774  // Write 8th EKF packet
775  ahrs.get_NavEKF2().getInnovations(1,velInnov, posInnov, magInnov, tasInnov, yawInnov);
776  struct log_NKF3 pkt8 = {
778  time_us : time_us,
779  innovVN : (int16_t)(100*velInnov.x),
780  innovVE : (int16_t)(100*velInnov.y),
781  innovVD : (int16_t)(100*velInnov.z),
782  innovPN : (int16_t)(100*posInnov.x),
783  innovPE : (int16_t)(100*posInnov.y),
784  innovPD : (int16_t)(100*posInnov.z),
785  innovMX : (int16_t)(magInnov.x),
786  innovMY : (int16_t)(magInnov.y),
787  innovMZ : (int16_t)(magInnov.z),
788  innovYaw : (int16_t)(100*degrees(yawInnov)),
789  innovVT : (int16_t)(100*tasInnov)
790  };
791  WriteBlock(&pkt8, sizeof(pkt8));
792 
793  // Write 9th EKF packet
794  ahrs.get_NavEKF2().getVariances(1,velVar, posVar, hgtVar, magVar, tasVar, offset);
795  tempVar = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z);
796  ahrs.get_NavEKF2().getFilterFaults(1,faultStatus);
797  ahrs.get_NavEKF2().getFilterTimeouts(1,timeoutStatus);
798  ahrs.get_NavEKF2().getFilterStatus(1,solutionStatus);
799  ahrs.get_NavEKF2().getFilterGpsStatus(1,gpsStatus);
800  ahrs.get_NavEKF2().getTiltError(1,tiltError);
801  struct log_NKF4 pkt9 = {
803  time_us : time_us,
804  sqrtvarV : (int16_t)(100*velVar),
805  sqrtvarP : (int16_t)(100*posVar),
806  sqrtvarH : (int16_t)(100*hgtVar),
807  sqrtvarM : (int16_t)(100*tempVar),
808  sqrtvarVT : (int16_t)(100*tasVar),
809  tiltErr : (float)tiltError,
810  offsetNorth : (int8_t)(offset.x),
811  offsetEast : (int8_t)(offset.y),
812  faults : (uint16_t)(faultStatus),
813  timeouts : (uint8_t)(timeoutStatus),
814  solution : (uint16_t)(solutionStatus.value),
815  gps : (uint16_t)(gpsStatus.value),
816  primary : (int8_t)primaryIndex
817  };
818  WriteBlock(&pkt9, sizeof(pkt9));
819 
820  ahrs.get_NavEKF2().getQuaternion(1, quat);
821  struct log_Quaternion pktq2 = {
823  time_us : time_us,
824  q1 : quat.q1,
825  q2 : quat.q2,
826  q3 : quat.q3,
827  q4 : quat.q4
828  };
829  WriteBlock(&pktq2, sizeof(pktq2));
830  }
831 
832  // write range beacon fusion debug packet if the range value is non-zero
833  if (ahrs.get_beacon() != nullptr) {
834  uint8_t ID;
835  float rng;
836  float innovVar;
837  float innov;
838  float testRatio;
839  Vector3f beaconPosNED;
840  float bcnPosOffsetHigh;
841  float bcnPosOffsetLow;
842  if (ahrs.get_NavEKF2().getRangeBeaconDebug(-1, ID, rng, innov, innovVar, testRatio, beaconPosNED, bcnPosOffsetHigh, bcnPosOffsetLow)) {
843  if (rng > 0.0f) {
844  struct log_RngBcnDebug pkt10 = {
846  time_us : time_us,
847  ID : (uint8_t)ID,
848  rng : (int16_t)(100*rng),
849  innov : (int16_t)(100*innov),
850  sqrtInnovVar : (uint16_t)(100*safe_sqrt(innovVar)),
851  testRatio : (uint16_t)(100*constrain_float(testRatio,0.0f,650.0f)),
852  beaconPosN : (int16_t)(100*beaconPosNED.x),
853  beaconPosE : (int16_t)(100*beaconPosNED.y),
854  beaconPosD : (int16_t)(100*beaconPosNED.z),
855  offsetHigh : (int16_t)(100*bcnPosOffsetHigh),
856  offsetLow : (int16_t)(100*bcnPosOffsetLow),
857  posN : 0,
858  posE : 0,
859  posD : 0
860  };
861  WriteBlock(&pkt10, sizeof(pkt10));
862  }
863  }
864  }
865 
866  // log EKF timing statistics every 5s
867  static uint32_t lastTimingLogTime_ms = 0;
868  if (AP_HAL::millis() - lastTimingLogTime_ms > 5000) {
869  lastTimingLogTime_ms = AP_HAL::millis();
870  struct ekf_timing timing;
871  for (uint8_t i=0; i<ahrs.get_NavEKF2().activeCores(); i++) {
872  ahrs.get_NavEKF2().getTimingStatistics(i, timing);
873  Log_Write_EKF_Timing(i==0?"NKT1":"NKT2", time_us, timing);
874  }
875  }
876 }
877 
878 
879 void DataFlash_Class::Log_Write_EKF3(AP_AHRS_NavEKF &ahrs)
880 {
881  uint64_t time_us = AP_HAL::micros64();
882  // Write first EKF packet
883  Vector3f euler;
884  Vector2f posNE;
885  float posD;
886  Vector3f velNED;
887  Vector3f gyroBias;
888  float posDownDeriv;
889  Location originLLH;
890  ahrs.get_NavEKF3().getEulerAngles(0,euler);
891  ahrs.get_NavEKF3().getVelNED(0,velNED);
892  ahrs.get_NavEKF3().getPosNE(0,posNE);
893  ahrs.get_NavEKF3().getPosD(0,posD);
894  ahrs.get_NavEKF3().getGyroBias(0,gyroBias);
895  posDownDeriv = ahrs.get_NavEKF3().getPosDownDerivative(0);
896  if (!ahrs.get_NavEKF3().getOriginLLH(0,originLLH)) {
897  originLLH.alt = 0;
898  }
899  struct log_EKF1 pkt = {
901  time_us : time_us,
902  roll : (int16_t)(100*degrees(euler.x)), // roll angle (centi-deg, displayed as deg due to format string)
903  pitch : (int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg, displayed as deg due to format string)
904  yaw : (uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg, displayed as deg due to format string)
905  velN : (float)(velNED.x), // velocity North (m/s)
906  velE : (float)(velNED.y), // velocity East (m/s)
907  velD : (float)(velNED.z), // velocity Down (m/s)
908  posD_dot : (float)(posDownDeriv), // first derivative of down position
909  posN : (float)(posNE.x), // metres North
910  posE : (float)(posNE.y), // metres East
911  posD : (float)(posD), // metres Down
912  gyrX : (int16_t)(100*degrees(gyroBias.x)), // cd/sec, displayed as deg/sec due to format string
913  gyrY : (int16_t)(100*degrees(gyroBias.y)), // cd/sec, displayed as deg/sec due to format string
914  gyrZ : (int16_t)(100*degrees(gyroBias.z)), // cd/sec, displayed as deg/sec due to format string
915  originHgt : originLLH.alt // WGS-84 altitude of EKF origin in cm
916  };
917  WriteBlock(&pkt, sizeof(pkt));
918 
919  // Write second EKF packet
920  Vector3f accelBias;
921  Vector3f wind;
922  Vector3f magNED;
923  Vector3f magXYZ;
924  uint8_t magIndex = ahrs.get_NavEKF3().getActiveMag(0);
925  ahrs.get_NavEKF3().getAccelBias(0,accelBias);
926  ahrs.get_NavEKF3().getWind(0,wind);
927  ahrs.get_NavEKF3().getMagNED(0,magNED);
928  ahrs.get_NavEKF3().getMagXYZ(0,magXYZ);
929  struct log_NKF2a pkt2 = {
931  time_us : time_us,
932  accBiasX : (int16_t)(100*accelBias.x),
933  accBiasY : (int16_t)(100*accelBias.y),
934  accBiasZ : (int16_t)(100*accelBias.z),
935  windN : (int16_t)(100*wind.x),
936  windE : (int16_t)(100*wind.y),
937  magN : (int16_t)(magNED.x),
938  magE : (int16_t)(magNED.y),
939  magD : (int16_t)(magNED.z),
940  magX : (int16_t)(magXYZ.x),
941  magY : (int16_t)(magXYZ.y),
942  magZ : (int16_t)(magXYZ.z),
943  index : (uint8_t)(magIndex)
944  };
945  WriteBlock(&pkt2, sizeof(pkt2));
946 
947  // Write third EKF packet
948  Vector3f velInnov;
949  Vector3f posInnov;
950  Vector3f magInnov;
951  float tasInnov = 0;
952  float yawInnov = 0;
953  ahrs.get_NavEKF3().getInnovations(0,velInnov, posInnov, magInnov, tasInnov, yawInnov);
954  struct log_NKF3 pkt3 = {
956  time_us : time_us,
957  innovVN : (int16_t)(100*velInnov.x),
958  innovVE : (int16_t)(100*velInnov.y),
959  innovVD : (int16_t)(100*velInnov.z),
960  innovPN : (int16_t)(100*posInnov.x),
961  innovPE : (int16_t)(100*posInnov.y),
962  innovPD : (int16_t)(100*posInnov.z),
963  innovMX : (int16_t)(magInnov.x),
964  innovMY : (int16_t)(magInnov.y),
965  innovMZ : (int16_t)(magInnov.z),
966  innovYaw : (int16_t)(100*degrees(yawInnov)),
967  innovVT : (int16_t)(100*tasInnov)
968  };
969  WriteBlock(&pkt3, sizeof(pkt3));
970 
971  // Write fourth EKF packet
972  float velVar = 0;
973  float posVar = 0;
974  float hgtVar = 0;
975  Vector3f magVar;
976  float tasVar = 0;
977  Vector2f offset;
978  uint16_t faultStatus=0;
979  uint8_t timeoutStatus=0;
980  nav_filter_status solutionStatus {};
981  nav_gps_status gpsStatus {};
982  ahrs.get_NavEKF3().getVariances(0,velVar, posVar, hgtVar, magVar, tasVar, offset);
983  float tempVar = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z);
984  ahrs.get_NavEKF3().getFilterFaults(0,faultStatus);
985  ahrs.get_NavEKF3().getFilterTimeouts(0,timeoutStatus);
986  ahrs.get_NavEKF3().getFilterStatus(0,solutionStatus);
987  ahrs.get_NavEKF3().getFilterGpsStatus(0,gpsStatus);
988  float tiltError;
989  ahrs.get_NavEKF3().getTiltError(0,tiltError);
990  uint8_t primaryIndex = ahrs.get_NavEKF3().getPrimaryCoreIndex();
991  struct log_NKF4 pkt4 = {
993  time_us : time_us,
994  sqrtvarV : (int16_t)(100*velVar),
995  sqrtvarP : (int16_t)(100*posVar),
996  sqrtvarH : (int16_t)(100*hgtVar),
997  sqrtvarM : (int16_t)(100*tempVar),
998  sqrtvarVT : (int16_t)(100*tasVar),
999  tiltErr : (float)tiltError,
1000  offsetNorth : (int8_t)(offset.x),
1001  offsetEast : (int8_t)(offset.y),
1002  faults : (uint16_t)(faultStatus),
1003  timeouts : (uint8_t)(timeoutStatus),
1004  solution : (uint16_t)(solutionStatus.value),
1005  gps : (uint16_t)(gpsStatus.value),
1006  primary : (int8_t)primaryIndex
1007  };
1008  WriteBlock(&pkt4, sizeof(pkt4));
1009 
1010  // Write fifth EKF packet - take data from the primary instance
1011  float normInnov=0; // normalised innovation variance ratio for optical flow observations fused by the main nav filter
1012  float gndOffset=0; // estimated vertical position of the terrain relative to the nav filter zero datum
1013  float flowInnovX=0, flowInnovY=0; // optical flow LOS rate vector innovations from the main nav filter
1014  float auxFlowInnov=0; // optical flow LOS rate innovation from terrain offset estimator
1015  float HAGL=0; // height above ground level
1016  float rngInnov=0; // range finder innovations
1017  float range=0; // measured range
1018  float gndOffsetErr=0; // filter ground offset state error
1019  Vector3f predictorErrors; // output predictor angle, velocity and position tracking error
1020  ahrs.get_NavEKF3().getFlowDebug(-1,normInnov, gndOffset, flowInnovX, flowInnovY, auxFlowInnov, HAGL, rngInnov, range, gndOffsetErr);
1021  ahrs.get_NavEKF3().getOutputTrackingError(-1,predictorErrors);
1022  struct log_NKF5 pkt5 = {
1024  time_us : time_us,
1025  normInnov : (uint8_t)(MIN(100*normInnov,255)),
1026  FIX : (int16_t)(1000*flowInnovX),
1027  FIY : (int16_t)(1000*flowInnovY),
1028  AFI : (int16_t)(1000*auxFlowInnov),
1029  HAGL : (int16_t)(100*HAGL),
1030  offset : (int16_t)(100*gndOffset),
1031  RI : (int16_t)(100*rngInnov),
1032  meaRng : (uint16_t)(100*range),
1033  errHAGL : (uint16_t)(100*gndOffsetErr),
1034  angErr : (float)predictorErrors.x,
1035  velErr : (float)predictorErrors.y,
1036  posErr : (float)predictorErrors.z
1037  };
1038  WriteBlock(&pkt5, sizeof(pkt5));
1039 
1040  // log quaternion
1041  Quaternion quat;
1042  ahrs.get_NavEKF3().getQuaternion(0, quat);
1043  struct log_Quaternion pktq1 = {
1045  time_us : time_us,
1046  q1 : quat.q1,
1047  q2 : quat.q2,
1048  q3 : quat.q3,
1049  q4 : quat.q4
1050  };
1051  WriteBlock(&pktq1, sizeof(pktq1));
1052 
1053  // log innovations for the second IMU if enabled
1054  if (ahrs.get_NavEKF3().activeCores() >= 2) {
1055  // Write 6th EKF packet
1056  ahrs.get_NavEKF3().getEulerAngles(1,euler);
1057  ahrs.get_NavEKF3().getVelNED(1,velNED);
1058  ahrs.get_NavEKF3().getPosNE(1,posNE);
1059  ahrs.get_NavEKF3().getPosD(1,posD);
1060  ahrs.get_NavEKF3().getGyroBias(1,gyroBias);
1061  posDownDeriv = ahrs.get_NavEKF3().getPosDownDerivative(1);
1062  if (!ahrs.get_NavEKF3().getOriginLLH(1,originLLH)) {
1063  originLLH.alt = 0;
1064  }
1065  struct log_EKF1 pkt6 = {
1067  time_us : time_us,
1068  roll : (int16_t)(100*degrees(euler.x)), // roll angle (centi-deg, displayed as deg due to format string)
1069  pitch : (int16_t)(100*degrees(euler.y)), // pitch angle (centi-deg, displayed as deg due to format string)
1070  yaw : (uint16_t)wrap_360_cd(100*degrees(euler.z)), // yaw angle (centi-deg, displayed as deg due to format string)
1071  velN : (float)(velNED.x), // velocity North (m/s)
1072  velE : (float)(velNED.y), // velocity East (m/s)
1073  velD : (float)(velNED.z), // velocity Down (m/s)
1074  posD_dot : (float)(posDownDeriv), // first derivative of down position
1075  posN : (float)(posNE.x), // metres North
1076  posE : (float)(posNE.y), // metres East
1077  posD : (float)(posD), // metres Down
1078  gyrX : (int16_t)(100*degrees(gyroBias.x)), // cd/sec, displayed as deg/sec due to format string
1079  gyrY : (int16_t)(100*degrees(gyroBias.y)), // cd/sec, displayed as deg/sec due to format string
1080  gyrZ : (int16_t)(100*degrees(gyroBias.z)), // cd/sec, displayed as deg/sec due to format string
1081  originHgt : originLLH.alt // WGS-84 altitude of EKF origin in cm
1082  };
1083  WriteBlock(&pkt6, sizeof(pkt6));
1084 
1085  // Write 7th EKF packet
1086  ahrs.get_NavEKF3().getAccelBias(1,accelBias);
1087  ahrs.get_NavEKF3().getWind(1,wind);
1088  ahrs.get_NavEKF3().getMagNED(1,magNED);
1089  ahrs.get_NavEKF3().getMagXYZ(1,magXYZ);
1090  magIndex = ahrs.get_NavEKF3().getActiveMag(1);
1091  struct log_NKF2a pkt7 = {
1093  time_us : time_us,
1094  accBiasX : (int16_t)(100*accelBias.x),
1095  accBiasY : (int16_t)(100*accelBias.y),
1096  accBiasZ : (int16_t)(100*accelBias.z),
1097  windN : (int16_t)(100*wind.x),
1098  windE : (int16_t)(100*wind.y),
1099  magN : (int16_t)(magNED.x),
1100  magE : (int16_t)(magNED.y),
1101  magD : (int16_t)(magNED.z),
1102  magX : (int16_t)(magXYZ.x),
1103  magY : (int16_t)(magXYZ.y),
1104  magZ : (int16_t)(magXYZ.z),
1105  index : (uint8_t)(magIndex)
1106  };
1107  WriteBlock(&pkt7, sizeof(pkt7));
1108 
1109  // Write 8th EKF packet
1110  ahrs.get_NavEKF3().getInnovations(1,velInnov, posInnov, magInnov, tasInnov, yawInnov);
1111  struct log_NKF3 pkt8 = {
1113  time_us : time_us,
1114  innovVN : (int16_t)(100*velInnov.x),
1115  innovVE : (int16_t)(100*velInnov.y),
1116  innovVD : (int16_t)(100*velInnov.z),
1117  innovPN : (int16_t)(100*posInnov.x),
1118  innovPE : (int16_t)(100*posInnov.y),
1119  innovPD : (int16_t)(100*posInnov.z),
1120  innovMX : (int16_t)(magInnov.x),
1121  innovMY : (int16_t)(magInnov.y),
1122  innovMZ : (int16_t)(magInnov.z),
1123  innovYaw : (int16_t)(100*degrees(yawInnov)),
1124  innovVT : (int16_t)(100*tasInnov)
1125  };
1126  WriteBlock(&pkt8, sizeof(pkt8));
1127 
1128  // Write 9th EKF packet
1129  ahrs.get_NavEKF3().getVariances(1,velVar, posVar, hgtVar, magVar, tasVar, offset);
1130  tempVar = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z);
1131  ahrs.get_NavEKF3().getFilterFaults(1,faultStatus);
1132  ahrs.get_NavEKF3().getFilterTimeouts(1,timeoutStatus);
1133  ahrs.get_NavEKF3().getFilterStatus(1,solutionStatus);
1134  ahrs.get_NavEKF3().getFilterGpsStatus(1,gpsStatus);
1135  ahrs.get_NavEKF3().getTiltError(1,tiltError);
1136  struct log_NKF4 pkt9 = {
1138  time_us : time_us,
1139  sqrtvarV : (int16_t)(100*velVar),
1140  sqrtvarP : (int16_t)(100*posVar),
1141  sqrtvarH : (int16_t)(100*hgtVar),
1142  sqrtvarM : (int16_t)(100*tempVar),
1143  sqrtvarVT : (int16_t)(100*tasVar),
1144  tiltErr : (float)tiltError,
1145  offsetNorth : (int8_t)(offset.x),
1146  offsetEast : (int8_t)(offset.y),
1147  faults : (uint16_t)(faultStatus),
1148  timeouts : (uint8_t)(timeoutStatus),
1149  solution : (uint16_t)(solutionStatus.value),
1150  gps : (uint16_t)(gpsStatus.value),
1151  primary : (int8_t)primaryIndex
1152  };
1153  WriteBlock(&pkt9, sizeof(pkt9));
1154 
1155  // log quaternion
1156  ahrs.get_NavEKF3().getQuaternion(1, quat);
1157  struct log_Quaternion pktq2 = {
1159  time_us : time_us,
1160  q1 : quat.q1,
1161  q2 : quat.q2,
1162  q3 : quat.q3,
1163  q4 : quat.q4
1164  };
1165  WriteBlock(&pktq2, sizeof(pktq2));
1166  }
1167  // write range beacon fusion debug packet if the range value is non-zero
1168  uint8_t ID;
1169  float rng;
1170  float innovVar;
1171  float innov;
1172  float testRatio;
1173  Vector3f beaconPosNED;
1174  float bcnPosOffsetHigh;
1175  float bcnPosOffsetLow;
1176  Vector3f posNED;
1177  if (ahrs.get_NavEKF3().getRangeBeaconDebug(-1, ID, rng, innov, innovVar, testRatio, beaconPosNED, bcnPosOffsetHigh, bcnPosOffsetLow, posNED)) {
1178  if (rng > 0.0f) {
1179  struct log_RngBcnDebug pkt10 = {
1181  time_us : time_us,
1182  ID : (uint8_t)ID,
1183  rng : (int16_t)(100*rng),
1184  innov : (int16_t)(100*innov),
1185  sqrtInnovVar : (uint16_t)(100*sqrtf(innovVar)),
1186  testRatio : (uint16_t)(100*constrain_float(testRatio,0.0f,650.0f)),
1187  beaconPosN : (int16_t)(100*beaconPosNED.x),
1188  beaconPosE : (int16_t)(100*beaconPosNED.y),
1189  beaconPosD : (int16_t)(100*beaconPosNED.z),
1190  offsetHigh : (int16_t)(100*bcnPosOffsetHigh),
1191  offsetLow : (int16_t)(100*bcnPosOffsetLow),
1192  posN : (int16_t)(100*posNED.x),
1193  posE : (int16_t)(100*posNED.y),
1194  posD : (int16_t)(100*posNED.z)
1195 
1196  };
1197  WriteBlock(&pkt10, sizeof(pkt10));
1198  }
1199  }
1200  // write debug data for body frame odometry fusion
1201  Vector3f velBodyInnov,velBodyInnovVar;
1202  static uint32_t lastUpdateTime_ms = 0;
1203  uint32_t updateTime_ms = ahrs.get_NavEKF3().getBodyFrameOdomDebug(-1, velBodyInnov, velBodyInnovVar);
1204  if (updateTime_ms > lastUpdateTime_ms) {
1205  struct log_ekfBodyOdomDebug pkt11 = {
1207  time_us : time_us,
1208  velInnovX : velBodyInnov.x,
1209  velInnovY : velBodyInnov.y,
1210  velInnovZ : velBodyInnov.z,
1211  velInnovVarX : velBodyInnovVar.x,
1212  velInnovVarY : velBodyInnovVar.y,
1213  velInnovVarZ : velBodyInnovVar.z
1214  };
1215  WriteBlock(&pkt11, sizeof(pkt11));
1216  lastUpdateTime_ms = updateTime_ms;
1217  }
1218 
1219  // log state variances every 0.49s
1220  static uint32_t lastEkfStateVarLogTime_ms = 0;
1221  if (AP_HAL::millis() - lastEkfStateVarLogTime_ms > 490) {
1222  lastEkfStateVarLogTime_ms = AP_HAL::millis();
1223  float stateVar[24];
1224  ahrs.get_NavEKF3().getStateVariances(-1, stateVar);
1225  struct log_ekfStateVar pktv1 = {
1227  time_us : time_us,
1228  v00 : stateVar[0],
1229  v01 : stateVar[1],
1230  v02 : stateVar[2],
1231  v03 : stateVar[3],
1232  v04 : stateVar[4],
1233  v05 : stateVar[5],
1234  v06 : stateVar[6],
1235  v07 : stateVar[7],
1236  v08 : stateVar[8],
1237  v09 : stateVar[9],
1238  v10 : stateVar[10],
1239  v11 : stateVar[11]
1240  };
1241  WriteBlock(&pktv1, sizeof(pktv1));
1242  struct log_ekfStateVar pktv2 = {
1244  time_us : time_us,
1245  v00 : stateVar[12],
1246  v01 : stateVar[13],
1247  v02 : stateVar[14],
1248  v03 : stateVar[15],
1249  v04 : stateVar[16],
1250  v05 : stateVar[17],
1251  v06 : stateVar[18],
1252  v07 : stateVar[19],
1253  v08 : stateVar[20],
1254  v09 : stateVar[21],
1255  v10 : stateVar[22],
1256  v11 : stateVar[23]
1257  };
1258  WriteBlock(&pktv2, sizeof(pktv2));
1259  }
1260 
1261 
1262  // log EKF timing statistics every 5s
1263  static uint32_t lastTimingLogTime_ms = 0;
1264  if (AP_HAL::millis() - lastTimingLogTime_ms > 5000) {
1265  lastTimingLogTime_ms = AP_HAL::millis();
1266  struct ekf_timing timing;
1267  for (uint8_t i=0; i<ahrs.get_NavEKF3().activeCores(); i++) {
1268  ahrs.get_NavEKF3().getTimingStatistics(i, timing);
1269  Log_Write_EKF_Timing(i==0?"XKT1":"XKT2", time_us, timing);
1270  }
1271  }
1272 }
1273 #endif
1274 
1275 // Write a command processing packet
1276 bool DataFlash_Backend::Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t& mav_cmd)
1277 {
1278  struct log_Cmd pkt = {
1281  command_total : (uint16_t)cmd_total,
1282  sequence : (uint16_t)mav_cmd.seq,
1283  command : (uint16_t)mav_cmd.command,
1284  param1 : (float)mav_cmd.param1,
1285  param2 : (float)mav_cmd.param2,
1286  param3 : (float)mav_cmd.param3,
1287  param4 : (float)mav_cmd.param4,
1288  latitude : (float)mav_cmd.x,
1289  longitude : (float)mav_cmd.y,
1290  altitude : (float)mav_cmd.z,
1291  frame : (uint8_t)mav_cmd.frame
1292  };
1293  return WriteBlock(&pkt, sizeof(pkt));
1294 }
1295 
1296 void DataFlash_Class::Log_Write_Radio(const mavlink_radio_t &packet)
1297 {
1298  struct log_Radio pkt = {
1301  rssi : packet.rssi,
1302  remrssi : packet.remrssi,
1303  txbuf : packet.txbuf,
1304  noise : packet.noise,
1305  remnoise : packet.remnoise,
1306  rxerrors : packet.rxerrors,
1307  fixed : packet.fixed
1308  };
1309  WriteBlock(&pkt, sizeof(pkt));
1310 }
1311 
1312 // Write a Camera packet
1313 void DataFlash_Class::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location &current_loc)
1314 {
1315  int32_t altitude, altitude_rel, altitude_gps;
1316  if (current_loc.flags.relative_alt) {
1317  altitude = current_loc.alt+ahrs.get_home().alt;
1318  altitude_rel = current_loc.alt;
1319  } else {
1320  altitude = current_loc.alt;
1321  altitude_rel = current_loc.alt - ahrs.get_home().alt;
1322  }
1323  const AP_GPS &gps = AP::gps();
1324  if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
1325  altitude_gps = gps.location().alt;
1326  } else {
1327  altitude_gps = 0;
1328  }
1329 
1330  struct log_Camera pkt = {
1331  LOG_PACKET_HEADER_INIT(static_cast<uint8_t>(msg)),
1333  gps_time : gps.time_week_ms(),
1334  gps_week : gps.time_week(),
1335  latitude : current_loc.lat,
1336  longitude : current_loc.lng,
1337  altitude : altitude,
1340  roll : (int16_t)ahrs.roll_sensor,
1341  pitch : (int16_t)ahrs.pitch_sensor,
1342  yaw : (uint16_t)ahrs.yaw_sensor
1343  };
1344  WriteCriticalBlock(&pkt, sizeof(pkt));
1345 }
1346 
1347 // Write a Camera packet
1348 void DataFlash_Class::Log_Write_Camera(const AP_AHRS &ahrs, const Location &current_loc)
1349 {
1350  Log_Write_CameraInfo(LOG_CAMERA_MSG, ahrs, current_loc);
1351 }
1352 
1353 // Write a Trigger packet
1354 void DataFlash_Class::Log_Write_Trigger(const AP_AHRS &ahrs, const Location &current_loc)
1355 {
1356  Log_Write_CameraInfo(LOG_TRIGGER_MSG, ahrs, current_loc);
1357 }
1358 
1359 // Write an attitude packet
1361 {
1362  struct log_Attitude pkt = {
1365  control_roll : (int16_t)targets.x,
1366  roll : (int16_t)ahrs.roll_sensor,
1367  control_pitch : (int16_t)targets.y,
1368  pitch : (int16_t)ahrs.pitch_sensor,
1369  control_yaw : (uint16_t)targets.z,
1370  yaw : (uint16_t)ahrs.yaw_sensor,
1371  error_rp : (uint16_t)(ahrs.get_error_rp() * 100),
1372  error_yaw : (uint16_t)(ahrs.get_error_yaw() * 100)
1373  };
1374  WriteBlock(&pkt, sizeof(pkt));
1375 }
1376 
1377 // Write an attitude packet
1379 {
1380  struct log_Attitude pkt = {
1383  control_roll : (int16_t)targets.x,
1384  roll : (int16_t)ahrs.roll_sensor,
1385  control_pitch : (int16_t)targets.y,
1386  pitch : (int16_t)ahrs.pitch_sensor,
1387  control_yaw : (uint16_t)targets.z,
1388  yaw : (uint16_t)ahrs.yaw_sensor,
1389  error_rp : (uint16_t)(ahrs.get_error_rp() * 100),
1390  error_yaw : (uint16_t)(ahrs.get_error_yaw() * 100)
1391  };
1392  WriteBlock(&pkt, sizeof(pkt));
1393 }
1394 
1396  const uint8_t battery_instance,
1397  const enum LogMessages type,
1398  const enum LogMessages celltype)
1399 {
1401  float temp;
1402  bool has_temp = battery.get_temperature(temp, battery_instance);
1403  struct log_Current pkt = {
1404  LOG_PACKET_HEADER_INIT(type),
1405  time_us : time_us,
1406  voltage : battery.voltage(battery_instance),
1407  voltage_resting : battery.voltage_resting_estimate(battery_instance),
1408  current_amps : battery.current_amps(battery_instance),
1409  current_total : battery.consumed_mah(battery_instance),
1410  consumed_wh : battery.consumed_wh(battery_instance),
1411  temperature : (int16_t)(has_temp ? (temp * 100) : 0),
1412  resistance : battery.get_resistance(battery_instance)
1413  };
1414  WriteBlock(&pkt, sizeof(pkt));
1415 
1416  // individual cell voltages
1417  if (battery.has_cell_voltages(battery_instance)) {
1418  const AP_BattMonitor::cells &cells = battery.get_cell_voltages(battery_instance);
1419  struct log_Current_Cells cell_pkt = {
1420  LOG_PACKET_HEADER_INIT(celltype),
1421  time_us : time_us,
1422  voltage : battery.voltage(battery_instance)
1423  };
1424  for (uint8_t i = 0; i < ARRAY_SIZE(cells.cells); i++) {
1425  cell_pkt.cell_voltages[i] = cells.cells[i] + 1;
1426  }
1427  WriteBlock(&cell_pkt, sizeof(cell_pkt));
1428 
1429  // check battery structure can hold all cells
1430  static_assert(ARRAY_SIZE(cells.cells) == (sizeof(cell_pkt.cell_voltages) / sizeof(cell_pkt.cell_voltages[0])),
1431  "Battery cell number doesn't match in library and log structure");
1432  }
1433 }
1434 
1435 // Write an Current data packet
1437 {
1438  const uint64_t time_us = AP_HAL::micros64();
1439  const uint8_t num_instances = AP::battery().num_instances();
1440  if (num_instances >= 1) {
1441  Log_Write_Current_instance(time_us,
1442  0,
1445  }
1446 
1447  if (num_instances >= 2) {
1448  Log_Write_Current_instance(time_us,
1449  1,
1452  }
1453 }
1454 
1455 void DataFlash_Class::Log_Write_Compass_instance(const Compass &compass, const uint64_t time_us, const uint8_t mag_instance, const enum LogMessages type)
1456 {
1457  const Vector3f &mag_field = compass.get_field(mag_instance);
1458  const Vector3f &mag_offsets = compass.get_offsets(mag_instance);
1459  const Vector3f &mag_motor_offsets = compass.get_motor_offsets(mag_instance);
1460  struct log_Compass pkt = {
1461  LOG_PACKET_HEADER_INIT(type),
1462  time_us : time_us,
1463  mag_x : (int16_t)mag_field.x,
1464  mag_y : (int16_t)mag_field.y,
1465  mag_z : (int16_t)mag_field.z,
1466  offset_x : (int16_t)mag_offsets.x,
1467  offset_y : (int16_t)mag_offsets.y,
1468  offset_z : (int16_t)mag_offsets.z,
1469  motor_offset_x : (int16_t)mag_motor_offsets.x,
1470  motor_offset_y : (int16_t)mag_motor_offsets.y,
1471  motor_offset_z : (int16_t)mag_motor_offsets.z,
1472  health : (uint8_t)compass.healthy(mag_instance),
1473  SUS : compass.last_update_usec(mag_instance)
1474  };
1475  WriteBlock(&pkt, sizeof(pkt));
1476 }
1477 
1478 // Write a Compass packet
1480 {
1481  if (time_us == 0) {
1482  time_us = AP_HAL::micros64();
1483  }
1484  Log_Write_Compass_instance(compass, time_us, 0, LOG_COMPASS_MSG);
1485 
1486  if (compass.get_count() > 1) {
1487  Log_Write_Compass_instance(compass, time_us, 1, LOG_COMPASS2_MSG);
1488  }
1489 
1490  if (compass.get_count() > 2) {
1491  Log_Write_Compass_instance(compass, time_us, 2, LOG_COMPASS3_MSG);
1492  }
1493 }
1494 
1495 // Write a mode packet.
1496 bool DataFlash_Backend::Log_Write_Mode(uint8_t mode, uint8_t reason)
1497 {
1498  struct log_Mode pkt = {
1501  mode : mode,
1502  mode_num : mode,
1503  mode_reason : reason
1504  };
1505  return WriteCriticalBlock(&pkt, sizeof(pkt));
1506 }
1507 
1508 // Write ESC status messages
1510 {
1511 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
1512  static int _esc_status_sub = -1;
1513  struct esc_status_s esc_status;
1514 
1515  if (_esc_status_sub == -1) {
1516  // subscribe to ORB topic on first call
1517  _esc_status_sub = orb_subscribe(ORB_ID(esc_status));
1518  }
1519 
1520  // check for new ESC status data
1521  bool esc_updated = false;
1522  orb_check(_esc_status_sub, &esc_updated);
1523  if (esc_updated && (OK == orb_copy(ORB_ID(esc_status), _esc_status_sub, &esc_status))) {
1524  if (esc_status.esc_count > 8) {
1525  esc_status.esc_count = 8;
1526  }
1527  uint64_t time_us = AP_HAL::micros64();
1528  for (uint8_t i = 0; i < esc_status.esc_count; i++) {
1529  // skip logging ESCs with a esc_address of zero, and this
1530  // are probably not populated. The Pixhawk itself should
1531  // be address zero
1532  if (esc_status.esc[i].esc_address != 0) {
1533  struct log_Esc pkt = {
1534  LOG_PACKET_HEADER_INIT((uint8_t)(LOG_ESC1_MSG + i)),
1535  time_us : time_us,
1536  rpm : (int32_t)(esc_status.esc[i].esc_rpm/10),
1537  voltage : (uint16_t)(esc_status.esc[i].esc_voltage*100.0f + .5f),
1538  current : (uint16_t)(esc_status.esc[i].esc_current*100.0f + .5f),
1539  temperature : (int16_t)(esc_status.esc[i].esc_temperature*100.0f + .5f),
1540  current_tot : 0
1541  };
1542 
1543  WriteBlock(&pkt, sizeof(pkt));
1544  }
1545  }
1546  }
1547 #endif // CONFIG_HAL_BOARD
1548 }
1549 
1550 // Write a AIRSPEED packet
1552 {
1553  uint64_t now = AP_HAL::micros64();
1554  for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {
1555  if (!airspeed.enabled(i)) {
1556  continue;
1557  }
1558  float temperature;
1559  if (!airspeed.get_temperature(i, temperature)) {
1560  temperature = 0;
1561  }
1562  struct log_AIRSPEED pkt = {
1564  time_us : now,
1565  airspeed : airspeed.get_raw_airspeed(i),
1567  temperature : (int16_t)(temperature * 100.0f),
1568  rawpressure : airspeed.get_corrected_pressure(i),
1569  offset : airspeed.get_offset(i),
1570  use : airspeed.use(i),
1571  healthy : airspeed.healthy(i),
1572  primary : airspeed.get_primary()
1573  };
1574  WriteBlock(&pkt, sizeof(pkt));
1575  }
1576 }
1577 
1578 // Write a Yaw PID packet
1579 void DataFlash_Class::Log_Write_PID(uint8_t msg_type, const PID_Info &info)
1580 {
1581  struct log_PID pkt = {
1582  LOG_PACKET_HEADER_INIT(msg_type),
1584  desired : info.desired,
1585  P : info.P,
1586  I : info.I,
1587  D : info.D,
1588  FF : info.FF,
1589  AFF : info.AFF
1590  };
1591  WriteBlock(&pkt, sizeof(pkt));
1592 }
1593 
1594 void DataFlash_Class::Log_Write_Origin(uint8_t origin_type, const Location &loc)
1595 {
1596  uint64_t time_us = AP_HAL::micros64();
1597  struct log_ORGN pkt = {
1599  time_us : time_us,
1601  latitude : loc.lat,
1602  longitude : loc.lng,
1603  altitude : loc.alt
1604  };
1605  WriteBlock(&pkt, sizeof(pkt));
1606 }
1607 
1609 {
1610  struct log_RPM pkt = {
1613  rpm1 : rpm_sensor.get_rpm(0),
1614  rpm2 : rpm_sensor.get_rpm(1)
1615  };
1616  WriteBlock(&pkt, sizeof(pkt));
1617 }
1618 
1619 // Write a rate packet
1621  const AP_Motors &motors,
1622  const AC_AttitudeControl &attitude_control,
1623  const AC_PosControl &pos_control)
1624 {
1625  const Vector3f &rate_targets = attitude_control.rate_bf_targets();
1626  const Vector3f &accel_target = pos_control.get_accel_target();
1627  struct log_Rate pkt_rate = {
1630  control_roll : degrees(rate_targets.x),
1631  roll : degrees(ahrs.get_gyro().x),
1632  roll_out : motors.get_roll(),
1633  control_pitch : degrees(rate_targets.y),
1634  pitch : degrees(ahrs.get_gyro().y),
1635  pitch_out : motors.get_pitch(),
1636  control_yaw : degrees(rate_targets.z),
1637  yaw : degrees(ahrs.get_gyro().z),
1638  yaw_out : motors.get_yaw(),
1639  control_accel : (float)accel_target.z,
1640  accel : (float)(-(ahrs.get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f),
1641  accel_out : motors.get_throttle()
1642  };
1643  WriteBlock(&pkt_rate, sizeof(pkt_rate));
1644 }
1645 
1646 // Write rally points
1648 {
1649  RallyLocation rally_point;
1650  for (uint8_t i=0; i<rally.get_rally_total(); i++) {
1651  if (rally.get_rally_point_with_index(i, rally_point)) {
1652  struct log_Rally pkt_rally = {
1655  total : rally.get_rally_total(),
1656  sequence : i,
1657  latitude : rally_point.lat,
1658  longitude : rally_point.lng,
1659  altitude : rally_point.alt
1660  };
1661  WriteBlock(&pkt_rally, sizeof(pkt_rally));
1662  }
1663  }
1664 }
1665 
1666 // Write visual odometry sensor data
1667 void DataFlash_Class::Log_Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
1668 {
1669  struct log_VisualOdom pkt_visualodom = {
1673  angle_delta_x : angle_delta.x,
1674  angle_delta_y : angle_delta.y,
1675  angle_delta_z : angle_delta.z,
1676  position_delta_x : position_delta.x,
1677  position_delta_y : position_delta.y,
1678  position_delta_z : position_delta.z,
1679  confidence : confidence
1680  };
1681  WriteBlock(&pkt_visualodom, sizeof(log_VisualOdom));
1682 }
1683 
1684 // Write AOA and SSA
1686 {
1687  struct log_AOA_SSA aoa_ssa = {
1690  AOA : ahrs.getAOA(),
1691  SSA : ahrs.getSSA()
1692  };
1693 
1694  WriteBlock(&aoa_ssa, sizeof(aoa_ssa));
1695 }
1696 
1697 // Write beacon sensor (position) data
1699 {
1700  if (!beacon.enabled()) {
1701  return;
1702  }
1703  // position
1704  Vector3f pos;
1705  float accuracy = 0.0f;
1706  beacon.get_vehicle_position_ned(pos, accuracy);
1707 
1708  struct log_Beacon pkt_beacon = {
1711  health : (uint8_t)beacon.healthy(),
1712  count : (uint8_t)beacon.count(),
1713  dist0 : beacon.beacon_distance(0),
1714  dist1 : beacon.beacon_distance(1),
1715  dist2 : beacon.beacon_distance(2),
1716  dist3 : beacon.beacon_distance(3),
1717  posx : pos.x,
1718  posy : pos.y,
1719  posz : pos.z
1720  };
1721  WriteBlock(&pkt_beacon, sizeof(pkt_beacon));
1722 }
1723 
1724 // Write proximity sensor distances
1726 {
1727  // exit immediately if not enabled
1728  if (proximity.get_status() == AP_Proximity::Proximity_NotConnected) {
1729  return;
1730  }
1731 
1733  proximity.get_horizontal_distances(dist_array);
1734 
1735  float dist_up;
1736  if (!proximity.get_upward_distance(dist_up)) {
1737  dist_up = 0.0f;
1738  }
1739 
1740  float close_ang = 0.0f, close_dist = 0.0f;
1741  proximity.get_closest_object(close_ang, close_dist);
1742 
1743  struct log_Proximity pkt_proximity = {
1746  health : (uint8_t)proximity.get_status(),
1747  dist0 : dist_array.distance[0],
1748  dist45 : dist_array.distance[1],
1749  dist90 : dist_array.distance[2],
1750  dist135 : dist_array.distance[3],
1751  dist180 : dist_array.distance[4],
1752  dist225 : dist_array.distance[5],
1753  dist270 : dist_array.distance[6],
1754  dist315 : dist_array.distance[7],
1755  distup : dist_up,
1756  closest_angle : close_ang,
1757  closest_dist : close_dist
1758  };
1759  WriteBlock(&pkt_proximity, sizeof(pkt_proximity));
1760 }
1761 
1762 void DataFlash_Class::Log_Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& breadcrumb)
1763 {
1764  struct log_SRTL pkt_srtl = {
1767  active : active,
1770  action : action,
1771  N : breadcrumb.x,
1772  E : breadcrumb.y,
1773  D : breadcrumb.z
1774  };
1775  WriteBlock(&pkt_srtl, sizeof(pkt_srtl));
1776 }
uint16_t sqrtInnovVar
Definition: LogStructure.h:554
uint8_t remrssi
Definition: LogStructure.h:628
void getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
int8_t offsetEast
Definition: LogStructure.h:500
char labels[64]
Definition: LogStructure.h:43
int16_t magZ
Definition: LogStructure.h:437
uint64_t time_us
Definition: LogStructure.h:163
uint64_t time_us
Definition: LogStructure.h:677
float position_delta_y
Definition: LogStructure.h:575
uint64_t time_us
Definition: LogStructure.h:286
bool get_soft_armed() const
Definition: Util.h:15
Definition: AP_GPS.h:48
float ground_temp
Definition: LogStructure.h:337
uint16_t chan4
Definition: LogStructure.h:290
uint8_t get_primary(void) const
Definition: AP_Airspeed.h:168
int16_t magY
Definition: LogStructure.h:419
AP_RangeFinder_Backend * get_backend(uint8_t id) const
int8_t offsetNorth
Definition: LogStructure.h:499
float get_climb_rate(void)
Definition: AP_Baro.cpp:319
uint16_t chan7
Definition: LogStructure.h:312
void getTiltError(int8_t instance, float &ang) const
Definition: AP_NavEKF3.cpp:887
uint64_t time_us
Definition: LogStructure.h:638
const char * units
Definition: LogStructure.h:23
float vibe_y
Definition: LogStructure.h:242
bool enabled(uint8_t i) const
Definition: AP_Airspeed.h:85
int16_t innovYaw
Definition: LogStructure.h:468
float AFF
Definition: LogStructure.h:672
uint32_t count
Definition: AP_Nav_Common.h:65
float rpm2
Definition: LogStructure.h:901
uint16_t current
Definition: LogStructure.h:834
uint32_t SUS
Definition: LogStructure.h:707
int16_t innovVN
Definition: LogStructure.h:459
void Log_Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets)
Definition: LogFile.cpp:1378
float position_delta_z
Definition: LogStructure.h:576
int32_t lng
Definition: AP_Rally.h:26
float dtIMUavg_max
Definition: AP_Nav_Common.h:67
uint8_t primary
Definition: LogStructure.h:849
uint16_t command
Definition: LogStructure.h:613
void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
uint8_t num_instances(void) const
Definition: AP_Baro.h:158
uint8_t health
Definition: LogStructure.h:706
bool Log_Write_Message(const char *message)
Definition: LogFile.cpp:426
const char * name
Definition: LogStructure.h:20
float accel_z
Definition: LogStructure.h:200
float pressure
Definition: LogStructure.h:332
uint8_t get_rally_total() const
Definition: AP_Rally.h:48
float dtEKFavg_min
Definition: AP_Nav_Common.h:68
void Log_Write_AOA_SSA(AP_AHRS &ahrs)
Definition: LogFile.cpp:1685
float delVelDT_max
Definition: AP_Nav_Common.h:72
uint64_t time_us
Definition: LogStructure.h:988
Object managing Rally Points.
Definition: AP_Rally.h:37
uint32_t gyro_error
Definition: LogStructure.h:201
uint16_t chan10
Definition: LogStructure.h:296
uint16_t chan6
Definition: LogStructure.h:292
float getAOA(void)
Definition: AP_AHRS.cpp:434
uint8_t timeouts
Definition: LogStructure.h:502
uint8_t index
Definition: LogStructure.h:438
uint64_t time_us
Definition: LogStructure.h:198
bool getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow, Vector3f &posNED) const
float vibe_x
Definition: LogStructure.h:242
AP_Beacon beacon
uint8_t getActiveMag(int8_t instance) const
Definition: AP_NavEKF2.cpp:947
void getTiltError(int8_t instance, float &ang) const
Definition: AP_NavEKF2.cpp:849
void Log_Write_Trigger(const AP_AHRS &ahrs, const Location &current_loc)
Definition: LogFile.cpp:1354
uint16_t chan8
Definition: LogStructure.h:294
float delAngDT_min
Definition: AP_Nav_Common.h:71
int16_t windN
Definition: LogStructure.h:430
float q1
Definition: quaternion.h:27
int16_t offsetHigh
Definition: LogStructure.h:559
void getMagNED(int8_t instance, Vector3f &magNED) const
Definition: AP_NavEKF2.cpp:929
void Log_Write_Current()
Definition: LogFile.cpp:1436
int32_t pitch_sensor
Definition: AP_AHRS_View.h:172
ap_var_type
Definition: AP_Param.h:124
float accel_y
Definition: LogStructure.h:200
virtual float board_voltage(void)=0
uint8_t gyro_health
Definition: LogStructure.h:203
uint16_t chan12
Definition: LogStructure.h:317
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
uint64_t time_us
Definition: LogStructure.h:180
uint8_t index
Definition: LogStructure.h:421
int16_t magZ
Definition: LogStructure.h:420
const Vector3f & get_accel_target() const
float accel_out
Definition: LogStructure.h:918
float get_rpm(uint8_t instance) const
Definition: AP_RPM.h:77
uint64_t time_us
Definition: LogStructure.h:330
int16_t magD
Definition: LogStructure.h:417
int16_t FIY
Definition: LogStructure.h:527
virtual const Vector3f & get_accel_ef_blended(void) const
Definition: AP_AHRS.h:201
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const
bool Log_Write_Format_Units(const struct LogStructure *structure)
Definition: LogFile.cpp:101
bool getPosNE(int8_t instance, Vector2f &posNE) const
Definition: AP_NavEKF2.cpp:781
uint8_t type
Definition: LogStructure.h:39
uint64_t time_us
Definition: LogStructure.h:492
enum Rotation orientation() const
virtual const Vector3f & get_gyro(void) const =0
int16_t innovPN
Definition: LogStructure.h:462
bool Log_Write_Format(const struct LogStructure *structure)
Definition: LogFile.cpp:60
float beacon_distance(uint8_t beacon_instance) const
Definition: AP_Beacon.cpp:204
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
uint64_t time_us
Definition: LogStructure.h:373
float delAngDT_max
Definition: AP_Nav_Common.h:70
uint64_t time_us
Definition: LogStructure.h:890
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void Log_Write_Airspeed(AP_Airspeed &airspeed)
Definition: LogFile.cpp:1551
uint8_t activeCores(void) const
Definition: AP_NavEKF2.h:50
virtual uint16_t read(uint8_t ch)=0
void getGyroScaleErrorPercentage(int8_t instance, Vector3f &gyroScale) const
Definition: AP_NavEKF2.cpp:840
bool Log_Write_Parameter(const char *name, float value)
Definition: LogFile.cpp:111
uint16_t distance_cm() const
int32_t altitude_rel
Definition: LogStructure.h:644
const Vector3f & get_motor_offsets(uint8_t i) const
Definition: AP_Compass.h:250
int16_t pitch
Definition: LogStructure.h:657
int32_t yaw_sensor
Definition: AP_AHRS_View.h:173
const char * multipliers
Definition: LogStructure.h:24
int16_t sqrtvarV
Definition: LogStructure.h:493
uint64_t time_us
Definition: LogStructure.h:458
uint8_t msg_type
Definition: LogStructure.h:18
uint64_t time_us
Definition: LogStructure.h:978
const Vector3f & get_gyro(uint8_t i) const
float get_temperature(void) const
Definition: AP_Baro.h:63
bool get_upward_distance(uint8_t instance, float &distance) const
int16_t beaconPosE
Definition: LogStructure.h:557
uint16_t chan9
Definition: LogStructure.h:314
float alt
Definition: LogStructure.h:357
float get_baro_drift_offset(void)
Definition: AP_Baro.h:167
virtual bool get_position(struct Location &loc) const =0
float gyro_x
Definition: LogStructure.h:199
float dtIMUavg_min
Definition: AP_Nav_Common.h:66
int16_t altitude
Definition: LogStructure.h:983
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
Definition: AP_Math.cpp:140
uint32_t getBodyFrameOdomDebug(int8_t instance, Vector3f &velInnov, Vector3f &velInnovVar) const
int32_t altitude
Definition: LogStructure.h:171
Object managing Mission.
Definition: AP_Mission.h:45
int16_t pitch
Definition: LogStructure.h:375
int32_t altitude
Definition: LogStructure.h:894
void getOutputTrackingError(int8_t instance, Vector3f &error) const
char name[16]
Definition: LogStructure.h:145
float rel_home_alt
Definition: LogStructure.h:358
uint32_t clipping_1
Definition: LogStructure.h:243
float param1
Definition: LogStructure.h:614
float read_receiver_rssi()
Definition: AP_RSSI.cpp:129
float q1
Definition: LogStructure.h:349
void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
float accel
Definition: LogStructure.h:917
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
bool getOriginLLH(int8_t instance, struct Location &loc) const
Definition: AP_NavEKF2.cpp:992
int32_t lat
Definition: LogStructure.h:347
const char ID
Definition: LogStructure.h:69
int16_t sqrtvarVT
Definition: LogStructure.h:497
uint16_t num_commands() const
Definition: AP_Mission.h:330
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
Definition: AP_NavEKF3.cpp:869
void Log_Write_Beacon(AP_Beacon &beacon)
Definition: LogFile.cpp:1698
float get_offset(uint8_t i) const
Definition: AP_Airspeed.h:105
float yaw
Definition: LogStructure.h:914
float posN
Definition: LogStructure.h:381
char msg[64]
Definition: LogStructure.h:193
uint16_t yaw
Definition: LogStructure.h:376
float velD
Definition: LogStructure.h:379
int16_t offset_x
Definition: LogStructure.h:700
int16_t beaconPosN
Definition: LogStructure.h:556
virtual float get_error_yaw(void) const =0
float posErr
Definition: LogStructure.h:536
void getFilterStatus(int8_t instance, nav_filter_status &status) const
void Log_Write_Rate(const AP_AHRS &ahrs, const AP_Motors &motors, const AC_AttitudeControl &attitude_control, const AC_PosControl &pos_control)
Definition: LogFile.cpp:1620
uint16_t time_week(uint8_t instance) const
Definition: AP_GPS.h:276
bool WriteCriticalBlock(const void *pBuffer, uint16_t size)
void Log_Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f &point)
Definition: LogFile.cpp:1762
void getEulerAngles(int8_t instance, Vector3f &eulers) const
float altitude
Definition: LogStructure.h:620
bool getPosD(int8_t instance, float &posD) const
Definition: AP_NavEKF2.cpp:793
void Log_Write_Proximity(AP_Proximity &proximity)
Definition: LogFile.cpp:1725
const struct UnitStructure * unit(uint8_t unit) const
float drift_offset
Definition: LogStructure.h:336
float get_temperature(uint8_t instance) const
AP_HAL::Util * util
Definition: HAL.h:115
int16_t offset_z
Definition: LogStructure.h:702
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
Definition: AP_NavEKF3.cpp:965
void getGyroBias(int8_t instance, Vector3f &gyroBias) const
Definition: AP_NavEKF2.cpp:831
uint8_t accel_health
Definition: LogStructure.h:203
float delta_vel_z
Definition: LogStructure.h:212
void Log_Write_ESC(void)
Definition: LogFile.cpp:1509
float q4
Definition: LogStructure.h:349
uint32_t last_message_time_ms(uint8_t instance) const
Definition: AP_GPS.h:310
bool Log_Write_Unit(const struct UnitStructure *s)
Definition: LogFile.cpp:70
uint16_t max_points
float longitude
Definition: LogStructure.h:619
float pitch
Definition: LogStructure.h:911
void getFlowDebug(int8_t instance, float &varFlow, float &gndOffset, float &flowInnovX, float &flowInnovY, float &auxInnov, float &HAGL, float &rngInnov, float &range, float &gndOffsetErr) const
virtual bool get_secondary_quaternion(Quaternion &quat) const
Definition: AP_AHRS.h:424
const char * format
Definition: LogStructure.h:21
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
int16_t RI
Definition: LogStructure.h:531
int16_t mag_z
Definition: LogStructure.h:699
uint64_t time_us
Definition: LogStructure.h:364
float Vcc
Definition: LogStructure.h:365
void Log_Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
Definition: LogFile.cpp:367
static void gps_time(uint16_t *time_week, uint32_t *time_week_ms)
Definition: sitl_gps.cpp:176
void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
float control_yaw
Definition: LogStructure.h:913
bool Log_Write_Mission_Cmd(const AP_Mission &mission, const AP_Mission::Mission_Command &cmd)
Definition: LogFile.cpp:409
void Log_Write_Radio(const mavlink_radio_t &packet)
Definition: LogFile.cpp:1296
int8_t AZbias
Definition: LogStructure.h:409
int32_t altitude_gps
Definition: LogStructure.h:645
void Log_Write_Compass_instance(const Compass &compass, uint64_t time_us, uint8_t mag_instance, enum LogMessages type)
Definition: LogFile.cpp:1455
float ground_course(uint8_t instance) const
Definition: AP_GPS.h:245
int16_t alt
Definition: AP_Rally.h:27
int16_t innovMY
Definition: LogStructure.h:466
bool has_cell_voltages()
int32_t latitude
Definition: LogStructure.h:641
const Location & location(uint8_t instance) const
Definition: AP_GPS.h:200
int16_t motor_offset_y
Definition: LogStructure.h:704
uint8_t mode_reason
Definition: LogStructure.h:715
const char * name
Definition: BusTest.cpp:11
AP_RSSI * rssi()
Definition: AP_RSSI.cpp:220
uint16_t last_message_delta_time_ms(uint8_t instance) const
Definition: AP_GPS.h:318
uint16_t chan11
Definition: LogStructure.h:297
int16_t windN
Definition: LogStructure.h:413
float ground_course
Definition: LogStructure.h:173
bool Log_Write_MavCmd(uint16_t cmd_total, const mavlink_mission_item_t &mav_cmd)
Definition: LogFile.cpp:1276
uint16_t yaw
Definition: LogStructure.h:648
uint16_t cells[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN]
float get_error_rp(void) const
Definition: AP_AHRS_View.h:158
int32_t lng
Definition: LogStructure.h:348
float vel_z
Definition: LogStructure.h:174
uint8_t normInnov
Definition: LogStructure.h:525
uint16_t current_tot
Definition: LogStructure.h:836
void Log_Write_PID(uint8_t msg_type, const PID_Info &info)
Definition: LogFile.cpp:1579
uint8_t activeCores(void) const
Definition: AP_NavEKF3.h:47
float delta_vel_y
Definition: LogStructure.h:212
uint32_t sample_ms
Definition: LogStructure.h:186
float q3
Definition: quaternion.h:27
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
#define MIN(a, b)
Definition: usb_conf.h:215
int16_t control_pitch
Definition: LogStructure.h:656
uint16_t sacc
Definition: LogStructure.h:184
int32_t roll_sensor
Definition: AP_AHRS.h:229
const char * labels
Definition: LogStructure.h:22
uint16_t chan3
Definition: LogStructure.h:308
uint32_t clipping_0
Definition: LogStructure.h:243
uint8_t format_type
Definition: LogStructure.h:63
int16_t magE
Definition: LogStructure.h:416
uint8_t txbuf
Definition: LogStructure.h:629
virtual uint16_t power_status_flags(void)
Definition: AnalogIn.h:52
int32_t longitude
Definition: LogStructure.h:642
float vibe_z
Definition: LogStructure.h:242
void getQuaternion(int8_t instance, Quaternion &quat) const
uint8_t total
Definition: LogStructure.h:979
uint8_t status
Definition: LogStructure.h:164
AP_MotorsMatrix motors(400)
int16_t magN
Definition: LogStructure.h:432
static AP_InertialSensor ins
Definition: AHRS_Test.cpp:18
float voltage_resting
Definition: LogStructure.h:679
const Vector3f & get_accel(uint8_t i) const
float consumed_wh(uint8_t instance) const
consumed_wh - returns total energy drawn since start-up in watt.hours
const Vector3f & get_field(uint8_t i) const
Return the current field as a Vector3f in milligauss.
Definition: AP_Compass.h:122
NavEKF3 & get_NavEKF3(void)
A system for managing and storing variables that are of general interest to the system.
float temperature
Definition: Airspeed.cpp:32
static bool mission_cmd_to_mavlink(const AP_Mission::Mission_Command &cmd, mavlink_mission_item_t &packet)
Definition: AP_Mission.cpp:973
T y
Definition: vector2.h:37
uint16_t chan13
Definition: LogStructure.h:299
float rpm1
Definition: LogStructure.h:900
uint64_t time_us
Definition: LogStructure.h:899
float delta_ang_z
Definition: LogStructure.h:211
uint8_t mode_num
Definition: LogStructure.h:714
uint16_t get_gyro_rate_hz(uint8_t instance) const
uint64_t time_us
Definition: LogStructure.h:626
int16_t magX
Definition: LogStructure.h:435
bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const
void getWind(int8_t instance, Vector3f &wind) const
Definition: AP_NavEKF2.cpp:920
uint8_t active
uint16_t chan13
Definition: LogStructure.h:318
int16_t sqrtvarH
Definition: LogStructure.h:495
float q2
Definition: LogStructure.h:349
#define HEAD_BYTE1
Definition: LogStructure.h:13
float param3
Definition: LogStructure.h:616
uint8_t orient1
Definition: LogStructure.h:725
uint8_t orient2
Definition: LogStructure.h:727
float rel_origin_alt
Definition: LogStructure.h:359
bool get_closest_object(float &angle_deg, float &distance) const
float rawpressure
Definition: LogStructure.h:845
uint8_t remnoise
Definition: LogStructure.h:631
int16_t accBiasX
Definition: LogStructure.h:427
uint16_t delta_ms
Definition: LogStructure.h:187
const Vector3f & velocity(uint8_t instance) const
Definition: AP_GPS.h:224
void Log_Write_RSSI(AP_RSSI &rssi)
Definition: LogFile.cpp:248
uint8_t mode
Definition: LogStructure.h:713
float gyro_z
Definition: LogStructure.h:199
int16_t magN
Definition: LogStructure.h:415
void Log_Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
Definition: LogFile.cpp:1667
int16_t mag_x
Definition: LogStructure.h:697
void getVelNED(int8_t instance, Vector3f &vel) const
Definition: AP_NavEKF3.cpp:841
int16_t accBiasZ
Definition: LogStructure.h:429
uint8_t safety_and_arm
Definition: LogStructure.h:368
ArduCopter attitude control library.
uint64_t time_us
Definition: LogStructure.h:324
float velErr
Definition: LogStructure.h:535
void Log_Write_Compass(const Compass &compass, uint64_t time_us=0)
Definition: LogFile.cpp:1479
float voltage_resting_estimate(uint8_t instance) const
int16_t innovPD
Definition: LogStructure.h:464
const char * unit
Definition: LogStructure.h:70
float ground_speed(uint8_t instance) const
Definition: AP_GPS.h:232
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
float diffpressure
Definition: LogStructure.h:843
int32_t pitch_sensor
Definition: AP_AHRS.h:230
void Log_Write_IMU_instance(uint64_t time_us, uint8_t imu_instance, enum LogMessages type)
Definition: LogFile.cpp:294
uint16_t chan7
Definition: LogStructure.h:293
bool use_gyro(uint8_t instance) const
int16_t scaleZ
Definition: LogStructure.h:412
uint8_t action
uint64_t time_us
Definition: LogStructure.h:569
void getInnovations(int8_t index, Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const
bool speed_accuracy(uint8_t instance, float &sacc) const
Definition: AP_GPS.cpp:316
int16_t gyrZ
Definition: LogStructure.h:386
#define GRAVITY_MSS
Definition: definitions.h:47
void Log_Write_Rally(const AP_Rally &rally)
Definition: LogFile.cpp:1647
float resistance
Definition: LogStructure.h:684
Proximity_Status get_status(uint8_t instance) const
bool get_vehicle_position_ned(Vector3f &pos, float &accuracy_estimate) const
Definition: AP_Beacon.cpp:149
void Log_Write_Camera(const AP_AHRS &ahrs, const Location &current_loc)
Definition: LogFile.cpp:1348
int16_t gyrY
Definition: LogStructure.h:385
uint64_t time_us
Definition: LogStructure.h:209
bool enabled(void)
Definition: AP_Beacon.cpp:101
#define f(i)
float desired
Definition: LogStructure.h:667
uint32_t get_accel_error_count(uint8_t i) const
void Log_Write_POS(AP_AHRS &ahrs)
Definition: LogFile.cpp:485
uint8_t frame
Definition: LogStructure.h:621
void Log_Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt)
Definition: LogFile.cpp:45
float getSSA(void)
Definition: AP_AHRS.cpp:441
uint16_t chan10
Definition: LogStructure.h:315
uint16_t fixed
Definition: LogStructure.h:633
int16_t windE
Definition: LogStructure.h:414
int16_t sqrtvarM
Definition: LogStructure.h:496
bool getPosD(int8_t instance, float &posD) const
Definition: AP_NavEKF3.cpp:831
T y
Definition: vector3.h:67
uint16_t control_yaw
Definition: LogStructure.h:658
int32_t longitude
Definition: LogStructure.h:893
float roll
Definition: LogStructure.h:908
uint64_t time_us
Definition: LogStructure.h:305
float delta_ang_dt
Definition: LogStructure.h:210
Vector3f rate_bf_targets() const
static AP_Baro baro
Definition: ModuleTest.cpp:18
int16_t control_roll
Definition: LogStructure.h:654
bool healthy(void)
Definition: AP_Beacon.cpp:107
uint32_t millis()
Definition: system.cpp:157
float control_roll
Definition: LogStructure.h:907
const Vector3f & get_offsets(uint8_t i) const
Definition: AP_Compass.h:166
uint32_t time_week_ms(uint8_t instance) const
Definition: AP_GPS.h:268
void getEulerAngles(int8_t instance, Vector3f &eulers) const
uint16_t dist1
Definition: LogStructure.h:724
void Log_Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
Definition: LogFile.cpp:1360
uint32_t gps_week_ms
Definition: LogStructure.h:165
float get_raw_airspeed(uint8_t i) const
Definition: AP_Airspeed.h:59
uint16_t hdop
Definition: LogStructure.h:168
Definition: AP_RPM.h:27
uint16_t chan5
Definition: LogStructure.h:291
int16_t magD
Definition: LogStructure.h:434
int16_t scaleX
Definition: LogStructure.h:410
T z
Definition: vector3.h:67
int16_t pitch
Definition: LogStructure.h:647
uint16_t rxerrors
Definition: LogStructure.h:632
uint8_t origin_type
Definition: LogStructure.h:891
float altitude
Definition: LogStructure.h:331
uint64_t micros64()
Definition: system.cpp:162
virtual float servorail_voltage(void)
Definition: AnalogIn.h:49
uint16_t chan14
Definition: LogStructure.h:319
uint16_t error_yaw
Definition: LogStructure.h:661
float get_corrected_pressure(uint8_t i) const
Definition: AP_Airspeed.h:111
void getVariances(int8_t instance, float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const
int8_t getPrimaryCoreIndex(void) const
Definition: AP_NavEKF2.cpp:760
virtual enum safety_state safety_switch_state(void)
Definition: Util.h:42
void Log_Write_Current_instance(uint64_t time_us, uint8_t battery_instance, enum LogMessages type, enum LogMessages celltype)
Definition: LogFile.cpp:1395
float latitude
Definition: LogStructure.h:618
uint64_t time_us
Definition: LogStructure.h:541
bool healthy[COMPASS_MAX_INSTANCES]
Definition: AP_Compass.h:301
uint64_t time_us
Definition: LogStructure.h:712
float Vservo
Definition: LogStructure.h:366
char name[4]
Definition: LogStructure.h:41
uint32_t get_accel_clip_count(uint8_t instance) const
float param2
Definition: LogStructure.h:615
float current_amps(uint8_t instance) const
current_amps - returns the instantaneous current draw in amperes
float delta_vel_x
Definition: LogStructure.h:212
uint16_t chan1
Definition: LogStructure.h:306
uint64_t time_us
Definition: LogStructure.h:524
void Log_Write_RCOUT(void)
Definition: LogFile.cpp:223
float D
Definition: LogStructure.h:670
virtual float get_error_rp(void) const =0
uint16_t get_hdop(uint8_t instance) const
Definition: AP_GPS.h:284
int16_t accBiasY
Definition: LogStructure.h:428
float get_roll() const
float dtEKFavg_max
Definition: AP_Nav_Common.h:69
void getFilterFaults(int8_t instance, uint16_t &faults) const
void Log_Write_AHRS2(AP_AHRS &ahrs)
Definition: LogFile.cpp:458
bool healthy(void) const
Definition: AP_Baro.h:52
float get_pressure(void) const
Definition: AP_Baro.h:59
uint16_t flags
Definition: LogStructure.h:367
float pitch_out
Definition: LogStructure.h:912
bool get_temperature(uint8_t i, float &temperature)
static Compass compass
Definition: AHRS_Test.cpp:20
int16_t pitch
Definition: LogStructure.h:344
GPS_Status status(uint8_t instance) const
Query GPS status.
Definition: AP_GPS.h:189
uint64_t time_us
Definition: LogStructure.h:995
uint64_t time_us
Definition: LogStructure.h:610
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
int16_t sqrtvarP
Definition: LogStructure.h:494
float delta_ang_x
Definition: LogStructure.h:211
float velN
Definition: LogStructure.h:377
void set_mission(const AP_Mission *mission)
uint64_t time_us
Definition: LogStructure.h:241
const struct MultiplierStructure * multiplier(uint8_t multiplier) const
float get_differential_pressure(uint8_t i) const
Definition: AP_Airspeed.h:99
float current_amps
Definition: LogStructure.h:680
uint8_t used
Definition: LogStructure.h:175
#define AIRSPEED_MAX_SENSORS
Definition: AP_Airspeed.h:11
int16_t roll
Definition: LogStructure.h:655
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
uint16_t chan1
Definition: LogStructure.h:287
void Log_Write_EntireMission(const AP_Mission &mission)
Definition: LogFile.cpp:417
int32_t altitude
Definition: LogStructure.h:643
float get_delta_time() const
uint64_t time_us
Definition: LogStructure.h:192
uint16_t dist2
Definition: LogStructure.h:726
AP_BattMonitor & battery()
float position_delta_x
Definition: LogStructure.h:574
int32_t longitude
Definition: LogStructure.h:982
int32_t rpm
Definition: LogStructure.h:832
void Log_Write_GPS(uint8_t instance, uint64_t time_us=0)
Definition: LogFile.cpp:136
uint16_t hacc
Definition: LogStructure.h:182
uint64_t time_us
Definition: LogStructure.h:62
void getFilterGpsStatus(int8_t instance, nav_gps_status &faults) const
virtual void set_dataflash_backend(class DataFlash_Backend *backend)
uint16_t get_vdop(uint8_t instance) const
Definition: AP_GPS.h:292
bool get_horizontal_distances(Proximity_Distance_Array &prx_dist_array) const
uint8_t get_count(void) const
Definition: AP_Compass.h:119
int32_t lng
Definition: LogStructure.h:356
uint16_t gps_week
Definition: LogStructure.h:640
int16_t windE
Definition: LogStructure.h:431
int16_t innovMX
Definition: LogStructure.h:465
void Log_Write_RPM(const AP_RPM &rpm_sensor)
Definition: LogFile.cpp:1608
void getFilterFaults(int8_t instance, uint16_t &faults) const
uint16_t errHAGL
Definition: LogStructure.h:533
uint16_t accel_rate
Definition: LogStructure.h:204
AP_Airspeed airspeed
Definition: Airspeed.cpp:34
void Log_Write_EKF_Timing(const char *name, uint64_t time_us, const struct ekf_timing &timing)
float posD_dot
Definition: LogStructure.h:380
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt)
Definition: LogFile.cpp:29
bool get_rally_point_with_index(uint8_t i, RallyLocation &ret) const
Definition: AP_Rally.cpp:59
float RXRSSI
Definition: LogStructure.h:325
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
uint8_t length
Definition: LogStructure.h:40
T x
Definition: vector2.h:37
int16_t roll
Definition: LogStructure.h:646
char multipliers[16]
Definition: LogStructure.h:65
float get_altitude(void) const
Definition: AP_Baro.h:84
uint64_t time_us
Definition: LogStructure.h:666
uint8_t health
Definition: LogStructure.h:996
float P
Definition: LogStructure.h:668
void Log_Write_Power(void)
Definition: LogFile.cpp:437
float get_yaw() const
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
int16_t magX
Definition: LogStructure.h:418
void getMagNED(int8_t instance, Vector3f &magNED) const
Definition: AP_NavEKF3.cpp:956
int16_t beaconPosD
Definition: LogStructure.h:558
uint8_t num_sats(uint8_t instance) const
Definition: AP_GPS.h:260
uint32_t last_update_usec(void) const
Definition: AP_Compass.h:289
float get_delta_angle_dt(uint8_t i) const
NavEKF2 & get_NavEKF2(void)
bool getPosNE(int8_t instance, Vector2f &posNE) const
Definition: AP_NavEKF3.cpp:819
uint8_t num_sats
Definition: LogStructure.h:167
uint64_t time_us
Definition: LogStructure.h:342
uint16_t faults
Definition: LogStructure.h:501
int16_t innovPE
Definition: LogStructure.h:463
float cast_to_float(enum ap_var_type type) const
cast a variable to a float given its type
Definition: AP_Param.cpp:1587
void Log_Write_Origin(uint8_t origin_type, const Location &loc)
Definition: LogFile.cpp:1594
float ground_speed
Definition: LogStructure.h:172
float control_accel
Definition: LogStructure.h:916
int32_t lat
Definition: LogStructure.h:355
void getFilterTimeouts(int8_t instance, uint8_t &timeouts) const
float get_delta_velocity_dt(uint8_t i) const
void getQuaternion(int8_t instance, Quaternion &quat) const
uint32_t clipping_2
Definition: LogStructure.h:243
int8_t getPrimaryCoreIndex(void) const
Definition: AP_NavEKF3.cpp:798
void getVelNED(int8_t instance, Vector3f &vel) const
Definition: AP_NavEKF2.cpp:803
float angErr
Definition: LogStructure.h:534
uint16_t chan14
Definition: LogStructure.h:300
uint16_t vacc
Definition: LogStructure.h:183
float posE
Definition: LogStructure.h:382
int32_t latitude
Definition: LogStructure.h:169
void Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location &current_loc)
Definition: LogFile.cpp:1313
float alt
Definition: LogStructure.h:346
uint64_t time_us
Definition: LogStructure.h:593
uint16_t gps_week
Definition: LogStructure.h:166
float q4
Definition: quaternion.h:27
#define N
char format[16]
Definition: LogStructure.h:42
float velE
Definition: LogStructure.h:378
uint16_t num_points
char type
Definition: LogStructure.h:49
int16_t roll
Definition: LogStructure.h:343
float delta_vel_dt
Definition: LogStructure.h:210
uint16_t solution
Definition: LogStructure.h:503
bool getOriginLLH(int8_t instance, struct Location &loc) const
uint8_t primary_sensor(void) const
Definition: AP_GPS.h:184
void getTimingStatistics(int8_t instance, struct ekf_timing &timing) const
int16_t mag_y
Definition: LogStructure.h:698
float voltage
static uint16_t get_radio_in(const uint8_t chan)
uint16_t chan11
Definition: LogStructure.h:316
uint32_t accel_error
Definition: LogStructure.h:201
int16_t motor_offset_x
Definition: LogStructure.h:703
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
uint8_t have_vv
Definition: LogStructure.h:185
uint64_t time_us
Definition: LogStructure.h:831
int32_t latitude
Definition: LogStructure.h:981
virtual bool get_secondary_attitude(Vector3f &eulers) const
Definition: AP_AHRS.h:419
void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar=false) const
Definition: AP_Param.cpp:714
float value
float get_ground_temperature(void) const
Definition: AP_Baro.cpp:331
virtual bool get_secondary_position(struct Location &loc) const
Definition: AP_AHRS.h:429
uint8_t get_gyro_count(void) const
const AP_Beacon * get_beacon(void) const
Definition: AP_AHRS.h:178
uint16_t yaw
Definition: LogStructure.h:659
bool get_temperature(float &temperature) const
uint64_t time_us
Definition: LogStructure.h:144
uint32_t sample_time_ms
Definition: LogStructure.h:335
float I
Definition: LogStructure.h:669
const double multiplier
Definition: LogStructure.h:75
AP_InertialSensor & ins()
AP_GPS & gps()
Definition: AP_GPS.cpp:1550
void getStateVariances(int8_t instance, float stateVar[24]) const
uint16_t command_total
Definition: LogStructure.h:611
uint16_t chan2
Definition: LogStructure.h:307
bool get_gyro_health(uint8_t instance) const
uint64_t time_us
Definition: LogStructure.h:841
float get_pitch() const
float q3
Definition: LogStructure.h:349
float tiltErr
Definition: LogStructure.h:498
int16_t innovMZ
Definition: LogStructure.h:467
int16_t scaleY
Definition: LogStructure.h:411
void Log_Write_RFND(const RangeFinder &rangefinder)
Definition: LogFile.cpp:182
uint8_t sequence
Definition: LogStructure.h:980
static AP_GPS gps
Definition: AHRS_Test.cpp:22
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
float getPosDownDerivative(int8_t instance) const
Definition: AP_NavEKF3.cpp:850
#define degrees(x)
Definition: moduletest.c:23
uint16_t chan9
Definition: LogStructure.h:295
int16_t HAGL
Definition: LogStructure.h:529
uint64_t time_us
AP_Baro & baro()
Definition: AP_Baro.cpp:737
uint64_t time_us
Definition: LogStructure.h:653
float get_throttle() const
uint16_t chan4
Definition: LogStructure.h:309
int32_t lat
Definition: AP_Rally.h:25
float get_error_yaw(void) const
Definition: AP_AHRS_View.h:164
uint64_t time_us
Definition: LogStructure.h:354
uint16_t chan5
Definition: LogStructure.h:310
uint32_t get_gyro_error_count(uint8_t i) const
uint64_t time_us
Definition: LogStructure.h:48
void getAccelBias(int8_t instance, Vector3f &accelBias) const
Definition: AP_NavEKF3.cpp:878
float control_pitch
Definition: LogStructure.h:910
void getWind(int8_t instance, Vector3f &wind) const
Definition: AP_NavEKF3.cpp:947
float getPosDownDerivative(int8_t instance) const
Definition: AP_NavEKF2.cpp:812
uint64_t time_us
Definition: LogStructure.h:408
bool Log_Write(uint8_t msg_type, va_list arg_list, bool is_critical=false)
int8_t primary
Definition: LogStructure.h:505
void Log_Write_IMUDT_instance(uint64_t time_us, uint8_t imu_instance, enum LogMessages type)
Definition: LogFile.cpp:341
uint16_t sequence
Definition: LogStructure.h:612
int32_t roll_sensor
Definition: AP_AHRS_View.h:171
bool vertical_accuracy(uint8_t instance, float &vacc) const
Definition: AP_GPS.cpp:334
uint8_t num_instances(void) const
int32_t longitude
Definition: LogStructure.h:170
int16_t motor_offset_z
Definition: LogStructure.h:705
void getOutputTrackingError(int8_t instance, Vector3f &error) const
void Log_Write_Vibration()
Definition: LogFile.cpp:390
float delta_ang_y
Definition: LogStructure.h:211
bool WriteBlock(const void *pBuffer, uint16_t size)
float voltage(uint8_t instance) const
voltage - returns battery voltage in millivolts
float consumed_mah(uint8_t instance) const
consumed_mah - returns total current drawn since start-up in milliampere.hours
Vector3f get_vibration_levels() const
int16_t gyrX
Definition: LogStructure.h:384
float get_resistance() const
uint64_t time_us
Definition: LogStructure.h:426
void getFilterStatus(int8_t instance, nav_filter_status &status) const
uint64_t time_us
void getAccelZBias(int8_t instance, float &zbias) const
Definition: AP_NavEKF2.cpp:911
int32_t yaw_sensor
Definition: AP_AHRS.h:231
bool healthy(uint8_t i) const
Definition: AP_Airspeed.h:135
int16_t roll
Definition: LogStructure.h:374
uint16_t chan3
Definition: LogStructure.h:289
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
LogMessages
static float noise(void)
Definition: Derivative.cpp:21
float delVelDT_min
Definition: AP_Nav_Common.h:73
float gyro_y
Definition: LogStructure.h:199
void getMagXYZ(int8_t instance, Vector3f &magXYZ) const
Definition: AP_NavEKF2.cpp:938
bool horizontal_accuracy(uint8_t instance, float &hacc) const
Definition: AP_GPS.cpp:325
void Log_Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
Definition: LogFile.cpp:258
float roll_out
Definition: LogStructure.h:909
int16_t innovVE
Definition: LogStructure.h:460
int16_t magE
Definition: LogStructure.h:433
int16_t offset_y
Definition: LogStructure.h:701
uint16_t chan6
Definition: LogStructure.h:311
uint16_t chan12
Definition: LogStructure.h:298
uint16_t chan8
Definition: LogStructure.h:313
int32_t latitude
Definition: LogStructure.h:892
uint8_t msg_len
Definition: LogStructure.h:19
uint16_t cell_voltages[10]
Definition: LogStructure.h:691
int16_t innovVT
Definition: LogStructure.h:469
virtual void get_relative_position_D_home(float &posD) const =0
float consumed_wh
Definition: LogStructure.h:682
uint8_t count() const
Definition: AP_Beacon.cpp:167
virtual bool get_relative_position_D_origin(float &posD) const
Definition: AP_AHRS.h:354
uint16_t error_rp
Definition: LogStructure.h:660
uint16_t vdop
Definition: LogStructure.h:181
int32_t originHgt
Definition: LogStructure.h:387
float yaw_out
Definition: LogStructure.h:915
float FF
Definition: LogStructure.h:671
uint32_t get_last_update(void) const
Definition: AP_Baro.h:116
int16_t AFI
Definition: LogStructure.h:528
char unit[64]
Definition: LogStructure.h:50
uint64_t time_us
Definition: LogStructure.h:906
float param4
Definition: LogStructure.h:617
uint64_t time_us
Definition: LogStructure.h:550
uint16_t yaw
Definition: LogStructure.h:345
void Log_Write_RCIN(void)
Definition: LogFile.cpp:199
uint16_t gyro_rate
Definition: LogStructure.h:204
float q2
Definition: quaternion.h:27
int16_t FIX
Definition: LogStructure.h:526
void Log_Write_Baro(uint64_t time_us=0)
Definition: LogFile.cpp:279
void Log_Write_IMU()
Definition: LogFile.cpp:320
bool getRangeBeaconDebug(int8_t instance, uint8_t &ID, float &rng, float &innov, float &innovVar, float &testRatio, Vector3f &beaconPosNED, float &offsetHigh, float &offsetLow) const
T x
Definition: vector3.h:67
bool Log_Write_Multiplier(const struct MultiplierStructure *s)
Definition: LogFile.cpp:86
uint8_t get_accel_count(void) const
int16_t innovVD
Definition: LogStructure.h:461
uint8_t getActiveMag(int8_t instance) const
Definition: AP_NavEKF3.cpp:974
float posD
Definition: LogStructure.h:383
int16_t magY
Definition: LogStructure.h:436
float accel_x
Definition: LogStructure.h:200
uint64_t time_us
Definition: LogStructure.h:696
const cells & get_cell_voltages() const
bool get_accel_health(uint8_t instance) const
uint16_t chan2
Definition: LogStructure.h:288
uint16_t meaRng
Definition: LogStructure.h:532
uint64_t time_us
Definition: LogStructure.h:723
bool have_vertical_velocity(uint8_t instance) const
Definition: AP_GPS.h:326
uint16_t get_accel_rate_hz(uint8_t instance) const
#define HEAD_BYTE2
Definition: LogStructure.h:14
float current_total
Definition: LogStructure.h:681
float delta_time
Definition: LogStructure.h:210
bool Log_Write_Mode(uint8_t mode, uint8_t reason=0)
Definition: LogFile.cpp:1496
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
AP_Int8 use
Definition: AP_Airspeed.h:181