SIM_CRRCSim.h 2.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879
  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 CRRCSim
  15. */
  16. #pragma once
  17. #include <AP_HAL/utility/Socket.h>
  18. #include "SIM_Aircraft.h"
  19. namespace SITL {
  20. /*
  21. a CRRCSim simulator
  22. */
  23. class CRRCSim : public Aircraft {
  24. public:
  25. CRRCSim(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 CRRCSim(frame_str);
  31. }
  32. private:
  33. /*
  34. packet sent to CRRCSim
  35. */
  36. struct servo_packet {
  37. float roll_rate;
  38. float pitch_rate;
  39. float throttle;
  40. float yaw_rate;
  41. float col_pitch;
  42. };
  43. /*
  44. reply packet sent from CRRCSim to ArduPilot
  45. */
  46. struct fdm_packet {
  47. double timestamp;
  48. double latitude, longitude;
  49. double altitude;
  50. double heading;
  51. double speedN, speedE, speedD;
  52. double xAccel, yAccel, zAccel;
  53. double rollRate, pitchRate, yawRate;
  54. double roll, pitch, yaw;
  55. double airspeed;
  56. };
  57. void send_servos_heli(const struct sitl_input &input);
  58. void send_servos_fixed_wing(const struct sitl_input &input);
  59. void recv_fdm(const struct sitl_input &input);
  60. void send_servos(const struct sitl_input &input);
  61. bool heli_servos;
  62. double last_timestamp;
  63. SocketAPM sock;
  64. };
  65. } // namespace SITL