PX4 Firmware
PX4 Autopilot Software http://px4.io
mavlink_log_handler.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2014, 2015 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 #pragma once
35 
36 /// @file mavlink_log_handler.h
37 /// @author px4dev, Gus Grubba <mavlink@grubba.com>
38 
39 #include <dirent.h>
40 #include <queue.h>
41 #include <time.h>
42 #include <stdio.h>
43 #include <cstdbool>
44 #include <v2.0/mavlink_types.h>
45 #include <drivers/drv_hrt.h>
46 
47 class Mavlink;
48 
49 // Log Listing Helper
51 {
52 public:
53  LogListHelper();
55 
56 public:
57  static void delete_all(const char *dir);
58 
59 public:
60 
61  bool get_entry(int idx, uint32_t &size, uint32_t &date, char *filename = 0, int filename_len = 0);
62  bool open_for_transmit();
63  size_t get_log_data(uint8_t len, uint8_t *buffer);
64 
65  enum {
69  };
70 
73  int log_count;
74 
77  uint32_t current_log_size;
82 
83 private:
84  void _init();
85  bool _get_session_date(const char *path, const char *dir, time_t &date);
86  void _scan_logs(FILE *f, const char *dir, time_t &date);
87  bool _get_log_time_size(const char *path, const char *file, time_t &date, uint32_t &size);
88 };
89 
90 // MAVLink LOG_* Message Handler
92 {
93 public:
94  MavlinkLogHandler(Mavlink *mavlink);
95 
96  // Handle possible LOG message
97  void handle_message(const mavlink_message_t *msg);
98 
99  /**
100  * Handle sending of messages. Call this regularly at a fixed frequency.
101  * @param t current time
102  */
103  void send(const hrt_abstime t);
104 
105  unsigned get_size();
106 
107 private:
108  void _log_message(const mavlink_message_t *msg);
109  void _log_request_list(const mavlink_message_t *msg);
110  void _log_request_data(const mavlink_message_t *msg);
111  void _log_request_erase(const mavlink_message_t *msg);
112  void _log_request_end(const mavlink_message_t *msg);
113 
114  size_t _log_send_listing();
115  size_t _log_send_data();
116 
119 };
static void delete_all(const char *dir)
uint16_t current_log_index
uint32_t current_log_data_remaining
void * send(void *data)
char current_log_filename[128]
size_t get_log_data(uint8_t len, uint8_t *buffer)
High-resolution timer with callouts and timekeeping.
bool _get_log_time_size(const char *path, const char *file, time_t &date, uint32_t &size)
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
bool get_entry(int idx, uint32_t &size, uint32_t &date, char *filename=0, int filename_len=0)
bool _get_session_date(const char *path, const char *dir, time_t &date)
void _scan_logs(FILE *f, const char *dir, time_t &date)
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
uint32_t current_log_data_offset
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
uint32_t current_log_size
struct @83::@85::@87 file