AP_IRLock_SITL_Gazebo.cpp 2.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. * AP_IRLock_SITL.cpp
  15. *
  16. * Created on: June 09, 2016
  17. * Author: Ian Chen
  18. */
  19. #include <AP_HAL/AP_HAL.h>
  20. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  21. #include "AP_IRLock_SITL_Gazebo.h"
  22. #include <SITL/SITL.h>
  23. #include <fcntl.h>
  24. #include <unistd.h>
  25. #include <iostream>
  26. extern const AP_HAL::HAL& hal;
  27. AP_IRLock_SITL_Gazebo::AP_IRLock_SITL_Gazebo() :
  28. _last_timestamp(0),
  29. sock(true)
  30. {}
  31. void AP_IRLock_SITL_Gazebo::init(int8_t bus)
  32. {
  33. SITL::SITL *sitl = AP::sitl();
  34. // try to bind to a specific port so that if we restart ArduPilot
  35. // Gazebo keeps sending us packets. Not strictly necessary but
  36. // useful for debugging
  37. sock.bind("127.0.0.1", sitl->irlock_port);
  38. sock.reuseaddress();
  39. sock.set_blocking(false);
  40. hal.console->printf("AP_IRLock_SITL::init()\n");
  41. _flags.healthy = true;
  42. }
  43. // retrieve latest sensor data - returns true if new data is available
  44. bool AP_IRLock_SITL_Gazebo::update()
  45. {
  46. // return immediately if not healthy
  47. if (!_flags.healthy) {
  48. return false;
  49. }
  50. // receive packet from Gazebo IRLock plugin
  51. /*
  52. reply packet sent from simulator to ArduPilot
  53. */
  54. struct irlock_packet {
  55. uint64_t timestamp; // in miliseconds
  56. uint16_t num_targets;
  57. float pos_x;
  58. float pos_y;
  59. float size_x;
  60. float size_y;
  61. } pkt;
  62. const int wait_ms = 0;
  63. ssize_t s = sock.recv(&pkt, sizeof(irlock_packet), wait_ms);
  64. bool new_data = false;
  65. if (s == sizeof(irlock_packet) && pkt.timestamp > _last_timestamp) {
  66. // fprintf(stderr, " posx %f posy %f sizex %f sizey %f\n", pkt.pos_x, pkt.pos_y, pkt.size_x, pkt.size_y);
  67. _target_info.timestamp = pkt.timestamp;
  68. _target_info.pos_x = pkt.pos_x;
  69. _target_info.pos_y = pkt.pos_y;
  70. _last_timestamp = pkt.timestamp;
  71. _last_update_ms = _last_timestamp;
  72. new_data = true;
  73. }
  74. // return true if new data found
  75. return new_data;
  76. }
  77. #endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL