APM:Libraries
SIM_Gazebo.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  simulator connector for ardupilot version of Gazebo
17 */
18 
19 #include "SIM_Gazebo.h"
20 
21 #include <stdio.h>
22 #include <errno.h>
23 
24 #include <AP_HAL/AP_HAL.h>
25 
26 extern const AP_HAL::HAL& hal;
27 
28 namespace SITL {
29 
30 Gazebo::Gazebo(const char *home_str, const char *frame_str) :
31  Aircraft(home_str, frame_str),
32  last_timestamp(0),
33  socket_sitl{true}
34 {
35  // try to bind to a specific port so that if we restart ArduPilot
36  // Gazebo keeps sending us packets. Not strictly necessary but
37  // useful for debugging
38  fprintf(stdout, "Starting SITL Gazebo\n");
39 }
40 
41 /*
42  Create and set in/out socket
43 */
44 void Gazebo::set_interface_ports(const char* address, const int port_in, const int port_out)
45 {
46  if (!socket_sitl.bind("0.0.0.0", port_in)) {
47  fprintf(stderr, "SITL: socket in bind failed on sim in : %d - %s\n", port_in, strerror(errno));
48  fprintf(stderr, "Abording launch...\n");
49  exit(1);
50  }
51  printf("Bind %s:%d for SITL in\n", "127.0.0.1", port_in);
52  socket_sitl.reuseaddress();
53  socket_sitl.set_blocking(false);
54 
55  _gazebo_address = address;
56  _gazebo_port = port_out;
57  printf("Setting Gazebo interface to %s:%d \n", _gazebo_address, _gazebo_port);
58 }
59 
60 /*
61  decode and send servos
62 */
63 void Gazebo::send_servos(const struct sitl_input &input)
64 {
65  servo_packet pkt;
66  // should rename servo_command
67  // 16 because struct sitl_input.servos is 16 large in SIM_Aircraft.h
68  for (unsigned i = 0; i < 16; ++i)
69  {
70  pkt.motor_speed[i] = (input.servos[i]-1000) / 1000.0f;
71  }
72  socket_sitl.sendto(&pkt, sizeof(pkt), _gazebo_address, _gazebo_port);
73 }
74 
75 /*
76  receive an update from the FDM
77  This is a blocking function
78  */
79 void Gazebo::recv_fdm(const struct sitl_input &input)
80 {
81  fdm_packet pkt;
82 
83  /*
84  we re-send the servo packet every 0.1 seconds until we get a
85  reply. This allows us to cope with some packet loss to the FDM
86  */
87  while (socket_sitl.recv(&pkt, sizeof(pkt), 100) != sizeof(pkt)) {
88  send_servos(input);
89  // Reset the timestamp after a long disconnection, also catch gazebo reset
91  last_timestamp = 0;
92  }
93  }
94 
95  const double deltat = pkt.timestamp - last_timestamp; // in seconds
96  if (deltat < 0) { // don't use old paquet
97  time_now_us += 1;
98  return;
99  }
100  // get imu stuff
101  accel_body = Vector3f(static_cast<float>(pkt.imu_linear_acceleration_xyz[0]),
102  static_cast<float>(pkt.imu_linear_acceleration_xyz[1]),
103  static_cast<float>(pkt.imu_linear_acceleration_xyz[2]));
104 
105  gyro = Vector3f(static_cast<float>(pkt.imu_angular_velocity_rpy[0]),
106  static_cast<float>(pkt.imu_angular_velocity_rpy[1]),
107  static_cast<float>(pkt.imu_angular_velocity_rpy[2]));
108 
109  // compute dcm from imu orientation
110  Quaternion quat(static_cast<float>(pkt.imu_orientation_quat[0]),
111  static_cast<float>(pkt.imu_orientation_quat[1]),
112  static_cast<float>(pkt.imu_orientation_quat[2]),
113  static_cast<float>(pkt.imu_orientation_quat[3]));
114  quat.rotation_matrix(dcm);
115 
116  velocity_ef = Vector3f(static_cast<float>(pkt.velocity_xyz[0]),
117  static_cast<float>(pkt.velocity_xyz[1]),
118  static_cast<float>(pkt.velocity_xyz[2]));
119 
120  position = Vector3f(static_cast<float>(pkt.position_xyz[0]),
121  static_cast<float>(pkt.position_xyz[1]),
122  static_cast<float>(pkt.position_xyz[2]));
123 
124 
125  // auto-adjust to simulation frame rate
126  time_now_us += static_cast<uint64_t>(deltat * 1.0e6);
127 
128  if (deltat < 0.01 && deltat > 0) {
129  adjust_frame_time(static_cast<float>(1.0/deltat));
130  }
132 
133 }
134 
135 /*
136  Drain remaining data on the socket to prevent phase lag.
137  */
139 {
140  const uint16_t buflen = 1024;
141  char buf[buflen];
142  ssize_t received;
143  errno = 0;
144  do {
145  received = socket_sitl.recv(buf, buflen, 0);
146  if (received < 0) {
147  if (errno != EAGAIN && errno != EWOULDBLOCK && errno != 0) {
148  fprintf(stderr, "error recv on socket in: %s \n",
149  strerror(errno));
150  }
151  } else {
152  // fprintf(stderr, "received from control socket: %s\n", buf);
153  }
154  } while (received > 0);
155 
156 }
157 
158 /*
159  update the Gazebo simulation by one time step
160  */
161 void Gazebo::update(const struct sitl_input &input)
162 {
163  send_servos(input);
164  recv_fdm(input);
165  update_position();
166 
167  time_advance();
168  // update magnetic field
170  drain_sockets();
171 }
172 
173 } // namespace SITL
Vector3f accel_body
Definition: SIM_Aircraft.h:142
int printf(const char *fmt,...)
Definition: stdio.c:113
Vector3f position
Definition: SIM_Aircraft.h:140
int _gazebo_port
Definition: SIM_Gazebo.h:73
static const uint64_t GAZEBO_TIMEOUT_US
Definition: SIM_Gazebo.h:74
Vector3< float > Vector3f
Definition: vector3.h:246
void drain_sockets()
Definition: SIM_Gazebo.cpp:138
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
double imu_linear_acceleration_xyz[3]
Definition: SIM_Gazebo.h:59
uint64_t get_wall_time_us(void) const
double imu_orientation_quat[4]
Definition: SIM_Gazebo.h:60
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void recv_fdm(const struct sitl_input &input)
Definition: SIM_Gazebo.cpp:79
double last_timestamp
Definition: SIM_Gazebo.h:69
void update(const struct sitl_input &input)
Definition: SIM_Gazebo.cpp:161
#define f(i)
Vector3f velocity_ef
Definition: SIM_Aircraft.h:136
const char * _gazebo_address
Definition: SIM_Gazebo.h:72
uint64_t time_now_us
Definition: SIM_Aircraft.h:160
void rotation_matrix(Matrix3f &m) const
Definition: quaternion.cpp:24
void adjust_frame_time(float rate)
static uint8_t buflen
Definition: srxl.cpp:57
void update_mag_field_bf(void)
void update_position(void)
void send_servos(const struct sitl_input &input)
Definition: SIM_Gazebo.cpp:63
Gazebo(const char *home_str, const char *frame_str)
Definition: SIM_Gazebo.cpp:30
SocketAPM socket_sitl
Definition: SIM_Gazebo.h:71
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
uint64_t last_wall_time_us
Definition: SIM_Aircraft.h:169
void set_interface_ports(const char *address, const int port_in, const int port_out)
Definition: SIM_Gazebo.cpp:44
double imu_angular_velocity_rpy[3]
Definition: SIM_Gazebo.h:58