APM:Libraries
SIM_CRRCSim.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 CRRCSim
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 CRRCSim simulator
29  */
30 class CRRCSim : public Aircraft {
31 public:
32  CRRCSim(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 CRRCSim(home_str, frame_str);
40  }
41 
42 private:
43  /*
44  packet sent to CRRCSim
45  */
46  struct servo_packet {
47  float roll_rate;
48  float pitch_rate;
49  float throttle;
50  float yaw_rate;
51  float col_pitch;
52  };
53 
54  /*
55  reply packet sent from CRRCSim to ArduPilot
56  */
57  struct fdm_packet {
58  double timestamp;
59  double latitude, longitude;
60  double altitude;
61  double heading;
62  double speedN, speedE, speedD;
63  double xAccel, yAccel, zAccel;
64  double rollRate, pitchRate, yawRate;
65  double roll, pitch, yaw;
66  double airspeed;
67  };
68 
69  void send_servos_heli(const struct sitl_input &input);
70  void send_servos_fixed_wing(const struct sitl_input &input);
71  void recv_fdm(const struct sitl_input &input);
72  void send_servos(const struct sitl_input &input);
73 
76  SocketAPM sock;
77 };
78 
79 } // namespace SITL
SocketAPM sock
Definition: SIM_CRRCSim.h:76
void send_servos_fixed_wing(const struct sitl_input &input)
Definition: SIM_CRRCSim.cpp:73
static Aircraft * create(const char *home_str, const char *frame_str)
Definition: SIM_CRRCSim.h:38
void send_servos_heli(const struct sitl_input &input)
Definition: SIM_CRRCSim.cpp:47
double last_timestamp
Definition: SIM_CRRCSim.h:75
void update(const struct sitl_input &input)
void send_servos(const struct sitl_input &input)
Definition: SIM_CRRCSim.cpp:93
void recv_fdm(const struct sitl_input &input)
CRRCSim(const char *home_str, const char *frame_str)
Definition: SIM_CRRCSim.cpp:29
bool heli_servos
Definition: SIM_CRRCSim.h:74