2016-06-17 09:03:00 -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 Xplane
|
|
|
|
*/
|
|
|
|
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_HAL/utility/Socket.h>
|
|
|
|
|
|
|
|
#include "SIM_Aircraft.h"
|
|
|
|
|
|
|
|
namespace SITL {
|
|
|
|
|
|
|
|
/*
|
|
|
|
a Xplane simulator
|
|
|
|
*/
|
|
|
|
class XPlane : public Aircraft {
|
|
|
|
public:
|
2019-08-15 01:01:24 -03:00
|
|
|
XPlane(const char *frame_str);
|
2016-06-17 09:03:00 -03:00
|
|
|
|
|
|
|
/* update model by one time step */
|
2019-02-21 19:12:05 -04:00
|
|
|
void update(const struct sitl_input &input) override;
|
2016-06-17 09:03:00 -03:00
|
|
|
|
|
|
|
/* static object creator */
|
2019-08-15 01:01:24 -03:00
|
|
|
static Aircraft *create(const char *frame_str) {
|
|
|
|
return new XPlane(frame_str);
|
2016-06-17 09:03:00 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
private:
|
|
|
|
bool receive_data(void);
|
2016-06-30 07:26:00 -03:00
|
|
|
void send_dref(const char *name, float value);
|
2016-06-17 09:03:00 -03:00
|
|
|
void send_data(const struct sitl_input &input);
|
2016-06-19 07:57:34 -03:00
|
|
|
void select_data(uint64_t usel_mask, uint64_t sel_mask);
|
2016-06-17 09:03:00 -03:00
|
|
|
|
|
|
|
const char *xplane_ip = "127.0.0.1";
|
|
|
|
uint16_t xplane_port = 49000;
|
|
|
|
uint16_t bind_port = 49001;
|
|
|
|
// udp socket, input and output
|
|
|
|
SocketAPM socket_in{true};
|
|
|
|
SocketAPM socket_out{true};
|
|
|
|
|
|
|
|
uint64_t time_base_us;
|
|
|
|
uint32_t last_data_time_ms;
|
|
|
|
Vector3f position_zero;
|
|
|
|
Vector3f accel_earth;
|
|
|
|
float throttle_sent = -1;
|
|
|
|
bool connected = false;
|
2016-06-19 22:18:14 -03:00
|
|
|
uint32_t xplane_frame_time;
|
|
|
|
struct {
|
|
|
|
uint32_t last_report_ms;
|
|
|
|
uint32_t data_count;
|
|
|
|
uint32_t frame_count;
|
|
|
|
} report;
|
2016-06-30 07:26:00 -03:00
|
|
|
float last_flap;
|
2016-06-17 09:03:00 -03:00
|
|
|
|
2016-07-12 01:39:44 -03:00
|
|
|
// are we controlling a heli?
|
|
|
|
bool heli_frame;
|
2017-01-06 23:41:23 -04:00
|
|
|
|
|
|
|
uint64_t unselected_mask;
|
2016-07-12 01:39:44 -03:00
|
|
|
|
2016-06-19 08:10:49 -03:00
|
|
|
// throttle joystick input is very weird. See comments in the main code
|
2016-07-04 20:40:04 -03:00
|
|
|
const float throttle_magic = 0.000123f;
|
|
|
|
const float throttle_magic_scale = 1.0e6;
|
2016-06-17 09:03:00 -03:00
|
|
|
|
|
|
|
// DATA@ frame types. Thanks to TauLabs xplanesimulator.h
|
|
|
|
// (which strangely enough acknowledges APM as a source!)
|
|
|
|
enum {
|
|
|
|
FramRate = 0,
|
|
|
|
Times = 1,
|
|
|
|
SimStats = 2,
|
|
|
|
Speed = 3,
|
|
|
|
Gload = 4,
|
|
|
|
AtmosphereWeather = 5,
|
|
|
|
AtmosphereAircraft = 6,
|
|
|
|
SystemPressures = 7,
|
|
|
|
Joystick1 = 8,
|
|
|
|
Joystick2 = 9,
|
|
|
|
ArtStab = 10,
|
|
|
|
FlightCon = 11,
|
|
|
|
WingSweep = 12,
|
|
|
|
Trim = 13,
|
|
|
|
Brakes = 14,
|
|
|
|
AngularMoments = 15,
|
|
|
|
AngularVelocities = 16,
|
|
|
|
PitchRollHeading = 17,
|
|
|
|
AoA = 18,
|
|
|
|
MagCompass = 19,
|
|
|
|
LatLonAlt = 20,
|
|
|
|
LocVelDistTraveled = 21,
|
|
|
|
ThrottleCommand = 25,
|
2016-07-22 06:14:46 -03:00
|
|
|
Mixture = 29,
|
|
|
|
CarbHeat = 30,
|
2016-07-12 01:39:44 -03:00
|
|
|
EngineRPM = 37,
|
|
|
|
PropRPM = 38,
|
|
|
|
PropPitch = 39,
|
|
|
|
Generator = 58,
|
2016-06-17 09:03:00 -03:00
|
|
|
};
|
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
} // namespace SITL
|