|
virtual bool | send (const hrt_abstime t)=0 |
|
virtual void | update_data () |
| Function to collect/update data for the streams at a high rate independant of actual stream rate. More...
|
|
§ const_rate()
virtual bool MavlinkStream::const_rate |
( |
| ) |
|
|
inlinevirtual |
§ first_message_sent()
bool MavlinkStream::first_message_sent |
( |
| ) |
const |
|
inline |
- Returns
- true if the first message of this stream has been sent
§ get_interval()
int MavlinkStream::get_interval |
( |
| ) |
|
|
inline |
Get the interval.
- Returns
- the inveral in microseconds (us) between messages
§ get_size_avg()
virtual unsigned MavlinkStream::get_size_avg |
( |
| ) |
|
|
inlinevirtual |
Get the average message size.
For a normal stream this equals the message size, for something like a parameter or mission message this equals usually zero, as no bandwidth needs to be reserved
§ reset_last_sent()
void MavlinkStream::reset_last_sent |
( |
| ) |
|
|
inline |
Reset the time of last sent to 0.
Can be used if a message over this stream needs to be sent immediately.
§ set_interval()
void MavlinkStream::set_interval |
( |
const int |
interval | ) |
|
|
inline |
Get the interval.
- Parameters
-
interval | the interval in microseconds (us) between messages |
§ update()
Update subscriptions and send message if necessary.
- Returns
- 0 if updated / sent, -1 if unchanged
§ update_data()
virtual void MavlinkStream::update_data |
( |
| ) |
|
|
inlineprotectedvirtual |
Function to collect/update data for the streams at a high rate independant of actual stream rate.
This function is called at every iteration of the mavlink module.
Reimplemented in MavlinkStreamHighLatency2.
The documentation for this class was generated from the following files: