Firmware
mavlink_high_latency2.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2018 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 
40 #pragma once
41 
42 #include "mavlink_main.h"
43 #include "mavlink_messages.h"
45 #include "mavlink_stream.h"
46 
48 {
49 public:
50  const char *get_name() const
51  {
52  return MavlinkStreamHighLatency2::get_name_static();
53  }
54 
55  static const char *get_name_static()
56  {
57  return "HIGH_LATENCY2";
58  }
59 
60  static uint16_t get_id_static()
61  {
62  return MAVLINK_MSG_ID_HIGH_LATENCY2;
63  }
64 
65  uint16_t get_id()
66  {
67  return get_id_static();
68  }
69 
70  static MavlinkStream *new_instance(Mavlink *mavlink)
71  {
72  return new MavlinkStreamHighLatency2(mavlink);
73  }
74 
75  unsigned get_size()
76  {
77  return MAVLINK_MSG_ID_HIGH_LATENCY2_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
78  }
79 
80  bool const_rate()
81  {
82  return true;
83  }
84 
85 private:
86  MavlinkOrbSubscription *_actuator_sub_0;
87  uint64_t _actuator_time_0;
88 
89  MavlinkOrbSubscription *_actuator_sub_1;
90  uint64_t _actuator_time_1;
91 
92  MavlinkOrbSubscription *_airspeed_sub;
93  uint64_t _airspeed_time;
94 
95  MavlinkOrbSubscription *_attitude_sp_sub;
96  uint64_t _attitude_sp_time;
97 
98  MavlinkOrbSubscription *_battery_sub;
99  uint64_t _battery_time;
100 
101  MavlinkOrbSubscription *_estimator_status_sub;
102  uint64_t _estimator_status_time;
103 
104  MavlinkOrbSubscription *_pos_ctrl_status_sub;
105  uint64_t _pos_ctrl_status_time;
106 
107  MavlinkOrbSubscription *_geofence_sub;
108  uint64_t _geofence_time;
109 
110  MavlinkOrbSubscription *_global_pos_sub;
111  uint64_t _global_pos_time;
112 
113  MavlinkOrbSubscription *_gps_sub;
114  uint64_t _gps_time;
115 
116  MavlinkOrbSubscription *_mission_result_sub;
117  uint64_t _mission_result_time;
118 
119  MavlinkOrbSubscription *_status_sub;
120  uint64_t _status_time;
121 
122  MavlinkOrbSubscription *_status_flags_sub;
123  uint64_t _status_flags_time;
124 
125  MavlinkOrbSubscription *_tecs_status_sub;
126  uint64_t _tecs_time;
127 
128  MavlinkOrbSubscription *_wind_sub;
129  uint64_t _wind_time;
130 
131  SimpleAnalyzer _airspeed;
132  SimpleAnalyzer _airspeed_sp;
133  SimpleAnalyzer _battery;
134  SimpleAnalyzer _climb_rate;
135  SimpleAnalyzer _eph;
136  SimpleAnalyzer _epv;
137  SimpleAnalyzer _groundspeed;
138  SimpleAnalyzer _temperature;
139  SimpleAnalyzer _throttle;
140  SimpleAnalyzer _windspeed;
141 
142  hrt_abstime _last_reset_time = 0;
143  hrt_abstime _last_update_time = 0;
144  float _update_rate_filtered = 0.0f;
145 
146  /* do not allow top copying this class */
149 
150 protected:
151  explicit MavlinkStreamHighLatency2(Mavlink *mavlink);
152 
153  bool send(const hrt_abstime t);
154 
155  void reset_analysers(const hrt_abstime t);
156 
157  bool write_airspeed(mavlink_high_latency2_t *msg);
158 
159  bool write_attitude_sp(mavlink_high_latency2_t *msg);
160 
161  bool write_battery_status(mavlink_high_latency2_t *msg);
162 
163  bool write_estimator_status(mavlink_high_latency2_t *msg);
164 
165  bool write_fw_ctrl_status(mavlink_high_latency2_t *msg);
166 
167  bool write_geofence_result(mavlink_high_latency2_t *msg);
168 
169  bool write_global_position(mavlink_high_latency2_t *msg);
170 
171  bool write_mission_result(mavlink_high_latency2_t *msg);
172 
173  bool write_tecs_status(mavlink_high_latency2_t *msg);
174 
175  bool write_vehicle_status(mavlink_high_latency2_t *msg);
176 
177  bool write_vehicle_status_flags(mavlink_high_latency2_t *msg);
178 
179  bool write_wind_estimate(mavlink_high_latency2_t *msg);
180 
181  void update_data();
182 
183  void update_airspeed();
184 
185  void update_tecs_status();
186 
187  void update_battery_status();
188 
189  void update_global_position();
190 
191  void update_gps();
192 
193  void update_vehicle_status();
194 
195  void update_wind_estimate();
196 
197  void set_default_values(mavlink_high_latency2_t &msg) const;
198 };
void update_data()
Function to collect/update data for the streams at a high rate independant of actual stream rate...
Definition: mavlink_high_latency2.cpp:459
bool const_rate()
Definition: mavlink_high_latency2.h:80
Definition: mavlink_stream.h:50
SimpleAnalyzer.
Definition: mavlink_simple_analyzer.h:61
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Definition: mavlink_orb_subscription.h:48
Definition: mavlink_high_latency2.h:47
unsigned get_size()
Get maximal total messages size on update.
Definition: mavlink_high_latency2.h:75