SIM_XPlane.h 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114
  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. simulator connection for ardupilot version of Xplane
  15. */
  16. #pragma once
  17. #include <AP_HAL/utility/Socket.h>
  18. #include "SIM_Aircraft.h"
  19. namespace SITL {
  20. /*
  21. a Xplane simulator
  22. */
  23. class XPlane : public Aircraft {
  24. public:
  25. XPlane(const char *frame_str);
  26. /* update model by one time step */
  27. void update(const struct sitl_input &input) override;
  28. /* static object creator */
  29. static Aircraft *create(const char *frame_str) {
  30. return new XPlane(frame_str);
  31. }
  32. private:
  33. bool receive_data(void);
  34. void send_dref(const char *name, float value);
  35. void send_data(const struct sitl_input &input);
  36. void select_data(uint64_t usel_mask, uint64_t sel_mask);
  37. const char *xplane_ip = "127.0.0.1";
  38. uint16_t xplane_port = 49000;
  39. uint16_t bind_port = 49001;
  40. // udp socket, input and output
  41. SocketAPM socket_in{true};
  42. SocketAPM socket_out{true};
  43. uint64_t time_base_us;
  44. uint32_t last_data_time_ms;
  45. Vector3f position_zero;
  46. Vector3f accel_earth;
  47. float throttle_sent = -1;
  48. bool connected = false;
  49. uint32_t xplane_frame_time;
  50. struct {
  51. uint32_t last_report_ms;
  52. uint32_t data_count;
  53. uint32_t frame_count;
  54. } report;
  55. float last_flap;
  56. // are we controlling a heli?
  57. bool heli_frame;
  58. uint64_t unselected_mask;
  59. // throttle joystick input is very weird. See comments in the main code
  60. const float throttle_magic = 0.000123f;
  61. const float throttle_magic_scale = 1.0e6;
  62. // DATA@ frame types. Thanks to TauLabs xplanesimulator.h
  63. // (which strangely enough acknowledges APM as a source!)
  64. enum {
  65. FramRate = 0,
  66. Times = 1,
  67. SimStats = 2,
  68. Speed = 3,
  69. Gload = 4,
  70. AtmosphereWeather = 5,
  71. AtmosphereAircraft = 6,
  72. SystemPressures = 7,
  73. Joystick1 = 8,
  74. Joystick2 = 9,
  75. ArtStab = 10,
  76. FlightCon = 11,
  77. WingSweep = 12,
  78. Trim = 13,
  79. Brakes = 14,
  80. AngularMoments = 15,
  81. AngularVelocities = 16,
  82. PitchRollHeading = 17,
  83. AoA = 18,
  84. MagCompass = 19,
  85. LatLonAlt = 20,
  86. LocVelDistTraveled = 21,
  87. ThrottleCommand = 25,
  88. Mixture = 29,
  89. CarbHeat = 30,
  90. EngineRPM = 37,
  91. PropRPM = 38,
  92. PropPitch = 39,
  93. Generator = 58,
  94. };
  95. };
  96. } // namespace SITL