APM:Libraries
SIM_XPlane.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 Xplane
17 */
18 
19 #pragma once
20 
21 #include <AP_HAL/utility/Socket.h>
22 
23 #include "SIM_Aircraft.h"
24 
25 namespace SITL {
26 
27 /*
28  a Xplane simulator
29  */
30 class XPlane : public Aircraft {
31 public:
32  XPlane(const char *home_str, const char *frame_str);
33 
34  /* update model by one time step */
35  void update(const struct sitl_input &input);
36 
37  /* static object creator */
38  static Aircraft *create(const char *home_str, const char *frame_str) {
39  return new XPlane(home_str, frame_str);
40  }
41 
42 private:
43  bool receive_data(void);
44  void send_dref(const char *name, float value);
45  void send_data(const struct sitl_input &input);
46  void select_data(uint64_t usel_mask, uint64_t sel_mask);
47 
48  const char *xplane_ip = "127.0.0.1";
49  uint16_t xplane_port = 49000;
50  uint16_t bind_port = 49001;
51  // udp socket, input and output
52  SocketAPM socket_in{true};
53  SocketAPM socket_out{true};
54 
55  uint64_t time_base_us;
59  float throttle_sent = -1;
60  bool connected = false;
62  struct {
63  uint32_t last_report_ms;
64  uint32_t data_count;
65  uint32_t frame_count;
66  } report;
67  float last_flap;
68 
69  // are we controlling a heli?
70  bool heli_frame;
71 
72  uint64_t unselected_mask;
73 
74  // throttle joystick input is very weird. See comments in the main code
75  const float throttle_magic = 0.000123f;
76  const float throttle_magic_scale = 1.0e6;
77 
78  // DATA@ frame types. Thanks to TauLabs xplanesimulator.h
79  // (which strangely enough acknowledges APM as a source!)
80  enum {
81  FramRate = 0,
82  Times = 1,
83  SimStats = 2,
84  Speed = 3,
85  Gload = 4,
89  Joystick1 = 8,
90  Joystick2 = 9,
91  ArtStab = 10,
92  FlightCon = 11,
93  WingSweep = 12,
94  Trim = 13,
95  Brakes = 14,
99  AoA = 18,
101  LatLonAlt = 20,
104  Mixture = 29,
105  CarbHeat = 30,
106  EngineRPM = 37,
107  PropRPM = 38,
108  PropPitch = 39,
109  Generator = 58,
110  };
111 };
112 
113 
114 } // namespace SITL
uint32_t frame_count
Definition: SIM_XPlane.h:65
void select_data(uint64_t usel_mask, uint64_t sel_mask)
Definition: SIM_XPlane.cpp:59
bool heli_frame
Definition: SIM_XPlane.h:70
void send_dref(const char *name, float value)
Definition: SIM_XPlane.cpp:446
uint32_t data_count
Definition: SIM_XPlane.h:64
const char * name
Definition: BusTest.cpp:11
float throttle_sent
Definition: SIM_XPlane.h:59
Vector3f accel_earth
Definition: SIM_XPlane.h:58
static Aircraft * create(const char *home_str, const char *frame_str)
Definition: SIM_XPlane.h:38
bool receive_data(void)
Definition: SIM_XPlane.cpp:101
bool connected
Definition: SIM_XPlane.h:60
const char * xplane_ip
Definition: SIM_XPlane.h:48
SocketAPM socket_in
Definition: SIM_XPlane.h:52
void update(const struct sitl_input &input)
Definition: SIM_XPlane.cpp:461
uint32_t xplane_frame_time
Definition: SIM_XPlane.h:61
SocketAPM socket_out
Definition: SIM_XPlane.h:53
uint64_t unselected_mask
Definition: SIM_XPlane.h:72
void send_data(const struct sitl_input &input)
Definition: SIM_XPlane.cpp:357
const float throttle_magic_scale
Definition: SIM_XPlane.h:76
float value
Vector3f position_zero
Definition: SIM_XPlane.h:57
struct SITL::XPlane::@211 report
uint64_t time_base_us
Definition: SIM_XPlane.h:55
uint32_t last_data_time_ms
Definition: SIM_XPlane.h:56
uint16_t bind_port
Definition: SIM_XPlane.h:50
XPlane(const char *home_str, const char *frame_str)
Definition: SIM_XPlane.cpp:35
uint16_t xplane_port
Definition: SIM_XPlane.h:49
float last_flap
Definition: SIM_XPlane.h:67
uint32_t last_report_ms
Definition: SIM_XPlane.h:63
const float throttle_magic
Definition: SIM_XPlane.h:75