SIM_FlightAxis.h 7.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188
  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 FlightAxis
  15. */
  16. #pragma once
  17. #include <AP_HAL/utility/Socket.h>
  18. #include "SIM_Aircraft.h"
  19. namespace SITL {
  20. /*
  21. a FlightAxis simulator
  22. */
  23. class FlightAxis : public Aircraft {
  24. public:
  25. FlightAxis(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 FlightAxis(frame_str);
  31. }
  32. struct state {
  33. double rcin[8];
  34. double m_airspeed_MPS;
  35. double m_altitudeASL_MTR;
  36. double m_altitudeAGL_MTR;
  37. double m_groundspeed_MPS;
  38. double m_pitchRate_DEGpSEC;
  39. double m_rollRate_DEGpSEC;
  40. double m_yawRate_DEGpSEC;
  41. double m_azimuth_DEG;
  42. double m_inclination_DEG;
  43. double m_roll_DEG;
  44. double m_aircraftPositionX_MTR;
  45. double m_aircraftPositionY_MTR;
  46. double m_velocityWorldU_MPS;
  47. double m_velocityWorldV_MPS;
  48. double m_velocityWorldW_MPS;
  49. double m_velocityBodyU_MPS;
  50. double m_velocityBodyV_MPS;
  51. double m_velocityBodyW_MPS;
  52. double m_accelerationWorldAX_MPS2;
  53. double m_accelerationWorldAY_MPS2;
  54. double m_accelerationWorldAZ_MPS2;
  55. double m_accelerationBodyAX_MPS2;
  56. double m_accelerationBodyAY_MPS2;
  57. double m_accelerationBodyAZ_MPS2;
  58. double m_windX_MPS;
  59. double m_windY_MPS;
  60. double m_windZ_MPS;
  61. double m_propRPM;
  62. double m_heliMainRotorRPM;
  63. double m_batteryVoltage_VOLTS;
  64. double m_batteryCurrentDraw_AMPS;
  65. double m_batteryRemainingCapacity_MAH;
  66. double m_fuelRemaining_OZ;
  67. double m_isLocked;
  68. double m_hasLostComponents;
  69. double m_anEngineIsRunning;
  70. double m_isTouchingGround;
  71. double m_currentAircraftStatus;
  72. double m_currentPhysicsTime_SEC;
  73. double m_currentPhysicsSpeedMultiplier;
  74. double m_orientationQuaternion_X;
  75. double m_orientationQuaternion_Y;
  76. double m_orientationQuaternion_Z;
  77. double m_orientationQuaternion_W;
  78. double m_flightAxisControllerIsActive;
  79. double m_resetButtonHasBeenPressed;
  80. } state;
  81. static const uint16_t num_keys = sizeof(state)/sizeof(double);
  82. struct keytable {
  83. const char *key;
  84. double &ref;
  85. } keytable[num_keys] = {
  86. { "item", state.rcin[0] },
  87. { "item", state.rcin[1] },
  88. { "item", state.rcin[2] },
  89. { "item", state.rcin[3] },
  90. { "item", state.rcin[4] },
  91. { "item", state.rcin[5] },
  92. { "item", state.rcin[6] },
  93. { "item", state.rcin[7] },
  94. { "m-airspeed-MPS", state.m_airspeed_MPS },
  95. { "m-altitudeASL-MTR", state.m_altitudeASL_MTR },
  96. { "m-altitudeAGL-MTR", state.m_altitudeAGL_MTR },
  97. { "m-groundspeed-MPS", state.m_groundspeed_MPS },
  98. { "m-pitchRate-DEGpSEC", state.m_pitchRate_DEGpSEC },
  99. { "m-rollRate-DEGpSEC", state.m_rollRate_DEGpSEC },
  100. { "m-yawRate-DEGpSEC", state.m_yawRate_DEGpSEC },
  101. { "m-azimuth-DEG", state.m_azimuth_DEG },
  102. { "m-inclination-DEG", state.m_inclination_DEG },
  103. { "m-roll-DEG", state.m_roll_DEG },
  104. { "m-aircraftPositionX-MTR", state.m_aircraftPositionX_MTR },
  105. { "m-aircraftPositionY-MTR", state.m_aircraftPositionY_MTR },
  106. { "m-velocityWorldU-MPS", state.m_velocityWorldU_MPS },
  107. { "m-velocityWorldV-MPS", state.m_velocityWorldV_MPS },
  108. { "m-velocityWorldW-MPS", state.m_velocityWorldW_MPS },
  109. { "m-velocityBodyU-MPS", state.m_velocityBodyU_MPS },
  110. { "m-velocityBodyV-MPS", state.m_velocityBodyV_MPS },
  111. { "m-velocityBodyW-MPS", state.m_velocityBodyW_MPS },
  112. { "m-accelerationWorldAX-MPS2", state.m_accelerationWorldAX_MPS2 },
  113. { "m-accelerationWorldAY-MPS2", state.m_accelerationWorldAY_MPS2 },
  114. { "m-accelerationWorldAZ-MPS2", state.m_accelerationWorldAZ_MPS2 },
  115. { "m-accelerationBodyAX-MPS2", state.m_accelerationBodyAX_MPS2 },
  116. { "m-accelerationBodyAY-MPS2", state.m_accelerationBodyAY_MPS2 },
  117. { "m-accelerationBodyAZ-MPS2", state.m_accelerationBodyAZ_MPS2 },
  118. { "m-windX-MPS", state.m_windX_MPS },
  119. { "m-windY-MPS", state.m_windY_MPS },
  120. { "m-windZ-MPS", state.m_windZ_MPS },
  121. { "m-propRPM", state.m_propRPM },
  122. { "m-heliMainRotorRPM", state.m_heliMainRotorRPM },
  123. { "m-batteryVoltage-VOLTS", state.m_batteryVoltage_VOLTS },
  124. { "m-batteryCurrentDraw-AMPS", state.m_batteryCurrentDraw_AMPS },
  125. { "m-batteryRemainingCapacity-MAH", state.m_batteryRemainingCapacity_MAH },
  126. { "m-fuelRemaining-OZ", state.m_fuelRemaining_OZ },
  127. { "m-isLocked", state.m_isLocked },
  128. { "m-hasLostComponents", state.m_hasLostComponents },
  129. { "m-anEngineIsRunning", state.m_anEngineIsRunning },
  130. { "m-isTouchingGround", state.m_isTouchingGround },
  131. { "m-currentAircraftStatus", state.m_currentAircraftStatus },
  132. { "m-currentPhysicsTime-SEC", state.m_currentPhysicsTime_SEC },
  133. { "m-currentPhysicsSpeedMultiplier", state.m_currentPhysicsSpeedMultiplier },
  134. { "m-orientationQuaternion-X", state.m_orientationQuaternion_X },
  135. { "m-orientationQuaternion-Y", state.m_orientationQuaternion_Y },
  136. { "m-orientationQuaternion-Z", state.m_orientationQuaternion_Z },
  137. { "m-orientationQuaternion-W", state.m_orientationQuaternion_W },
  138. { "m-flightAxisControllerIsActive", state.m_flightAxisControllerIsActive },
  139. { "m-resetButtonHasBeenPressed", state.m_resetButtonHasBeenPressed },
  140. };
  141. private:
  142. char *soap_request(const char *action, const char *fmt, ...);
  143. void exchange_data(const struct sitl_input &input);
  144. void parse_reply(const char *reply);
  145. static void *update_thread(void *arg);
  146. void update_loop(void);
  147. void report_FPS(void);
  148. struct sitl_input last_input;
  149. double average_frame_time_s;
  150. double extrapolated_s;
  151. double initial_time_s;
  152. double last_time_s;
  153. bool heli_demix;
  154. bool rev4_servos;
  155. bool controller_started;
  156. uint64_t frame_counter;
  157. uint64_t activation_frame_counter;
  158. uint64_t socket_frame_counter;
  159. uint64_t last_socket_frame_counter;
  160. double last_frame_count_s;
  161. Vector3f position_offset;
  162. Vector3f last_velocity_ef;
  163. const char *controller_ip = "127.0.0.1";
  164. uint16_t controller_port = 18083;
  165. pthread_t thread;
  166. HAL_Semaphore mutex;
  167. };
  168. } // namespace SITL