ardupilot/libraries/SITL/SIM_Gazebo.h

78 lines
2.1 KiB
C
Raw Normal View History

2015-07-16 19:31:24 -03:00
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
simulator connection for ardupilot version of Gazebo
*/
#pragma once
2015-07-16 19:31:24 -03:00
#include "SIM_Aircraft.h"
#include <AP_HAL/utility/Socket.h>
2015-10-22 10:04:42 -03:00
namespace SITL {
2015-07-16 19:31:24 -03:00
/*
Gazebo simulator
*/
class Gazebo : public Aircraft {
2015-07-16 19:31:24 -03:00
public:
2019-08-15 01:01:24 -03:00
Gazebo(const char *frame_str);
2015-07-16 19:31:24 -03:00
/* update model by one time step */
2019-02-21 19:12:05 -04:00
void update(const struct sitl_input &input) override;
2015-07-16 19:31:24 -03:00
/* static object creator */
2019-08-15 01:01:24 -03:00
static Aircraft *create(const char *frame_str) {
return new Gazebo(frame_str);
2015-07-16 19:31:24 -03:00
}
/* Create and set in/out socket for Gazebo simulator */
2019-02-21 19:12:05 -04:00
void set_interface_ports(const char* address, const int port_in, const int port_out) override;
2015-07-16 19:31:24 -03:00
private:
/*
packet sent to Gazebo
*/
struct servo_packet {
// size matches sitl_input upstream
float motor_speed[16];
2015-07-16 19:31:24 -03:00
};
2015-10-22 10:15:20 -03:00
2015-07-16 19:31:24 -03:00
/*
reply packet sent from Gazebo to ArduPilot
*/
struct fdm_packet {
double timestamp; // in seconds
2015-07-16 19:31:24 -03:00
double imu_angular_velocity_rpy[3];
double imu_linear_acceleration_xyz[3];
double imu_orientation_quat[4];
2015-07-16 19:31:24 -03:00
double velocity_xyz[3];
double position_xyz[3];
};
void recv_fdm(const struct sitl_input &input);
void send_servos(const struct sitl_input &input);
2016-11-18 05:52:10 -04:00
void drain_sockets();
2015-07-16 19:31:24 -03:00
double last_timestamp;
2016-09-21 17:46:12 -03:00
SocketAPM socket_sitl;
const char *_gazebo_address = "127.0.0.1";
int _gazebo_port = 9002;
static const uint64_t GAZEBO_TIMEOUT_US = 5000000;
2015-07-16 19:31:24 -03:00
};
2016-12-19 06:49:56 -04:00
} // namespace SITL