SITL_State.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591
  1. #include <AP_HAL/AP_HAL.h>
  2. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  3. #include "AP_HAL_SITL.h"
  4. #include "AP_HAL_SITL_Namespace.h"
  5. #include "HAL_SITL_Class.h"
  6. #include "UARTDriver.h"
  7. #include "Scheduler.h"
  8. #include <stdio.h>
  9. #include <signal.h>
  10. #include <unistd.h>
  11. #include <stdlib.h>
  12. #include <errno.h>
  13. #include <sys/select.h>
  14. #include <AP_Param/AP_Param.h>
  15. #include <SITL/SIM_JSBSim.h>
  16. #include <AP_HAL/utility/Socket.h>
  17. extern const AP_HAL::HAL& hal;
  18. using namespace HALSITL;
  19. void SITL_State::_set_param_default(const char *parm)
  20. {
  21. char *pdup = strdup(parm);
  22. char *p = strchr(pdup, '=');
  23. if (p == nullptr) {
  24. printf("Please specify parameter as NAME=VALUE");
  25. exit(1);
  26. }
  27. float value = strtof(p+1, nullptr);
  28. *p = 0;
  29. enum ap_var_type var_type;
  30. AP_Param *vp = AP_Param::find(pdup, &var_type);
  31. if (vp == nullptr) {
  32. printf("Unknown parameter %s\n", pdup);
  33. exit(1);
  34. }
  35. if (var_type == AP_PARAM_FLOAT) {
  36. ((AP_Float *)vp)->set_and_save(value);
  37. } else if (var_type == AP_PARAM_INT32) {
  38. ((AP_Int32 *)vp)->set_and_save(value);
  39. } else if (var_type == AP_PARAM_INT16) {
  40. ((AP_Int16 *)vp)->set_and_save(value);
  41. } else if (var_type == AP_PARAM_INT8) {
  42. ((AP_Int8 *)vp)->set_and_save(value);
  43. } else {
  44. printf("Unable to set parameter %s\n", pdup);
  45. exit(1);
  46. }
  47. printf("Set parameter %s to %f\n", pdup, value);
  48. free(pdup);
  49. }
  50. /*
  51. setup for SITL handling
  52. */
  53. void SITL_State::_sitl_setup(const char *home_str)
  54. {
  55. _home_str = home_str;
  56. #if !defined(__CYGWIN__) && !defined(__CYGWIN64__)
  57. _parent_pid = getppid();
  58. #endif
  59. #ifndef HIL_MODE
  60. _setup_fdm();
  61. #endif
  62. fprintf(stdout, "Starting SITL input\n");
  63. // find the barometer object if it exists
  64. _sitl = AP::sitl();
  65. _barometer = AP_Baro::get_singleton();
  66. _ins = AP_InertialSensor::get_singleton();
  67. _compass = Compass::get_singleton();
  68. #if AP_TERRAIN_AVAILABLE
  69. _terrain = reinterpret_cast<AP_Terrain *>(AP_Param::find_object("TERRAIN_"));
  70. #endif
  71. if (_sitl != nullptr) {
  72. // setup some initial values
  73. #ifndef HIL_MODE
  74. _update_airspeed(0);
  75. _update_gps(0, 0, 0, 0, 0, 0, 0, false);
  76. _update_rangefinder(0);
  77. #endif
  78. if (enable_gimbal) {
  79. gimbal = new SITL::Gimbal(_sitl->state);
  80. }
  81. sitl_model->set_sprayer(&_sitl->sprayer_sim);
  82. sitl_model->set_gripper_servo(&_sitl->gripper_sim);
  83. sitl_model->set_gripper_epm(&_sitl->gripper_epm_sim);
  84. sitl_model->set_parachute(&_sitl->parachute_sim);
  85. sitl_model->set_precland(&_sitl->precland_sim);
  86. if (_use_fg_view) {
  87. fg_socket.connect(_fg_address, _fg_view_port);
  88. }
  89. fprintf(stdout, "Using Irlock at port : %d\n", _irlock_port);
  90. _sitl->irlock_port = _irlock_port;
  91. }
  92. if (_synthetic_clock_mode) {
  93. // start with non-zero clock
  94. hal.scheduler->stop_clock(1);
  95. }
  96. }
  97. #ifndef HIL_MODE
  98. /*
  99. setup a SITL FDM listening UDP port
  100. */
  101. void SITL_State::_setup_fdm(void)
  102. {
  103. if (!_sitl_rc_in.reuseaddress()) {
  104. fprintf(stderr, "SITL: socket reuseaddress failed on RC in port: %d - %s\n", _rcin_port, strerror(errno));
  105. fprintf(stderr, "Aborting launch...\n");
  106. exit(1);
  107. }
  108. if (!_sitl_rc_in.bind("0.0.0.0", _rcin_port)) {
  109. fprintf(stderr, "SITL: socket bind failed on RC in port : %d - %s\n", _rcin_port, strerror(errno));
  110. fprintf(stderr, "Aborting launch...\n");
  111. exit(1);
  112. }
  113. if (!_sitl_rc_in.set_blocking(false)) {
  114. fprintf(stderr, "SITL: socket set_blocking(false) failed on RC in port: %d - %s\n", _rcin_port, strerror(errno));
  115. fprintf(stderr, "Aborting launch...\n");
  116. exit(1);
  117. }
  118. if (!_sitl_rc_in.set_cloexec()) {
  119. fprintf(stderr, "SITL: socket set_cloexec() failed on RC in port: %d - %s\n", _rcin_port, strerror(errno));
  120. fprintf(stderr, "Aborting launch...\n");
  121. exit(1);
  122. }
  123. }
  124. #endif
  125. /*
  126. step the FDM by one time step
  127. */
  128. void SITL_State::_fdm_input_step(void)
  129. {
  130. static uint32_t last_pwm_input = 0;
  131. _fdm_input_local();
  132. /* make sure we die if our parent dies */
  133. if (kill(_parent_pid, 0) != 0) {
  134. exit(1);
  135. }
  136. if (_scheduler->interrupts_are_blocked() || _sitl == nullptr) {
  137. return;
  138. }
  139. // simulate RC input at 50Hz
  140. if (AP_HAL::millis() - last_pwm_input >= 20 && _sitl->rc_fail != SITL::SITL::SITL_RCFail_NoPulses) {
  141. last_pwm_input = AP_HAL::millis();
  142. new_rc_input = true;
  143. }
  144. _scheduler->sitl_begin_atomic();
  145. if (_update_count == 0 && _sitl != nullptr) {
  146. _update_gps(0, 0, 0, 0, 0, 0, 0, false);
  147. _scheduler->timer_event();
  148. _scheduler->sitl_end_atomic();
  149. return;
  150. }
  151. if (_sitl != nullptr) {
  152. _update_gps(_sitl->state.latitude, _sitl->state.longitude,
  153. _sitl->state.altitude,
  154. _sitl->state.speedN, _sitl->state.speedE, _sitl->state.speedD,
  155. _sitl->state.yawDeg,
  156. !_sitl->gps_disable);
  157. _update_airspeed(_sitl->state.airspeed);
  158. _update_rangefinder(_sitl->state.range);
  159. if (_sitl->adsb_plane_count >= 0 &&
  160. adsb == nullptr) {
  161. adsb = new SITL::ADSB(_sitl->state, _home_str);
  162. } else if (_sitl->adsb_plane_count == -1 &&
  163. adsb != nullptr) {
  164. delete adsb;
  165. adsb = nullptr;
  166. }
  167. }
  168. // trigger all APM timers.
  169. _scheduler->timer_event();
  170. _scheduler->sitl_end_atomic();
  171. }
  172. void SITL_State::wait_clock(uint64_t wait_time_usec)
  173. {
  174. while (AP_HAL::micros64() < wait_time_usec) {
  175. if (hal.scheduler->in_main_thread() ||
  176. Scheduler::from(hal.scheduler)->semaphore_wait_hack_required()) {
  177. _fdm_input_step();
  178. } else {
  179. usleep(1000);
  180. }
  181. }
  182. }
  183. #define streq(a, b) (!strcmp(a, b))
  184. int SITL_State::sim_fd(const char *name, const char *arg)
  185. {
  186. if (streq(name, "vicon")) {
  187. if (vicon != nullptr) {
  188. AP_HAL::panic("Only one vicon system at a time");
  189. }
  190. vicon = new SITL::Vicon();
  191. return vicon->fd();
  192. }
  193. AP_HAL::panic("unknown simulated device: %s", name);
  194. }
  195. #ifndef HIL_MODE
  196. /*
  197. check for a SITL RC input packet
  198. */
  199. void SITL_State::_check_rc_input(void)
  200. {
  201. uint32_t count = 0;
  202. while (_read_rc_sitl_input()) {
  203. count++;
  204. }
  205. if (count > 100) {
  206. ::fprintf(stderr, "Read %u rc inputs\n", count);
  207. }
  208. }
  209. bool SITL_State::_read_rc_sitl_input()
  210. {
  211. struct pwm_packet {
  212. uint16_t pwm[16];
  213. } pwm_pkt;
  214. const ssize_t size = _sitl_rc_in.recv(&pwm_pkt, sizeof(pwm_pkt), 0);
  215. switch (size) {
  216. case -1:
  217. return false;
  218. case 8*2:
  219. case 16*2: {
  220. // a packet giving the receiver PWM inputs
  221. for (uint8_t i=0; i<size/2; i++) {
  222. // setup the pwm input for the RC channel inputs
  223. if (i < _sitl->state.rcin_chan_count) {
  224. // we're using rc from simulator
  225. continue;
  226. }
  227. uint16_t pwm = pwm_pkt.pwm[i];
  228. if (pwm != 0) {
  229. if (_sitl->rc_fail == SITL::SITL::SITL_RCFail_Throttle950) {
  230. if (i == 2) {
  231. // set throttle (assumed to be on channel 3...)
  232. pwm = 950;
  233. } else {
  234. // centre all other inputs
  235. pwm = 1500;
  236. }
  237. }
  238. pwm_input[i] = pwm;
  239. }
  240. }
  241. return true;
  242. }
  243. default:
  244. fprintf(stderr, "Malformed SITL RC input (%li)", size);
  245. }
  246. return false;
  247. }
  248. /*
  249. output current state to flightgear
  250. */
  251. void SITL_State::_output_to_flightgear(void)
  252. {
  253. SITL::FGNetFDM fdm {};
  254. const SITL::sitl_fdm &sfdm = _sitl->state;
  255. fdm.version = 0x18;
  256. fdm.padding = 0;
  257. fdm.longitude = DEG_TO_RAD_DOUBLE*sfdm.longitude;
  258. fdm.latitude = DEG_TO_RAD_DOUBLE*sfdm.latitude;
  259. fdm.altitude = sfdm.altitude;
  260. fdm.agl = sfdm.altitude;
  261. fdm.phi = radians(sfdm.rollDeg);
  262. fdm.theta = radians(sfdm.pitchDeg);
  263. fdm.psi = radians(sfdm.yawDeg);
  264. if (_vehicle == ArduCopter) {
  265. fdm.num_engines = 4;
  266. for (uint8_t i=0; i<4; i++) {
  267. fdm.rpm[i] = constrain_float((pwm_output[i]-1000), 0, 1000);
  268. }
  269. } else {
  270. fdm.num_engines = 4;
  271. fdm.rpm[0] = constrain_float((pwm_output[2]-1000)*3, 0, 3000);
  272. // for quadplane
  273. fdm.rpm[1] = constrain_float((pwm_output[5]-1000)*12, 0, 12000);
  274. fdm.rpm[2] = constrain_float((pwm_output[6]-1000)*12, 0, 12000);
  275. fdm.rpm[3] = constrain_float((pwm_output[7]-1000)*12, 0, 12000);
  276. }
  277. fdm.ByteSwap();
  278. fg_socket.send(&fdm, sizeof(fdm));
  279. }
  280. /*
  281. get FDM input from a local model
  282. */
  283. void SITL_State::_fdm_input_local(void)
  284. {
  285. struct sitl_input input;
  286. // check for direct RC input
  287. _check_rc_input();
  288. // construct servos structure for FDM
  289. _simulator_servos(input);
  290. // update the model
  291. sitl_model->update_model(input);
  292. // get FDM output from the model
  293. if (_sitl) {
  294. sitl_model->fill_fdm(_sitl->state);
  295. _sitl->update_rate_hz = sitl_model->get_rate_hz();
  296. if (_sitl->rc_fail == SITL::SITL::SITL_RCFail_None) {
  297. for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) {
  298. pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000;
  299. }
  300. }
  301. }
  302. if (gimbal != nullptr) {
  303. gimbal->update();
  304. }
  305. if (adsb != nullptr) {
  306. adsb->update();
  307. }
  308. if (vicon != nullptr) {
  309. Quaternion attitude;
  310. sitl_model->get_attitude(attitude);
  311. vicon->update(sitl_model->get_location(),
  312. sitl_model->get_position(),
  313. attitude);
  314. }
  315. if (_sitl && _use_fg_view) {
  316. _output_to_flightgear();
  317. }
  318. // update simulation time
  319. if (_sitl) {
  320. hal.scheduler->stop_clock(_sitl->state.timestamp_us);
  321. } else {
  322. hal.scheduler->stop_clock(AP_HAL::micros64()+100);
  323. }
  324. set_height_agl();
  325. _synthetic_clock_mode = true;
  326. _update_count++;
  327. }
  328. #endif
  329. /*
  330. create sitl_input structure for sending to FDM
  331. */
  332. void SITL_State::_simulator_servos(struct sitl_input &input)
  333. {
  334. static uint32_t last_update_usec;
  335. /* this maps the registers used for PWM outputs. The RC
  336. * driver updates these whenever it wants the channel output
  337. * to change */
  338. uint8_t i;
  339. if (last_update_usec == 0 || !output_ready) {
  340. for (i=0; i<SITL_NUM_CHANNELS; i++) {
  341. pwm_output[i] = 1000;
  342. }
  343. if (_vehicle == ArduPlane) {
  344. pwm_output[0] = pwm_output[1] = pwm_output[3] = 1500;
  345. }
  346. if (_vehicle == APMrover2) {
  347. pwm_output[0] = pwm_output[1] = pwm_output[2] = pwm_output[3] = 1500;
  348. }
  349. }
  350. // output at chosen framerate
  351. uint32_t now = AP_HAL::micros();
  352. last_update_usec = now;
  353. float altitude = _barometer?_barometer->get_altitude():0;
  354. float wind_speed = 0;
  355. float wind_direction = 0;
  356. float wind_dir_z = 0;
  357. // give 5 seconds to calibrate airspeed sensor at 0 wind speed
  358. if (wind_start_delay_micros == 0) {
  359. wind_start_delay_micros = now;
  360. } else if (_sitl && (now - wind_start_delay_micros) > 5000000 ) {
  361. // The EKF does not like step inputs so this LPF keeps it happy.
  362. wind_speed = _sitl->wind_speed_active = (0.95f*_sitl->wind_speed_active) + (0.05f*_sitl->wind_speed);
  363. wind_direction = _sitl->wind_direction_active = (0.95f*_sitl->wind_direction_active) + (0.05f*_sitl->wind_direction);
  364. wind_dir_z = _sitl->wind_dir_z_active = (0.95f*_sitl->wind_dir_z_active) + (0.05f*_sitl->wind_dir_z);
  365. // pass wind into simulators using different wind types via param SIM_WIND_T*.
  366. switch (_sitl->wind_type) {
  367. case SITL::SITL::WIND_TYPE_SQRT:
  368. if (altitude < _sitl->wind_type_alt) {
  369. wind_speed *= sqrtf(MAX(altitude / _sitl->wind_type_alt, 0));
  370. }
  371. break;
  372. case SITL::SITL::WIND_TYPE_COEF:
  373. wind_speed += (altitude - _sitl->wind_type_alt) * _sitl->wind_type_coef;
  374. break;
  375. case SITL::SITL::WIND_TYPE_NO_LIMIT:
  376. default:
  377. break;
  378. }
  379. // never allow negative wind velocity
  380. wind_speed = MAX(wind_speed, 0);
  381. }
  382. input.wind.speed = wind_speed;
  383. input.wind.direction = wind_direction;
  384. input.wind.turbulence = _sitl?_sitl->wind_turbulance:0;
  385. input.wind.dir_z = wind_dir_z;
  386. for (i=0; i<SITL_NUM_CHANNELS; i++) {
  387. if (pwm_output[i] == 0xFFFF) {
  388. input.servos[i] = 0;
  389. } else {
  390. input.servos[i] = pwm_output[i];
  391. }
  392. }
  393. float engine_mul = _sitl?_sitl->engine_mul.get():1;
  394. uint8_t engine_fail = _sitl?_sitl->engine_fail.get():0;
  395. bool motors_on = false;
  396. if (engine_fail >= ARRAY_SIZE(input.servos)) {
  397. engine_fail = 0;
  398. }
  399. // apply engine multiplier to motor defined by the SIM_ENGINE_FAIL parameter
  400. if (_vehicle != APMrover2) {
  401. input.servos[engine_fail] = ((input.servos[engine_fail]-1000) * engine_mul) + 1000;
  402. } else {
  403. input.servos[engine_fail] = static_cast<uint16_t>(((input.servos[engine_fail] - 1500) * engine_mul) + 1500);
  404. }
  405. if (_vehicle == ArduPlane) {
  406. motors_on = ((input.servos[2] - 1000) / 1000.0f) > 0;
  407. } else if (_vehicle == APMrover2) {
  408. input.servos[2] = static_cast<uint16_t>(constrain_int16(input.servos[2], 1000, 2000));
  409. input.servos[0] = static_cast<uint16_t>(constrain_int16(input.servos[0], 1000, 2000));
  410. motors_on = !is_zero(((input.servos[2] - 1500) / 500.0f));
  411. } else {
  412. motors_on = false;
  413. // run checks on each motor
  414. for (i=0; i<4; i++) {
  415. // check motors do not exceed their limits
  416. if (input.servos[i] > 2000) input.servos[i] = 2000;
  417. if (input.servos[i] < 1000) input.servos[i] = 1000;
  418. // update motor_on flag
  419. if ((input.servos[i]-1000)/1000.0f > 0) {
  420. motors_on = true;
  421. }
  422. }
  423. }
  424. if (_sitl) {
  425. _sitl->motors_on = motors_on;
  426. }
  427. float voltage = 0;
  428. _current = 0;
  429. if (_sitl != nullptr) {
  430. if (_sitl->state.battery_voltage <= 0) {
  431. if (_vehicle == ArduSub) {
  432. voltage = _sitl->batt_voltage;
  433. for (i = 0; i < 6; i++) {
  434. float pwm = input.servos[i];
  435. //printf("i: %d, pwm: %.2f\n", i, pwm);
  436. float fraction = fabsf((pwm - 1500) / 500.0f);
  437. voltage -= fraction * 0.5f;
  438. float draw = fraction * 15;
  439. _current += draw;
  440. }
  441. } else {
  442. // simulate simple battery setup
  443. float throttle;
  444. if (_vehicle == APMrover2) {
  445. throttle = motors_on ? (input.servos[2] - 1500) / 500.0f : 0;
  446. } else {
  447. throttle = motors_on ? (input.servos[2] - 1000) / 1000.0f : 0;
  448. }
  449. // lose 0.7V at full throttle
  450. voltage = _sitl->batt_voltage - 0.7f*fabsf(throttle);
  451. // assume 50A at full throttle
  452. _current = 50.0f * fabsf(throttle);
  453. }
  454. } else {
  455. // FDM provides voltage and current
  456. voltage = _sitl->state.battery_voltage;
  457. _current = _sitl->state.battery_current;
  458. }
  459. }
  460. // assume 3DR power brick
  461. voltage_pin_value = ((voltage / 10.1f) / 5.0f) * 1024;
  462. current_pin_value = ((_current / 17.0f) / 5.0f) * 1024;
  463. // fake battery2 as just a 25% gain on the first one
  464. voltage2_pin_value = ((voltage * 0.25f / 10.1f) / 5.0f) * 1024;
  465. current2_pin_value = ((_current * 0.25f / 17.0f) / 5.0f) * 1024;
  466. }
  467. void SITL_State::init(int argc, char * const argv[])
  468. {
  469. pwm_input[0] = pwm_input[1] = pwm_input[3] = 1500;
  470. pwm_input[4] = pwm_input[7] = 1800;
  471. pwm_input[2] = pwm_input[5] = pwm_input[6] = 1000;
  472. _scheduler = Scheduler::from(hal.scheduler);
  473. _parse_command_line(argc, argv);
  474. }
  475. /*
  476. set height above the ground in meters
  477. */
  478. void SITL_State::set_height_agl(void)
  479. {
  480. static float home_alt = -1;
  481. if (!_sitl) {
  482. // in example program
  483. return;
  484. }
  485. if (is_equal(home_alt, -1.0f) && _sitl->state.altitude > 0) {
  486. // remember home altitude as first non-zero altitude
  487. home_alt = _sitl->state.altitude;
  488. }
  489. #if AP_TERRAIN_AVAILABLE
  490. if (_terrain != nullptr &&
  491. _sitl != nullptr &&
  492. _sitl->terrain_enable) {
  493. // get height above terrain from AP_Terrain. This assumes
  494. // AP_Terrain is working
  495. float terrain_height_amsl;
  496. struct Location location;
  497. location.lat = _sitl->state.latitude*1.0e7;
  498. location.lng = _sitl->state.longitude*1.0e7;
  499. if (_terrain->height_amsl(location, terrain_height_amsl, false)) {
  500. _sitl->height_agl = _sitl->state.altitude - terrain_height_amsl;
  501. return;
  502. }
  503. }
  504. #endif
  505. if (_sitl != nullptr) {
  506. // fall back to flat earth model
  507. _sitl->height_agl = _sitl->state.altitude - home_alt;
  508. }
  509. }
  510. #endif