49 #include <uORB/topics/ulog_stream.h> 50 #include <uORB/topics/ulog_stream_ack.h> 52 #include "mavlink_bridge_header.h" 75 static MavlinkULog *
try_start(
int datarate,
float max_rate_factor, uint8_t target_system, uint8_t target_component);
96 float current_data_rate()
const {
return _current_rate_factor; }
97 float maximum_data_rate()
const {
return _max_rate_factor; }
99 int get_ulog_stream_fd()
const {
return _ulog_stream_sub; }
102 MavlinkULog(
int datarate,
float max_rate_factor, uint8_t target_system, uint8_t target_component);
108 do {}
while (px4_sem_wait(&_lock) != 0);
113 px4_sem_post(&_lock);
116 void publish_ack(uint16_t sequence);
118 static px4_sem_t _lock;
121 static const float _rate_calculation_delta_t;
123 int _ulog_stream_sub = -1;
125 uint16_t _wait_for_ack_sequence;
126 uint8_t _sent_tries = 0;
127 volatile bool _ack_received =
false;
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;
134 const float _max_rate_factor;
135 const int _max_num_messages;
136 float _current_rate_factor;
137 int _current_num_msgs = 0;
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