41 #ifndef MAVLINK_STREAM_H_ 42 #define MAVLINK_STREAM_H_ 45 #include <px4_platform_common/module_params.h> 82 virtual const char *
get_name()
const = 0;
83 virtual uint16_t
get_id() = 0;
virtual const char * get_name() const =0
virtual uint16_t get_id()=0
int get_interval()
Get the interval.
An intrusive linked list.
int _interval
if set to negative value = unlimited rate
High-resolution timer with callouts and timekeeping.
MavlinkStream & operator=(const MavlinkStream &)=delete
virtual unsigned get_size_avg()
Get the average message size.
void set_interval(const int interval)
Get the interval.
virtual bool const_rate()
virtual void update_data()
Function to collect/update data for the streams at a high rate independant of actual stream rate...
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
virtual unsigned get_size()=0
Get maximal total messages size on update.
int update(const hrt_abstime &t)
Update subscriptions and send message if necessary.
MavlinkStream(Mavlink *mavlink)
virtual ~MavlinkStream()=default
bool first_message_sent() const
void reset_last_sent()
Reset the time of last sent to 0.
virtual bool send(const hrt_abstime t)=0