Browse Source

SITL: change SIM_ADSB default to -1 to default disabled to leave telem port available

master
Tom Pittenger 9 years ago
parent
commit
1770f314ac
  1. 5
      libraries/AP_HAL_SITL/SITL_State.cpp
  2. 2
      libraries/SITL/SITL.cpp

5
libraries/AP_HAL_SITL/SITL_State.cpp

@ -97,7 +97,10 @@ void SITL_State::_sitl_setup(const char *home_str)
gimbal = new SITL::Gimbal(_sitl->state); gimbal = new SITL::Gimbal(_sitl->state);
} }
adsb = new SITL::ADSB(_sitl->state, home_str); if (_sitl->adsb_plane_count >= 0) {
adsb = new SITL::ADSB(_sitl->state, home_str);
}
fg_socket.connect("127.0.0.1", 5503); fg_socket.connect("127.0.0.1", 5503);
} }

2
libraries/SITL/SITL.cpp

@ -76,7 +76,7 @@ const AP_Param::GroupInfo SITL::var_info[] = {
AP_GROUPINFO("ACC2_RND", 42, SITL, accel2_noise, 0), AP_GROUPINFO("ACC2_RND", 42, SITL, accel2_noise, 0),
AP_GROUPINFO("ARSPD_FAIL", 43, SITL, arspd_fail, 0), AP_GROUPINFO("ARSPD_FAIL", 43, SITL, arspd_fail, 0),
AP_GROUPINFO("GYR_SCALE", 44, SITL, gyro_scale, 0), AP_GROUPINFO("GYR_SCALE", 44, SITL, gyro_scale, 0),
AP_GROUPINFO("ADSB_COUNT", 45, SITL, adsb_plane_count, 0), AP_GROUPINFO("ADSB_COUNT", 45, SITL, adsb_plane_count, -1),
AP_GROUPINFO("ADSB_RADIUS", 46, SITL, adsb_radius_m, 1000), AP_GROUPINFO("ADSB_RADIUS", 46, SITL, adsb_radius_m, 1000),
AP_GROUPINFO("ADSB_ALT", 47, SITL, adsb_altitude_m, 1000), AP_GROUPINFO("ADSB_ALT", 47, SITL, adsb_altitude_m, 1000),
AP_GROUPEND AP_GROUPEND

Loading…
Cancel
Save