LogFile.cpp 33 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005
  1. #include <stdlib.h>
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_Baro/AP_Baro.h>
  4. #include <AP_BattMonitor/AP_BattMonitor.h>
  5. #include <AP_Compass/AP_Compass.h>
  6. #include <AP_HAL/AP_HAL.h>
  7. #include <AP_Math/AP_Math.h>
  8. #include <AP_Param/AP_Param.h>
  9. #include <AP_Motors/AP_Motors.h>
  10. #include <AC_AttitudeControl/AC_AttitudeControl.h>
  11. #include <AC_AttitudeControl/AC_PosControl.h>
  12. #include <AP_RSSI/AP_RSSI.h>
  13. #include <AP_GPS/AP_GPS.h>
  14. #include "AP_Logger.h"
  15. #include "AP_Logger_File.h"
  16. #include "AP_Logger_MAVLink.h"
  17. #include "LoggerMessageWriter.h"
  18. extern const AP_HAL::HAL& hal;
  19. /*
  20. write a structure format to the log - should be in frontend
  21. */
  22. void AP_Logger_Backend::Fill_Format(const struct LogStructure *s, struct log_Format &pkt)
  23. {
  24. memset(&pkt, 0, sizeof(pkt));
  25. pkt.head1 = HEAD_BYTE1;
  26. pkt.head2 = HEAD_BYTE2;
  27. pkt.msgid = LOG_FORMAT_MSG;
  28. pkt.type = s->msg_type;
  29. pkt.length = s->msg_len;
  30. strncpy(pkt.name, s->name, sizeof(pkt.name));
  31. strncpy(pkt.format, s->format, sizeof(pkt.format));
  32. strncpy(pkt.labels, s->labels, sizeof(pkt.labels));
  33. }
  34. /*
  35. Pack a LogStructure packet into a structure suitable to go to the logfile:
  36. */
  37. void AP_Logger_Backend::Fill_Format_Units(const struct LogStructure *s, struct log_Format_Units &pkt)
  38. {
  39. memset(&pkt, 0, sizeof(pkt));
  40. pkt.head1 = HEAD_BYTE1;
  41. pkt.head2 = HEAD_BYTE2;
  42. pkt.msgid = LOG_FORMAT_UNITS_MSG;
  43. pkt.time_us = AP_HAL::micros64();
  44. pkt.format_type = s->msg_type;
  45. strncpy(pkt.units, s->units, sizeof(pkt.units));
  46. strncpy(pkt.multipliers, s->multipliers, sizeof(pkt.multipliers));
  47. }
  48. /*
  49. write a structure format to the log
  50. */
  51. bool AP_Logger_Backend::Write_Format(const struct LogStructure *s)
  52. {
  53. struct log_Format pkt;
  54. Fill_Format(s, pkt);
  55. return WriteCriticalBlock(&pkt, sizeof(pkt));
  56. }
  57. /*
  58. write a unit definition
  59. */
  60. bool AP_Logger_Backend::Write_Unit(const struct UnitStructure *s)
  61. {
  62. struct log_Unit pkt{
  63. LOG_PACKET_HEADER_INIT(LOG_UNIT_MSG),
  64. time_us : AP_HAL::micros64(),
  65. type : s->ID,
  66. unit : { }
  67. };
  68. strncpy(pkt.unit, s->unit, sizeof(pkt.unit));
  69. return WriteCriticalBlock(&pkt, sizeof(pkt));
  70. }
  71. /*
  72. write a unit-multiplier definition
  73. */
  74. bool AP_Logger_Backend::Write_Multiplier(const struct MultiplierStructure *s)
  75. {
  76. const struct log_Format_Multiplier pkt{
  77. LOG_PACKET_HEADER_INIT(LOG_MULT_MSG),
  78. time_us : AP_HAL::micros64(),
  79. type : s->ID,
  80. multiplier : s->multiplier,
  81. };
  82. return WriteCriticalBlock(&pkt, sizeof(pkt));
  83. }
  84. /*
  85. write the units for a format to the log
  86. */
  87. bool AP_Logger_Backend::Write_Format_Units(const struct LogStructure *s)
  88. {
  89. struct log_Format_Units pkt;
  90. Fill_Format_Units(s, pkt);
  91. return WriteCriticalBlock(&pkt, sizeof(pkt));
  92. }
  93. /*
  94. write a parameter to the log
  95. */
  96. bool AP_Logger_Backend::Write_Parameter(const char *name, float value)
  97. {
  98. struct log_Parameter pkt{
  99. LOG_PACKET_HEADER_INIT(LOG_PARAMETER_MSG),
  100. time_us : AP_HAL::micros64(),
  101. name : {},
  102. value : value
  103. };
  104. strncpy(pkt.name, name, sizeof(pkt.name));
  105. return WriteCriticalBlock(&pkt, sizeof(pkt));
  106. }
  107. /*
  108. write a parameter to the log
  109. */
  110. bool AP_Logger_Backend::Write_Parameter(const AP_Param *ap,
  111. const AP_Param::ParamToken &token,
  112. enum ap_var_type type)
  113. {
  114. char name[16];
  115. ap->copy_name_token(token, &name[0], sizeof(name), true);
  116. return Write_Parameter(name, ap->cast_to_float(type));
  117. }
  118. // Write an GPS packet
  119. void AP_Logger::Write_GPS(uint8_t i, uint64_t time_us)
  120. {
  121. const AP_GPS &gps = AP::gps();
  122. if (time_us == 0) {
  123. time_us = AP_HAL::micros64();
  124. }
  125. const struct Location &loc = gps.location(i);
  126. float yaw_deg=0, yaw_accuracy_deg=0;
  127. gps.gps_yaw_deg(i, yaw_deg, yaw_accuracy_deg);
  128. const struct log_GPS pkt = {
  129. LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GPS_MSG+i)),
  130. time_us : time_us,
  131. status : (uint8_t)gps.status(i),
  132. gps_week_ms : gps.time_week_ms(i),
  133. gps_week : gps.time_week(i),
  134. num_sats : gps.num_sats(i),
  135. hdop : gps.get_hdop(i),
  136. latitude : loc.lat,
  137. longitude : loc.lng,
  138. altitude : loc.alt,
  139. ground_speed : gps.ground_speed(i),
  140. ground_course : gps.ground_course(i),
  141. vel_z : gps.velocity(i).z,
  142. yaw : yaw_deg,
  143. used : (uint8_t)(gps.primary_sensor() == i)
  144. };
  145. WriteBlock(&pkt, sizeof(pkt));
  146. /* write auxiliary accuracy information as well */
  147. float hacc = 0, vacc = 0, sacc = 0;
  148. gps.horizontal_accuracy(i, hacc);
  149. gps.vertical_accuracy(i, vacc);
  150. gps.speed_accuracy(i, sacc);
  151. struct log_GPA pkt2{
  152. LOG_PACKET_HEADER_INIT((uint8_t)(LOG_GPA_MSG+i)),
  153. time_us : time_us,
  154. vdop : gps.get_vdop(i),
  155. hacc : (uint16_t)MIN((hacc*100), UINT16_MAX),
  156. vacc : (uint16_t)MIN((vacc*100), UINT16_MAX),
  157. sacc : (uint16_t)MIN((sacc*100), UINT16_MAX),
  158. have_vv : (uint8_t)gps.have_vertical_velocity(i),
  159. sample_ms : gps.last_message_time_ms(i),
  160. delta_ms : gps.last_message_delta_time_ms(i)
  161. };
  162. WriteBlock(&pkt2, sizeof(pkt2));
  163. }
  164. // Write an RCIN packet
  165. void AP_Logger::Write_RCIN(void)
  166. {
  167. uint16_t values[14] = {};
  168. rc().get_radio_in(values, ARRAY_SIZE(values));
  169. const struct log_RCIN pkt{
  170. LOG_PACKET_HEADER_INIT(LOG_RCIN_MSG),
  171. time_us : AP_HAL::micros64(),
  172. chan1 : values[0],
  173. chan2 : values[1],
  174. chan3 : values[2],
  175. chan4 : values[3],
  176. chan5 : values[4],
  177. chan6 : values[5],
  178. chan7 : values[6],
  179. chan8 : values[7],
  180. chan9 : values[8],
  181. chan10 : values[9],
  182. chan11 : values[10],
  183. chan12 : values[11],
  184. chan13 : values[12],
  185. chan14 : values[13]
  186. };
  187. WriteBlock(&pkt, sizeof(pkt));
  188. }
  189. // Write an SERVO packet
  190. void AP_Logger::Write_RCOUT(void)
  191. {
  192. const struct log_RCOUT pkt{
  193. LOG_PACKET_HEADER_INIT(LOG_RCOUT_MSG),
  194. time_us : AP_HAL::micros64(),
  195. chan1 : hal.rcout->read(0),
  196. chan2 : hal.rcout->read(1),
  197. chan3 : hal.rcout->read(2),
  198. chan4 : hal.rcout->read(3),
  199. chan5 : hal.rcout->read(4),
  200. chan6 : hal.rcout->read(5),
  201. chan7 : hal.rcout->read(6),
  202. chan8 : hal.rcout->read(7),
  203. chan9 : hal.rcout->read(8),
  204. chan10 : hal.rcout->read(9),
  205. chan11 : hal.rcout->read(10),
  206. chan12 : hal.rcout->read(11),
  207. chan13 : hal.rcout->read(12),
  208. chan14 : hal.rcout->read(13)
  209. };
  210. WriteBlock(&pkt, sizeof(pkt));
  211. }
  212. // Write an RSSI packet
  213. void AP_Logger::Write_RSSI()
  214. {
  215. AP_RSSI *rssi = AP::rssi();
  216. if (rssi == nullptr) {
  217. return;
  218. }
  219. const struct log_RSSI pkt{
  220. LOG_PACKET_HEADER_INIT(LOG_RSSI_MSG),
  221. time_us : AP_HAL::micros64(),
  222. RXRSSI : rssi->read_receiver_rssi()
  223. };
  224. WriteBlock(&pkt, sizeof(pkt));
  225. }
  226. void AP_Logger::Write_Baro_instance(uint64_t time_us, uint8_t baro_instance, enum LogMessages type)
  227. {
  228. AP_Baro &baro = AP::baro();
  229. float climbrate = baro.get_climb_rate();
  230. float drift_offset = baro.get_baro_drift_offset();
  231. float ground_temp = baro.get_ground_temperature();
  232. const struct log_BARO pkt{
  233. LOG_PACKET_HEADER_INIT(type),
  234. time_us : time_us,
  235. altitude : baro.get_altitude(baro_instance),
  236. pressure : baro.get_pressure(baro_instance),
  237. temperature : (int16_t)(baro.get_temperature(baro_instance) * 100 + 0.5f),
  238. climbrate : climbrate,
  239. sample_time_ms: baro.get_last_update(baro_instance),
  240. drift_offset : drift_offset,
  241. ground_temp : ground_temp,
  242. healthy : (uint8_t)baro.healthy(baro_instance)
  243. };
  244. WriteBlock(&pkt, sizeof(pkt));
  245. }
  246. // Write a BARO packet
  247. void AP_Logger::Write_Baro(uint64_t time_us)
  248. {
  249. if (time_us == 0) {
  250. time_us = AP_HAL::micros64();
  251. }
  252. const AP_Baro &baro = AP::baro();
  253. Write_Baro_instance(time_us, 0, LOG_BARO_MSG);
  254. if (baro.num_instances() > 1 && baro.healthy(1)) {
  255. Write_Baro_instance(time_us, 1, LOG_BAR2_MSG);
  256. }
  257. if (baro.num_instances() > 2 && baro.healthy(2)) {
  258. Write_Baro_instance(time_us, 2, LOG_BAR3_MSG);
  259. }
  260. }
  261. void AP_Logger::Write_IMU_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type)
  262. {
  263. const AP_InertialSensor &ins = AP::ins();
  264. const Vector3f &gyro = ins.get_gyro(imu_instance);
  265. const Vector3f &accel = ins.get_accel(imu_instance);
  266. const struct log_IMU pkt{
  267. LOG_PACKET_HEADER_INIT(type),
  268. time_us : time_us,
  269. gyro_x : gyro.x,
  270. gyro_y : gyro.y,
  271. gyro_z : gyro.z,
  272. accel_x : accel.x,
  273. accel_y : accel.y,
  274. accel_z : accel.z,
  275. gyro_error : ins.get_gyro_error_count(imu_instance),
  276. accel_error : ins.get_accel_error_count(imu_instance),
  277. temperature : ins.get_temperature(imu_instance),
  278. gyro_health : (uint8_t)ins.get_gyro_health(imu_instance),
  279. accel_health : (uint8_t)ins.get_accel_health(imu_instance),
  280. gyro_rate : ins.get_gyro_rate_hz(imu_instance),
  281. accel_rate : ins.get_accel_rate_hz(imu_instance),
  282. };
  283. WriteBlock(&pkt, sizeof(pkt));
  284. }
  285. // Write an raw accel/gyro data packet
  286. void AP_Logger::Write_IMU()
  287. {
  288. uint64_t time_us = AP_HAL::micros64();
  289. const AP_InertialSensor &ins = AP::ins();
  290. Write_IMU_instance(time_us, 0, LOG_IMU_MSG);
  291. if (ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) {
  292. return;
  293. }
  294. Write_IMU_instance(time_us, 1, LOG_IMU2_MSG);
  295. if (ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) {
  296. return;
  297. }
  298. Write_IMU_instance(time_us, 2, LOG_IMU3_MSG);
  299. }
  300. // Write an accel/gyro delta time data packet
  301. void AP_Logger::Write_IMUDT_instance(const uint64_t time_us, const uint8_t imu_instance, const enum LogMessages type)
  302. {
  303. const AP_InertialSensor &ins = AP::ins();
  304. float delta_t = ins.get_delta_time();
  305. float delta_vel_t = ins.get_delta_velocity_dt(imu_instance);
  306. float delta_ang_t = ins.get_delta_angle_dt(imu_instance);
  307. Vector3f delta_angle, delta_velocity;
  308. ins.get_delta_angle(imu_instance, delta_angle);
  309. ins.get_delta_velocity(imu_instance, delta_velocity);
  310. const struct log_IMUDT pkt{
  311. LOG_PACKET_HEADER_INIT(type),
  312. time_us : time_us,
  313. delta_time : delta_t,
  314. delta_vel_dt : delta_vel_t,
  315. delta_ang_dt : delta_ang_t,
  316. delta_ang_x : delta_angle.x,
  317. delta_ang_y : delta_angle.y,
  318. delta_ang_z : delta_angle.z,
  319. delta_vel_x : delta_velocity.x,
  320. delta_vel_y : delta_velocity.y,
  321. delta_vel_z : delta_velocity.z
  322. };
  323. WriteBlock(&pkt, sizeof(pkt));
  324. }
  325. void AP_Logger::Write_IMUDT(uint64_t time_us, uint8_t imu_mask)
  326. {
  327. const AP_InertialSensor &ins = AP::ins();
  328. if (imu_mask & 1) {
  329. Write_IMUDT_instance(time_us, 0, LOG_IMUDT_MSG);
  330. }
  331. if ((ins.get_gyro_count() < 2 && ins.get_accel_count() < 2) || !ins.use_gyro(1)) {
  332. return;
  333. }
  334. if (imu_mask & 2) {
  335. Write_IMUDT_instance(time_us, 1, LOG_IMUDT2_MSG);
  336. }
  337. if ((ins.get_gyro_count() < 3 && ins.get_accel_count() < 3) || !ins.use_gyro(2)) {
  338. return;
  339. }
  340. if (imu_mask & 4) {
  341. Write_IMUDT_instance(time_us, 2, LOG_IMUDT3_MSG);
  342. }
  343. }
  344. void AP_Logger::Write_Vibration()
  345. {
  346. uint64_t time_us = AP_HAL::micros64();
  347. const AP_InertialSensor &ins = AP::ins();
  348. const Vector3f vibration = ins.get_vibration_levels();
  349. const struct log_Vibe pkt{
  350. LOG_PACKET_HEADER_INIT(LOG_VIBE_MSG),
  351. time_us : time_us,
  352. vibe_x : vibration.x,
  353. vibe_y : vibration.y,
  354. vibe_z : vibration.z,
  355. clipping_0 : ins.get_accel_clip_count(0),
  356. clipping_1 : ins.get_accel_clip_count(1),
  357. clipping_2 : ins.get_accel_clip_count(2)
  358. };
  359. WriteBlock(&pkt, sizeof(pkt));
  360. }
  361. void AP_Logger::Write_Command(const mavlink_command_int_t &packet,
  362. const MAV_RESULT result,
  363. bool was_command_long)
  364. {
  365. const struct log_MAVLink_Command pkt{
  366. LOG_PACKET_HEADER_INIT(LOG_MAVLINK_COMMAND_MSG),
  367. time_us : AP_HAL::micros64(),
  368. target_system : packet.target_system,
  369. target_component: packet.target_component,
  370. frame : packet.frame,
  371. command : packet.command,
  372. current : packet.current,
  373. autocontinue : packet.autocontinue,
  374. param1 : packet.param1,
  375. param2 : packet.param2,
  376. param3 : packet.param3,
  377. param4 : packet.param4,
  378. x : packet.x,
  379. y : packet.y,
  380. z : packet.z,
  381. result : (uint8_t)result,
  382. was_command_long:was_command_long,
  383. };
  384. return WriteBlock(&pkt, sizeof(pkt));
  385. }
  386. bool AP_Logger_Backend::Write_Mission_Cmd(const AP_Mission &mission,
  387. const AP_Mission::Mission_Command &cmd)
  388. {
  389. mavlink_mission_item_int_t mav_cmd = {};
  390. AP_Mission::mission_cmd_to_mavlink_int(cmd,mav_cmd);
  391. const struct log_Cmd pkt{
  392. LOG_PACKET_HEADER_INIT(LOG_CMD_MSG),
  393. time_us : AP_HAL::micros64(),
  394. command_total : mission.num_commands(),
  395. sequence : mav_cmd.seq,
  396. command : mav_cmd.command,
  397. param1 : mav_cmd.param1,
  398. param2 : mav_cmd.param2,
  399. param3 : mav_cmd.param3,
  400. param4 : mav_cmd.param4,
  401. latitude : mav_cmd.x,
  402. longitude : mav_cmd.y,
  403. altitude : mav_cmd.z,
  404. frame : mav_cmd.frame
  405. };
  406. return WriteBlock(&pkt, sizeof(pkt));
  407. }
  408. void AP_Logger_Backend::Write_EntireMission()
  409. {
  410. LoggerMessageWriter_WriteEntireMission writer{};
  411. writer.set_logger_backend(this);
  412. writer.process();
  413. }
  414. // Write a text message to the log
  415. bool AP_Logger_Backend::Write_Message(const char *message)
  416. {
  417. struct log_Message pkt{
  418. LOG_PACKET_HEADER_INIT(LOG_MESSAGE_MSG),
  419. time_us : AP_HAL::micros64(),
  420. msg : {}
  421. };
  422. strncpy(pkt.msg, message, sizeof(pkt.msg));
  423. return WriteCriticalBlock(&pkt, sizeof(pkt));
  424. }
  425. void AP_Logger::Write_Power(void)
  426. {
  427. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  428. uint8_t safety_and_armed = uint8_t(hal.util->safety_switch_state());
  429. if (hal.util->get_soft_armed()) {
  430. // encode armed state in bit 3
  431. safety_and_armed |= 1U<<2;
  432. }
  433. const struct log_POWR pkt{
  434. LOG_PACKET_HEADER_INIT(LOG_POWR_MSG),
  435. time_us : AP_HAL::micros64(),
  436. Vcc : hal.analogin->board_voltage(),
  437. Vservo : hal.analogin->servorail_voltage(),
  438. flags : hal.analogin->power_status_flags(),
  439. safety_and_arm : safety_and_armed
  440. };
  441. WriteBlock(&pkt, sizeof(pkt));
  442. #endif
  443. }
  444. // Write an AHRS2 packet
  445. void AP_Logger::Write_AHRS2(AP_AHRS &ahrs)
  446. {
  447. Vector3f euler;
  448. struct Location loc;
  449. Quaternion quat;
  450. if (!ahrs.get_secondary_attitude(euler) || !ahrs.get_secondary_position(loc) || !ahrs.get_secondary_quaternion(quat)) {
  451. return;
  452. }
  453. const struct log_AHRS pkt{
  454. LOG_PACKET_HEADER_INIT(LOG_AHR2_MSG),
  455. time_us : AP_HAL::micros64(),
  456. roll : (int16_t)(degrees(euler.x)*100),
  457. pitch : (int16_t)(degrees(euler.y)*100),
  458. yaw : (uint16_t)(wrap_360_cd(degrees(euler.z)*100)),
  459. alt : loc.alt*1.0e-2f,
  460. lat : loc.lat,
  461. lng : loc.lng,
  462. q1 : quat.q1,
  463. q2 : quat.q2,
  464. q3 : quat.q3,
  465. q4 : quat.q4,
  466. };
  467. WriteBlock(&pkt, sizeof(pkt));
  468. }
  469. // Write a POS packet
  470. void AP_Logger::Write_POS(AP_AHRS &ahrs)
  471. {
  472. Location loc;
  473. if (!ahrs.get_position(loc)) {
  474. return;
  475. }
  476. float home, origin;
  477. ahrs.get_relative_position_D_home(home);
  478. const struct log_POS pkt{
  479. LOG_PACKET_HEADER_INIT(LOG_POS_MSG),
  480. time_us : AP_HAL::micros64(),
  481. lat : loc.lat,
  482. lng : loc.lng,
  483. alt : loc.alt*1.0e-2f,
  484. rel_home_alt : -home,
  485. rel_origin_alt : ahrs.get_relative_position_D_origin(origin) ? -origin : quiet_nanf(),
  486. };
  487. WriteBlock(&pkt, sizeof(pkt));
  488. }
  489. void AP_Logger::Write_Radio(const mavlink_radio_t &packet)
  490. {
  491. const struct log_Radio pkt{
  492. LOG_PACKET_HEADER_INIT(LOG_RADIO_MSG),
  493. time_us : AP_HAL::micros64(),
  494. rssi : packet.rssi,
  495. remrssi : packet.remrssi,
  496. txbuf : packet.txbuf,
  497. noise : packet.noise,
  498. remnoise : packet.remnoise,
  499. rxerrors : packet.rxerrors,
  500. fixed : packet.fixed
  501. };
  502. WriteBlock(&pkt, sizeof(pkt));
  503. }
  504. // Write a Camera packet
  505. void AP_Logger::Write_CameraInfo(enum LogMessages msg, const Location &current_loc, uint64_t timestamp_us)
  506. {
  507. const AP_AHRS &ahrs = AP::ahrs();
  508. int32_t altitude, altitude_rel, altitude_gps;
  509. if (current_loc.relative_alt) {
  510. altitude = current_loc.alt+ahrs.get_home().alt;
  511. altitude_rel = current_loc.alt;
  512. } else {
  513. altitude = current_loc.alt;
  514. altitude_rel = current_loc.alt - ahrs.get_home().alt;
  515. }
  516. const AP_GPS &gps = AP::gps();
  517. if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
  518. altitude_gps = gps.location().alt;
  519. } else {
  520. altitude_gps = 0;
  521. }
  522. const struct log_Camera pkt{
  523. LOG_PACKET_HEADER_INIT(static_cast<uint8_t>(msg)),
  524. time_us : timestamp_us?timestamp_us:AP_HAL::micros64(),
  525. gps_time : gps.time_week_ms(),
  526. gps_week : gps.time_week(),
  527. latitude : current_loc.lat,
  528. longitude : current_loc.lng,
  529. altitude : altitude,
  530. altitude_rel: altitude_rel,
  531. altitude_gps: altitude_gps,
  532. roll : (int16_t)ahrs.roll_sensor,
  533. pitch : (int16_t)ahrs.pitch_sensor,
  534. yaw : (uint16_t)ahrs.yaw_sensor
  535. };
  536. WriteCriticalBlock(&pkt, sizeof(pkt));
  537. }
  538. // Write a Camera packet
  539. void AP_Logger::Write_Camera(const Location &current_loc, uint64_t timestamp_us)
  540. {
  541. Write_CameraInfo(LOG_CAMERA_MSG, current_loc, timestamp_us);
  542. }
  543. // Write a Trigger packet
  544. void AP_Logger::Write_Trigger(const Location &current_loc)
  545. {
  546. Write_CameraInfo(LOG_TRIGGER_MSG, current_loc, 0);
  547. }
  548. // Write an attitude packet
  549. void AP_Logger::Write_Attitude(AP_AHRS &ahrs, const Vector3f &targets)
  550. {
  551. const struct log_Attitude pkt{
  552. LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
  553. time_us : AP_HAL::micros64(),
  554. control_roll : (int16_t)targets.x,
  555. roll : (int16_t)ahrs.roll_sensor,
  556. control_pitch : (int16_t)targets.y,
  557. pitch : (int16_t)ahrs.pitch_sensor,
  558. control_yaw : (uint16_t)wrap_360_cd(targets.z),
  559. yaw : (uint16_t)wrap_360_cd(ahrs.yaw_sensor),
  560. error_rp : (uint16_t)(ahrs.get_error_rp() * 100),
  561. error_yaw : (uint16_t)(ahrs.get_error_yaw() * 100)
  562. };
  563. WriteBlock(&pkt, sizeof(pkt));
  564. }
  565. // Write an attitude packet
  566. void AP_Logger::Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets)
  567. {
  568. const struct log_Attitude pkt{
  569. LOG_PACKET_HEADER_INIT(LOG_ATTITUDE_MSG),
  570. time_us : AP_HAL::micros64(),
  571. control_roll : (int16_t)targets.x,
  572. roll : (int16_t)ahrs.roll_sensor,
  573. control_pitch : (int16_t)targets.y,
  574. pitch : (int16_t)ahrs.pitch_sensor,
  575. control_yaw : (uint16_t)wrap_360_cd(targets.z),
  576. yaw : (uint16_t)wrap_360_cd(ahrs.yaw_sensor),
  577. error_rp : (uint16_t)(ahrs.get_error_rp() * 100),
  578. error_yaw : (uint16_t)(ahrs.get_error_yaw() * 100)
  579. };
  580. WriteBlock(&pkt, sizeof(pkt));
  581. }
  582. void AP_Logger::Write_Current_instance(const uint64_t time_us,
  583. const uint8_t battery_instance,
  584. const enum LogMessages type,
  585. const enum LogMessages celltype)
  586. {
  587. AP_BattMonitor &battery = AP::battery();
  588. float temp;
  589. bool has_temp = battery.get_temperature(temp, battery_instance);
  590. float current, consumed_mah, consumed_wh;
  591. if (!battery.current_amps(current, battery_instance)) {
  592. current = quiet_nanf();
  593. }
  594. if (!battery.consumed_mah(consumed_mah, battery_instance)) {
  595. consumed_mah = quiet_nanf();
  596. }
  597. if (!battery.consumed_wh(consumed_wh, battery_instance)) {
  598. consumed_wh = quiet_nanf();
  599. }
  600. const struct log_Current pkt = {
  601. LOG_PACKET_HEADER_INIT(type),
  602. time_us : time_us,
  603. voltage : battery.voltage(battery_instance),
  604. voltage_resting : battery.voltage_resting_estimate(battery_instance),
  605. current_amps : current,
  606. current_total : consumed_mah,
  607. consumed_wh : consumed_wh,
  608. temperature : (int16_t)(has_temp ? (temp * 100) : 0),
  609. resistance : battery.get_resistance(battery_instance)
  610. };
  611. WriteBlock(&pkt, sizeof(pkt));
  612. // individual cell voltages
  613. if (battery.has_cell_voltages(battery_instance)) {
  614. const AP_BattMonitor::cells &cells = battery.get_cell_voltages(battery_instance);
  615. struct log_Current_Cells cell_pkt{
  616. LOG_PACKET_HEADER_INIT(celltype),
  617. time_us : time_us,
  618. voltage : battery.voltage(battery_instance)
  619. };
  620. for (uint8_t i = 0; i < ARRAY_SIZE(cells.cells); i++) {
  621. cell_pkt.cell_voltages[i] = cells.cells[i] + 1;
  622. }
  623. WriteBlock(&cell_pkt, sizeof(cell_pkt));
  624. // check battery structure can hold all cells
  625. static_assert(ARRAY_SIZE(cells.cells) == (sizeof(cell_pkt.cell_voltages) / sizeof(cell_pkt.cell_voltages[0])),
  626. "Battery cell number doesn't match in library and log structure");
  627. }
  628. }
  629. // Write an Current data packet
  630. void AP_Logger::Write_Current()
  631. {
  632. // Big painful assert to ensure that logging won't produce suprising results when the
  633. // number of battery monitors changes, does have the built in expectation that
  634. // LOG_COMPASS_MSG follows the last LOG_CURRENT_CELLSx_MSG
  635. static_assert(((LOG_CURRENT_MSG + AP_BATT_MONITOR_MAX_INSTANCES) == LOG_CURRENT_CELLS_MSG) &&
  636. ((LOG_CURRENT_CELLS_MSG + AP_BATT_MONITOR_MAX_INSTANCES) == LOG_COMPASS_MSG),
  637. "The number of batt monitors has changed without updating the log "
  638. "table entries. Please add new enums for LOG_CURRENT_MSG, LOG_CURRENT_CELLS_MSG "
  639. "directly following the highest indexed fields. Don't forget to update the log "
  640. "description table as well.");
  641. const uint64_t time_us = AP_HAL::micros64();
  642. const uint8_t num_instances = AP::battery().num_instances();
  643. for (uint8_t i = 0; i < num_instances; i++) {
  644. Write_Current_instance(time_us,
  645. i,
  646. (LogMessages)((uint8_t)LOG_CURRENT_MSG + i),
  647. (LogMessages)((uint8_t)LOG_CURRENT_CELLS_MSG + i));
  648. }
  649. }
  650. void AP_Logger::Write_Compass_instance(const uint64_t time_us, const uint8_t mag_instance, const enum LogMessages type)
  651. {
  652. const Compass &compass = AP::compass();
  653. const Vector3f &mag_field = compass.get_field(mag_instance);
  654. const Vector3f &mag_offsets = compass.get_offsets(mag_instance);
  655. const Vector3f &mag_motor_offsets = compass.get_motor_offsets(mag_instance);
  656. const struct log_Compass pkt{
  657. LOG_PACKET_HEADER_INIT(type),
  658. time_us : time_us,
  659. mag_x : (int16_t)mag_field.x,
  660. mag_y : (int16_t)mag_field.y,
  661. mag_z : (int16_t)mag_field.z,
  662. offset_x : (int16_t)mag_offsets.x,
  663. offset_y : (int16_t)mag_offsets.y,
  664. offset_z : (int16_t)mag_offsets.z,
  665. motor_offset_x : (int16_t)mag_motor_offsets.x,
  666. motor_offset_y : (int16_t)mag_motor_offsets.y,
  667. motor_offset_z : (int16_t)mag_motor_offsets.z,
  668. health : (uint8_t)compass.healthy(mag_instance),
  669. SUS : compass.last_update_usec(mag_instance)
  670. };
  671. WriteBlock(&pkt, sizeof(pkt));
  672. }
  673. // Write a Compass packet
  674. void AP_Logger::Write_Compass(uint64_t time_us)
  675. {
  676. if (time_us == 0) {
  677. time_us = AP_HAL::micros64();
  678. }
  679. const Compass &compass = AP::compass();
  680. if (compass.get_count() > 0) {
  681. Write_Compass_instance(time_us, 0, LOG_COMPASS_MSG);
  682. }
  683. if (compass.get_count() > 1) {
  684. Write_Compass_instance(time_us, 1, LOG_COMPASS2_MSG);
  685. }
  686. if (compass.get_count() > 2) {
  687. Write_Compass_instance(time_us, 2, LOG_COMPASS3_MSG);
  688. }
  689. }
  690. // Write a mode packet.
  691. bool AP_Logger_Backend::Write_Mode(uint8_t mode, uint8_t reason)
  692. {
  693. const struct log_Mode pkt{
  694. LOG_PACKET_HEADER_INIT(LOG_MODE_MSG),
  695. time_us : AP_HAL::micros64(),
  696. mode : mode,
  697. mode_num : mode,
  698. mode_reason : reason
  699. };
  700. return WriteCriticalBlock(&pkt, sizeof(pkt));
  701. }
  702. // Write ESC status messages
  703. // id starts from 0
  704. // rpm is eRPM (rpm * 100)
  705. // voltage is in centi-volts
  706. // current is in centi-amps
  707. // temperature is in centi-degrees Celsius
  708. // current_tot is in centi-amp hours
  709. void AP_Logger::Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t temperature, uint16_t current_tot)
  710. {
  711. // sanity check id
  712. if (id >= 8) {
  713. return;
  714. }
  715. const struct log_Esc pkt{
  716. LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC1_MSG+id)),
  717. time_us : time_us,
  718. rpm : rpm,
  719. voltage : voltage,
  720. current : current,
  721. temperature : temperature,
  722. current_tot : current_tot
  723. };
  724. WriteBlock(&pkt, sizeof(pkt));
  725. }
  726. // Write a Yaw PID packet
  727. void AP_Logger::Write_PID(uint8_t msg_type, const PID_Info &info)
  728. {
  729. const struct log_PID pkt{
  730. LOG_PACKET_HEADER_INIT(msg_type),
  731. time_us : AP_HAL::micros64(),
  732. target : info.target,
  733. actual : info.actual,
  734. error : info.error,
  735. P : info.P,
  736. I : info.I,
  737. D : info.D,
  738. FF : info.FF
  739. };
  740. WriteBlock(&pkt, sizeof(pkt));
  741. }
  742. void AP_Logger::Write_Origin(uint8_t origin_type, const Location &loc)
  743. {
  744. const struct log_ORGN pkt{
  745. LOG_PACKET_HEADER_INIT(LOG_ORGN_MSG),
  746. time_us : AP_HAL::micros64(),
  747. origin_type : origin_type,
  748. latitude : loc.lat,
  749. longitude : loc.lng,
  750. altitude : loc.alt
  751. };
  752. WriteBlock(&pkt, sizeof(pkt));
  753. }
  754. void AP_Logger::Write_RPM(const AP_RPM &rpm_sensor)
  755. {
  756. const struct log_RPM pkt{
  757. LOG_PACKET_HEADER_INIT(LOG_RPM_MSG),
  758. time_us : AP_HAL::micros64(),
  759. rpm1 : rpm_sensor.get_rpm(0),
  760. rpm2 : rpm_sensor.get_rpm(1)
  761. };
  762. WriteBlock(&pkt, sizeof(pkt));
  763. }
  764. // Write a rate packet
  765. void AP_Logger::Write_Rate(const AP_AHRS_View *ahrs,
  766. const AP_Motors &motors,
  767. const AC_AttitudeControl &attitude_control,
  768. const AC_PosControl &pos_control)
  769. {
  770. const Vector3f &rate_targets = attitude_control.rate_bf_targets();
  771. const Vector3f &accel_target = pos_control.get_accel_target();
  772. const struct log_Rate pkt_rate{
  773. LOG_PACKET_HEADER_INIT(LOG_RATE_MSG),
  774. time_us : AP_HAL::micros64(),
  775. control_roll : degrees(rate_targets.x),
  776. roll : degrees(ahrs->get_gyro().x),
  777. roll_out : motors.get_roll(),
  778. control_pitch : degrees(rate_targets.y),
  779. pitch : degrees(ahrs->get_gyro().y),
  780. pitch_out : motors.get_pitch(),
  781. control_yaw : degrees(rate_targets.z),
  782. yaw : degrees(ahrs->get_gyro().z),
  783. yaw_out : motors.get_yaw(),
  784. control_accel : (float)accel_target.z,
  785. accel : (float)(-(ahrs->get_accel_ef_blended().z + GRAVITY_MSS) * 100.0f),
  786. accel_out : motors.get_throttle()
  787. };
  788. WriteBlock(&pkt_rate, sizeof(pkt_rate));
  789. }
  790. // Write visual odometry sensor data
  791. void AP_Logger::Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence)
  792. {
  793. const struct log_VisualOdom pkt_visualodom{
  794. LOG_PACKET_HEADER_INIT(LOG_VISUALODOM_MSG),
  795. time_us : AP_HAL::micros64(),
  796. time_delta : time_delta,
  797. angle_delta_x : angle_delta.x,
  798. angle_delta_y : angle_delta.y,
  799. angle_delta_z : angle_delta.z,
  800. position_delta_x : position_delta.x,
  801. position_delta_y : position_delta.y,
  802. position_delta_z : position_delta.z,
  803. confidence : confidence
  804. };
  805. WriteBlock(&pkt_visualodom, sizeof(log_VisualOdom));
  806. }
  807. // Write AOA and SSA
  808. void AP_Logger::Write_AOA_SSA(AP_AHRS &ahrs)
  809. {
  810. const struct log_AOA_SSA aoa_ssa{
  811. LOG_PACKET_HEADER_INIT(LOG_AOA_SSA_MSG),
  812. time_us : AP_HAL::micros64(),
  813. AOA : ahrs.getAOA(),
  814. SSA : ahrs.getSSA()
  815. };
  816. WriteBlock(&aoa_ssa, sizeof(aoa_ssa));
  817. }
  818. // Write beacon sensor (position) data
  819. void AP_Logger::Write_Beacon(AP_Beacon &beacon)
  820. {
  821. if (!beacon.enabled()) {
  822. return;
  823. }
  824. // position
  825. Vector3f pos;
  826. float accuracy = 0.0f;
  827. beacon.get_vehicle_position_ned(pos, accuracy);
  828. const struct log_Beacon pkt_beacon{
  829. LOG_PACKET_HEADER_INIT(LOG_BEACON_MSG),
  830. time_us : AP_HAL::micros64(),
  831. health : (uint8_t)beacon.healthy(),
  832. count : (uint8_t)beacon.count(),
  833. dist0 : beacon.beacon_distance(0),
  834. dist1 : beacon.beacon_distance(1),
  835. dist2 : beacon.beacon_distance(2),
  836. dist3 : beacon.beacon_distance(3),
  837. posx : pos.x,
  838. posy : pos.y,
  839. posz : pos.z
  840. };
  841. WriteBlock(&pkt_beacon, sizeof(pkt_beacon));
  842. }
  843. // Write proximity sensor distances
  844. void AP_Logger::Write_Proximity(AP_Proximity &proximity)
  845. {
  846. // exit immediately if not enabled
  847. if (proximity.get_status() == AP_Proximity::Proximity_NotConnected) {
  848. return;
  849. }
  850. AP_Proximity::Proximity_Distance_Array dist_array {};
  851. proximity.get_horizontal_distances(dist_array);
  852. float dist_up;
  853. if (!proximity.get_upward_distance(dist_up)) {
  854. dist_up = 0.0f;
  855. }
  856. float close_ang = 0.0f, close_dist = 0.0f;
  857. proximity.get_closest_object(close_ang, close_dist);
  858. const struct log_Proximity pkt_proximity{
  859. LOG_PACKET_HEADER_INIT(LOG_PROXIMITY_MSG),
  860. time_us : AP_HAL::micros64(),
  861. health : (uint8_t)proximity.get_status(),
  862. dist0 : dist_array.distance[0],
  863. dist45 : dist_array.distance[1],
  864. dist90 : dist_array.distance[2],
  865. dist135 : dist_array.distance[3],
  866. dist180 : dist_array.distance[4],
  867. dist225 : dist_array.distance[5],
  868. dist270 : dist_array.distance[6],
  869. dist315 : dist_array.distance[7],
  870. distup : dist_up,
  871. closest_angle : close_ang,
  872. closest_dist : close_dist
  873. };
  874. WriteBlock(&pkt_proximity, sizeof(pkt_proximity));
  875. }
  876. void AP_Logger::Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& breadcrumb)
  877. {
  878. const struct log_SRTL pkt_srtl{
  879. LOG_PACKET_HEADER_INIT(LOG_SRTL_MSG),
  880. time_us : AP_HAL::micros64(),
  881. active : active,
  882. num_points : num_points,
  883. max_points : max_points,
  884. action : action,
  885. N : breadcrumb.x,
  886. E : breadcrumb.y,
  887. D : breadcrumb.z
  888. };
  889. WriteBlock(&pkt_srtl, sizeof(pkt_srtl));
  890. }
  891. void AP_Logger::Write_OABendyRuler(bool active, float target_yaw, float margin, const Location &final_dest, const Location &oa_dest)
  892. {
  893. const struct log_OABendyRuler pkt{
  894. LOG_PACKET_HEADER_INIT(LOG_OA_BENDYRULER_MSG),
  895. time_us : AP_HAL::micros64(),
  896. active : active,
  897. target_yaw : (uint16_t)wrap_360(target_yaw),
  898. yaw : (uint16_t)wrap_360(AP::ahrs().yaw_sensor * 0.01f),
  899. margin : margin,
  900. final_lat : final_dest.lat,
  901. final_lng : final_dest.lng,
  902. oa_lat : oa_dest.lat,
  903. oa_lng : oa_dest.lng
  904. };
  905. WriteBlock(&pkt, sizeof(pkt));
  906. }
  907. void AP_Logger::Write_OADijkstra(uint8_t state, uint8_t curr_point, uint8_t tot_points, const Location &final_dest, const Location &oa_dest)
  908. {
  909. struct log_OADijkstra pkt{
  910. LOG_PACKET_HEADER_INIT(LOG_OA_DIJKSTRA_MSG),
  911. time_us : AP_HAL::micros64(),
  912. state : state,
  913. curr_point : curr_point,
  914. tot_points : tot_points,
  915. final_lat : final_dest.lat,
  916. final_lng : final_dest.lng,
  917. oa_lat : oa_dest.lat,
  918. oa_lng : oa_dest.lng
  919. };
  920. WriteBlock(&pkt, sizeof(pkt));
  921. }