SIM_Vicon.h 2.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576
  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. simple particle sensor simulation
  15. */
  16. #pragma once
  17. #include "SIM_Aircraft.h"
  18. #include <SITL/SITL.h>
  19. #include <AP_HAL/utility/RingBuffer.h>
  20. namespace SITL {
  21. class Vicon {
  22. public:
  23. Vicon();
  24. // update state
  25. void update(const Location &loc, const Vector3f &position, const Quaternion &attitude);
  26. // return fd on which data from the device can be read, and data
  27. // to the device can be written
  28. int fd() { return fd_their_end; }
  29. private:
  30. SITL *_sitl;
  31. // TODO: make these parameters:
  32. const uint8_t system_id = 17;
  33. const uint8_t component_id = 18;
  34. // we share channels with the ArduPilot binary!
  35. const mavlink_channel_t mavlink_ch = (mavlink_channel_t)(MAVLINK_COMM_0+5);
  36. int fd_their_end;
  37. int fd_my_end;
  38. uint64_t last_observation_usec;
  39. uint64_t time_send_us;
  40. uint64_t time_offset_us;
  41. mavlink_message_t obs_msg;
  42. struct obs_elements {
  43. uint32_t time_ms; // measurement timestamp (msec)
  44. Vector3f position;
  45. Quaternion attitude;
  46. };
  47. void update_vicon_position_estimate(const Location &loc,
  48. const Vector3f &position,
  49. const Quaternion &attitude);
  50. void maybe_send_heartbeat();
  51. uint32_t last_heartbeat_ms;
  52. bool init_sitl_pointer();
  53. };
  54. }