SIM_Morse.h 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154
  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 morse simulator http://morse-simulator.github.io/
  15. */
  16. #pragma once
  17. #include <AP_HAL/utility/Socket.h>
  18. #include "SIM_Aircraft.h"
  19. namespace SITL {
  20. /*
  21. simulation interface
  22. */
  23. class Morse : public Aircraft {
  24. public:
  25. Morse(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 Morse(frame_str);
  31. }
  32. private:
  33. // loopback to convert inbound Morse lidar data into inbound mavlink msgs
  34. const char *mavlink_loopback_address = "127.0.0.1";
  35. const uint16_t mavlink_loopback_port = 5762;
  36. SocketAPM mav_socket { false };
  37. struct {
  38. // socket to telem2 on aircraft
  39. bool connected;
  40. mavlink_message_t rxmsg;
  41. mavlink_status_t status;
  42. uint8_t seq;
  43. } mavlink {};
  44. void send_report(void);
  45. uint32_t send_report_last_ms;
  46. const char *morse_ip = "127.0.0.1";
  47. // assume sensors are streamed on port 60000
  48. uint16_t morse_sensors_port = 60000;
  49. // assume we control vehicle on port 60001
  50. uint16_t morse_control_port = 60001;
  51. enum {
  52. OUTPUT_ROVER=1,
  53. OUTPUT_QUAD=2,
  54. OUTPUT_PWM=3
  55. } output_type;
  56. bool connect_sockets(void);
  57. bool parse_sensors(const char *json);
  58. bool sensors_receive(void);
  59. void output_rover(const struct sitl_input &input);
  60. void output_quad(const struct sitl_input &input);
  61. void output_pwm(const struct sitl_input &input);
  62. void report_FPS();
  63. // buffer for parsing pose data in JSON format
  64. uint8_t sensor_buffer[50000];
  65. uint32_t sensor_buffer_len;
  66. SocketAPM *sensors_sock;
  67. SocketAPM *control_sock;
  68. uint32_t no_data_counter;
  69. uint32_t connect_counter;
  70. double initial_time_s;
  71. double last_time_s;
  72. double extrapolated_s;
  73. double average_frame_time_s;
  74. uint64_t socket_frame_counter;
  75. uint64_t last_socket_frame_counter;
  76. uint64_t frame_counter;
  77. double last_frame_count_s;
  78. enum data_type {
  79. DATA_FLOAT,
  80. DATA_DOUBLE,
  81. DATA_VECTOR3F,
  82. DATA_VECTOR3F_ARRAY,
  83. DATA_FLOAT_ARRAY,
  84. };
  85. struct {
  86. double timestamp;
  87. struct {
  88. Vector3f angular_velocity;
  89. Vector3f linear_acceleration;
  90. Vector3f magnetic_field;
  91. } imu;
  92. struct {
  93. float x, y, z;
  94. } gps;
  95. struct {
  96. float roll, pitch, yaw;
  97. } pose;
  98. struct {
  99. Vector3f world_linear_velocity;
  100. } velocity;
  101. struct {
  102. struct vector3f_array points;
  103. struct float_array ranges;
  104. } scanner;
  105. } state, last_state;
  106. // table to aid parsing of JSON sensor data
  107. struct keytable {
  108. const char *section;
  109. const char *key;
  110. void *ptr;
  111. enum data_type type;
  112. } keytable[13] = {
  113. { "", "timestamp", &state.timestamp, DATA_DOUBLE },
  114. { ".imu", "angular_velocity", &state.imu.angular_velocity, DATA_VECTOR3F },
  115. { ".imu", "linear_acceleration", &state.imu.linear_acceleration, DATA_VECTOR3F },
  116. { ".imu", "magnetic_field", &state.imu.magnetic_field, DATA_VECTOR3F },
  117. { ".gps", "x", &state.gps.x, DATA_FLOAT },
  118. { ".gps", "y", &state.gps.y, DATA_FLOAT },
  119. { ".gps", "z", &state.gps.z, DATA_FLOAT },
  120. { ".pose", "roll", &state.pose.roll, DATA_FLOAT },
  121. { ".pose", "pitch", &state.pose.pitch, DATA_FLOAT },
  122. { ".pose", "yaw", &state.pose.yaw, DATA_FLOAT },
  123. { ".velocity", "world_linear_velocity", &state.velocity.world_linear_velocity, DATA_VECTOR3F },
  124. { ".scan", "point_list", &state.scanner.points, DATA_VECTOR3F_ARRAY },
  125. { ".scan", "range_list", &state.scanner.ranges, DATA_FLOAT_ARRAY },
  126. };
  127. };
  128. } // namespace SITL