SIM_Scrimmage.h 2.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  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 Scrimmage Simulator
  15. */
  16. #pragma once
  17. #include <string>
  18. #include <AP_HAL/utility/Socket.h>
  19. #include "SIM_Aircraft.h"
  20. namespace SITL {
  21. /*
  22. a last_letter simulator
  23. */
  24. class Scrimmage : public Aircraft {
  25. public:
  26. Scrimmage(const char *frame_str);
  27. /* update model by one time step */
  28. void update(const struct sitl_input &input) override;
  29. /* static object creator */
  30. static Aircraft *create(const char *frame_str) {
  31. return new Scrimmage(frame_str);
  32. }
  33. void set_config(const char *config) override;
  34. /* Create and set in/out socket for extenal simulator */
  35. void set_interface_ports(const char* address, const int port_in, const int port_out) override;
  36. private:
  37. uint16_t fdm_port_in;
  38. uint16_t fdm_port_out;
  39. const char* fdm_address;
  40. /*
  41. packet sent to Scrimmage from ArduPilot
  42. */
  43. static const int MAX_NUM_SERVOS = 16;
  44. struct servo_packet {
  45. uint16_t servos[MAX_NUM_SERVOS];
  46. };
  47. /*
  48. state packet sent from Scrimmage to ArduPilot
  49. */
  50. struct fdm_packet {
  51. uint64_t timestamp_us; // simulation time in microseconds
  52. double latitude, longitude;
  53. double altitude;
  54. double heading;
  55. double speedN, speedE, speedD;
  56. double xAccel, yAccel, zAccel;
  57. double rollRate, pitchRate, yawRate;
  58. double roll, pitch, yaw;
  59. double airspeed;
  60. };
  61. void recv_fdm(const struct sitl_input &input);
  62. void send_servos(const struct sitl_input &input);
  63. void start_scrimmage(void);
  64. uint64_t prev_timestamp_us;
  65. SocketAPM recv_sock;
  66. SocketAPM send_sock;
  67. const char *frame_str;
  68. // Use ArduPlane by default
  69. const char *mission_name = "arduplane.xml";
  70. const char *motion_model = "JSBSimControl";
  71. const char *visual_model = "zephyr-blue";
  72. const char *terrain = "mcmillan";
  73. };
  74. } // namespace SITL