|
|
|
@ -63,6 +63,8 @@ void SITL_State::_set_param_default(const char *parm)
@@ -63,6 +63,8 @@ void SITL_State::_set_param_default(const char *parm)
|
|
|
|
|
*/ |
|
|
|
|
void SITL_State::_sitl_setup(const char *home_str) |
|
|
|
|
{ |
|
|
|
|
_home_str = home_str; |
|
|
|
|
|
|
|
|
|
#ifndef __CYGWIN__ |
|
|
|
|
_parent_pid = getppid(); |
|
|
|
|
#endif |
|
|
|
@ -97,10 +99,6 @@ void SITL_State::_sitl_setup(const char *home_str)
@@ -97,10 +99,6 @@ void SITL_State::_sitl_setup(const char *home_str)
|
|
|
|
|
gimbal = new SITL::Gimbal(_sitl->state); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (_sitl->adsb_plane_count >= 0) { |
|
|
|
|
adsb = new SITL::ADSB(_sitl->state, home_str); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
fg_socket.connect("127.0.0.1", 5503); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -173,6 +171,15 @@ void SITL_State::_fdm_input_step(void)
@@ -173,6 +171,15 @@ void SITL_State::_fdm_input_step(void)
|
|
|
|
|
_update_barometer(_sitl->state.altitude); |
|
|
|
|
_update_compass(_sitl->state.rollDeg, _sitl->state.pitchDeg, _sitl->state.yawDeg); |
|
|
|
|
_update_flow(); |
|
|
|
|
|
|
|
|
|
if (_sitl->adsb_plane_count >= 0 && |
|
|
|
|
adsb == nullptr) { |
|
|
|
|
adsb = new SITL::ADSB(_sitl->state, _home_str); |
|
|
|
|
} else if (_sitl->adsb_plane_count == -1 && |
|
|
|
|
adsb != nullptr) { |
|
|
|
|
delete adsb; |
|
|
|
|
adsb = nullptr; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// trigger all APM timers.
|
|
|
|
|