54 #include <px4_platform_common/module_params.h> 55 #include <px4_platform_common/posix.h> 73 #include <v2.0/common/mavlink.h> 74 #include <v2.0/mavlink_types.h> 97 template <
typename RType>
class Report 102 _max_readers(readers),
103 _report_len(sizeof(RType))
106 px4_sem_init(&_lock, 0, _max_readers);
113 if (len != _report_len) {
118 memcpy(outbuf, &
_buf[_readidx], _report_len);
125 memcpy(&
_buf[!_readidx], inbuf, _report_len);
126 _readidx = !_readidx;
135 for (
int i = 0; i < _max_readers; i++) {
136 px4_sem_wait(&_lock);
141 for (
int i = 0; i < _max_readers; i++) {
142 px4_sem_post(&_lock);
166 static int start(
int argc,
char *argv[]);
168 bool getGPSSample(uint8_t *buf,
int len);
170 void write_gps_data(
void *buf);
173 void set_port(
unsigned port);
177 ModuleParams(nullptr)
180 gps_data.
eph = UINT16_MAX;
181 gps_data.epv = UINT16_MAX;
183 _gps.writeData(&gps_data);
187 _px4_accel.set_sample_rate(250);
188 _px4_gyro.set_sample_rate(250);
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);
231 unsigned int _port{14560};
235 double _realtime_factor{1.0};
246 mavlink_hil_actuator_controls_t actuator_controls_from_outputs(
const actuator_outputs_s &actuators);
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);
261 void poll_for_MAVLink_messages();
262 void request_hil_state_quaternion();
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);
270 static void *sending_trampoline(
void *);
280 int _actuator_outputs_sub{-1};
281 int _vehicle_status_sub{-1};
286 bool _hil_local_proj_inited{
false};
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};
300 (ParamFloat<px4::params::SIM_BAT_DRAIN>) _param_sim_bat_drain,
301 (ParamFloat<px4::params::SIM_BAT_MIN_PCT>) _battery_min_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
measure the time elapsed performing an event
API for the uORB lightweight object broker.
Definition of geo / math functions to perform geodesic calculations.
bool copyData(void *outbuf, int len)
High-resolution timer with callouts and timekeeping.
Library calls for battery functionality.
uint8_t satellites_visible
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
static Simulator * _instance
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
static unsigned char _buf[2048]
static void parameters_update()
update all parameters
void writeData(void *inbuf)
void perf_free(perf_counter_t handle)
Free a counter.
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.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
measure the interval between instances of an event
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
Performance measuring tools.