2012-12-14 21:54:26 -04:00
|
|
|
/*
|
|
|
|
SITL handling
|
|
|
|
|
|
|
|
This emulates the ADS7844 ADC
|
|
|
|
|
|
|
|
Andrew Tridgell November 2011
|
|
|
|
*/
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-05-04 03:15:12 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2012-12-14 21:54:26 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "AP_HAL_SITL.h"
|
2015-05-04 03:15:12 -03:00
|
|
|
#include "AP_HAL_SITL_Namespace.h"
|
|
|
|
#include "HAL_SITL_Class.h"
|
2012-12-14 21:54:26 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2015-08-15 19:51:46 -03:00
|
|
|
#include <AP_Compass/AP_Compass.h>
|
|
|
|
#include <AP_Declination/AP_Declination.h>
|
|
|
|
#include <AP_RangeFinder/AP_RangeFinder.h>
|
|
|
|
#include <SITL/SITL.h>
|
2012-12-14 21:54:26 -04:00
|
|
|
#include "Scheduler.h"
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2015-08-15 19:51:46 -03:00
|
|
|
#include <AP_ADC/AP_ADC.h>
|
2015-08-11 03:28:43 -03:00
|
|
|
#include "SITL_State.h"
|
2014-04-21 02:25:07 -03:00
|
|
|
#include <fenv.h>
|
2012-12-14 21:54:26 -04:00
|
|
|
|
2015-04-13 03:16:22 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
2013-11-26 01:42:43 -04:00
|
|
|
|
2015-05-04 03:15:12 -03:00
|
|
|
using namespace HALSITL;
|
2012-12-14 21:54:26 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
convert airspeed in m/s to an airspeed sensor value
|
|
|
|
*/
|
|
|
|
uint16_t SITL_State::_airspeed_sensor(float airspeed)
|
|
|
|
{
|
2015-05-04 21:59:07 -03:00
|
|
|
const float airspeed_ratio = 1.9936f;
|
|
|
|
const float airspeed_offset = 2013;
|
|
|
|
float airspeed_pressure, airspeed_raw;
|
|
|
|
|
|
|
|
airspeed_pressure = (airspeed*airspeed) / airspeed_ratio;
|
|
|
|
airspeed_raw = airspeed_pressure + airspeed_offset;
|
|
|
|
if (airspeed_raw/4 > 0xFFFF) {
|
|
|
|
return 0xFFFF;
|
|
|
|
}
|
2015-04-13 03:16:22 -03:00
|
|
|
// add delay
|
2015-11-19 23:11:17 -04:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2015-04-13 03:16:22 -03:00
|
|
|
uint32_t best_time_delta_wind = 200; // initialise large time representing buffer entry closest to current time - delay.
|
|
|
|
uint8_t best_index_wind = 0; // initialise number representing the index of the entry in buffer closest to delay.
|
|
|
|
|
|
|
|
// storing data from sensor to buffer
|
|
|
|
if (now - last_store_time_wind >= 10) { // store data every 10 ms.
|
|
|
|
last_store_time_wind = now;
|
|
|
|
if (store_index_wind > wind_buffer_length-1) { // reset buffer index if index greater than size of buffer
|
|
|
|
store_index_wind = 0;
|
|
|
|
}
|
|
|
|
buffer_wind[store_index_wind].data = airspeed_raw; // add data to current index
|
|
|
|
buffer_wind[store_index_wind].time = last_store_time_wind; // add time to current index
|
|
|
|
store_index_wind = store_index_wind + 1; // increment index
|
|
|
|
}
|
|
|
|
|
|
|
|
// return delayed measurement
|
|
|
|
delayed_time_wind = now - _sitl->wind_delay; // get time corresponding to delay
|
|
|
|
// find data corresponding to delayed time in buffer
|
|
|
|
for (uint8_t i=0; i<=wind_buffer_length-1; i++) {
|
2016-05-11 18:54:16 -03:00
|
|
|
// find difference between delayed time and time stamp in buffer
|
|
|
|
time_delta_wind = abs(
|
|
|
|
(int32_t)(delayed_time_wind - buffer_wind[i].time));
|
2015-04-13 03:16:22 -03:00
|
|
|
// if this difference is smaller than last delta, store this time
|
|
|
|
if (time_delta_wind < best_time_delta_wind) {
|
|
|
|
best_index_wind = i;
|
|
|
|
best_time_delta_wind = time_delta_wind;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (best_time_delta_wind < 200) { // only output stored state if < 200 msec retrieval error
|
|
|
|
airspeed_raw = buffer_wind[best_index_wind].data;
|
|
|
|
}
|
|
|
|
|
2015-05-04 21:59:07 -03:00
|
|
|
return airspeed_raw/4;
|
2012-12-14 21:54:26 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2015-01-03 06:47:54 -04:00
|
|
|
/*
|
|
|
|
emulate an analog rangefinder
|
|
|
|
*/
|
|
|
|
uint16_t SITL_State::_ground_sonar(void)
|
2013-11-26 01:42:43 -04:00
|
|
|
{
|
2016-11-19 02:21:54 -04:00
|
|
|
float altitude = _sitl->height_agl;
|
2015-01-03 06:47:54 -04:00
|
|
|
|
2016-10-16 18:13:41 -03:00
|
|
|
// sensor position offset in body frame
|
|
|
|
Vector3f relPosSensorBF = _sitl->rngfnd_pos_offset;
|
|
|
|
|
|
|
|
// adjust altitude for position of the sensor on the vehicle if position offset is non-zero
|
|
|
|
if (!relPosSensorBF.is_zero()) {
|
|
|
|
// get a rotation matrix following DCM conventions (body to earth)
|
|
|
|
Matrix3f rotmat;
|
|
|
|
rotmat.from_euler(radians(_sitl->state.rollDeg),
|
|
|
|
radians(_sitl->state.pitchDeg),
|
|
|
|
radians(_sitl->state.yawDeg));
|
|
|
|
// rotate the offset into earth frame
|
|
|
|
Vector3f relPosSensorEF = rotmat * relPosSensorBF;
|
|
|
|
// correct the altitude at the sensor
|
|
|
|
altitude -= relPosSensorEF.z;
|
|
|
|
}
|
|
|
|
|
2015-01-03 06:47:54 -04:00
|
|
|
float voltage = 5.0f;
|
|
|
|
if (fabsf(_sitl->state.rollDeg) < 90 &&
|
2015-05-04 21:59:07 -03:00
|
|
|
fabsf(_sitl->state.pitchDeg) < 90) {
|
2015-01-03 06:47:54 -04:00
|
|
|
// adjust for apparent altitude with roll
|
2015-05-15 12:59:52 -03:00
|
|
|
altitude /= cosf(radians(_sitl->state.rollDeg)) * cosf(radians(_sitl->state.pitchDeg));
|
2015-05-04 21:59:07 -03:00
|
|
|
|
2015-01-03 06:47:54 -04:00
|
|
|
altitude += _sitl->sonar_noise * _rand_float();
|
|
|
|
|
|
|
|
// Altitude in in m, scaler in meters/volt
|
|
|
|
voltage = altitude / _sitl->sonar_scale;
|
|
|
|
voltage = constrain_float(voltage, 0, 5.0f);
|
2015-05-04 21:59:07 -03:00
|
|
|
|
2015-01-03 06:47:54 -04:00
|
|
|
if (_sitl->sonar_glitch >= (_rand_float() + 1.0f)/2.0f) {
|
|
|
|
voltage = 5.0f;
|
2014-08-10 09:37:07 -03:00
|
|
|
}
|
2015-01-03 06:47:54 -04:00
|
|
|
}
|
2015-05-04 21:59:07 -03:00
|
|
|
|
2015-01-03 06:47:54 -04:00
|
|
|
return 1023*(voltage / 5.0f);
|
2013-11-26 01:42:43 -04:00
|
|
|
}
|
|
|
|
|
2012-12-14 21:54:26 -04:00
|
|
|
/*
|
|
|
|
setup the INS input channels with new input
|
|
|
|
|
|
|
|
Note that this uses roll, pitch and yaw only as inputs. The
|
|
|
|
simulator rollrates are instantaneous, whereas we need to use
|
|
|
|
average rates to cope with slow update rates.
|
|
|
|
|
|
|
|
inputs are in degrees
|
|
|
|
|
|
|
|
phi - roll
|
|
|
|
theta - pitch
|
|
|
|
psi - true heading
|
|
|
|
alpha - angle of attack
|
|
|
|
beta - side slip
|
|
|
|
phidot - roll rate
|
|
|
|
thetadot - pitch rate
|
|
|
|
psidot - yaw rate
|
|
|
|
v_north - north velocity in local/body frame
|
|
|
|
v_east - east velocity in local/body frame
|
|
|
|
v_down - down velocity in local/body frame
|
|
|
|
A_X_pilot - X accel in body frame
|
|
|
|
A_Y_pilot - Y accel in body frame
|
|
|
|
A_Z_pilot - Z accel in body frame
|
|
|
|
|
|
|
|
Note: doubles on high prec. stuff are preserved until the last moment
|
|
|
|
|
|
|
|
*/
|
|
|
|
void SITL_State::_update_ins(float roll, float pitch, float yaw, // Relative to earth
|
2015-05-04 21:59:07 -03:00
|
|
|
double rollRate, double pitchRate,double yawRate, // Local to plane
|
|
|
|
double xAccel, double yAccel, double zAccel, // Local to plane
|
|
|
|
float airspeed, float altitude)
|
2012-12-14 21:54:26 -04:00
|
|
|
{
|
2016-10-30 02:24:21 -03:00
|
|
|
if (_ins == nullptr) {
|
2015-05-04 21:59:07 -03:00
|
|
|
// no inertial sensor in this sketch
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
sonar_pin_value = _ground_sonar();
|
2016-05-10 16:42:37 -03:00
|
|
|
float airspeed_simulated = (fabsf(_sitl->arspd_fail) > 1.0e-6f) ? _sitl->arspd_fail : airspeed;
|
|
|
|
airspeed_pin_value = _airspeed_sensor(airspeed_simulated + (_sitl->arspd_noise * _rand_float()));
|
2012-12-14 21:54:26 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
#endif
|