APM:Libraries
SIM_FlightAxis.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 FlightAxis
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 FlightAxis simulator
29  */
30 class FlightAxis : public Aircraft {
31 public:
32  FlightAxis(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 FlightAxis(home_str, frame_str);
40  }
41 
42  struct state {
43  double rcin[8];
51  double m_azimuth_DEG;
53  double m_roll_DEG;
68  double m_windX_MPS;
69  double m_windY_MPS;
70  double m_windZ_MPS;
71  double m_propRPM;
77  double m_isLocked;
90  } state;
91 
92  static const uint16_t num_keys = sizeof(state)/sizeof(double);
93 
94  struct keytable {
95  const char *key;
96  double &ref;
97  } keytable[num_keys] = {
98  { "item", state.rcin[0] },
99  { "item", state.rcin[1] },
100  { "item", state.rcin[2] },
101  { "item", state.rcin[3] },
102  { "item", state.rcin[4] },
103  { "item", state.rcin[5] },
104  { "item", state.rcin[6] },
105  { "item", state.rcin[7] },
106  { "m-airspeed-MPS", state.m_airspeed_MPS },
107  { "m-altitudeASL-MTR", state.m_altitudeASL_MTR },
108  { "m-altitudeAGL-MTR", state.m_altitudeAGL_MTR },
109  { "m-groundspeed-MPS", state.m_groundspeed_MPS },
110  { "m-pitchRate-DEGpSEC", state.m_pitchRate_DEGpSEC },
111  { "m-rollRate-DEGpSEC", state.m_rollRate_DEGpSEC },
112  { "m-yawRate-DEGpSEC", state.m_yawRate_DEGpSEC },
113  { "m-azimuth-DEG", state.m_azimuth_DEG },
114  { "m-inclination-DEG", state.m_inclination_DEG },
115  { "m-roll-DEG", state.m_roll_DEG },
116  { "m-aircraftPositionX-MTR", state.m_aircraftPositionX_MTR },
117  { "m-aircraftPositionY-MTR", state.m_aircraftPositionY_MTR },
118  { "m-velocityWorldU-MPS", state.m_velocityWorldU_MPS },
119  { "m-velocityWorldV-MPS", state.m_velocityWorldV_MPS },
120  { "m-velocityWorldW-MPS", state.m_velocityWorldW_MPS },
121  { "m-velocityBodyU-MPS", state.m_velocityBodyU_MPS },
122  { "m-velocityBodyV-MPS", state.m_velocityBodyV_MPS },
123  { "m-velocityBodyW-MPS", state.m_velocityBodyW_MPS },
124  { "m-accelerationWorldAX-MPS2", state.m_accelerationWorldAX_MPS2 },
125  { "m-accelerationWorldAY-MPS2", state.m_accelerationWorldAY_MPS2 },
126  { "m-accelerationWorldAZ-MPS2", state.m_accelerationWorldAZ_MPS2 },
127  { "m-accelerationBodyAX-MPS2", state.m_accelerationBodyAX_MPS2 },
128  { "m-accelerationBodyAY-MPS2", state.m_accelerationBodyAY_MPS2 },
129  { "m-accelerationBodyAZ-MPS2", state.m_accelerationBodyAZ_MPS2 },
130  { "m-windX-MPS", state.m_windX_MPS },
131  { "m-windY-MPS", state.m_windY_MPS },
132  { "m-windZ-MPS", state.m_windZ_MPS },
133  { "m-propRPM", state.m_propRPM },
134  { "m-heliMainRotorRPM", state.m_heliMainRotorRPM },
135  { "m-batteryVoltage-VOLTS", state.m_batteryVoltage_VOLTS },
136  { "m-batteryCurrentDraw-AMPS", state.m_batteryCurrentDraw_AMPS },
137  { "m-batteryRemainingCapacity-MAH", state.m_batteryRemainingCapacity_MAH },
138  { "m-fuelRemaining-OZ", state.m_fuelRemaining_OZ },
139  { "m-isLocked", state.m_isLocked },
140  { "m-hasLostComponents", state.m_hasLostComponents },
141  { "m-anEngineIsRunning", state.m_anEngineIsRunning },
142  { "m-isTouchingGround", state.m_isTouchingGround },
143  { "m-currentAircraftStatus", state.m_currentAircraftStatus },
144  { "m-currentPhysicsTime-SEC", state.m_currentPhysicsTime_SEC },
145  { "m-currentPhysicsSpeedMultiplier", state.m_currentPhysicsSpeedMultiplier },
146  { "m-orientationQuaternion-X", state.m_orientationQuaternion_X },
147  { "m-orientationQuaternion-Y", state.m_orientationQuaternion_Y },
148  { "m-orientationQuaternion-Z", state.m_orientationQuaternion_Z },
149  { "m-orientationQuaternion-W", state.m_orientationQuaternion_W },
150  { "m-flightAxisControllerIsActive", state.m_flightAxisControllerIsActive },
151  { "m-resetButtonHasBeenPressed", state.m_resetButtonHasBeenPressed },
152  };
153 
154 private:
155  char *soap_request(const char *action, const char *fmt, ...);
156  void exchange_data(const struct sitl_input &input);
157  void parse_reply(const char *reply);
158 
159  static void *update_thread(void *arg);
160  void update_loop(void);
161  void report_FPS(void);
162 
163  struct sitl_input last_input;
164 
168  double last_time_s;
172  uint64_t frame_counter;
179 
180  const char *controller_ip = "127.0.0.1";
181  uint16_t controller_port = 18083;
182 
183  pthread_t thread;
185 };
186 
187 
188 } // namespace SITL
struct sitl_input last_input
double m_currentPhysicsSpeedMultiplier
void parse_reply(const char *reply)
AP_HAL::Semaphore * mutex
struct SITL::FlightAxis::state state
uint64_t activation_frame_counter
static void * update_thread(void *arg)
FlightAxis(const char *home_str, const char *frame_str)
static Aircraft * create(const char *home_str, const char *frame_str)
const char * fmt
Definition: Printf.cpp:14
uint16_t controller_port
Vector3f position_offset
const char * controller_ip
uint64_t socket_frame_counter
Vector3f last_velocity_ef
char * soap_request(const char *action, const char *fmt,...)
void update_loop(void)
uint64_t frame_counter
static const uint16_t num_keys
void exchange_data(const struct sitl_input &input)
double average_frame_time_s
uint64_t last_socket_frame_counter
void update(const struct sitl_input &input)