SIM_Gazebo.cpp 5.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173
  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 connector for ardupilot version of Gazebo
  15. */
  16. #include "SIM_Gazebo.h"
  17. #include <stdio.h>
  18. #include <errno.h>
  19. #include <AP_HAL/AP_HAL.h>
  20. extern const AP_HAL::HAL& hal;
  21. namespace SITL {
  22. Gazebo::Gazebo(const char *frame_str) :
  23. Aircraft(frame_str),
  24. last_timestamp(0),
  25. socket_sitl{true}
  26. {
  27. fprintf(stdout, "Starting SITL Gazebo\n");
  28. }
  29. /*
  30. Create and set in/out socket
  31. */
  32. void Gazebo::set_interface_ports(const char* address, const int port_in, const int port_out)
  33. {
  34. // try to bind to a specific port so that if we restart ArduPilot
  35. // Gazebo keeps sending us packets. Not strictly necessary but
  36. // useful for debugging
  37. if (!socket_sitl.bind("0.0.0.0", port_in)) {
  38. fprintf(stderr, "SITL: socket in bind failed on sim in : %d - %s\n", port_in, strerror(errno));
  39. fprintf(stderr, "Aborting launch...\n");
  40. exit(1);
  41. }
  42. printf("Bind %s:%d for SITL in\n", "127.0.0.1", port_in);
  43. socket_sitl.reuseaddress();
  44. socket_sitl.set_blocking(false);
  45. _gazebo_address = address;
  46. _gazebo_port = port_out;
  47. printf("Setting Gazebo interface to %s:%d \n", _gazebo_address, _gazebo_port);
  48. }
  49. /*
  50. decode and send servos
  51. */
  52. void Gazebo::send_servos(const struct sitl_input &input)
  53. {
  54. servo_packet pkt;
  55. // should rename servo_command
  56. // 16 because struct sitl_input.servos is 16 large in SIM_Aircraft.h
  57. for (unsigned i = 0; i < 16; ++i)
  58. {
  59. pkt.motor_speed[i] = (input.servos[i]-1000) / 1000.0f;
  60. }
  61. socket_sitl.sendto(&pkt, sizeof(pkt), _gazebo_address, _gazebo_port);
  62. }
  63. /*
  64. receive an update from the FDM
  65. This is a blocking function
  66. */
  67. void Gazebo::recv_fdm(const struct sitl_input &input)
  68. {
  69. fdm_packet pkt;
  70. /*
  71. we re-send the servo packet every 0.1 seconds until we get a
  72. reply. This allows us to cope with some packet loss to the FDM
  73. */
  74. while (socket_sitl.recv(&pkt, sizeof(pkt), 100) != sizeof(pkt)) {
  75. send_servos(input);
  76. // Reset the timestamp after a long disconnection, also catch gazebo reset
  77. if (get_wall_time_us() > last_wall_time_us + GAZEBO_TIMEOUT_US) {
  78. last_timestamp = 0;
  79. }
  80. }
  81. const double deltat = pkt.timestamp - last_timestamp; // in seconds
  82. if (deltat < 0) { // don't use old packet
  83. time_now_us += 1;
  84. return;
  85. }
  86. // get imu stuff
  87. accel_body = Vector3f(static_cast<float>(pkt.imu_linear_acceleration_xyz[0]),
  88. static_cast<float>(pkt.imu_linear_acceleration_xyz[1]),
  89. static_cast<float>(pkt.imu_linear_acceleration_xyz[2]));
  90. gyro = Vector3f(static_cast<float>(pkt.imu_angular_velocity_rpy[0]),
  91. static_cast<float>(pkt.imu_angular_velocity_rpy[1]),
  92. static_cast<float>(pkt.imu_angular_velocity_rpy[2]));
  93. // compute dcm from imu orientation
  94. Quaternion quat(static_cast<float>(pkt.imu_orientation_quat[0]),
  95. static_cast<float>(pkt.imu_orientation_quat[1]),
  96. static_cast<float>(pkt.imu_orientation_quat[2]),
  97. static_cast<float>(pkt.imu_orientation_quat[3]));
  98. quat.rotation_matrix(dcm);
  99. velocity_ef = Vector3f(static_cast<float>(pkt.velocity_xyz[0]),
  100. static_cast<float>(pkt.velocity_xyz[1]),
  101. static_cast<float>(pkt.velocity_xyz[2]));
  102. position = Vector3f(static_cast<float>(pkt.position_xyz[0]),
  103. static_cast<float>(pkt.position_xyz[1]),
  104. static_cast<float>(pkt.position_xyz[2]));
  105. // auto-adjust to simulation frame rate
  106. time_now_us += static_cast<uint64_t>(deltat * 1.0e6);
  107. if (deltat < 0.01 && deltat > 0) {
  108. adjust_frame_time(static_cast<float>(1.0/deltat));
  109. }
  110. last_timestamp = pkt.timestamp;
  111. }
  112. /*
  113. Drain remaining data on the socket to prevent phase lag.
  114. */
  115. void Gazebo::drain_sockets()
  116. {
  117. const uint16_t buflen = 1024;
  118. char buf[buflen];
  119. ssize_t received;
  120. errno = 0;
  121. do {
  122. received = socket_sitl.recv(buf, buflen, 0);
  123. if (received < 0) {
  124. if (errno != EAGAIN && errno != EWOULDBLOCK && errno != 0) {
  125. fprintf(stderr, "error recv on socket in: %s \n",
  126. strerror(errno));
  127. }
  128. } else {
  129. // fprintf(stderr, "received from control socket: %s\n", buf);
  130. }
  131. } while (received > 0);
  132. }
  133. /*
  134. update the Gazebo simulation by one time step
  135. */
  136. void Gazebo::update(const struct sitl_input &input)
  137. {
  138. send_servos(input);
  139. recv_fdm(input);
  140. update_position();
  141. time_advance();
  142. // update magnetic field
  143. update_mag_field_bf();
  144. drain_sockets();
  145. }
  146. } // namespace SITL