Firmware
mavlink_ulog.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016 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 
41 #pragma once
42 
43 #include <stddef.h>
44 #include <stdint.h>
45 #include <px4_tasks.h>
46 #include <px4_sem.h>
47 #include <drivers/drv_hrt.h>
48 
49 #include <uORB/topics/ulog_stream.h>
50 #include <uORB/topics/ulog_stream_ack.h>
51 
52 #include "mavlink_bridge_header.h"
53 
59 {
60 public:
64  static void initialize();
65 
75  static MavlinkULog *try_start(int datarate, float max_rate_factor, uint8_t target_system, uint8_t target_component);
76 
82  void stop();
83 
88  int handle_update(mavlink_channel_t channel);
89 
91  void handle_ack(mavlink_logging_ack_t ack);
92 
94  void start_ack_received();
95 
96  float current_data_rate() const { return _current_rate_factor; }
97  float maximum_data_rate() const { return _max_rate_factor; }
98 
99  int get_ulog_stream_fd() const { return _ulog_stream_sub; }
100 private:
101 
102  MavlinkULog(int datarate, float max_rate_factor, uint8_t target_system, uint8_t target_component);
103 
104  ~MavlinkULog();
105 
106  static void lock()
107  {
108  do {} while (px4_sem_wait(&_lock) != 0);
109  }
110 
111  static void unlock()
112  {
113  px4_sem_post(&_lock);
114  }
115 
116  void publish_ack(uint16_t sequence);
117 
118  static px4_sem_t _lock;
119  static bool _init;
120  static MavlinkULog *_instance;
121  static const float _rate_calculation_delta_t;
122 
123  int _ulog_stream_sub = -1;
124  orb_advert_t _ulog_stream_ack_pub = nullptr;
125  uint16_t _wait_for_ack_sequence;
126  uint8_t _sent_tries = 0;
127  volatile bool _ack_received = false;
128  hrt_abstime _last_sent_time = 0;
129  ulog_stream_s _ulog_data;
130  bool _waiting_for_initial_ack = false;
131  const uint8_t _target_system;
132  const uint8_t _target_component;
133 
134  const float _max_rate_factor;
135  const int _max_num_messages;
136  float _current_rate_factor;
137  int _current_num_msgs = 0;
138  hrt_abstime _next_rate_check;
139 
140  /* do not allow copying this class */
141  MavlinkULog(const MavlinkULog &) = delete;
142  MavlinkULog operator=(const MavlinkULog &) = delete;
143 };
static MavlinkULog * try_start(int datarate, float max_rate_factor, uint8_t target_system, uint8_t target_component)
try to start a new stream.
Definition: mavlink_ulog.cpp:219
void start_ack_received()
this is called when we got an vehicle_command_ack from the logger
Definition: mavlink_ulog.cpp:90
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
High-resolution timer with callouts and timekeeping.
Synchronization primitive: Semaphore.
static void initialize()
initialize: call this once on startup (this function is not thread-safe!)
Definition: mavlink_ulog.cpp:209
ULog streaming class.
Definition: mavlink_ulog.h:58
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
void stop()
stop the stream.
Definition: mavlink_ulog.cpp:243
int handle_update(mavlink_channel_t channel)
periodic update method: check for ulog stream messages and handle retransmission. ...
Definition: mavlink_ulog.cpp:99
void handle_ack(mavlink_logging_ack_t ack)
ack from mavlink for a data message
Definition: mavlink_ulog.cpp:255