PX4 Firmware
PX4 Autopilot Software http://px4.io
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 
34 /**
35  * @file mavlink_high_latency2.h
36  *
37  * @author Achermann Florian <acfloria@ethz.ch>
38  */
39 
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  {
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 
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 
87  struct PerBatteryData {
91  uint64_t timestamp{0};
92  bool connected{false};
93  };
94 
96  uint64_t _actuator_time_0;
97 
99  uint64_t _actuator_time_1;
100 
102  uint64_t _airspeed_time;
103 
106 
109 
112 
114  uint64_t _geofence_time;
115 
118 
120  uint64_t _gps_time;
121 
124 
126  uint64_t _status_time;
127 
130 
132  uint64_t _tecs_time;
133 
135  uint64_t _wind_time;
136 
146 
149  float _update_rate_filtered = 0.0f;
150 
152 
153  /* do not allow top copying this class */
156 
157 protected:
158  explicit MavlinkStreamHighLatency2(Mavlink *mavlink);
159 
160  bool send(const hrt_abstime t);
161 
162  void reset_analysers(const hrt_abstime t);
163 
164  bool write_airspeed(mavlink_high_latency2_t *msg);
165 
166  bool write_attitude_sp(mavlink_high_latency2_t *msg);
167 
168  bool write_battery_status(mavlink_high_latency2_t *msg);
169 
170  bool write_estimator_status(mavlink_high_latency2_t *msg);
171 
172  bool write_fw_ctrl_status(mavlink_high_latency2_t *msg);
173 
174  bool write_geofence_result(mavlink_high_latency2_t *msg);
175 
176  bool write_global_position(mavlink_high_latency2_t *msg);
177 
178  bool write_mission_result(mavlink_high_latency2_t *msg);
179 
180  bool write_tecs_status(mavlink_high_latency2_t *msg);
181 
182  bool write_vehicle_status(mavlink_high_latency2_t *msg);
183 
184  bool write_vehicle_status_flags(mavlink_high_latency2_t *msg);
185 
186  bool write_wind_estimate(mavlink_high_latency2_t *msg);
187 
188  void update_data();
189 
190  void update_airspeed();
191 
192  void update_tecs_status();
193 
194  void update_battery_status();
195 
196  void update_global_position();
197 
198  void update_gps();
199 
200  void update_vehicle_status();
201 
202  void update_wind_estimate();
203 
204  void set_default_values(mavlink_high_latency2_t &msg) const;
205 };
SimpleAnalyzer.
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
#define ORB_MULTI_MAX_INSTANCES
Maximum number of multi topic instances.
Definition: uORB.h:62