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> 60 #include <drivers/drv_mag.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> 105 #pragma pack(push, 1) 112 #pragma pack(push, 1) 119 #pragma pack(push, 1) 133 uint8_t satellites_visible;
142 _max_readers(readers),
143 _report_len(
sizeof(RType))
145 memset(_buf, 0,
sizeof(_buf));
146 px4_sem_init(&_lock, 0, _max_readers);
151 bool copyData(
void *outbuf,
int len)
153 if (len != _report_len) {
158 memcpy(outbuf, &_buf[_readidx], _report_len);
162 void writeData(
void *inbuf)
165 memcpy(&_buf[!_readidx], inbuf, _report_len);
166 _readidx = !_readidx;
171 void read_lock() { px4_sem_wait(&_lock); }
172 void read_unlock() { px4_sem_post(&_lock); }
175 for (
int i = 0; i < _max_readers; i++) {
176 px4_sem_wait(&_lock);
181 for (
int i = 0; i < _max_readers; i++) {
182 px4_sem_post(&_lock);
188 const int _max_readers;
189 const int _report_len;
211 sample() : x(0), y(0), z(0) {}
212 sample(
float a,
float b,
float c) : x(a), y(b), z(c) {}
215 enum class InternetProtocol {
220 static int start(
int argc,
char *argv[]);
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);
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);
236 bool isInitialized() {
return _initialized; }
238 void set_ip(InternetProtocol ip);
239 void set_port(
unsigned port);
246 gps_data.eph = UINT16_MAX;
247 gps_data.epv = UINT16_MAX;
249 _gps.writeData(&gps_data);
275 void initialize_sensor_data();
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);
314 unsigned int _port{14560};
316 InternetProtocol _ip{InternetProtocol::UDP};
318 bool _initialized{
false};
320 double _realtime_factor{1.0};
327 battery_status_s _battery_status{};
331 mavlink_hil_actuator_controls_t actuator_controls_from_outputs(
const actuator_outputs_s &actuators);
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);
344 void parameters_update(
bool force);
346 void poll_for_MAVLink_messages();
347 void request_hil_state_quaternion();
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);
356 static void *sending_trampoline(
void *);
365 int _actuator_outputs_sub{-1};
366 int _vehicle_status_sub{-1};
369 struct map_projection_reference_s _hil_local_proj_ref {};
371 bool _hil_local_proj_inited{
false};
372 bool _publish{
false};
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};
380 input_rc_s _rc_input {};
381 manual_control_setpoint_s _manual {};
382 vehicle_attitude_s _attitude {};
383 vehicle_status_s _vehicle_status {};
Accelerometer driver interface.
Definition: px4_param.h:313
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
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.