PX4 Firmware
PX4 Autopilot Software http://px4.io
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 
36 /**
37  * @file simulator.h
38  *
39  * This module interfaces via MAVLink to a software in the loop simulator (SITL)
40  * such as jMAVSim or Gazebo.
41  */
42 
43 #pragma once
44 
45 #include <battery/battery.h>
46 #include <drivers/drv_hrt.h>
47 #include <drivers/drv_rc_input.h>
52 #include <lib/ecl/geo/geo.h>
53 #include <perf/perf_counter.h>
54 #include <px4_platform_common/module_params.h>
55 #include <px4_platform_common/posix.h>
56 #include <uORB/Subscription.hpp>
71 #include <uORB/uORB.h>
72 
73 #include <v2.0/common/mavlink.h>
74 #include <v2.0/mavlink_types.h>
75 
76 namespace simulator
77 {
78 
79 #pragma pack(push, 1)
80 struct RawGPSData {
81  uint64_t timestamp;
82  int32_t lat;
83  int32_t lon;
84  int32_t alt;
85  uint16_t eph;
86  uint16_t epv;
87  uint16_t vel;
88  int16_t vn;
89  int16_t ve;
90  int16_t vd;
91  uint16_t cog;
92  uint8_t fix_type;
94 };
95 #pragma pack(pop)
96 
97 template <typename RType> class Report
98 {
99 public:
100  Report(int readers) :
101  _readidx(0),
102  _max_readers(readers),
103  _report_len(sizeof(RType))
104  {
105  memset(_buf, 0, sizeof(_buf));
106  px4_sem_init(&_lock, 0, _max_readers);
107  }
108 
109  ~Report() {}
110 
111  bool copyData(void *outbuf, int len)
112  {
113  if (len != _report_len) {
114  return false;
115  }
116 
117  read_lock();
118  memcpy(outbuf, &_buf[_readidx], _report_len);
119  read_unlock();
120  return true;
121  }
122  void writeData(void *inbuf)
123  {
124  write_lock();
125  memcpy(&_buf[!_readidx], inbuf, _report_len);
126  _readidx = !_readidx;
127  write_unlock();
128  }
129 
130 protected:
131  void read_lock() { px4_sem_wait(&_lock); }
132  void read_unlock() { px4_sem_post(&_lock); }
133  void write_lock()
134  {
135  for (int i = 0; i < _max_readers; i++) {
136  px4_sem_wait(&_lock);
137  }
138  }
140  {
141  for (int i = 0; i < _max_readers; i++) {
142  px4_sem_post(&_lock);
143  }
144  }
145 
146  int _readidx;
147  px4_sem_t _lock;
148  const int _max_readers;
149  const int _report_len;
150  RType _buf[2];
151 };
152 
153 } // namespace simulator
154 
155 
156 class Simulator : public ModuleParams
157 {
158 public:
159  static Simulator *getInstance();
160 
161  enum class InternetProtocol {
162  TCP,
163  UDP
164  };
165 
166  static int start(int argc, char *argv[]);
167 
168  bool getGPSSample(uint8_t *buf, int len);
169 
170  void write_gps_data(void *buf);
171 
172  void set_ip(InternetProtocol ip);
173  void set_port(unsigned port);
174 
175 private:
177  ModuleParams(nullptr)
178  {
179  simulator::RawGPSData gps_data{};
180  gps_data.eph = UINT16_MAX;
181  gps_data.epv = UINT16_MAX;
182 
183  _gps.writeData(&gps_data);
184 
185  _battery_status.timestamp = hrt_absolute_time();
186 
187  _px4_accel.set_sample_rate(250);
188  _px4_gyro.set_sample_rate(250);
189  }
190 
192  {
193  // free perf counters
194  perf_free(_perf_gps);
195  perf_free(_perf_sim_delay);
196  perf_free(_perf_sim_interval);
197 
198  _instance = nullptr;
199  }
200 
201  // class methods
202 
203  int publish_flow_topic(const mavlink_hil_optical_flow_t *flow);
204  int publish_odometry_topic(const mavlink_message_t *odom_mavlink);
205  int publish_distance_topic(const mavlink_distance_sensor_t *dist);
206 
208 
209  // simulated sensor instances
210  PX4Accelerometer _px4_accel{1311244, ORB_PRIO_DEFAULT, ROTATION_NONE}; // 1311244: DRV_ACC_DEVTYPE_ACCELSIM, BUS: 1, ADDR: 1, TYPE: SIMULATION
211  PX4Gyroscope _px4_gyro{2294028, ORB_PRIO_DEFAULT, ROTATION_NONE}; // 2294028: DRV_GYR_DEVTYPE_GYROSIM, BUS: 1, ADDR: 2, TYPE: SIMULATION
212  PX4Magnetometer _px4_mag{197388, ORB_PRIO_DEFAULT, ROTATION_NONE}; // 197388: DRV_MAG_DEVTYPE_MAGSIM, BUS: 3, ADDR: 1, TYPE: SIMULATION
213  PX4Barometer _px4_baro{6620172, ORB_PRIO_DEFAULT}; // 6620172: DRV_BARO_DEVTYPE_BAROSIM, BUS: 1, ADDR: 4, TYPE: SIMULATION
214 
216 
217  perf_counter_t _perf_gps{perf_alloc_once(PC_ELAPSED, "sim_gps_delay")};
218  perf_counter_t _perf_sim_delay{perf_alloc_once(PC_ELAPSED, "sim_network_delay")};
219  perf_counter_t _perf_sim_interval{perf_alloc(PC_INTERVAL, "sim_network_interval")};
220 
221  // uORB publisher handlers
222  orb_advert_t _battery_pub{nullptr};
223  orb_advert_t _differential_pressure_pub{nullptr};
224  orb_advert_t _dist_pub{nullptr};
225  orb_advert_t _flow_pub{nullptr};
226  orb_advert_t _irlock_report_pub{nullptr};
227  orb_advert_t _visual_odometry_pub{nullptr};
228 
229  uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)};
230 
231  unsigned int _port{14560};
232 
233  InternetProtocol _ip{InternetProtocol::UDP};
234 
235  double _realtime_factor{1.0}; ///< How fast the simulation runs in comparison to real system time
236 
237  hrt_abstime _last_sim_timestamp{0};
238  hrt_abstime _last_sitl_timestamp{0};
239 
240  // Lib used to do the battery calculations.
241  Battery _battery {};
242  battery_status_s _battery_status{};
243 
244 #ifndef __PX4_QURT
245 
246  mavlink_hil_actuator_controls_t actuator_controls_from_outputs(const actuator_outputs_s &actuators);
247 
248  void handle_message(const mavlink_message_t *msg);
249  void handle_message_distance_sensor(const mavlink_message_t *msg);
250  void handle_message_hil_gps(const mavlink_message_t *msg);
251  void handle_message_hil_sensor(const mavlink_message_t *msg);
252  void handle_message_hil_state_quaternion(const mavlink_message_t *msg);
253  void handle_message_landing_target(const mavlink_message_t *msg);
254  void handle_message_odometry(const mavlink_message_t *msg);
255  void handle_message_optical_flow(const mavlink_message_t *msg);
256  void handle_message_rc_channels(const mavlink_message_t *msg);
257  void handle_message_vision_position_estimate(const mavlink_message_t *msg);
258 
259  void parameters_update(bool force);
260  void poll_topics();
261  void poll_for_MAVLink_messages();
262  void request_hil_state_quaternion();
263  void send();
264  void send_controls();
265  void send_heartbeat();
266  void send_mavlink_message(const mavlink_message_t &aMsg);
267  void update_sensors(const hrt_abstime &time, const mavlink_hil_sensor_t &imu);
268  void update_gps(const mavlink_hil_gps_t *gps_sim);
269 
270  static void *sending_trampoline(void *);
271 
272  // uORB publisher handlers
273  orb_advert_t _vehicle_angular_velocity_pub{nullptr};
274  orb_advert_t _attitude_pub{nullptr};
275  orb_advert_t _gpos_pub{nullptr};
276  orb_advert_t _lpos_pub{nullptr};
277  orb_advert_t _rc_channels_pub{nullptr};
278 
279  // uORB subscription handlers
280  int _actuator_outputs_sub{-1};
281  int _vehicle_status_sub{-1};
282 
283  // hil map_ref data
285 
286  bool _hil_local_proj_inited{false};
287 
288  double _hil_ref_lat{0};
289  double _hil_ref_lon{0};
290  float _hil_ref_alt{0.0f};
291  uint64_t _hil_ref_timestamp{0};
292 
293  // uORB data containers
294  input_rc_s _rc_input {};
296  vehicle_attitude_s _attitude {};
297  vehicle_status_s _vehicle_status {};
298 
299  DEFINE_PARAMETERS(
300  (ParamFloat<px4::params::SIM_BAT_DRAIN>) _param_sim_bat_drain, ///< battery drain interval
301  (ParamFloat<px4::params::SIM_BAT_MIN_PCT>) _battery_min_percentage, //< minimum battery percentage
302  (ParamInt<px4::params::MAV_TYPE>) _param_mav_type,
303  (ParamInt<px4::params::MAV_SYS_ID>) _param_mav_sys_id,
304  (ParamInt<px4::params::MAV_COMP_ID>) _param_mav_comp_id
305  )
306 
307 #endif
308 };
R/C input interface.
measure the time elapsed performing an event
Definition: perf_counter.h:56
API for the uORB lightweight object broker.
Definition of geo / math functions to perform geodesic calculations.
const int _max_readers
Definition: simulator.h:148
void * send(void *data)
bool copyData(void *outbuf, int len)
Definition: simulator.h:111
InternetProtocol
Definition: simulator.h:161
const int _report_len
Definition: simulator.h:149
High-resolution timer with callouts and timekeeping.
Library calls for battery functionality.
uint8_t satellites_visible
Definition: simulator.h:93
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
static Simulator * _instance
Definition: simulator.h:207
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
Header common to all counters.
static void parameters_update()
update all parameters
void writeData(void *inbuf)
Definition: simulator.h:122
void perf_free(perf_counter_t handle)
Free a counter.
void write_unlock()
Definition: simulator.h:139
#define perf_alloc(a, b)
Definition: px4io.h:59
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.
Report(int readers)
Definition: simulator.h:100
~Simulator()
Definition: simulator.h:191
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
static int start()
Definition: dataman.cpp:1452
void read_unlock()
Definition: simulator.h:132
px4_sem_t _lock
Definition: simulator.h:147
measure the interval between instances of an event
Definition: perf_counter.h:57
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
Performance measuring tools.