PX4 Firmware
PX4 Autopilot Software http://px4.io
mavlink_stream.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2014-2017 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 
34 /**
35  * @file mavlink_stream.h
36  * Mavlink messages stream definition.
37  *
38  * @author Anton Babushkin <anton.babushkin@me.com>
39  */
40 
41 #ifndef MAVLINK_STREAM_H_
42 #define MAVLINK_STREAM_H_
43 
44 #include <drivers/drv_hrt.h>
45 #include <px4_platform_common/module_params.h>
46 #include <containers/List.hpp>
47 
48 class Mavlink;
49 
50 class MavlinkStream : public ListNode<MavlinkStream *>
51 {
52 
53 public:
54 
55  MavlinkStream(Mavlink *mavlink);
56  virtual ~MavlinkStream() = default;
57 
58  // no copy, assignment, move, move assignment
59  MavlinkStream(const MavlinkStream &) = delete;
60  MavlinkStream &operator=(const MavlinkStream &) = delete;
61  MavlinkStream(MavlinkStream &&) = delete;
63 
64  /**
65  * Get the interval
66  *
67  * @param interval the interval in microseconds (us) between messages
68  */
69  void set_interval(const int interval) { _interval = interval; }
70 
71  /**
72  * Get the interval
73  *
74  * @return the inveral in microseconds (us) between messages
75  */
76  int get_interval() { return _interval; }
77 
78  /**
79  * @return 0 if updated / sent, -1 if unchanged
80  */
81  int update(const hrt_abstime &t);
82  virtual const char *get_name() const = 0;
83  virtual uint16_t get_id() = 0;
84 
85  /**
86  * @return true if steam rate shouldn't be adjusted
87  */
88  virtual bool const_rate() { return false; }
89 
90  /**
91  * Get maximal total messages size on update
92  */
93  virtual unsigned get_size() = 0;
94 
95  /**
96  * Get the average message size
97  *
98  * For a normal stream this equals the message size,
99  * for something like a parameter or mission message
100  * this equals usually zero, as no bandwidth
101  * needs to be reserved
102  */
103  virtual unsigned get_size_avg() { return get_size(); }
104 
105  /**
106  * @return true if the first message of this stream has been sent
107  */
108  bool first_message_sent() const { return _first_message_sent; }
109 
110  /**
111  * Reset the time of last sent to 0. Can be used if a message over this
112  * stream needs to be sent immediately.
113  */
114  void reset_last_sent() { _last_sent = 0; }
115 
116 protected:
118  int _interval{1000000}; ///< if set to negative value = unlimited rate
119 
120  virtual bool send(const hrt_abstime t) = 0;
121 
122  /**
123  * Function to collect/update data for the streams at a high rate independant of
124  * actual stream rate.
125  *
126  * This function is called at every iteration of the mavlink module.
127  */
128  virtual void update_data() { }
129 
130 private:
132  bool _first_message_sent{false};
133 };
134 
135 
136 #endif /* MAVLINK_STREAM_H_ */
An intrusive linked list.
High-resolution timer with callouts and timekeeping.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58