APM:Libraries
SITL.cpp
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 /*
17  SITL.cpp - software in the loop state
18 */
19 
20 #include "SITL.h"
21 
22 #include <AP_Common/AP_Common.h>
23 #include <AP_HAL/AP_HAL.h>
25 #include <DataFlash/DataFlash.h>
26 
27 extern const AP_HAL::HAL& hal;
28 
29 namespace SITL {
30 
31 SITL *SITL::_s_instance = nullptr;
32 
33 // table of user settable parameters
34 const AP_Param::GroupInfo SITL::var_info[] = {
35  AP_GROUPINFO("BARO_RND", 0, SITL, baro_noise, 0.2f),
36  AP_GROUPINFO("GYR_RND", 1, SITL, gyro_noise, 0),
37  AP_GROUPINFO("ACC_RND", 2, SITL, accel_noise, 0),
38  AP_GROUPINFO("MAG_RND", 3, SITL, mag_noise, 0),
39  AP_GROUPINFO("GPS_DISABLE",4, SITL, gps_disable, 0),
40  AP_GROUPINFO("DRIFT_SPEED",5, SITL, drift_speed, 0.05f),
41  AP_GROUPINFO("DRIFT_TIME", 6, SITL, drift_time, 5),
42  AP_GROUPINFO("GPS_DELAY", 7, SITL, gps_delay, 1),
43  AP_GROUPINFO("ENGINE_MUL", 8, SITL, engine_mul, 1),
44  AP_GROUPINFO("WIND_SPD", 9, SITL, wind_speed, 0),
45  AP_GROUPINFO("WIND_DIR", 10, SITL, wind_direction, 180),
46  AP_GROUPINFO("WIND_TURB", 11, SITL, wind_turbulance, 0),
47  AP_GROUPINFO("GPS_TYPE", 12, SITL, gps_type, SITL::GPS_TYPE_UBLOX),
48  AP_GROUPINFO("GPS_BYTELOSS", 13, SITL, gps_byteloss, 0),
49  AP_GROUPINFO("GPS_NUMSATS", 14, SITL, gps_numsats, 10),
50  AP_GROUPINFO("MAG_ERROR", 15, SITL, mag_error, 0),
51  AP_GROUPINFO("SERVO_SPEED", 16, SITL, servo_speed, 0.14),
52  AP_GROUPINFO("GPS_GLITCH", 17, SITL, gps_glitch, 0),
53  AP_GROUPINFO("GPS_HZ", 18, SITL, gps_hertz, 5),
54  AP_GROUPINFO("BATT_VOLTAGE", 19, SITL, batt_voltage, 12.6f),
55  AP_GROUPINFO("ARSPD_RND", 20, SITL, arspd_noise, 0.5f),
56  AP_GROUPINFO("ACCEL_FAIL", 21, SITL, accel_fail, 0),
57  AP_GROUPINFO("BARO_DRIFT", 22, SITL, baro_drift, 0),
58  AP_GROUPINFO("SONAR_GLITCH", 23, SITL, sonar_glitch, 0),
59  AP_GROUPINFO("SONAR_RND", 24, SITL, sonar_noise, 0),
60  AP_GROUPINFO("RC_FAIL", 25, SITL, rc_fail, 0),
61  AP_GROUPINFO("GPS2_ENABLE", 26, SITL, gps2_enable, 0),
62  AP_GROUPINFO("BARO_DISABLE", 27, SITL, baro_disable, 0),
63  AP_GROUPINFO("FLOAT_EXCEPT", 28, SITL, float_exception, 1),
64  AP_GROUPINFO("MAG_MOT", 29, SITL, mag_mot, 0),
65  AP_GROUPINFO("ACC_BIAS", 30, SITL, accel_bias, 0),
66  AP_GROUPINFO("BARO_GLITCH", 31, SITL, baro_glitch, 0),
67  AP_GROUPINFO("SONAR_SCALE", 32, SITL, sonar_scale, 12.1212f),
68  AP_GROUPINFO("FLOW_ENABLE", 33, SITL, flow_enable, 0),
69  AP_GROUPINFO("TERRAIN", 34, SITL, terrain_enable, 1),
70  AP_GROUPINFO("FLOW_RATE", 35, SITL, flow_rate, 10),
71  AP_GROUPINFO("FLOW_DELAY", 36, SITL, flow_delay, 0),
72  AP_GROUPINFO("GPS_DRIFTALT", 37, SITL, gps_drift_alt, 0),
73  AP_GROUPINFO("BARO_DELAY", 38, SITL, baro_delay, 0),
74  AP_GROUPINFO("MAG_DELAY", 39, SITL, mag_delay, 0),
75  AP_GROUPINFO("WIND_DELAY", 40, SITL, wind_delay, 0),
76  AP_GROUPINFO("MAG_OFS", 41, SITL, mag_ofs, 0),
77  AP_GROUPINFO("ACC2_RND", 42, SITL, accel2_noise, 0),
78  AP_GROUPINFO("ARSPD_FAIL", 43, SITL, arspd_fail, 0),
79  AP_GROUPINFO("GYR_SCALE", 44, SITL, gyro_scale, 0),
80  AP_GROUPINFO("ADSB_COUNT", 45, SITL, adsb_plane_count, -1),
81  AP_GROUPINFO("ADSB_RADIUS", 46, SITL, adsb_radius_m, 10000),
82  AP_GROUPINFO("ADSB_ALT", 47, SITL, adsb_altitude_m, 1000),
83  AP_GROUPINFO("MAG_ALY", 48, SITL, mag_anomaly_ned, 0),
84  AP_GROUPINFO("MAG_ALY_HGT", 49, SITL, mag_anomaly_hgt, 1.0f),
85  AP_GROUPINFO("PIN_MASK", 50, SITL, pin_mask, 0),
86  AP_GROUPINFO("ADSB_TX", 51, SITL, adsb_tx, 0),
87  AP_GROUPINFO("SPEEDUP", 52, SITL, speedup, -1),
88  AP_GROUPINFO("IMU_POS", 53, SITL, imu_pos_offset, 0),
89  AP_GROUPINFO("GPS_POS", 54, SITL, gps_pos_offset, 0),
90  AP_GROUPINFO("SONAR_POS", 55, SITL, rngfnd_pos_offset, 0),
91  AP_GROUPINFO("FLOW_POS", 56, SITL, optflow_pos_offset, 0),
92  AP_GROUPINFO("ACC2_BIAS", 57, SITL, accel2_bias, 0),
93  AP_GROUPINFO("GPS_NOISE", 58, SITL, gps_noise, 0),
94  AP_GROUPINFO("GP2_GLITCH", 59, SITL, gps2_glitch, 0),
95  AP_GROUPINFO("ENGINE_FAIL", 60, SITL, engine_fail, 0),
96  AP_GROUPINFO("GPS2_TYPE", 61, SITL, gps2_type, SITL::GPS_TYPE_UBLOX),
97  AP_GROUPINFO("ODOM_ENABLE", 62, SITL, odom_enable, 0),
98  AP_SUBGROUPEXTENSION("", 63, SITL, var_info2),
100 };
101 
102 // second table of user settable parameters for SITL.
103 const AP_Param::GroupInfo SITL::var_info2[] = {
104  AP_GROUPINFO("TEMP_START", 1, SITL, temp_start, 25),
105  AP_GROUPINFO("TEMP_FLIGHT", 2, SITL, temp_flight, 35),
106  AP_GROUPINFO("TEMP_TCONST", 3, SITL, temp_tconst, 30),
107  AP_GROUPINFO("TEMP_BFACTOR", 4, SITL, temp_baro_factor, 0),
108  AP_GROUPINFO("GPS_LOCKTIME", 5, SITL, gps_lock_time, 0),
109  AP_GROUPINFO("ARSPD_FAIL_P", 6, SITL, arspd_fail_pressure, 0),
110  AP_GROUPINFO("ARSPD_PITOT", 7, SITL, arspd_fail_pitot_pressure, 0),
111  AP_GROUPINFO("GPS_ALT_OFS", 8, SITL, gps_alt_offset, 0),
112  AP_GROUPINFO("ARSPD_SIGN", 9, SITL, arspd_signflip, 0),
113  AP_GROUPINFO("WIND_DIR_Z", 10, SITL, wind_dir_z, 0),
114  AP_GROUPINFO("ARSPD2_FAIL", 11, SITL, arspd2_fail, 0),
115  AP_GROUPINFO("ARSPD2_FAILP",12, SITL, arspd2_fail_pressure, 0),
116  AP_GROUPINFO("ARSPD2_PITOT",13, SITL, arspd2_fail_pitot_pressure, 0),
117  AP_GROUPINFO("VICON_HSTLEN",14, SITL, vicon_observation_history_length, 0),
118  AP_GROUPINFO("WIND_T" ,15, SITL, wind_type, SITL::WIND_TYPE_SQRT),
119  AP_GROUPINFO("WIND_T_ALT" ,16, SITL, wind_type_alt, 60),
120  AP_GROUPINFO("WIND_T_COEF", 17, SITL, wind_type_coef, 0.01f),
122 };
123 
124 
125 /* report SITL state via MAVLink */
126 void SITL::simstate_send(mavlink_channel_t chan)
127 {
128  float yaw;
129 
130  // convert to same conventions as DCM
131  yaw = state.yawDeg;
132  if (yaw > 180) {
133  yaw -= 360;
134  }
135 
136  mavlink_msg_simstate_send(chan,
137  ToRad(state.rollDeg),
138  ToRad(state.pitchDeg),
139  ToRad(yaw),
140  state.xAccel,
141  state.yAccel,
142  state.zAccel,
143  radians(state.rollRate),
144  radians(state.pitchRate),
145  radians(state.yawRate),
146  state.latitude*1.0e7,
147  state.longitude*1.0e7);
148 }
149 
150 /* report SITL state to DataFlash */
151 void SITL::Log_Write_SIMSTATE(DataFlash_Class *DataFlash)
152 {
153  float yaw;
154 
155  // convert to same conventions as DCM
156  yaw = state.yawDeg;
157  if (yaw > 180) {
158  yaw -= 360;
159  }
160 
161  struct log_AHRS pkt = {
164  roll : (int16_t)(state.rollDeg*100),
165  pitch : (int16_t)(state.pitchDeg*100),
166  yaw : (uint16_t)(wrap_360_cd(yaw*100)),
167  alt : (float)state.altitude,
168  lat : (int32_t)(state.latitude*1.0e7),
169  lng : (int32_t)(state.longitude*1.0e7),
170  q1 : state.quaternion.q1,
171  q2 : state.quaternion.q2,
172  q3 : state.quaternion.q3,
173  q4 : state.quaternion.q4,
174  };
175  DataFlash->WriteBlock(&pkt, sizeof(pkt));
176 }
177 
178 /*
179  convert a set of roll rates from earth frame to body frame
180  output values are in radians/second
181 */
182 void SITL::convert_body_frame(double rollDeg, double pitchDeg,
183  double rollRate, double pitchRate, double yawRate,
184  double *p, double *q, double *r)
185 {
186  double phi, theta, phiDot, thetaDot, psiDot;
187 
188  phi = ToRad(rollDeg);
189  theta = ToRad(pitchDeg);
190  phiDot = ToRad(rollRate);
191  thetaDot = ToRad(pitchRate);
192  psiDot = ToRad(yawRate);
193 
194  *p = phiDot - psiDot*sin(theta);
195  *q = cos(phi)*thetaDot + sin(phi)*psiDot*cos(theta);
196  *r = cos(phi)*psiDot*cos(theta) - sin(phi)*thetaDot;
197 }
198 
199 
200 /*
201  convert angular velocities from body frame to
202  earth frame.
203 
204  all inputs and outputs are in radians/s
205 */
206 Vector3f SITL::convert_earth_frame(const Matrix3f &dcm, const Vector3f &gyro)
207 {
208  float p = gyro.x;
209  float q = gyro.y;
210  float r = gyro.z;
211 
212  float phi, theta, psi;
213  dcm.to_euler(&phi, &theta, &psi);
214 
215  float phiDot = p + tanf(theta)*(q*sinf(phi) + r*cosf(phi));
216  float thetaDot = q*cosf(phi) - r*sinf(phi);
217  if (fabsf(cosf(theta)) < 1.0e-20f) {
218  theta += 1.0e-10f;
219  }
220  float psiDot = (q*sinf(phi) + r*cosf(phi))/cosf(theta);
221  return Vector3f(phiDot, thetaDot, psiDot);
222 }
223 
224 } // namespace SITL
225 
226 
227 namespace AP {
228 
230 {
231  return SITL::SITL::get_instance();
232 }
233 
234 };
void to_euler(float *roll, float *pitch, float *yaw) const
Definition: matrix3.cpp:49
Vector3< float > Vector3f
Definition: vector3.h:246
auto wrap_360_cd(const T angle) -> decltype(wrap_360(angle, 100.f))
Definition: AP_Math.cpp:140
#define ToRad(x)
Definition: AP_Common.h:53
float q1
Definition: LogStructure.h:349
int32_t lat
Definition: LogStructure.h:347
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
void WriteBlock(const void *pBuffer, uint16_t size)
Definition: DataFlash.cpp:481
float q4
Definition: LogStructure.h:349
int32_t lng
Definition: LogStructure.h:348
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
SITL::SITL * sitl()
Definition: SITL.cpp:229
#define AP_SUBGROUPEXTENSION(name, idx, clazz, vinfo)
Definition: AP_Param.h:113
float q2
Definition: LogStructure.h:349
Definition: AP_AHRS.cpp:486
#define f(i)
T y
Definition: vector3.h:67
T z
Definition: vector3.h:67
uint64_t micros64()
Definition: system.cpp:162
static int state
Definition: Util.cpp:20
int16_t pitch
Definition: LogStructure.h:344
Common definitions and utility routines for the ArduPilot libraries.
uint64_t time_us
Definition: LogStructure.h:342
DataFlash_Class DataFlash
static constexpr float radians(float deg)
Definition: AP_Math.h:158
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
float alt
Definition: LogStructure.h:346
static uint8_t gps_delay
Definition: sitl_gps.cpp:37
int16_t roll
Definition: LogStructure.h:343
float q3
Definition: LogStructure.h:349
static SITL * get_instance()
Definition: SITL.h:56
#define LOG_PACKET_HEADER_INIT(id)
Definition: LogStructure.h:8
uint16_t yaw
Definition: LogStructure.h:345
#define AP_GROUPEND
Definition: AP_Param.h:121
T x
Definition: vector3.h:67