SIM_Webots.h 3.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139
  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 webots simulator https://github.com/omichel/webots
  15. */
  16. #pragma once
  17. #include <cmath>
  18. #include <AP_HAL/utility/Socket.h>
  19. #include "SIM_Aircraft.h"
  20. namespace SITL {
  21. /*
  22. simulation interface
  23. */
  24. class Webots : public Aircraft {
  25. public:
  26. Webots(const char *frame_str);
  27. /* update model by one time step */
  28. void update(const struct sitl_input &input) override;
  29. /* output servo to simulator */
  30. void output(const struct sitl_input &input);
  31. /* static object creator */
  32. static Aircraft *create(const char *frame_str) {
  33. return new Webots(frame_str);
  34. }
  35. private:
  36. const char *webots_ip = "127.0.0.1";
  37. // assume sensors are streamed on port 5599
  38. uint16_t webots_sensors_port = 5599;
  39. enum {
  40. OUTPUT_ROVER=1,
  41. OUTPUT_QUAD=2,
  42. OUTPUT_PWM=3
  43. } output_type;
  44. bool connect_sockets(void);
  45. bool parse_sensors(const char *json);
  46. bool sensors_receive(void);
  47. void output_rover(const struct sitl_input &input);
  48. void output_quad(const struct sitl_input &input);
  49. void output_pwm(const struct sitl_input &input);
  50. void report_FPS();
  51. // buffer for parsing pose data in JSON format
  52. uint8_t sensor_buffer[50000];
  53. uint32_t sensor_buffer_len;
  54. SocketAPM *sim_sock;
  55. uint32_t no_data_counter;
  56. uint32_t connect_counter;
  57. double initial_time_s;
  58. double extrapolated_s;
  59. double average_frame_time_s;
  60. uint64_t socket_frame_counter;
  61. uint64_t last_socket_frame_counter;
  62. uint64_t frame_counter;
  63. double last_frame_count_s;
  64. enum data_type {
  65. DATA_FLOAT,
  66. DATA_DOUBLE,
  67. DATA_VECTOR3F,
  68. DATA_VECTOR3F_ARRAY,
  69. DATA_FLOAT_ARRAY,
  70. };
  71. struct {
  72. double timestamp;
  73. struct {
  74. Vector3f angular_velocity;
  75. Vector3f linear_acceleration;
  76. Vector3f magnetic_field;
  77. } imu;
  78. struct {
  79. float x, y, z;
  80. } gps;
  81. struct {
  82. float roll, pitch, yaw;
  83. } pose;
  84. struct {
  85. Vector3f world_linear_velocity;
  86. } velocity;
  87. struct {
  88. struct vector3f_array points;
  89. struct float_array ranges;
  90. } scanner;
  91. } state, last_state;
  92. // table to aid parsing of JSON sensor data
  93. struct keytable {
  94. const char *section;
  95. const char *key;
  96. void *ptr;
  97. enum data_type type;
  98. } keytable[13] = {
  99. { "", "ts", &state.timestamp, DATA_DOUBLE },
  100. { ".imu", "av", &state.imu.angular_velocity, DATA_VECTOR3F },
  101. { ".imu", "la", &state.imu.linear_acceleration, DATA_VECTOR3F },
  102. { ".imu", "mf", &state.imu.magnetic_field, DATA_VECTOR3F },
  103. { ".gps", "x", &state.gps.x, DATA_FLOAT },
  104. { ".gps", "y", &state.gps.y, DATA_FLOAT },
  105. { ".gps", "z", &state.gps.z, DATA_FLOAT },
  106. { ".pose", "roll", &state.pose.roll, DATA_FLOAT },
  107. { ".pose", "pitch", &state.pose.pitch, DATA_FLOAT },
  108. { ".pose", "yaw", &state.pose.yaw, DATA_FLOAT },
  109. { ".velocity", "wlv", &state.velocity.world_linear_velocity, DATA_VECTOR3F },
  110. { ".scan", "pl", &state.scanner.points, DATA_VECTOR3F_ARRAY },
  111. { ".scan", "rl", &state.scanner.ranges, DATA_FLOAT_ARRAY },
  112. };
  113. };
  114. } // namespace SITL