Firmware
simulator.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2015 Mark Charlebois. All rights reserved.
4  * Copyright (c) 2018 PX4 Development Team. All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions
8  * are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * 2. Redistributions in binary form must reproduce the above copyright
13  * notice, this list of conditions and the following disclaimer in
14  * the documentation and/or other materials provided with the
15  * distribution.
16  * 3. Neither the name PX4 nor the names of its contributors may be
17  * used to endorse or promote products derived from this software
18  * without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
27  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
28  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  ****************************************************************************/
34 
35 
43 #pragma once
44 
45 #include <px4_posix.h>
46 #include <px4_module_params.h>
47 #include <uORB/topics/manual_control_setpoint.h>
48 #include <uORB/topics/actuator_outputs.h>
49 #include <uORB/topics/vehicle_attitude.h>
50 #include <uORB/topics/vehicle_local_position.h>
51 #include <uORB/topics/vehicle_global_position.h>
52 #include <uORB/topics/vehicle_odometry.h>
53 #include <uORB/topics/vehicle_status.h>
54 #include <uORB/topics/battery_status.h>
55 #include <uORB/topics/irlock_report.h>
56 #include <uORB/topics/parameter_update.h>
57 #include <drivers/drv_accel.h>
58 #include <drivers/drv_gyro.h>
59 #include <drivers/drv_baro.h>
60 #include <drivers/drv_mag.h>
61 #include <drivers/drv_hrt.h>
62 #include <drivers/drv_rc_input.h>
63 #include <perf/perf_counter.h>
64 #include <battery/battery.h>
65 #include <uORB/uORB.h>
66 #include <uORB/topics/optical_flow.h>
67 #include <uORB/topics/distance_sensor.h>
68 #include <v2.0/mavlink_types.h>
69 #include <v2.0/common/mavlink.h>
70 #include <lib/ecl/geo/geo.h>
71 
72 namespace simulator
73 {
74 
75 #pragma pack(push, 1)
76 struct RawAccelData {
77  float temperature;
78  float x;
79  float y;
80  float z;
81 };
82 #pragma pack(pop)
83 
84 #pragma pack(push, 1)
85 struct RawMagData {
86  float temperature;
87  float x;
88  float y;
89  float z;
90 };
91 #pragma pack(pop)
92 
93 #pragma pack(push, 1)
94 struct RawMPUData {
95  float accel_x;
96  float accel_y;
97  float accel_z;
98  float temp;
99  float gyro_x;
100  float gyro_y;
101  float gyro_z;
102 };
103 #pragma pack(pop)
104 
105 #pragma pack(push, 1)
106 struct RawBaroData {
107  float pressure;
108  float temperature;
109 };
110 #pragma pack(pop)
111 
112 #pragma pack(push, 1)
114  float temperature;
115  float diff_pressure;
116 };
117 #pragma pack(pop)
118 
119 #pragma pack(push, 1)
120 struct RawGPSData {
121  uint64_t timestamp;
122  int32_t lat;
123  int32_t lon;
124  int32_t alt;
125  uint16_t eph;
126  uint16_t epv;
127  uint16_t vel;
128  int16_t vn;
129  int16_t ve;
130  int16_t vd;
131  uint16_t cog;
132  uint8_t fix_type;
133  uint8_t satellites_visible;
134 };
135 #pragma pack(pop)
136 
137 template <typename RType> class Report
138 {
139 public:
140  Report(int readers) :
141  _readidx(0),
142  _max_readers(readers),
143  _report_len(sizeof(RType))
144  {
145  memset(_buf, 0, sizeof(_buf));
146  px4_sem_init(&_lock, 0, _max_readers);
147  }
148 
149  ~Report() {}
150 
151  bool copyData(void *outbuf, int len)
152  {
153  if (len != _report_len) {
154  return false;
155  }
156 
157  read_lock();
158  memcpy(outbuf, &_buf[_readidx], _report_len);
159  read_unlock();
160  return true;
161  }
162  void writeData(void *inbuf)
163  {
164  write_lock();
165  memcpy(&_buf[!_readidx], inbuf, _report_len);
166  _readidx = !_readidx;
167  write_unlock();
168  }
169 
170 protected:
171  void read_lock() { px4_sem_wait(&_lock); }
172  void read_unlock() { px4_sem_post(&_lock); }
173  void write_lock()
174  {
175  for (int i = 0; i < _max_readers; i++) {
176  px4_sem_wait(&_lock);
177  }
178  }
179  void write_unlock()
180  {
181  for (int i = 0; i < _max_readers; i++) {
182  px4_sem_post(&_lock);
183  }
184  }
185 
186  int _readidx;
187  px4_sem_t _lock;
188  const int _max_readers;
189  const int _report_len;
190  RType _buf[2];
191 };
192 
193 } // namespace simulator
194 
195 
196 class Simulator : public ModuleParams
197 {
198 public:
199  static Simulator *getInstance();
200 
201  enum sim_dev_t {
202  SIM_GYRO,
203  SIM_ACCEL,
204  SIM_MAG
205  };
206 
207  struct sample {
208  float x;
209  float y;
210  float z;
211  sample() : x(0), y(0), z(0) {}
212  sample(float a, float b, float c) : x(a), y(b), z(c) {}
213  };
214 
215  enum class InternetProtocol {
216  TCP,
217  UDP
218  };
219 
220  static int start(int argc, char *argv[]);
221 
222  bool getAirspeedSample(uint8_t *buf, int len);
223  bool getBaroSample(uint8_t *buf, int len);
224  bool getGPSSample(uint8_t *buf, int len);
225  bool getMagReport(uint8_t *buf, int len);
226  bool getMPUReport(uint8_t *buf, int len);
227  bool getRawAccelReport(uint8_t *buf, int len);
228 
229  void write_airspeed_data(void *buf);
230  void write_accel_data(void *buf);
231  void write_baro_data(void *buf);
232  void write_gps_data(void *buf);
233  void write_mag_data(void *buf);
234  void write_MPU_data(void *buf);
235 
236  bool isInitialized() { return _initialized; }
237 
238  void set_ip(InternetProtocol ip);
239  void set_port(unsigned port);
240 
241 private:
242  Simulator() :
243  ModuleParams(nullptr)
244  {
245  simulator::RawGPSData gps_data{};
246  gps_data.eph = UINT16_MAX;
247  gps_data.epv = UINT16_MAX;
248 
249  _gps.writeData(&gps_data);
250 
251  _param_sub = orb_subscribe(ORB_ID(parameter_update));
252 
253  _battery_status.timestamp = hrt_absolute_time();
254  }
255 
256  ~Simulator()
257  {
258  // Unsubscribe from uORB topics.
259  orb_unsubscribe(_param_sub);
260 
261  // free perf counters
262  perf_free(_perf_accel);
263  perf_free(_perf_airspeed);
264  perf_free(_perf_baro);
265  perf_free(_perf_gps);
266  perf_free(_perf_mag);
267  perf_free(_perf_mpu);
268  perf_free(_perf_sim_delay);
269  perf_free(_perf_sim_interval);
270 
271  _instance = NULL;
272  }
273 
274  // class methods
275  void initialize_sensor_data();
276 
277  int publish_sensor_topics(const mavlink_hil_sensor_t *imu);
278  int publish_flow_topic(const mavlink_hil_optical_flow_t *flow);
279  int publish_odometry_topic(const mavlink_message_t *odom_mavlink);
280  int publish_distance_topic(const mavlink_distance_sensor_t *dist);
281 
282  static Simulator *_instance;
283 
284  // simulated sensor instances
291 
292  perf_counter_t _perf_accel{perf_alloc_once(PC_ELAPSED, "sim_accel_delay")};
293  perf_counter_t _perf_airspeed{perf_alloc_once(PC_ELAPSED, "sim_airspeed_delay")};
294  perf_counter_t _perf_baro{perf_alloc_once(PC_ELAPSED, "sim_baro_delay")};
295  perf_counter_t _perf_gps{perf_alloc_once(PC_ELAPSED, "sim_gps_delay")};
296  perf_counter_t _perf_mag{perf_alloc_once(PC_ELAPSED, "sim_mag_delay")};
297  perf_counter_t _perf_mpu{perf_alloc_once(PC_ELAPSED, "sim_mpu_delay")};
298  perf_counter_t _perf_sim_delay{perf_alloc_once(PC_ELAPSED, "sim_network_delay")};
299  perf_counter_t _perf_sim_interval{perf_alloc(PC_INTERVAL, "sim_network_interval")};
300 
301  // uORB publisher handlers
302  orb_advert_t _accel_pub{nullptr};
303  orb_advert_t _baro_pub{nullptr};
304  orb_advert_t _battery_pub{nullptr};
305  orb_advert_t _dist_pub{nullptr};
306  orb_advert_t _flow_pub{nullptr};
307  orb_advert_t _gyro_pub{nullptr};
308  orb_advert_t _irlock_report_pub{nullptr};
309  orb_advert_t _mag_pub{nullptr};
310  orb_advert_t _visual_odometry_pub{nullptr};
311 
312  int _param_sub{-1};
313 
314  unsigned int _port{14560};
315 
316  InternetProtocol _ip{InternetProtocol::UDP};
317 
318  bool _initialized{false};
319 
320  double _realtime_factor{1.0};
321 
322  hrt_abstime _last_sim_timestamp{0};
323  hrt_abstime _last_sitl_timestamp{0};
324 
325  // Lib used to do the battery calculations.
326  Battery _battery {};
327  battery_status_s _battery_status{};
328 
329 #ifndef __PX4_QURT
330 
331  mavlink_hil_actuator_controls_t actuator_controls_from_outputs(const actuator_outputs_s &actuators);
332 
333  void handle_message(const mavlink_message_t *msg);
334  void handle_message_distance_sensor(const mavlink_message_t *msg);
335  void handle_message_hil_gps(const mavlink_message_t *msg);
336  void handle_message_hil_sensor(const mavlink_message_t *msg);
337  void handle_message_hil_state_quaternion(const mavlink_message_t *msg);
338  void handle_message_landing_target(const mavlink_message_t *msg);
339  void handle_message_odometry(const mavlink_message_t *msg);
340  void handle_message_optical_flow(const mavlink_message_t *msg);
341  void handle_message_rc_channels(const mavlink_message_t *msg);
342  void handle_message_vision_position_estimate(const mavlink_message_t *msg);
343 
344  void parameters_update(bool force);
345  void poll_topics();
346  void poll_for_MAVLink_messages();
347  void request_hil_state_quaternion();
348  void send();
349  void send_controls();
350  void send_heartbeat();
351  void send_mavlink_message(const mavlink_message_t &aMsg);
352  void set_publish(const bool publish = true);
353  void update_sensors(const mavlink_hil_sensor_t *imu);
354  void update_gps(const mavlink_hil_gps_t *gps_sim);
355 
356  static void *sending_trampoline(void *);
357 
358  // uORB publisher handlers
359  orb_advert_t _attitude_pub{nullptr};
360  orb_advert_t _gpos_pub{nullptr};
361  orb_advert_t _lpos_pub{nullptr};
362  orb_advert_t _rc_channels_pub{nullptr};
363 
364  // uORB subscription handlers
365  int _actuator_outputs_sub{-1};
366  int _vehicle_status_sub{-1};
367 
368  // hil map_ref data
369  struct map_projection_reference_s _hil_local_proj_ref {};
370 
371  bool _hil_local_proj_inited{false};
372  bool _publish{false};
373 
374  double _hil_ref_lat{0};
375  double _hil_ref_lon{0};
376  float _hil_ref_alt{0.0f};
377  uint64_t _hil_ref_timestamp{0};
378 
379  // uORB data containers
380  input_rc_s _rc_input {};
381  manual_control_setpoint_s _manual {};
382  vehicle_attitude_s _attitude {};
383  vehicle_status_s _vehicle_status {};
384 
385  DEFINE_PARAMETERS(
386  (ParamFloat<px4::params::SIM_BAT_DRAIN>) _param_sim_bat_drain,
387  (ParamInt<px4::params::MAV_TYPE>) _param_mav_type,
388  (ParamInt<px4::params::MAV_SYS_ID>) _param_mav_sys_id,
389  (ParamInt<px4::params::MAV_COMP_ID>) _param_mav_comp_id
390  )
391 
392 #endif
393 };
Accelerometer driver interface.
Definition: px4_param.h:313
R/C input interface.
Definition: simulator.h:120
Definition: simulator.h:85
Gyroscope driver interface.
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
measure the time elapsed performing an event
Definition: perf_counter.h:56
int orb_unsubscribe(int handle)
Definition: uORB.cpp:85
Definition: simulator.h:106
Definition: simulator.h:76
Includes POSIX-like functions for virtual character devices.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
Definition: simulator.h:196
int orb_subscribe(const struct orb_metadata *meta)
Definition: uORB.cpp:75
High-resolution timer with callouts and timekeeping.
Library calls for battery functionality.
Definition: simulator.h:113
Header common to all counters.
Definition: perf_counter.cpp:65
API for the uORB lightweight object broker.
Definition: px4_param.h:318
C++ base class for modules/classes using configuration parameters.
Definition: px4_module_params.h:46
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
Definition: simulator.h:137
Definition: parameter_update.py:1
Definition: simulator.h:94
Definition: simulator.h:207
__BEGIN_DECLS __EXPORT perf_counter_t perf_alloc(enum perf_counter_type type, const char *name)
Create a new local counter.
Definition: perf_counter.cpp:123
__EXPORT perf_counter_t perf_alloc_once(enum perf_counter_type type, const char *name)
Get the reference to an existing counter or create a new one if it does not exist.
Definition: perf_counter.cpp:156
Barometric pressure sensor driver interface.
Definition: simulator.h:72
hrt_abstime hrt_absolute_time()
Get absolute time in [us] (does not wrap).
Definition: drv_hrt.cpp:155
measure the interval between instances of an event
Definition: perf_counter.h:57
__EXPORT void perf_free(perf_counter_t handle)
Free a counter.
Definition: perf_counter.cpp:185
Performance measuring tools.
Definition: battery.h:49