diff --git a/src/modules/simulator/simulator.cpp b/src/modules/simulator/simulator.cpp index b62ef3913e..f0345ba036 100644 --- a/src/modules/simulator/simulator.cpp +++ b/src/modules/simulator/simulator.cpp @@ -164,6 +164,15 @@ int simulator_main(int argc, char *argv[]) 1500, Simulator::start, argv); + + // now wait for the command to complete + while(true) { + if (Simulator::getInstance() && Simulator::getInstance()->isInitialized()) { + break; + } else { + usleep(100000); + } + } } else { diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h index 5d9eaa1f4b..a0901a9ad6 100644 --- a/src/modules/simulator/simulator.h +++ b/src/modules/simulator/simulator.h @@ -197,6 +197,8 @@ public: void write_baro_data(void *buf); void write_gps_data(void *buf); + bool isInitialized() { return _initialized; } + private: Simulator() : _accel(1), @@ -204,11 +206,12 @@ private: _baro(1), _mag(1), _gps(1), -#ifndef __PX4_QURT _accel_pub(nullptr), _baro_pub(nullptr), _gyro_pub(nullptr), _mag_pub(nullptr), + _initialized(false), +#ifndef __PX4_QURT _rc_channels_pub(nullptr), _actuator_outputs_sub(-1), _vehicle_attitude_sub(-1), @@ -238,6 +241,8 @@ private: orb_advert_t _gyro_pub; orb_advert_t _mag_pub; + bool _initialized; + // class methods int publish_sensor_topics(mavlink_hil_sensor_t *imu); diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 6871e66a7e..52f595cd43 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -405,6 +405,7 @@ void Simulator::pollForMAVLinkMessages(bool publish) pret = ::poll(&fds[0], (sizeof(fds[0])/sizeof(fds[0])), 100); } PX4_WARN("Found initial message, pret = %d",pret); + _initialized = true; if (fds[0].revents & POLLIN) { len = recvfrom(_fd, _buf, sizeof(_buf), 0, (struct sockaddr *)&_srcaddr, &_addrlen);