Browse Source

Sim: Enforce boot order is correct, sim starts first

sbg
Lorenz Meier 10 years ago
parent
commit
5a1af860ab
  1. 9
      src/modules/simulator/simulator.cpp
  2. 7
      src/modules/simulator/simulator.h
  3. 1
      src/modules/simulator/simulator_mavlink.cpp

9
src/modules/simulator/simulator.cpp

@ -164,6 +164,15 @@ int simulator_main(int argc, char *argv[]) @@ -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
{

7
src/modules/simulator/simulator.h

@ -197,6 +197,8 @@ public: @@ -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: @@ -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: @@ -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);

1
src/modules/simulator/simulator_mavlink.cpp

@ -405,6 +405,7 @@ void Simulator::pollForMAVLinkMessages(bool publish) @@ -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);

Loading…
Cancel
Save