2015-05-02 05:09:30 -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/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
parent class for aircraft simulators
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "SIM_Aircraft.h"
|
2015-10-22 10:58:33 -03:00
|
|
|
|
2015-05-02 07:28:57 -03:00
|
|
|
#include <stdio.h>
|
2015-10-22 10:58:33 -03:00
|
|
|
#include <sys/time.h>
|
|
|
|
#include <unistd.h>
|
2016-09-21 17:46:12 -03:00
|
|
|
|
2015-10-22 10:58:33 -03:00
|
|
|
|
2018-03-02 00:27:58 -04:00
|
|
|
#if defined(__CYGWIN__) || defined(__CYGWIN64__)
|
2015-05-25 03:48:13 -03:00
|
|
|
#include <windows.h>
|
|
|
|
#include <time.h>
|
2017-08-05 00:21:55 -03:00
|
|
|
#include <mmsystem.h>
|
2015-05-25 03:48:13 -03:00
|
|
|
#endif
|
2015-05-02 05:09:30 -03:00
|
|
|
|
2016-06-04 01:21:21 -03:00
|
|
|
#include <DataFlash/DataFlash.h>
|
2016-07-19 01:42:31 -03:00
|
|
|
#include <AP_Param/AP_Param.h>
|
2016-06-04 01:21:21 -03:00
|
|
|
|
2017-10-20 21:57:59 -03:00
|
|
|
using namespace SITL;
|
2015-10-22 10:04:42 -03:00
|
|
|
|
2015-05-02 05:09:30 -03:00
|
|
|
/*
|
|
|
|
parent class for all simulator types
|
|
|
|
*/
|
|
|
|
|
2015-05-03 04:47:58 -03:00
|
|
|
Aircraft::Aircraft(const char *home_str, const char *frame_str) :
|
2016-12-19 05:48:27 -04:00
|
|
|
ground_level(0.0f),
|
|
|
|
frame_height(0.0f),
|
2015-05-02 05:09:30 -03:00
|
|
|
dcm(),
|
|
|
|
gyro(),
|
2016-10-16 18:58:59 -03:00
|
|
|
gyro_prev(),
|
|
|
|
ang_accel(),
|
2015-05-02 05:09:30 -03:00
|
|
|
velocity_ef(),
|
2016-12-19 05:48:27 -04:00
|
|
|
mass(0.0f),
|
|
|
|
accel_body(0.0f, 0.0f, -GRAVITY_MSS),
|
2015-05-02 05:09:30 -03:00
|
|
|
time_now_us(0),
|
|
|
|
gyro_noise(radians(0.1f)),
|
2016-12-19 05:48:27 -04:00
|
|
|
accel_noise(0.3f),
|
|
|
|
rate_hz(1200.0f),
|
2016-10-30 02:24:21 -03:00
|
|
|
autotest_dir(nullptr),
|
2015-06-01 20:08:55 -03:00
|
|
|
frame(frame_str),
|
2018-03-02 00:27:58 -04:00
|
|
|
#if defined(__CYGWIN__) || defined(__CYGWIN64__)
|
2015-05-25 03:48:13 -03:00
|
|
|
min_sleep_time(20000)
|
2015-05-25 08:48:42 -03:00
|
|
|
#else
|
|
|
|
min_sleep_time(5000)
|
|
|
|
#endif
|
2015-05-02 05:09:30 -03:00
|
|
|
{
|
2016-06-16 19:35:08 -03:00
|
|
|
// make the SIM_* variables available to simulator backends
|
|
|
|
sitl = (SITL *)AP_Param::find_object("SIM_");
|
2018-02-19 21:33:14 -04:00
|
|
|
|
|
|
|
if (!parse_home(home_str, home, home_yaw)) {
|
|
|
|
::printf("Failed to parse home string (%s). Should be LAT,LON,ALT,HDG e.g. 37.4003371,-122.0800351,0,353\n", home_str);
|
|
|
|
}
|
|
|
|
::printf("Home: %f %f alt=%fm hdg=%f\n",
|
|
|
|
home.lat*1e-7,
|
|
|
|
home.lng*1e-7,
|
|
|
|
home.alt*0.01,
|
|
|
|
home_yaw);
|
2015-05-02 05:09:30 -03:00
|
|
|
location = home;
|
2016-12-19 05:48:27 -04:00
|
|
|
ground_level = home.alt * 0.01f;
|
2015-05-02 05:09:30 -03:00
|
|
|
|
2016-12-19 05:48:27 -04:00
|
|
|
dcm.from_euler(0.0f, 0.0f, radians(home_yaw));
|
2015-05-02 08:41:33 -03:00
|
|
|
|
2016-12-19 05:48:27 -04:00
|
|
|
set_speedup(1.0f);
|
2015-05-26 22:51:33 -03:00
|
|
|
|
|
|
|
last_wall_time_us = get_wall_time_us();
|
|
|
|
frame_counter = 0;
|
2016-07-19 01:42:31 -03:00
|
|
|
|
2017-11-22 23:26:01 -04:00
|
|
|
// allow for orientation settings, such as with tailsitters
|
|
|
|
enum ap_var_type ptype;
|
|
|
|
ahrs_orientation = (AP_Int8 *)AP_Param::find("AHRS_ORIENTATION", &ptype);
|
|
|
|
|
2016-07-19 01:42:31 -03:00
|
|
|
terrain = (AP_Terrain *)AP_Param::find_object("TERRAIN_");
|
2015-05-02 05:09:30 -03:00
|
|
|
}
|
|
|
|
|
2015-11-18 21:20:01 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
parse a home string into a location and yaw
|
|
|
|
*/
|
|
|
|
bool Aircraft::parse_home(const char *home_str, Location &loc, float &yaw_degrees)
|
|
|
|
{
|
2016-12-19 05:48:27 -04:00
|
|
|
char *saveptr = nullptr;
|
2015-11-18 21:20:01 -04:00
|
|
|
char *s = strdup(home_str);
|
|
|
|
if (!s) {
|
2016-12-19 05:48:27 -04:00
|
|
|
free(s);
|
2018-02-19 21:33:14 -04:00
|
|
|
::printf("No home string supplied\n");
|
2015-11-18 21:20:01 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
char *lat_s = strtok_r(s, ",", &saveptr);
|
|
|
|
if (!lat_s) {
|
2016-04-26 03:46:06 -03:00
|
|
|
free(s);
|
2018-02-19 21:33:14 -04:00
|
|
|
::printf("Failed to parse latitude\n");
|
2015-11-18 21:20:01 -04:00
|
|
|
return false;
|
|
|
|
}
|
2016-10-30 02:24:21 -03:00
|
|
|
char *lon_s = strtok_r(nullptr, ",", &saveptr);
|
2015-11-18 21:20:01 -04:00
|
|
|
if (!lon_s) {
|
2016-04-26 03:46:06 -03:00
|
|
|
free(s);
|
2018-02-19 21:33:14 -04:00
|
|
|
::printf("Failed to parse longitude\n");
|
2015-11-18 21:20:01 -04:00
|
|
|
return false;
|
|
|
|
}
|
2016-10-30 02:24:21 -03:00
|
|
|
char *alt_s = strtok_r(nullptr, ",", &saveptr);
|
2015-11-18 21:20:01 -04:00
|
|
|
if (!alt_s) {
|
2016-04-26 03:46:06 -03:00
|
|
|
free(s);
|
2018-02-19 21:33:14 -04:00
|
|
|
::printf("Failed to parse altitude\n");
|
2015-11-18 21:20:01 -04:00
|
|
|
return false;
|
|
|
|
}
|
2016-10-30 02:24:21 -03:00
|
|
|
char *yaw_s = strtok_r(nullptr, ",", &saveptr);
|
2015-11-18 21:20:01 -04:00
|
|
|
if (!yaw_s) {
|
2016-04-26 03:46:06 -03:00
|
|
|
free(s);
|
2018-02-19 21:33:14 -04:00
|
|
|
::printf("Failed to parse yaw\n");
|
2015-11-18 21:20:01 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
memset(&loc, 0, sizeof(loc));
|
2016-12-19 05:48:27 -04:00
|
|
|
loc.lat = static_cast<int32_t>(strtof(lat_s, nullptr) * 1.0e7f);
|
|
|
|
loc.lng = static_cast<int32_t>(strtof(lon_s, nullptr) * 1.0e7f);
|
|
|
|
loc.alt = static_cast<int32_t>(strtof(alt_s, nullptr) * 1.0e2f);
|
2015-11-18 21:20:01 -04:00
|
|
|
|
2017-11-19 03:24:08 -04:00
|
|
|
if (loc.lat == 0 && loc.lng == 0) {
|
|
|
|
// default to CMAC instead of middle of the ocean. This makes
|
|
|
|
// SITL in MissionPlanner a bit more useful
|
|
|
|
loc.lat = -35.363261*1e7;
|
|
|
|
loc.lng = 149.165230*1e7;
|
|
|
|
loc.alt = 584*100;
|
|
|
|
}
|
|
|
|
|
2016-10-30 02:24:21 -03:00
|
|
|
yaw_degrees = strtof(yaw_s, nullptr);
|
2015-11-18 21:20:01 -04:00
|
|
|
free(s);
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
2016-12-19 05:48:27 -04:00
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
/*
|
2016-11-22 20:09:33 -04:00
|
|
|
return difference in altitude between home position and current loc
|
2015-05-02 05:09:30 -03:00
|
|
|
*/
|
2016-11-22 20:09:33 -04:00
|
|
|
float Aircraft::ground_height_difference() const
|
2015-05-02 05:09:30 -03:00
|
|
|
{
|
2016-07-19 01:42:31 -03:00
|
|
|
float h1, h2;
|
2018-05-14 18:21:17 -03:00
|
|
|
if (sitl &&
|
|
|
|
sitl->terrain_enable && terrain &&
|
2016-07-19 01:42:31 -03:00
|
|
|
terrain->height_amsl(home, h1, false) &&
|
|
|
|
terrain->height_amsl(location, h2, false)) {
|
2016-11-22 20:09:33 -04:00
|
|
|
return h2 - h1;
|
2016-07-19 01:42:31 -03:00
|
|
|
}
|
2016-11-22 20:09:33 -04:00
|
|
|
return 0.0f;
|
|
|
|
}
|
|
|
|
|
2016-11-22 20:19:02 -04:00
|
|
|
/*
|
|
|
|
return current height above ground level (metres)
|
|
|
|
*/
|
|
|
|
float Aircraft::hagl() const
|
|
|
|
{
|
2016-12-19 05:48:27 -04:00
|
|
|
return (-position.z) + home.alt * 0.01f - ground_level - frame_height - ground_height_difference();
|
2016-11-22 20:19:02 -04:00
|
|
|
}
|
2016-11-22 20:09:33 -04:00
|
|
|
/*
|
|
|
|
return true if we are on the ground
|
|
|
|
*/
|
2016-11-22 20:15:58 -04:00
|
|
|
bool Aircraft::on_ground() const
|
2016-11-22 20:09:33 -04:00
|
|
|
{
|
2016-11-22 20:19:02 -04:00
|
|
|
return hagl() <= 0;
|
2015-05-02 05:09:30 -03:00
|
|
|
}
|
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
/*
|
|
|
|
update location from position
|
2015-05-02 05:09:30 -03:00
|
|
|
*/
|
|
|
|
void Aircraft::update_position(void)
|
|
|
|
{
|
|
|
|
location = home;
|
2016-06-04 01:21:21 -03:00
|
|
|
location_offset(location, position.x, position.y);
|
2015-05-02 05:09:30 -03:00
|
|
|
|
2016-12-19 05:48:27 -04:00
|
|
|
location.alt = static_cast<int32_t>(home.alt - position.z * 100.0f);
|
2015-05-02 07:28:57 -03:00
|
|
|
|
2016-06-04 01:21:21 -03:00
|
|
|
#if 0
|
|
|
|
// logging of raw sitl data
|
|
|
|
Vector3f accel_ef = dcm * accel_body;
|
|
|
|
DataFlash_Class::instance()->Log_Write("SITL", "TimeUS,VN,VE,VD,AN,AE,AD,PN,PE,PD", "Qfffffffff",
|
|
|
|
AP_HAL::micros64(),
|
|
|
|
velocity_ef.x, velocity_ef.y, velocity_ef.z,
|
|
|
|
accel_ef.x, accel_ef.y, accel_ef.z,
|
|
|
|
position.x, position.y, position.z);
|
|
|
|
#endif
|
2015-05-02 05:09:30 -03:00
|
|
|
}
|
|
|
|
|
2016-06-17 00:46:12 -03:00
|
|
|
/*
|
|
|
|
update body magnetic field from position and rotation
|
|
|
|
*/
|
|
|
|
void Aircraft::update_mag_field_bf()
|
|
|
|
{
|
2016-06-17 02:25:23 -03:00
|
|
|
// get the magnetic field intensity and orientation
|
|
|
|
float intensity;
|
|
|
|
float declination;
|
|
|
|
float inclination;
|
2017-08-17 06:09:14 -03:00
|
|
|
AP_Declination::get_mag_field_ef(location.lat * 1e-7f, location.lng * 1e-7f, intensity, declination, inclination);
|
2016-06-17 02:25:23 -03:00
|
|
|
|
|
|
|
// create a field vector and rotate to the required orientation
|
2016-12-19 05:48:27 -04:00
|
|
|
Vector3f mag_ef(1e3f * intensity, 0.0f, 0.0f);
|
2016-06-17 00:46:12 -03:00
|
|
|
Matrix3f R;
|
2016-12-19 05:48:27 -04:00
|
|
|
R.from_euler(0.0f, -ToRad(inclination), ToRad(declination));
|
2016-06-17 00:46:12 -03:00
|
|
|
mag_ef = R * mag_ef;
|
|
|
|
|
2016-06-17 02:25:23 -03:00
|
|
|
// calculate frame height above ground
|
2016-12-19 05:48:27 -04:00
|
|
|
const float frame_height_agl = fmaxf((-position.z) + home.alt * 0.01f - ground_level, 0.0f);
|
2016-06-17 00:46:12 -03:00
|
|
|
|
|
|
|
// calculate scaling factor that varies from 1 at ground level to 1/8 at sitl->mag_anomaly_hgt
|
|
|
|
// Assume magnetic anomaly strength scales with 1/R**3
|
|
|
|
float anomaly_scaler = (sitl->mag_anomaly_hgt / (frame_height_agl + sitl->mag_anomaly_hgt));
|
|
|
|
anomaly_scaler = anomaly_scaler * anomaly_scaler * anomaly_scaler;
|
|
|
|
|
|
|
|
// add scaled anomaly to earth field
|
|
|
|
mag_ef += sitl->mag_anomaly_ned.get() * anomaly_scaler;
|
|
|
|
|
|
|
|
// Rotate into body frame
|
|
|
|
mag_bf = dcm.transposed() * mag_ef;
|
|
|
|
|
|
|
|
// add motor interference
|
|
|
|
mag_bf += sitl->mag_mot.get() * battery_current;
|
|
|
|
}
|
|
|
|
|
2015-05-02 05:09:30 -03:00
|
|
|
/* advance time by deltat in seconds */
|
2017-03-03 06:23:40 -04:00
|
|
|
void Aircraft::time_advance()
|
2015-05-02 05:09:30 -03:00
|
|
|
{
|
2017-03-03 06:23:40 -04:00
|
|
|
// we only advance time if it hasn't been advanced already by the
|
|
|
|
// backend
|
|
|
|
if (last_time_us == time_now_us) {
|
|
|
|
time_now_us += frame_time_us;
|
|
|
|
}
|
|
|
|
last_time_us = time_now_us;
|
|
|
|
if (use_time_sync) {
|
|
|
|
sync_frame_time();
|
|
|
|
}
|
2015-05-02 05:09:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/* setup the frame step time */
|
|
|
|
void Aircraft::setup_frame_time(float new_rate, float new_speedup)
|
|
|
|
{
|
|
|
|
rate_hz = new_rate;
|
|
|
|
target_speedup = new_speedup;
|
2016-12-19 05:48:27 -04:00
|
|
|
frame_time_us = static_cast<uint64_t>(1.0e6f/rate_hz);
|
2015-05-02 05:09:30 -03:00
|
|
|
|
|
|
|
scaled_frame_time_us = frame_time_us/target_speedup;
|
|
|
|
last_wall_time_us = get_wall_time_us();
|
|
|
|
achieved_rate_hz = rate_hz;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* adjust frame_time calculation */
|
|
|
|
void Aircraft::adjust_frame_time(float new_rate)
|
|
|
|
{
|
2015-05-25 08:48:42 -03:00
|
|
|
if (rate_hz != new_rate) {
|
|
|
|
rate_hz = new_rate;
|
2016-12-19 05:48:27 -04:00
|
|
|
frame_time_us = static_cast<uint64_t>(1.0e6f/rate_hz);
|
2015-05-25 08:48:42 -03:00
|
|
|
scaled_frame_time_us = frame_time_us/target_speedup;
|
|
|
|
}
|
2015-05-02 05:09:30 -03:00
|
|
|
}
|
|
|
|
|
2015-10-22 10:15:20 -03:00
|
|
|
/*
|
2015-05-25 03:48:13 -03:00
|
|
|
try to synchronise simulation time with wall clock time, taking
|
2015-10-22 10:15:20 -03:00
|
|
|
into account desired speedup
|
2015-05-25 03:48:13 -03:00
|
|
|
This tries to take account of possible granularity of
|
|
|
|
get_wall_time_us() so it works reasonably well on windows
|
|
|
|
*/
|
2015-05-02 05:09:30 -03:00
|
|
|
void Aircraft::sync_frame_time(void)
|
|
|
|
{
|
2015-05-25 03:48:13 -03:00
|
|
|
frame_counter++;
|
2015-05-02 05:09:30 -03:00
|
|
|
uint64_t now = get_wall_time_us();
|
2015-05-25 08:48:42 -03:00
|
|
|
if (frame_counter >= 40 &&
|
|
|
|
now > last_wall_time_us) {
|
2016-12-19 05:48:27 -04:00
|
|
|
const float rate = frame_counter * 1.0e6f/(now - last_wall_time_us);
|
|
|
|
achieved_rate_hz = (0.99f*achieved_rate_hz) + (0.01f * rate);
|
2015-05-25 03:48:13 -03:00
|
|
|
if (achieved_rate_hz < rate_hz * target_speedup) {
|
2015-05-25 08:48:42 -03:00
|
|
|
scaled_frame_time_us *= 0.999f;
|
2015-05-25 03:48:13 -03:00
|
|
|
} else {
|
2015-05-25 08:48:42 -03:00
|
|
|
scaled_frame_time_us /= 0.999f;
|
2015-05-02 05:09:30 -03:00
|
|
|
}
|
2015-05-25 08:48:42 -03:00
|
|
|
#if 0
|
|
|
|
::printf("achieved_rate_hz=%.3f rate=%.2f rate_hz=%.3f sft=%.1f\n",
|
2016-12-19 05:48:27 -04:00
|
|
|
static_cast<double>(achieved_rate_hz),
|
|
|
|
static_cast<double>(rate),
|
|
|
|
static_cast<double>(rate_hz),
|
|
|
|
static_cast<double>(scaled_frame_time_us));
|
2015-05-25 08:48:42 -03:00
|
|
|
#endif
|
2016-12-19 05:48:27 -04:00
|
|
|
const uint32_t sleep_time = static_cast<uint32_t>(scaled_frame_time_us * frame_counter);
|
2015-05-25 08:48:42 -03:00
|
|
|
if (sleep_time > min_sleep_time) {
|
|
|
|
usleep(sleep_time);
|
2015-05-25 03:48:13 -03:00
|
|
|
}
|
|
|
|
last_wall_time_us = now;
|
|
|
|
frame_counter = 0;
|
2015-05-02 05:09:30 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/* add noise based on throttle level (from 0..1) */
|
|
|
|
void Aircraft::add_noise(float throttle)
|
|
|
|
{
|
|
|
|
gyro += Vector3f(rand_normal(0, 1),
|
|
|
|
rand_normal(0, 1),
|
2016-01-26 22:18:57 -04:00
|
|
|
rand_normal(0, 1)) * gyro_noise * fabsf(throttle);
|
2015-05-02 05:09:30 -03:00
|
|
|
accel_body += Vector3f(rand_normal(0, 1),
|
|
|
|
rand_normal(0, 1),
|
2016-01-26 22:18:57 -04:00
|
|
|
rand_normal(0, 1)) * accel_noise * fabsf(throttle);
|
2015-05-02 05:09:30 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
normal distribution random numbers
|
|
|
|
See
|
|
|
|
http://en.literateprograms.org/index.php?title=Special:DownloadCode/Box-Muller_transform_%28C%29&oldid=7011
|
|
|
|
*/
|
|
|
|
double Aircraft::rand_normal(double mean, double stddev)
|
|
|
|
{
|
|
|
|
static double n2 = 0.0;
|
|
|
|
static int n2_cached = 0;
|
2016-12-19 05:48:27 -04:00
|
|
|
if (!n2_cached) {
|
2015-05-02 05:09:30 -03:00
|
|
|
double x, y, r;
|
|
|
|
do
|
|
|
|
{
|
2016-12-19 05:48:27 -04:00
|
|
|
x = 2.0 * rand()/RAND_MAX - 1;
|
|
|
|
y = 2.0 * rand()/RAND_MAX - 1;
|
2015-05-02 05:09:30 -03:00
|
|
|
r = x*x + y*y;
|
2016-12-19 05:48:27 -04:00
|
|
|
} while (is_zero(r) || r > 1.0);
|
|
|
|
const double d = sqrt(-2.0 * log(r)/r);
|
|
|
|
const double n1 = x * d;
|
|
|
|
n2 = y * d;
|
|
|
|
const double result = n1 * stddev + mean;
|
|
|
|
n2_cached = 1;
|
|
|
|
return result;
|
|
|
|
} else {
|
2015-05-02 05:09:30 -03:00
|
|
|
n2_cached = 0;
|
2016-12-19 05:48:27 -04:00
|
|
|
return n2 * stddev + mean;
|
2015-05-02 05:09:30 -03:00
|
|
|
}
|
|
|
|
}
|
2015-05-02 07:28:57 -03:00
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
2015-05-04 22:49:54 -03:00
|
|
|
/*
|
|
|
|
fill a sitl_fdm structure from the simulator state
|
2015-05-02 07:28:57 -03:00
|
|
|
*/
|
2016-07-19 08:38:16 -03:00
|
|
|
void Aircraft::fill_fdm(struct sitl_fdm &fdm)
|
2015-05-02 07:28:57 -03:00
|
|
|
{
|
2016-07-19 08:38:16 -03:00
|
|
|
if (use_smoothing) {
|
|
|
|
smooth_sensors();
|
|
|
|
}
|
2015-05-02 07:28:57 -03:00
|
|
|
fdm.timestamp_us = time_now_us;
|
2017-05-02 06:35:57 -03:00
|
|
|
if (fdm.home.lat == 0 && fdm.home.lng == 0) {
|
|
|
|
// initialise home
|
|
|
|
fdm.home = home;
|
|
|
|
}
|
2015-05-02 07:28:57 -03:00
|
|
|
fdm.latitude = location.lat * 1.0e-7;
|
|
|
|
fdm.longitude = location.lng * 1.0e-7;
|
|
|
|
fdm.altitude = location.alt * 1.0e-2;
|
|
|
|
fdm.heading = degrees(atan2f(velocity_ef.y, velocity_ef.x));
|
|
|
|
fdm.speedN = velocity_ef.x;
|
|
|
|
fdm.speedE = velocity_ef.y;
|
|
|
|
fdm.speedD = velocity_ef.z;
|
|
|
|
fdm.xAccel = accel_body.x;
|
|
|
|
fdm.yAccel = accel_body.y;
|
|
|
|
fdm.zAccel = accel_body.z;
|
2015-05-24 19:42:51 -03:00
|
|
|
fdm.rollRate = degrees(gyro.x);
|
|
|
|
fdm.pitchRate = degrees(gyro.y);
|
|
|
|
fdm.yawRate = degrees(gyro.z);
|
2016-10-16 18:58:59 -03:00
|
|
|
fdm.angAccel.x = degrees(ang_accel.x);
|
|
|
|
fdm.angAccel.y = degrees(ang_accel.y);
|
|
|
|
fdm.angAccel.z = degrees(ang_accel.z);
|
2015-05-02 07:28:57 -03:00
|
|
|
float r, p, y;
|
|
|
|
dcm.to_euler(&r, &p, &y);
|
|
|
|
fdm.rollDeg = degrees(r);
|
|
|
|
fdm.pitchDeg = degrees(p);
|
|
|
|
fdm.yawDeg = degrees(y);
|
2017-04-15 08:20:28 -03:00
|
|
|
fdm.quaternion.from_rotation_matrix(dcm);
|
2016-04-19 22:48:37 -03:00
|
|
|
fdm.airspeed = airspeed_pitot;
|
2015-11-22 22:46:01 -04:00
|
|
|
fdm.battery_voltage = battery_voltage;
|
|
|
|
fdm.battery_current = battery_current;
|
|
|
|
fdm.rpm1 = rpm1;
|
|
|
|
fdm.rpm2 = rpm2;
|
2016-05-03 23:49:42 -03:00
|
|
|
fdm.rcin_chan_count = rcin_chan_count;
|
2017-01-09 05:16:13 -04:00
|
|
|
fdm.range = range;
|
2016-12-19 05:48:27 -04:00
|
|
|
memcpy(fdm.rcin, rcin, rcin_chan_count * sizeof(float));
|
2016-06-17 00:46:12 -03:00
|
|
|
fdm.bodyMagField = mag_bf;
|
2016-07-19 08:38:16 -03:00
|
|
|
|
|
|
|
if (smoothing.enabled) {
|
|
|
|
fdm.xAccel = smoothing.accel_body.x;
|
|
|
|
fdm.yAccel = smoothing.accel_body.y;
|
2016-12-19 05:48:27 -04:00
|
|
|
fdm.zAccel = smoothing.accel_body.z;
|
2016-07-19 08:38:16 -03:00
|
|
|
fdm.rollRate = degrees(smoothing.gyro.x);
|
|
|
|
fdm.pitchRate = degrees(smoothing.gyro.y);
|
|
|
|
fdm.yawRate = degrees(smoothing.gyro.z);
|
|
|
|
fdm.speedN = smoothing.velocity_ef.x;
|
|
|
|
fdm.speedE = smoothing.velocity_ef.y;
|
|
|
|
fdm.speedD = smoothing.velocity_ef.z;
|
|
|
|
fdm.latitude = smoothing.location.lat * 1.0e-7;
|
|
|
|
fdm.longitude = smoothing.location.lng * 1.0e-7;
|
|
|
|
fdm.altitude = smoothing.location.alt * 1.0e-2;
|
|
|
|
}
|
2016-09-18 18:45:24 -03:00
|
|
|
|
2017-11-22 23:26:01 -04:00
|
|
|
if (ahrs_orientation != nullptr) {
|
|
|
|
enum Rotation imu_rotation = (enum Rotation)ahrs_orientation->get();
|
|
|
|
|
|
|
|
if (imu_rotation != ROTATION_NONE) {
|
|
|
|
Matrix3f m = dcm;
|
|
|
|
Matrix3f rot;
|
|
|
|
rot.from_rotation(imu_rotation);
|
|
|
|
m = m * rot.transposed();
|
|
|
|
|
|
|
|
m.to_euler(&r, &p, &y);
|
|
|
|
fdm.rollDeg = degrees(r);
|
|
|
|
fdm.pitchDeg = degrees(p);
|
|
|
|
fdm.yawDeg = degrees(y);
|
|
|
|
fdm.quaternion.from_rotation_matrix(m);
|
|
|
|
}
|
2017-06-05 02:36:55 -03:00
|
|
|
}
|
|
|
|
|
2016-09-18 18:45:24 -03:00
|
|
|
if (last_speedup != sitl->speedup && sitl->speedup > 0) {
|
|
|
|
set_speedup(sitl->speedup);
|
|
|
|
last_speedup = sitl->speedup;
|
|
|
|
}
|
2015-05-02 07:28:57 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
uint64_t Aircraft::get_wall_time_us() const
|
|
|
|
{
|
2018-03-02 00:27:58 -04:00
|
|
|
#if defined(__CYGWIN__) || defined(__CYGWIN64__)
|
2015-05-25 03:48:13 -03:00
|
|
|
static DWORD tPrev;
|
|
|
|
static uint64_t last_ret_us;
|
|
|
|
if (tPrev == 0) {
|
|
|
|
tPrev = timeGetTime();
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
DWORD now = timeGetTime();
|
|
|
|
last_ret_us += (uint64_t)((now - tPrev)*1000UL);
|
|
|
|
tPrev = now;
|
|
|
|
return last_ret_us;
|
|
|
|
#else
|
2015-05-04 22:49:54 -03:00
|
|
|
struct timeval tp;
|
2016-12-19 05:48:27 -04:00
|
|
|
gettimeofday(&tp, nullptr);
|
|
|
|
return static_cast<uint64_t>(tp.tv_sec * 1.0e6 + tp.tv_usec);
|
2015-05-25 03:48:13 -03:00
|
|
|
#endif
|
2015-05-02 07:28:57 -03:00
|
|
|
}
|
2015-05-02 08:41:33 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
set simulation speedup
|
|
|
|
*/
|
|
|
|
void Aircraft::set_speedup(float speedup)
|
|
|
|
{
|
|
|
|
setup_frame_time(rate_hz, speedup);
|
|
|
|
}
|
2015-10-22 10:04:42 -03:00
|
|
|
|
2016-01-01 00:11:55 -04:00
|
|
|
/*
|
|
|
|
update the simulation attitude and relative position
|
|
|
|
*/
|
|
|
|
void Aircraft::update_dynamics(const Vector3f &rot_accel)
|
|
|
|
{
|
2016-12-19 05:48:27 -04:00
|
|
|
const float delta_time = frame_time_us * 1.0e-6f;
|
|
|
|
|
2016-01-01 00:11:55 -04:00
|
|
|
// update rotational rates in body frame
|
|
|
|
gyro += rot_accel * delta_time;
|
|
|
|
|
2016-12-19 05:48:27 -04:00
|
|
|
gyro.x = constrain_float(gyro.x, -radians(2000.0f), radians(2000.0f));
|
|
|
|
gyro.y = constrain_float(gyro.y, -radians(2000.0f), radians(2000.0f));
|
|
|
|
gyro.z = constrain_float(gyro.z, -radians(2000.0f), radians(2000.0f));
|
2016-10-16 18:58:59 -03:00
|
|
|
|
|
|
|
// estimate angular acceleration using a first order difference calculation
|
|
|
|
// TODO the simulator interface should provide the angular acceleration
|
|
|
|
ang_accel = (gyro - gyro_prev) / delta_time;
|
|
|
|
gyro_prev = gyro;
|
2016-12-19 05:48:27 -04:00
|
|
|
|
2016-01-01 00:11:55 -04:00
|
|
|
// update attitude
|
|
|
|
dcm.rotate(gyro * delta_time);
|
|
|
|
dcm.normalize();
|
|
|
|
|
|
|
|
Vector3f accel_earth = dcm * accel_body;
|
2016-12-19 05:48:27 -04:00
|
|
|
accel_earth += Vector3f(0.0f, 0.0f, GRAVITY_MSS);
|
2016-01-01 00:11:55 -04:00
|
|
|
|
|
|
|
// if we're on the ground, then our vertical acceleration is limited
|
|
|
|
// to zero. This effectively adds the force of the ground on the aircraft
|
2016-11-22 20:15:58 -04:00
|
|
|
if (on_ground() && accel_earth.z > 0) {
|
2016-01-01 00:11:55 -04:00
|
|
|
accel_earth.z = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
// work out acceleration as seen by the accelerometers. It sees the kinematic
|
|
|
|
// acceleration (ie. real movement), plus gravity
|
2016-12-19 05:48:27 -04:00
|
|
|
accel_body = dcm.transposed() * (accel_earth + Vector3f(0.0f, 0.0f, -GRAVITY_MSS));
|
2016-01-01 00:11:55 -04:00
|
|
|
|
|
|
|
// new velocity vector
|
|
|
|
velocity_ef += accel_earth * delta_time;
|
|
|
|
|
2016-11-22 20:15:58 -04:00
|
|
|
const bool was_on_ground = on_ground();
|
2016-01-01 00:11:55 -04:00
|
|
|
// new position vector
|
|
|
|
position += velocity_ef * delta_time;
|
|
|
|
|
2016-04-19 22:48:37 -03:00
|
|
|
// velocity relative to air mass, in earth frame
|
2016-09-15 21:59:27 -03:00
|
|
|
velocity_air_ef = velocity_ef + wind_ef;
|
2016-12-19 05:48:27 -04:00
|
|
|
|
2016-04-19 22:48:37 -03:00
|
|
|
// velocity relative to airmass in body frame
|
|
|
|
velocity_air_bf = dcm.transposed() * velocity_air_ef;
|
2016-12-19 05:48:27 -04:00
|
|
|
|
|
|
|
// airspeed
|
2016-04-19 22:48:37 -03:00
|
|
|
airspeed = velocity_air_ef.length();
|
2016-01-01 00:11:55 -04:00
|
|
|
|
2016-04-19 22:48:37 -03:00
|
|
|
// airspeed as seen by a fwd pitot tube (limited to 120m/s)
|
2016-12-19 05:48:27 -04:00
|
|
|
airspeed_pitot = constrain_float(velocity_air_bf * Vector3f(1.0f, 0.0f, 0.0f), 0.0f, 120.0f);
|
|
|
|
|
2016-01-01 00:11:55 -04:00
|
|
|
// constrain height to the ground
|
2016-11-22 20:15:58 -04:00
|
|
|
if (on_ground()) {
|
2016-11-22 20:09:33 -04:00
|
|
|
if (!was_on_ground && AP_HAL::millis() - last_ground_contact_ms > 1000) {
|
2016-01-01 00:11:55 -04:00
|
|
|
printf("Hit ground at %f m/s\n", velocity_ef.z);
|
2016-01-04 16:20:05 -04:00
|
|
|
last_ground_contact_ms = AP_HAL::millis();
|
2016-01-01 00:11:55 -04:00
|
|
|
}
|
2016-12-19 05:48:27 -04:00
|
|
|
position.z = -(ground_level + frame_height - home.alt * 0.01f + ground_height_difference());
|
2016-07-19 01:42:31 -03:00
|
|
|
|
|
|
|
switch (ground_behavior) {
|
|
|
|
case GROUND_BEHAVIOR_NONE:
|
|
|
|
break;
|
|
|
|
case GROUND_BEHAVIOR_NO_MOVEMENT: {
|
|
|
|
// zero roll/pitch, but keep yaw
|
|
|
|
float r, p, y;
|
|
|
|
dcm.to_euler(&r, &p, &y);
|
2016-12-19 05:48:27 -04:00
|
|
|
dcm.from_euler(0.0f, 0.0f, y);
|
2016-07-19 01:42:31 -03:00
|
|
|
// no X or Y movement
|
2016-12-19 05:48:27 -04:00
|
|
|
velocity_ef.x = 0.0f;
|
|
|
|
velocity_ef.y = 0.0f;
|
|
|
|
if (velocity_ef.z > 0.0f) {
|
|
|
|
velocity_ef.z = 0.0f;
|
2016-07-19 08:38:16 -03:00
|
|
|
}
|
|
|
|
gyro.zero();
|
|
|
|
use_smoothing = true;
|
2016-07-19 01:42:31 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
case GROUND_BEHAVIOR_FWD_ONLY: {
|
|
|
|
// zero roll/pitch, but keep yaw
|
|
|
|
float r, p, y;
|
|
|
|
dcm.to_euler(&r, &p, &y);
|
2016-12-19 05:48:27 -04:00
|
|
|
dcm.from_euler(0.0f, 0.0f, y);
|
2016-07-19 01:42:31 -03:00
|
|
|
// only fwd movement
|
|
|
|
Vector3f v_bf = dcm.transposed() * velocity_ef;
|
2016-12-19 05:48:27 -04:00
|
|
|
v_bf.y = 0.0f;
|
|
|
|
if (v_bf.x < 0.0f) {
|
|
|
|
v_bf.x = 0.0f;
|
2016-07-19 01:42:31 -03:00
|
|
|
}
|
|
|
|
velocity_ef = dcm * v_bf;
|
2016-12-19 05:48:27 -04:00
|
|
|
if (velocity_ef.z > 0.0f) {
|
|
|
|
velocity_ef.z = 0.0f;
|
2016-07-19 08:38:16 -03:00
|
|
|
}
|
|
|
|
gyro.zero();
|
2017-02-11 07:30:42 -04:00
|
|
|
use_smoothing = true;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
case GROUND_BEHAVIOR_TAILSITTER: {
|
|
|
|
// point straight up
|
|
|
|
float r, p, y;
|
|
|
|
dcm.to_euler(&r, &p, &y);
|
|
|
|
dcm.from_euler(0.0f, radians(90), y);
|
|
|
|
// no movement
|
|
|
|
if (accel_earth.z > -1.1*GRAVITY_MSS) {
|
|
|
|
velocity_ef.zero();
|
|
|
|
}
|
|
|
|
gyro.zero();
|
2016-07-19 08:38:16 -03:00
|
|
|
use_smoothing = true;
|
2016-07-19 01:42:31 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2016-01-01 00:11:55 -04:00
|
|
|
}
|
|
|
|
}
|
2016-04-19 22:48:37 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
update wind vector
|
|
|
|
*/
|
|
|
|
void Aircraft::update_wind(const struct sitl_input &input)
|
|
|
|
{
|
|
|
|
// wind vector in earth frame
|
2018-01-30 12:38:36 -04:00
|
|
|
wind_ef = Vector3f(cosf(radians(input.wind.direction))*cosf(radians(input.wind.dir_z)),
|
|
|
|
sinf(radians(input.wind.direction))*cosf(radians(input.wind.dir_z)),
|
|
|
|
sinf(radians(input.wind.dir_z))) * input.wind.speed;
|
2016-12-19 05:48:27 -04:00
|
|
|
|
|
|
|
const float wind_turb = input.wind.turbulence * 10.0f; // scale input.wind.turbulence to match standard deviation when using iir_coef=0.98
|
|
|
|
const float iir_coef = 0.98f; // filtering high frequencies from turbulence
|
|
|
|
|
2016-11-22 20:15:58 -04:00
|
|
|
if (wind_turb > 0 && !on_ground()) {
|
2016-11-13 20:41:06 -04:00
|
|
|
|
2016-11-18 14:42:10 -04:00
|
|
|
turbulence_azimuth = turbulence_azimuth + (2 * rand());
|
2016-11-13 20:41:06 -04:00
|
|
|
|
2016-12-19 05:48:27 -04:00
|
|
|
turbulence_horizontal_speed =
|
|
|
|
static_cast<float>(turbulence_horizontal_speed * iir_coef+wind_turb * rand_normal(0, 1) * (1 - iir_coef));
|
2016-11-13 20:41:06 -04:00
|
|
|
|
2016-12-19 05:48:27 -04:00
|
|
|
turbulence_vertical_speed = static_cast<float>((turbulence_vertical_speed * iir_coef) + (wind_turb * rand_normal(0, 1) * (1 - iir_coef)));
|
2016-11-13 20:41:06 -04:00
|
|
|
|
|
|
|
wind_ef += Vector3f(
|
2016-11-18 14:42:10 -04:00
|
|
|
cosf(radians(turbulence_azimuth)) * turbulence_horizontal_speed,
|
|
|
|
sinf(radians(turbulence_azimuth)) * turbulence_horizontal_speed,
|
2016-11-13 20:41:06 -04:00
|
|
|
turbulence_vertical_speed);
|
2016-12-19 05:48:27 -04:00
|
|
|
}
|
2016-04-19 22:48:37 -03:00
|
|
|
}
|
2016-06-17 02:25:23 -03:00
|
|
|
|
2016-07-19 08:38:16 -03:00
|
|
|
/*
|
|
|
|
smooth sensors for kinematic consistancy when we interact with the ground
|
|
|
|
*/
|
|
|
|
void Aircraft::smooth_sensors(void)
|
|
|
|
{
|
|
|
|
uint64_t now = time_now_us;
|
|
|
|
Vector3f delta_pos = position - smoothing.position;
|
|
|
|
if (smoothing.last_update_us == 0 || delta_pos.length() > 10) {
|
|
|
|
smoothing.position = position;
|
|
|
|
smoothing.rotation_b2e = dcm;
|
|
|
|
smoothing.accel_body = accel_body;
|
|
|
|
smoothing.velocity_ef = velocity_ef;
|
|
|
|
smoothing.gyro = gyro;
|
|
|
|
smoothing.last_update_us = now;
|
|
|
|
smoothing.location = location;
|
|
|
|
printf("Smoothing reset at %.3f\n", now * 1.0e-6f);
|
|
|
|
return;
|
|
|
|
}
|
2016-12-19 05:48:27 -04:00
|
|
|
const float delta_time = (now - smoothing.last_update_us) * 1.0e-6f;
|
2017-10-20 21:57:59 -03:00
|
|
|
if (delta_time < 0 || delta_time > 0.1) {
|
|
|
|
return;
|
|
|
|
}
|
2016-07-19 08:38:16 -03:00
|
|
|
|
|
|
|
// calculate required accel to get us to desired position and velocity in the time_constant
|
2016-12-19 05:48:27 -04:00
|
|
|
const float time_constant = 0.1f;
|
2016-07-19 08:38:16 -03:00
|
|
|
Vector3f dvel = (velocity_ef - smoothing.velocity_ef) + (delta_pos / time_constant);
|
2016-12-19 05:48:27 -04:00
|
|
|
Vector3f accel_e = dvel / time_constant + (dcm * accel_body + Vector3f(0.0f, 0.0f, GRAVITY_MSS));
|
|
|
|
const float accel_limit = 14 * GRAVITY_MSS;
|
2016-07-19 08:38:16 -03:00
|
|
|
accel_e.x = constrain_float(accel_e.x, -accel_limit, accel_limit);
|
|
|
|
accel_e.y = constrain_float(accel_e.y, -accel_limit, accel_limit);
|
|
|
|
accel_e.z = constrain_float(accel_e.z, -accel_limit, accel_limit);
|
2016-12-19 05:48:27 -04:00
|
|
|
smoothing.accel_body = smoothing.rotation_b2e.transposed() * (accel_e + Vector3f(0.0f, 0.0f, -GRAVITY_MSS));
|
2016-07-19 08:38:16 -03:00
|
|
|
|
|
|
|
// calculate rotational rate to get us to desired attitude in time constant
|
|
|
|
Quaternion desired_q, current_q, error_q;
|
|
|
|
desired_q.from_rotation_matrix(dcm);
|
|
|
|
desired_q.normalize();
|
|
|
|
current_q.from_rotation_matrix(smoothing.rotation_b2e);
|
|
|
|
current_q.normalize();
|
|
|
|
error_q = desired_q / current_q;
|
|
|
|
error_q.normalize();
|
|
|
|
|
|
|
|
Vector3f angle_differential;
|
|
|
|
error_q.to_axis_angle(angle_differential);
|
|
|
|
smoothing.gyro = gyro + angle_differential / time_constant;
|
|
|
|
|
2016-12-19 05:48:27 -04:00
|
|
|
float R, P, Y;
|
|
|
|
smoothing.rotation_b2e.to_euler(&R, &P, &Y);
|
|
|
|
float R2, P2, Y2;
|
|
|
|
dcm.to_euler(&R2, &P2, &Y2);
|
2016-07-19 08:38:16 -03:00
|
|
|
|
|
|
|
#if 0
|
|
|
|
DataFlash_Class::instance()->Log_Write("SMOO", "TimeUS,AEx,AEy,AEz,DPx,DPy,DPz,R,P,Y,R2,P2,Y2",
|
|
|
|
"Qffffffffffff",
|
|
|
|
AP_HAL::micros64(),
|
|
|
|
degrees(angle_differential.x),
|
|
|
|
degrees(angle_differential.y),
|
|
|
|
degrees(angle_differential.z),
|
|
|
|
delta_pos.x, delta_pos.y, delta_pos.z,
|
|
|
|
degrees(R), degrees(P), degrees(Y),
|
|
|
|
degrees(R2), degrees(P2), degrees(Y2));
|
|
|
|
#endif
|
2016-12-19 05:48:27 -04:00
|
|
|
|
2016-07-19 08:38:16 -03:00
|
|
|
|
|
|
|
// integrate to get new attitude
|
|
|
|
smoothing.rotation_b2e.rotate(smoothing.gyro * delta_time);
|
|
|
|
smoothing.rotation_b2e.normalize();
|
|
|
|
|
|
|
|
// integrate to get new position
|
|
|
|
smoothing.velocity_ef += accel_e * delta_time;
|
|
|
|
smoothing.position += smoothing.velocity_ef * delta_time;
|
|
|
|
|
|
|
|
smoothing.location = home;
|
|
|
|
location_offset(smoothing.location, smoothing.position.x, smoothing.position.y);
|
2016-12-19 05:48:27 -04:00
|
|
|
smoothing.location.alt = static_cast<int32_t>(home.alt - smoothing.position.z * 100.0f);
|
|
|
|
|
2016-07-19 08:38:16 -03:00
|
|
|
smoothing.last_update_us = now;
|
|
|
|
smoothing.enabled = true;
|
|
|
|
}
|
2016-10-25 05:54:56 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
return a filtered servo input as a value from -1 to 1
|
|
|
|
servo is assumed to be 1000 to 2000, trim at 1500
|
|
|
|
*/
|
|
|
|
float Aircraft::filtered_idx(float v, uint8_t idx)
|
|
|
|
{
|
|
|
|
if (sitl->servo_speed <= 0) {
|
|
|
|
return v;
|
|
|
|
}
|
2016-12-19 05:48:27 -04:00
|
|
|
const float cutoff = 1.0f / (2 * M_PI * sitl->servo_speed);
|
2016-10-25 05:54:56 -03:00
|
|
|
servo_filter[idx].set_cutoff_frequency(cutoff);
|
2016-12-19 05:48:27 -04:00
|
|
|
return servo_filter[idx].apply(v, frame_time_us * 1.0e-6f);
|
2016-10-25 05:54:56 -03:00
|
|
|
}
|
2016-12-19 05:48:27 -04:00
|
|
|
|
2016-10-25 05:54:56 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
return a filtered servo input as a value from -1 to 1
|
|
|
|
servo is assumed to be 1000 to 2000, trim at 1500
|
|
|
|
*/
|
|
|
|
float Aircraft::filtered_servo_angle(const struct sitl_input &input, uint8_t idx)
|
|
|
|
{
|
2016-12-19 05:48:27 -04:00
|
|
|
const float v = (input.servos[idx] - 1500)/500.0f;
|
2016-10-25 05:54:56 -03:00
|
|
|
return filtered_idx(v, idx);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
return a filtered servo input as a value from 0 to 1
|
|
|
|
servo is assumed to be 1000 to 2000
|
|
|
|
*/
|
|
|
|
float Aircraft::filtered_servo_range(const struct sitl_input &input, uint8_t idx)
|
|
|
|
{
|
2016-12-19 05:48:27 -04:00
|
|
|
const float v = (input.servos[idx] - 1000)/1000.0f;
|
2016-10-25 05:54:56 -03:00
|
|
|
return filtered_idx(v, idx);
|
|
|
|
}
|
|
|
|
|
2017-10-20 21:57:59 -03:00
|
|
|
// extrapolate sensors by a given delta time in seconds
|
|
|
|
void Aircraft::extrapolate_sensors(float delta_time)
|
|
|
|
{
|
|
|
|
Vector3f accel_earth = dcm * accel_body;
|
|
|
|
accel_earth.z += GRAVITY_MSS;
|
|
|
|
|
|
|
|
dcm.rotate(gyro * delta_time);
|
|
|
|
dcm.normalize();
|
|
|
|
|
|
|
|
// work out acceleration as seen by the accelerometers. It sees the kinematic
|
|
|
|
// acceleration (ie. real movement), plus gravity
|
|
|
|
accel_body = dcm.transposed() * (accel_earth + Vector3f(0,0,-GRAVITY_MSS));
|
|
|
|
|
|
|
|
// new velocity and position vectors
|
|
|
|
velocity_ef += accel_earth * delta_time;
|
|
|
|
position += velocity_ef * delta_time;
|
|
|
|
velocity_air_ef = velocity_ef + wind_ef;
|
|
|
|
velocity_air_bf = dcm.transposed() * velocity_air_ef;
|
|
|
|
}
|
|
|
|
|
|
|
|
|