45 #include <px4_platform_common/tasks.h> 46 #include <px4_platform_common/sem.h> 77 static MavlinkULog *
try_start(
int datarate,
float max_rate_factor, uint8_t target_system, uint8_t target_component);
103 MavlinkULog(
int datarate,
float max_rate_factor, uint8_t target_system, uint8_t target_component);
109 do {}
while (px4_sem_wait(&
_lock) != 0);
114 px4_sem_post(&
_lock);
void stop()
stop the stream.
float current_data_rate() const
static const float _rate_calculation_delta_t
rate update interval
const uint8_t _target_system
int _current_num_msgs
number of messages sent within the current time interval
void handle_ack(mavlink_logging_ack_t ack)
ack from mavlink for a data message
void publish_ack(uint16_t sequence)
void start_ack_received()
this is called when we got an vehicle_command_ack from the logger
uORB::Publication< ulog_stream_ack_s > _ulog_stream_ack_pub
High-resolution timer with callouts and timekeeping.
float _current_rate_factor
currently used rate percentage
int handle_update(mavlink_channel_t channel)
periodic update method: check for ulog stream messages and handle retransmission. ...
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
static MavlinkULog * try_start(int datarate, float max_rate_factor, uint8_t target_system, uint8_t target_component)
try to start a new stream.
volatile bool _ack_received
set to true if a matching ack received
static MavlinkULog * _instance
hrt_abstime _last_sent_time
last time we sent a message that requires an ack
bool _waiting_for_initial_ack
MavlinkULog operator=(const MavlinkULog &)=delete
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
const uint8_t _target_component
const int _max_num_messages
maximum number of messages we can send within _rate_calculation_delta_t
MavlinkULog(int datarate, float max_rate_factor, uint8_t target_system, uint8_t target_component)
float maximum_data_rate() const
static void initialize()
initialize: call this once on startup (this function is not thread-safe!)
const float _max_rate_factor
maximum rate percentage at which we're allowed to push data
hrt_abstime _next_rate_check
next timestamp at which to update the rate
uORB::SubscriptionData< ulog_stream_s > _ulog_stream_sub
uint16_t _wait_for_ack_sequence