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
|
|
|
|
|
2021-10-11 01:59:19 -03:00
|
|
|
#include <AP_HAL/AP_HAL_Boards.h>
|
|
|
|
|
|
|
|
#ifndef HAL_SIM_XPLANE_ENABLED
|
|
|
|
#define HAL_SIM_XPLANE_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if HAL_SIM_XPLANE_ENABLED
|
|
|
|
|
2016-06-17 09:03:00 -03:00
|
|
|
#include <AP_HAL/utility/Socket.h>
|
2023-01-28 01:47:25 -04:00
|
|
|
#include <AP_Filesystem/AP_Filesystem.h>
|
2016-06-17 09:03:00 -03:00
|
|
|
|
|
|
|
#include "SIM_Aircraft.h"
|
2023-01-28 01:47:25 -04:00
|
|
|
#include "picojson.h"
|
2016-06-17 09:03:00 -03:00
|
|
|
|
|
|
|
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:
|
2023-01-28 01:47:25 -04:00
|
|
|
|
2016-06-17 09:03:00 -03:00
|
|
|
bool receive_data(void);
|
2016-06-30 07:26:00 -03:00
|
|
|
void send_dref(const char *name, float value);
|
2023-01-28 01:47:25 -04:00
|
|
|
void request_drefs(void);
|
|
|
|
void request_dref(const char *name, uint8_t code, uint32_t rate_hz);
|
|
|
|
void send_drefs(const struct sitl_input &input);
|
|
|
|
void handle_rref(const uint8_t *p, uint32_t len);
|
|
|
|
void select_data(void);
|
|
|
|
void deselect_code(uint8_t code);
|
|
|
|
int8_t find_data_index(uint8_t id);
|
|
|
|
|
|
|
|
// return true if at least X
|
|
|
|
bool is_xplane12(void) const {
|
|
|
|
return xplane_version / 10000 >= 12;
|
|
|
|
}
|
|
|
|
|
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;
|
2021-06-20 23:59:02 -03:00
|
|
|
Vector3d position_zero;
|
2016-06-17 09:03:00 -03:00
|
|
|
Vector3f accel_earth;
|
|
|
|
bool connected = false;
|
2016-06-19 22:18:14 -03:00
|
|
|
uint32_t xplane_frame_time;
|
2023-01-28 01:47:25 -04:00
|
|
|
uint64_t seen_mask;
|
|
|
|
|
2016-06-19 22:18:14 -03:00
|
|
|
struct {
|
|
|
|
uint32_t last_report_ms;
|
|
|
|
uint32_t data_count;
|
|
|
|
uint32_t frame_count;
|
|
|
|
} report;
|
2017-01-06 23:41:23 -04:00
|
|
|
|
2023-01-28 01:47:25 -04:00
|
|
|
enum class DRefType {
|
|
|
|
ANGLE = 0,
|
|
|
|
RANGE = 1,
|
|
|
|
FIXED = 2,
|
|
|
|
};
|
|
|
|
|
|
|
|
struct DRef {
|
|
|
|
struct DRef *next;
|
|
|
|
char *name;
|
|
|
|
DRefType type;
|
|
|
|
uint8_t channel;
|
|
|
|
float range;
|
|
|
|
float fixed_value;
|
|
|
|
};
|
|
|
|
|
|
|
|
// list of DRefs;
|
|
|
|
struct DRef *drefs;
|
|
|
|
uint32_t dref_debug;
|
|
|
|
|
|
|
|
enum class JoyType {
|
|
|
|
AXIS = 0,
|
|
|
|
BUTTON = 1,
|
|
|
|
};
|
|
|
|
|
|
|
|
// list of joystick inputs
|
|
|
|
struct JoyInput {
|
|
|
|
struct JoyInput *next;
|
|
|
|
uint8_t axis;
|
|
|
|
uint8_t channel;
|
|
|
|
JoyType type;
|
|
|
|
float input_min, input_max;
|
|
|
|
uint32_t mask;
|
|
|
|
};
|
|
|
|
struct JoyInput *joyinputs;
|
|
|
|
|
|
|
|
char *map_filename;
|
|
|
|
struct stat map_st;
|
|
|
|
|
|
|
|
bool load_dref_map(const char *map_json);
|
|
|
|
void add_dref(const char *name, DRefType type, const picojson::value &dref);
|
|
|
|
void add_joyinput(const char *name, JoyType type, const picojson::value &d);
|
|
|
|
void handle_setting(const picojson::value &d);
|
|
|
|
|
|
|
|
void check_reload_dref(void);
|
|
|
|
|
|
|
|
uint32_t xplane_version;
|
2016-06-17 09:03:00 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
} // namespace SITL
|
2021-10-11 01:59:19 -03:00
|
|
|
|
|
|
|
|
|
|
|
#endif // HAL_SIM_XPLANE_ENABLED
|