APM:Libraries
SIM_Gazebo.h
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 connection for ardupilot version of Gazebo
17 */
18 
19 #pragma once
20 
21 #include "SIM_Aircraft.h"
22 #include <AP_HAL/utility/Socket.h>
23 
24 namespace SITL {
25 
26 /*
27  Gazebo simulator
28  */
29 class Gazebo : public Aircraft {
30 public:
31  Gazebo(const char *home_str, const char *frame_str);
32 
33  /* update model by one time step */
34  void update(const struct sitl_input &input);
35 
36  /* static object creator */
37  static Aircraft *create(const char *home_str, const char *frame_str) {
38  return new Gazebo(home_str, frame_str);
39  }
40 
41  /* Create and set in/out socket for Gazebo simulator */
42  void set_interface_ports(const char* address, const int port_in, const int port_out);
43 
44 private:
45  /*
46  packet sent to Gazebo
47  */
48  struct servo_packet {
49  // size matches sitl_input upstream
50  float motor_speed[16];
51  };
52 
53  /*
54  reply packet sent from Gazebo to ArduPilot
55  */
56  struct fdm_packet {
57  double timestamp; // in seconds
58  double imu_angular_velocity_rpy[3];
59  double imu_linear_acceleration_xyz[3];
60  double imu_orientation_quat[4];
61  double velocity_xyz[3];
62  double position_xyz[3];
63  };
64 
65  void recv_fdm(const struct sitl_input &input);
66  void send_servos(const struct sitl_input &input);
67  void drain_sockets();
68 
70 
71  SocketAPM socket_sitl;
72  const char *_gazebo_address = "127.0.0.1";
73  int _gazebo_port = 9002;
74  static const uint64_t GAZEBO_TIMEOUT_US = 5000000;
75 };
76 
77 } // namespace SITL
int _gazebo_port
Definition: SIM_Gazebo.h:73
static const uint64_t GAZEBO_TIMEOUT_US
Definition: SIM_Gazebo.h:74
void drain_sockets()
Definition: SIM_Gazebo.cpp:138
static Aircraft * create(const char *home_str, const char *frame_str)
Definition: SIM_Gazebo.h:37
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
const char * _gazebo_address
Definition: SIM_Gazebo.h:72
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
void set_interface_ports(const char *address, const int port_in, const int port_out)
Definition: SIM_Gazebo.cpp:44