AP_Logger_Backend.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437
  1. #include "AP_Logger_Backend.h"
  2. #include "LoggerMessageWriter.h"
  3. #include <AP_InternalError/AP_InternalError.h>
  4. extern const AP_HAL::HAL& hal;
  5. AP_Logger_Backend::AP_Logger_Backend(AP_Logger &front,
  6. class LoggerMessageWriter_DFLogStart *writer) :
  7. _front(front),
  8. _startup_messagewriter(writer)
  9. {
  10. writer->set_logger_backend(this);
  11. }
  12. uint8_t AP_Logger_Backend::num_types() const
  13. {
  14. return _front._num_types;
  15. }
  16. const struct LogStructure *AP_Logger_Backend::structure(uint8_t num) const
  17. {
  18. return _front.structure(num);
  19. }
  20. uint8_t AP_Logger_Backend::num_units() const
  21. {
  22. return _front._num_units;
  23. }
  24. const struct UnitStructure *AP_Logger_Backend::unit(uint8_t num) const
  25. {
  26. return _front.unit(num);
  27. }
  28. uint8_t AP_Logger_Backend::num_multipliers() const
  29. {
  30. return _front._num_multipliers;
  31. }
  32. const struct MultiplierStructure *AP_Logger_Backend::multiplier(uint8_t num) const
  33. {
  34. return _front.multiplier(num);
  35. }
  36. AP_Logger_Backend::vehicle_startup_message_Writer AP_Logger_Backend::vehicle_message_writer() {
  37. return _front._vehicle_messages;
  38. }
  39. void AP_Logger_Backend::periodic_10Hz(const uint32_t now)
  40. {
  41. }
  42. void AP_Logger_Backend::periodic_1Hz()
  43. {
  44. }
  45. void AP_Logger_Backend::periodic_fullrate()
  46. {
  47. }
  48. void AP_Logger_Backend::periodic_tasks()
  49. {
  50. uint32_t now = AP_HAL::millis();
  51. if (now - _last_periodic_1Hz > 1000) {
  52. periodic_1Hz();
  53. _last_periodic_1Hz = now;
  54. }
  55. if (now - _last_periodic_10Hz > 100) {
  56. periodic_10Hz(now);
  57. _last_periodic_10Hz = now;
  58. }
  59. periodic_fullrate();
  60. }
  61. void AP_Logger_Backend::start_new_log_reset_variables()
  62. {
  63. _startup_messagewriter->reset();
  64. _front.backend_starting_new_log(this);
  65. }
  66. // this method can be overridden to do extra things with your buffer.
  67. // for example, in AP_Logger_MAVLink we may push messages into the UART.
  68. void AP_Logger_Backend::push_log_blocks() {
  69. WriteMoreStartupMessages();
  70. }
  71. // returns true if all format messages have been written, and thus it is OK
  72. // for other messages to go out to the log
  73. bool AP_Logger_Backend::WriteBlockCheckStartupMessages()
  74. {
  75. #if APM_BUILD_TYPE(APM_BUILD_Replay)
  76. return true;
  77. #endif
  78. if (_startup_messagewriter->fmt_done()) {
  79. return true;
  80. }
  81. if (_writing_startup_messages) {
  82. // we have been called by a messagewriter, so writing is OK
  83. return true;
  84. }
  85. if (!_startup_messagewriter->finished() &&
  86. !hal.scheduler->in_main_thread()) {
  87. // only the main thread may write startup messages out
  88. return false;
  89. }
  90. // we're not writing startup messages, so this must be some random
  91. // caller hoping to write blocks out. Push out log blocks - we
  92. // might end up clearing the buffer.....
  93. push_log_blocks();
  94. // even if we did finish writing startup messages, we can't
  95. // permit any message to go in as its timestamp will be before
  96. // any we wrote in. Time going backwards annoys log readers.
  97. // sorry! currently busy writing out startup messages...
  98. return false;
  99. }
  100. // source more messages from the startup message writer:
  101. void AP_Logger_Backend::WriteMoreStartupMessages()
  102. {
  103. if (_startup_messagewriter->finished()) {
  104. return;
  105. }
  106. _writing_startup_messages = true;
  107. _startup_messagewriter->process();
  108. _writing_startup_messages = false;
  109. }
  110. /*
  111. * support for Write():
  112. */
  113. bool AP_Logger_Backend::Write_Emit_FMT(uint8_t msg_type)
  114. {
  115. // get log structure from front end:
  116. char ls_name[LS_NAME_SIZE] = {};
  117. char ls_format[LS_FORMAT_SIZE] = {};
  118. char ls_labels[LS_LABELS_SIZE] = {};
  119. char ls_units[LS_UNITS_SIZE] = {};
  120. char ls_multipliers[LS_MULTIPLIERS_SIZE] = {};
  121. struct LogStructure logstruct = {
  122. // these will be overwritten, but need to keep the compiler happy:
  123. 0,
  124. 0,
  125. ls_name,
  126. ls_format,
  127. ls_labels,
  128. ls_units,
  129. ls_multipliers
  130. };
  131. if (!_front.fill_log_write_logstructure(logstruct, msg_type)) {
  132. // this is a bug; we've been asked to write out the FMT
  133. // message for a msg_type, but the frontend can't supply the
  134. // required information
  135. AP::internalerror().error(AP_InternalError::error_t::logger_missing_logstructure);
  136. return false;
  137. }
  138. if (!Write_Format(&logstruct)) {
  139. return false;
  140. }
  141. if (!Write_Format_Units(&logstruct)) {
  142. return false;
  143. }
  144. return true;
  145. }
  146. bool AP_Logger_Backend::Write(const uint8_t msg_type, va_list arg_list, bool is_critical)
  147. {
  148. // stack-allocate a buffer so we can WriteBlock(); this could be
  149. // 255 bytes! If we were willing to lose the WriteBlock
  150. // abstraction we could do WriteBytes() here instead?
  151. const char *fmt = nullptr;
  152. uint8_t msg_len;
  153. AP_Logger::log_write_fmt *f;
  154. for (f = _front.log_write_fmts; f; f=f->next) {
  155. if (f->msg_type == msg_type) {
  156. fmt = f->fmt;
  157. msg_len = f->msg_len;
  158. break;
  159. }
  160. }
  161. if (fmt == nullptr) {
  162. AP::internalerror().error(AP_InternalError::error_t::logger_logwrite_missingfmt);
  163. return false;
  164. }
  165. if (bufferspace_available() < msg_len) {
  166. return false;
  167. }
  168. uint8_t buffer[msg_len];
  169. uint8_t offset = 0;
  170. buffer[offset++] = HEAD_BYTE1;
  171. buffer[offset++] = HEAD_BYTE2;
  172. buffer[offset++] = msg_type;
  173. for (uint8_t i=0; i<strlen(fmt); i++) {
  174. uint8_t charlen = 0;
  175. switch(fmt[i]) {
  176. case 'b': {
  177. int8_t tmp = va_arg(arg_list, int);
  178. memcpy(&buffer[offset], &tmp, sizeof(int8_t));
  179. offset += sizeof(int8_t);
  180. break;
  181. }
  182. case 'h':
  183. case 'c': {
  184. int16_t tmp = va_arg(arg_list, int);
  185. memcpy(&buffer[offset], &tmp, sizeof(int16_t));
  186. offset += sizeof(int16_t);
  187. break;
  188. }
  189. case 'd': {
  190. double tmp = va_arg(arg_list, double);
  191. memcpy(&buffer[offset], &tmp, sizeof(double));
  192. offset += sizeof(double);
  193. break;
  194. }
  195. case 'i':
  196. case 'L':
  197. case 'e': {
  198. int32_t tmp = va_arg(arg_list, int);
  199. memcpy(&buffer[offset], &tmp, sizeof(int32_t));
  200. offset += sizeof(int32_t);
  201. break;
  202. }
  203. case 'f': {
  204. float tmp = va_arg(arg_list, double);
  205. memcpy(&buffer[offset], &tmp, sizeof(float));
  206. offset += sizeof(float);
  207. break;
  208. }
  209. case 'n':
  210. charlen = 4;
  211. break;
  212. case 'M':
  213. case 'B': {
  214. uint8_t tmp = va_arg(arg_list, int);
  215. memcpy(&buffer[offset], &tmp, sizeof(uint8_t));
  216. offset += sizeof(uint8_t);
  217. break;
  218. }
  219. case 'H':
  220. case 'C': {
  221. uint16_t tmp = va_arg(arg_list, int);
  222. memcpy(&buffer[offset], &tmp, sizeof(uint16_t));
  223. offset += sizeof(uint16_t);
  224. break;
  225. }
  226. case 'I':
  227. case 'E': {
  228. uint32_t tmp = va_arg(arg_list, uint32_t);
  229. memcpy(&buffer[offset], &tmp, sizeof(uint32_t));
  230. offset += sizeof(uint32_t);
  231. break;
  232. }
  233. case 'N':
  234. charlen = 16;
  235. break;
  236. case 'Z':
  237. charlen = 64;
  238. break;
  239. case 'q': {
  240. int64_t tmp = va_arg(arg_list, int64_t);
  241. memcpy(&buffer[offset], &tmp, sizeof(int64_t));
  242. offset += sizeof(int64_t);
  243. break;
  244. }
  245. case 'Q': {
  246. uint64_t tmp = va_arg(arg_list, uint64_t);
  247. memcpy(&buffer[offset], &tmp, sizeof(uint64_t));
  248. offset += sizeof(uint64_t);
  249. break;
  250. }
  251. }
  252. if (charlen != 0) {
  253. char *tmp = va_arg(arg_list, char*);
  254. memcpy(&buffer[offset], tmp, charlen);
  255. offset += charlen;
  256. }
  257. }
  258. return WritePrioritisedBlock(buffer, msg_len, is_critical);
  259. }
  260. bool AP_Logger_Backend::StartNewLogOK() const
  261. {
  262. if (logging_started()) {
  263. return false;
  264. }
  265. if (_front._log_bitmask == 0) {
  266. return false;
  267. }
  268. if (_front.in_log_download()) {
  269. return false;
  270. }
  271. if (!hal.scheduler->in_main_thread()) {
  272. return false;
  273. }
  274. return true;
  275. }
  276. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  277. void AP_Logger_Backend::validate_WritePrioritisedBlock(const void *pBuffer,
  278. uint16_t size)
  279. {
  280. // just check the first few packets to avoid too much overhead
  281. // (finding the structures is expensive)
  282. static uint16_t count = 0;
  283. if (count > 65534) {
  284. return;
  285. }
  286. count++;
  287. // we assume here that we ever WritePrioritisedBlock for a single
  288. // message. If this assumption becomes false we can't do these
  289. // checks.
  290. if (size < 3) {
  291. AP_HAL::panic("Short prioritised block");
  292. }
  293. if (((uint8_t*)pBuffer)[0] != HEAD_BYTE1 ||
  294. ((uint8_t*)pBuffer)[1] != HEAD_BYTE2) {
  295. AP_HAL::panic("Not passed a message");
  296. }
  297. const uint8_t type = ((uint8_t*)pBuffer)[2];
  298. uint8_t type_len;
  299. const struct LogStructure *s = _front.structure_for_msg_type(type);
  300. if (s == nullptr) {
  301. const struct AP_Logger::log_write_fmt *t = _front.log_write_fmt_for_msg_type(type);
  302. if (t == nullptr) {
  303. AP_HAL::panic("No structure for msg_type=%u", type);
  304. }
  305. type_len = t->msg_len;
  306. } else {
  307. type_len = s->msg_len;
  308. }
  309. if (type_len != size) {
  310. char name[5] = {}; // get a null-terminated string
  311. memcpy(name, s->name, 4);
  312. AP_HAL::panic("Size mismatch for %u (%s) (expected=%u got=%u)\n",
  313. type, name, type_len, size);
  314. }
  315. }
  316. #endif
  317. bool AP_Logger_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
  318. {
  319. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  320. validate_WritePrioritisedBlock(pBuffer, size);
  321. #endif
  322. if (!ShouldLog(is_critical)) {
  323. return false;
  324. }
  325. if (StartNewLogOK()) {
  326. start_new_log();
  327. }
  328. if (!WritesOK()) {
  329. return false;
  330. }
  331. return _WritePrioritisedBlock(pBuffer, size, is_critical);
  332. }
  333. bool AP_Logger_Backend::ShouldLog(bool is_critical)
  334. {
  335. if (!_front.WritesEnabled()) {
  336. return false;
  337. }
  338. if (!_initialised) {
  339. return false;
  340. }
  341. if (!_startup_messagewriter->finished() &&
  342. !hal.scheduler->in_main_thread()) {
  343. // only the main thread may write startup messages out
  344. return false;
  345. }
  346. if (is_critical && have_logged_armed && !_front._params.file_disarm_rot) {
  347. // if we have previously logged while armed then we log all
  348. // critical messages from then on. That fixes a problem where
  349. // logs show the wrong flight mode if you disarm then arm again
  350. return true;
  351. }
  352. if (!_front.vehicle_is_armed() && !_front.log_while_disarmed()) {
  353. return false;
  354. }
  355. if (_front.vehicle_is_armed()) {
  356. have_logged_armed = true;
  357. }
  358. return true;
  359. }
  360. bool AP_Logger_Backend::Write_MessageF(const char *fmt, ...)
  361. {
  362. char msg[65] {}; // sizeof(log_Message.msg) + null-termination
  363. va_list ap;
  364. va_start(ap, fmt);
  365. hal.util->vsnprintf(msg, sizeof(msg), fmt, ap);
  366. va_end(ap);
  367. return Write_Message(msg);
  368. }
  369. // Write rally points
  370. bool AP_Logger_Backend::Write_RallyPoint(uint8_t total,
  371. uint8_t sequence,
  372. const RallyLocation &rally_point)
  373. {
  374. const struct log_Rally pkt_rally{
  375. LOG_PACKET_HEADER_INIT(LOG_RALLY_MSG),
  376. time_us : AP_HAL::micros64(),
  377. total : total,
  378. sequence : sequence,
  379. latitude : rally_point.lat,
  380. longitude : rally_point.lng,
  381. altitude : rally_point.alt
  382. };
  383. return WriteBlock(&pkt_rally, sizeof(pkt_rally));
  384. }
  385. // Write rally points
  386. void AP_Logger_Backend::Write_Rally()
  387. {
  388. LoggerMessageWriter_WriteAllRallyPoints writer;
  389. writer.set_logger_backend(this);
  390. writer.process();
  391. }