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
2019-12-31 22:49:28 -04:00
# include <GCS_MAVLink/GCS.h>
2019-01-18 00:23:42 -04:00
# include <AP_Logger/AP_Logger.h>
2016-07-19 01:42:31 -03:00
# include <AP_Param/AP_Param.h>
2019-08-27 17:07:52 -03:00
# include <AP_Declination/AP_Declination.h>
2021-02-14 22:51:06 -04:00
# include <AP_Terrain/AP_Terrain.h>
2021-07-14 20:11:44 -03:00
# include <AP_Scheduler/AP_Scheduler.h>
2022-01-28 00:56:24 -04:00
# include <AP_BoardConfig/AP_BoardConfig.h>
2024-01-31 18:01:48 -04:00
# include <AP_JSON/AP_JSON.h>
2023-01-28 01:47:25 -04:00
# include <AP_Filesystem/AP_Filesystem.h>
2024-04-28 00:21:41 -03:00
# include <AP_AHRS/AP_AHRS.h>
2024-06-08 04:42:26 -03:00
# include <AP_HAL_SITL/HAL_SITL_Class.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
2021-11-01 04:18:52 -03:00
extern const AP_HAL : : HAL & hal ;
2024-06-08 04:42:26 -03:00
// the SITL HAL can add information about pausing the simulation and its effect on the UART. Not present when we're compiling for simulation-on-hardware
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
extern const HAL_SITL & hal_sitl ;
# endif
2015-05-02 05:09:30 -03:00
/*
parent class for all simulator types
*/
2019-08-15 01:01:24 -03:00
Aircraft : : Aircraft ( const char * frame_str ) :
2020-09-22 19:44:18 -03:00
frame ( frame_str )
2015-05-02 05:09:30 -03:00
{
2016-06-16 19:35:08 -03:00
// make the SIM_* variables available to simulator backends
2018-06-27 15:36:22 -03:00
sitl = AP : : sitl ( ) ;
2018-02-19 21:33:14 -04:00
2019-08-15 01:01:24 -03:00
set_speedup ( 1.0f ) ;
last_wall_time_us = get_wall_time_us ( ) ;
// allow for orientation settings, such as with tailsitters
enum ap_var_type ptype ;
ahrs_orientation = ( AP_Int8 * ) AP_Param : : find ( " AHRS_ORIENTATION " , & ptype ) ;
2019-12-11 20:11:03 -04:00
2020-01-13 13:47:52 -04:00
// ahrs_orientation->get() returns ROTATION_NONE here, regardless of the actual value
2020-01-08 22:46:39 -04:00
enum Rotation imu_rotation = ahrs_orientation ? ( enum Rotation ) ahrs_orientation - > get ( ) : ROTATION_NONE ;
2019-12-11 20:11:03 -04:00
last_imu_rotation = imu_rotation ;
2020-05-15 11:10:11 -03:00
// sitl is null if running example program
if ( sitl ) {
sitl - > ahrs_rotation . from_rotation ( imu_rotation ) ;
sitl - > ahrs_rotation_inv = sitl - > ahrs_rotation . transposed ( ) ;
}
2019-12-11 20:11:03 -04:00
2023-08-20 21:51:13 -03:00
// init rangefinder array to NaN to signify no data
2022-10-02 05:21:54 -03:00
for ( uint8_t i = 0 ; i < ARRAY_SIZE ( rangefinder_m ) ; i + + ) {
2023-08-20 21:51:13 -03:00
rangefinder_m [ i ] = nanf ( " " ) ;
2020-07-17 20:37:34 -03:00
}
2019-08-15 01:01:24 -03:00
}
2019-08-15 03:53:35 -03:00
void Aircraft : : set_start_location ( const Location & start_loc , const float start_yaw )
2019-08-15 01:01:24 -03:00
{
2019-08-15 03:53:35 -03:00
home = start_loc ;
2021-07-10 03:10:54 -03:00
origin = home ;
position . xy ( ) . zero ( ) ;
2019-08-15 03:53:35 -03:00
home_yaw = start_yaw ;
home_is_set = true ;
2018-02-19 21:33:14 -04:00
: : printf ( " Home: %f %f alt=%fm hdg=%f \n " ,
home . lat * 1e-7 ,
home . lng * 1e-7 ,
home . alt * 0.01 ,
home_yaw ) ;
2019-08-15 03:53:35 -03:00
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
2021-07-10 03:10:54 -03:00
#if 0
// useful test for home position being very different from origin
home . offset ( - 3000 * 1000 , 1800 * 1000 ) ;
# endif
2016-12-19 05:48:27 -04:00
dcm . from_euler ( 0.0f , 0.0f , radians ( home_yaw ) ) ;
2015-05-02 05:09:30 -03: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
{
2021-02-14 22:51:06 -04:00
# if AP_TERRAIN_AVAILABLE
AP_Terrain * terrain = AP : : terrain ( ) ;
2016-07-19 01:42:31 -03:00
float h1 , h2 ;
2018-05-14 18:21:17 -03:00
if ( sitl & &
2021-02-14 22:51:06 -04:00
terrain ! = nullptr & &
sitl - > terrain_enable & &
2022-03-27 18:27:03 -03:00
terrain - > height_amsl ( home , h1 , false ) & &
terrain - > height_amsl ( location , h2 , false ) ) {
2021-02-08 08:13:19 -04:00
h2 + = local_ground_level ;
2016-11-22 20:09:33 -04:00
return h2 - h1 ;
2016-07-19 01:42:31 -03:00
}
2021-02-14 22:51:06 -04:00
# endif
2021-02-08 08:13:19 -04:00
return local_ground_level ;
2016-11-22 20:09:33 -04:00
}
2018-08-03 07:52:20 -03:00
void Aircraft : : set_precland ( SIM_Precland * _precland ) {
precland = _precland ;
precland - > set_default_location ( home . lat * 1.0e-7 f , home . lng * 1.0e-7 f , static_cast < int16_t > ( get_home_yaw ( ) ) ) ;
}
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
}
2020-06-04 05:07:26 -03: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
{
2018-09-06 10:38:18 -03:00
return hagl ( ) < = 0.001f ; // prevent bouncing around ground
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 )
{
2021-07-10 03:10:54 -03:00
location = origin ;
location . offset ( 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
2021-07-10 03:10:54 -03:00
Vector3d pos_home = position ;
pos_home . xy ( ) + = home . get_distance_NE_double ( origin ) ;
2016-06-04 01:21:21 -03:00
// logging of raw sitl data
Vector3f accel_ef = dcm * accel_body ;
2020-04-14 22:54:10 -03:00
// @LoggerMessage: SITL
// @Description: Simulation data
// @Field: TimeUS: Time since system startup
// @Field: VN: Velocity - North component
// @Field: VE: Velocity - East component
// @Field: VD: Velocity - Down component
// @Field: AN: Acceleration - North component
// @Field: AE: Acceleration - East component
// @Field: AD: Acceleration - Down component
// @Field: PN: Position - North component
// @Field: PE: Position - East component
// @Field: PD: Position - Down component
2021-08-17 06:57:41 -03:00
AP : : logger ( ) . WriteStreaming ( " SITL " , " TimeUS,VN,VE,VD,AN,AE,AD,PN,PE,PD " , " Qfffffffff " ,
2016-06-04 01:21:21 -03:00
AP_HAL : : micros64 ( ) ,
velocity_ef . x , velocity_ef . y , velocity_ef . z ,
accel_ef . x , accel_ef . y , accel_ef . z ,
2021-07-10 03:10:54 -03:00
pos_home . x , pos_home . y , pos_home . z ) ;
2016-06-04 01:21:21 -03:00
# endif
2021-07-10 03:10:54 -03:00
2024-04-28 00:21:41 -03:00
if ( ! disable_origin_movement ) {
uint32_t now = AP_HAL : : millis ( ) ;
if ( now - last_one_hz_ms > = 1000 ) {
// shift origin of position at 1Hz to current location
// this prevents sperical errors building up in the GPS data
last_one_hz_ms = now ;
Vector2d diffNE = origin . get_distance_NE_double ( location ) ;
position . xy ( ) - = diffNE ;
smoothing . position . xy ( ) - = diffNE ;
origin . lat = location . lat ;
origin . lng = location . lng ;
}
2021-07-10 03:10:54 -03:00
}
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-7 f , location . lng * 1e-7 f , 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 ( 1e3 f * 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
2018-11-04 01:31:13 -04:00
if ( ! sitl ) {
// running example program
return ;
}
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 ;
2020-06-04 06:00:40 -03:00
frame_time_us = uint64_t ( 1.0e6 f / rate_hz ) ;
2015-05-02 05:09:30 -03:00
last_wall_time_us = get_wall_time_us ( ) ;
}
/* adjust frame_time calculation */
void Aircraft : : adjust_frame_time ( float new_rate )
{
2020-06-04 06:00:40 -03:00
frame_time_us = uint64_t ( 1.0e6 f / new_rate ) ;
rate_hz = new_rate ;
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 ( ) ;
2020-06-04 06:00:40 -03:00
uint64_t dt_us = now - last_wall_time_us ;
const float target_dt_us = 1.0e6 / ( rate_hz * target_speedup ) ;
// accumulate sleep debt if we're running too fast
sleep_debt_us + = target_dt_us - dt_us ;
if ( sleep_debt_us < - 1.0e5 ) {
// don't let a large negative debt build up
sleep_debt_us = - 1.0e5 ;
}
if ( sleep_debt_us > min_sleep_time ) {
// sleep if we have built up a debt of min_sleep_tim
2021-11-01 04:18:52 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
2020-06-04 06:00:40 -03:00
usleep ( sleep_debt_us ) ;
2021-11-01 04:18:52 -03:00
# elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
hal . scheduler - > delay_microseconds ( sleep_debt_us ) ;
# else
// ??
# endif
2020-06-04 06:00:40 -03:00
sleep_debt_us - = ( get_wall_time_us ( ) - now ) ;
2015-05-02 05:09:30 -03:00
}
2020-06-04 06:00:40 -03:00
last_wall_time_us = get_wall_time_us ( ) ;
uint32_t now_ms = last_wall_time_us / 1000ULL ;
float dt_wall = ( now_ms - last_fps_report_ms ) * 0.001 ;
2023-09-20 22:23:11 -03:00
if ( dt_wall > 0.01 ) { // 0.01s average
achieved_rate_hz = ( frame_counter - last_frame_count ) / dt_wall ;
2020-08-15 04:58:35 -03:00
#if 0
2020-06-04 05:07:26 -03:00
: : printf ( " Rate: target:%.1f achieved:%.1f speedup %.1f/%.1f \n " ,
rate_hz * target_speedup , achieved_rate_hz ,
achieved_rate_hz / rate_hz , target_speedup ) ;
2020-08-15 04:58:35 -03:00
# endif
last_frame_count = frame_counter ;
last_fps_report_ms = now_ms ;
2020-06-04 05:07:26 -03:00
}
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
{
2020-06-04 05:07:26 -03:00
bool is_smoothed = false ;
2016-07-19 08:38:16 -03:00
if ( use_smoothing ) {
smooth_sensors ( ) ;
2020-06-04 05:07:26 -03:00
is_smoothed = true ;
2016-07-19 08:38:16 -03:00
}
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 ;
}
2021-05-17 21:25:12 -03:00
fdm . is_lock_step_scheduled = lock_step_scheduled ;
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 ) ;
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 ;
2020-11-24 22:44:46 -04:00
fdm . velocity_air_bf = velocity_air_bf ;
2015-11-22 22:46:01 -04:00
fdm . battery_voltage = battery_voltage ;
fdm . battery_current = battery_current ;
2022-08-18 06:00:36 -03:00
fdm . motor_mask = motor_mask | sitl - > vibe_motor_mask ;
2022-08-18 04:18:32 -03:00
memcpy ( fdm . rpm , rpm , sizeof ( fdm . rpm ) ) ;
2016-05-03 23:49:42 -03:00
fdm . rcin_chan_count = rcin_chan_count ;
2021-12-11 00:18:13 -04:00
fdm . range = rangefinder_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
2018-12-04 01:53:15 -04:00
// copy laser scanner results
fdm . scanner . points = scanner . points ;
fdm . scanner . ranges = scanner . ranges ;
2020-07-17 20:37:34 -03:00
// copy rangefinder
memcpy ( fdm . rangefinder_m , rangefinder_m , sizeof ( fdm . rangefinder_m ) ) ;
2020-08-15 12:35:50 -03:00
fdm . wind_vane_apparent . direction = wind_vane_apparent . direction ;
fdm . wind_vane_apparent . speed = wind_vane_apparent . speed ;
2022-07-29 22:45:27 -03:00
fdm . wind_ef = wind_ef ;
2020-06-04 05:07:26 -03:00
if ( is_smoothed ) {
2016-07-19 08:38:16 -03:00
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
2021-07-10 03:10:54 -03:00
2017-11-22 23:26:01 -04:00
if ( ahrs_orientation ! = nullptr ) {
enum Rotation imu_rotation = ( enum Rotation ) ahrs_orientation - > get ( ) ;
2019-12-11 20:11:03 -04:00
if ( imu_rotation ! = last_imu_rotation ) {
2021-11-05 13:13:20 -03:00
sitl - > ahrs_rotation . from_rotation ( imu_rotation ) ;
sitl - > ahrs_rotation_inv = sitl - > ahrs_rotation . transposed ( ) ;
last_imu_rotation = imu_rotation ;
2019-12-11 20:11:03 -04:00
}
2017-11-22 23:26:01 -04:00
if ( imu_rotation ! = ROTATION_NONE ) {
Matrix3f m = dcm ;
2020-01-13 13:47:52 -04:00
m = m * sitl - > ahrs_rotation_inv ;
2017-11-22 23:26:01 -04:00
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
}
2020-08-26 09:38:44 -03:00
// in the first call here, if a speedup option is specified, overwrite it
if ( is_equal ( last_speedup , - 1.0f ) & & ! is_equal ( get_speedup ( ) , 1.0f ) ) {
2022-07-20 06:41:54 -03:00
sitl - > speedup . set ( get_speedup ( ) ) ;
2020-08-26 09:38:44 -03:00
}
2017-06-05 02:36:55 -03:00
2018-08-14 23:37:10 -03:00
if ( ! is_equal ( last_speedup , float ( sitl - > speedup ) ) & & sitl - > speedup > 0 ) {
2016-09-18 18:45:24 -03:00
set_speedup ( sitl - > speedup ) ;
last_speedup = sitl - > speedup ;
}
2021-07-14 20:11:44 -03:00
2024-01-11 02:17:05 -04:00
# if HAL_LOGGING_ENABLED
2024-06-08 04:42:26 -03:00
# if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// the SITL HAL can add information about pausing the simulation
// and its effect on the UART. Not present when we're compiling
// for simulation-on-hardware
const uint32_t full_count = hal_sitl . get_uart_output_full_queue_count ( ) ;
# else
const uint32_t full_count = 0 ;
# endif
2021-07-14 20:11:44 -03:00
// for EKF comparison log relhome pos and velocity at loop rate
static uint16_t last_ticks ;
uint16_t ticks = AP : : scheduler ( ) . ticks ( ) ;
if ( last_ticks ! = ticks ) {
last_ticks = ticks ;
// @LoggerMessage: SIM2
// @Description: Additional simulator state
// @Field: TimeUS: Time since system startup
// @Field: PN: North position from home
// @Field: PE: East position from home
// @Field: PD: Down position from home
// @Field: VN: Velocity north
// @Field: VE: Velocity east
// @Field: VD: Velocity down
2022-01-26 02:33:38 -04:00
// @Field: As: Airspeed
2023-09-20 22:23:11 -03:00
// @Field: ASpdU: Achieved simulation speedup value
2024-06-08 04:42:26 -03:00
// @Field: UFC: Number of times simulation paused for serial0 output
2021-07-14 20:11:44 -03:00
Vector3d pos = get_position_relhome ( ) ;
Vector3f vel = get_velocity_ef ( ) ;
2024-06-08 04:42:26 -03:00
AP : : logger ( ) . WriteStreaming (
" SIM2 " ,
" TimeUS,PN,PE,PD,VN,VE,VD,As,ASpdU,UFC " ,
" QdddfffffI " ,
AP_HAL : : micros64 ( ) ,
pos . x , pos . y , pos . z ,
vel . x , vel . y , vel . z ,
airspeed_pitot ,
achieved_rate_hz / rate_hz ,
full_count
) ;
2021-07-14 20:11:44 -03:00
}
2024-01-11 02:17:05 -04:00
# endif
2015-05-02 07:28:57 -03:00
}
2021-12-11 00:18:13 -04:00
// returns perpendicular height to surface downward-facing rangefinder
// is bouncing off:
float Aircraft : : perpendicular_distance_to_rangefinder_surface ( ) const
{
2022-04-18 02:30:09 -03:00
switch ( ( Rotation ) sitl - > sonar_rot . get ( ) ) {
case Rotation : : ROTATION_PITCH_270 :
2024-01-07 22:07:46 -04:00
return sitl - > state . height_agl ;
2022-04-18 02:30:09 -03:00
case ROTATION_NONE . . . ROTATION_YAW_315 :
return sitl - > measure_distance_at_angle_bf ( location , sitl - > sonar_rot . get ( ) * 45 ) ;
default :
AP_BoardConfig : : config_error ( " Bad simulated sonar rotation " ) ;
}
2021-12-11 00:18:13 -04:00
}
2020-08-04 00:47:24 -03:00
float Aircraft : : rangefinder_range ( ) const
{
2022-04-18 02:30:09 -03:00
2021-12-11 00:18:13 -04:00
float roll = sitl - > state . rollDeg ;
float pitch = sitl - > state . pitchDeg ;
2020-08-04 00:47:24 -03:00
2021-12-11 00:18:13 -04:00
if ( roll > 0 ) {
roll - = rangefinder_beam_width ( ) ;
if ( roll < 0 ) {
roll = 0 ;
}
} else {
roll + = rangefinder_beam_width ( ) ;
if ( roll > 0 ) {
roll = 0 ;
}
}
if ( pitch > 0 ) {
pitch - = rangefinder_beam_width ( ) ;
if ( pitch < 0 ) {
pitch = 0 ;
}
} else {
pitch + = rangefinder_beam_width ( ) ;
if ( pitch > 0 ) {
pitch = 0 ;
}
}
if ( fabs ( roll ) > = 90.0 | | fabs ( pitch ) > = 90.0 ) {
// not going to hit the ground....
return INFINITY ;
2020-08-04 00:47:24 -03:00
}
2021-12-11 00:18:13 -04:00
float altitude = perpendicular_distance_to_rangefinder_surface ( ) ;
2020-08-04 00:47:24 -03:00
// sensor position offset in body frame
const Vector3f relPosSensorBF = sitl - > rngfnd_pos_offset ;
2022-04-18 02:30:09 -03:00
// n.b. the following code is assuming rotation-pitch-270:
2020-08-04 00:47:24 -03:00
// 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 ;
sitl - > state . quaternion . rotation_matrix ( rotmat ) ;
// rotate the offset into earth frame
const Vector3f relPosSensorEF = rotmat * relPosSensorBF ;
// correct the altitude at the sensor
altitude - = relPosSensorEF . z ;
}
2021-12-11 00:18:13 -04:00
// adjust for apparent altitude with roll
altitude / = cosf ( radians ( roll ) ) * cosf ( radians ( pitch ) ) ;
2021-12-07 21:49:54 -04:00
// Add some noise on reading
altitude + = sitl - > sonar_noise * rand_float ( ) ;
2020-08-04 00:47:24 -03:00
return altitude ;
}
2024-05-27 04:25:53 -03:00
# if defined(__CYGWIN__) || defined(__CYGWIN64__)
extern " C " { uint32_t timeGetTime ( ) ; }
# endif
2020-08-04 00:47:24 -03:00
2021-10-11 02:08:40 -03:00
// potentially replace this with a call to AP_HAL::Util::get_hw_rtc
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__)
2024-05-27 04:25:53 -03:00
static uint32_t tPrev ;
2015-05-25 03:48:13 -03:00
static uint64_t last_ret_us ;
if ( tPrev = = 0 ) {
tPrev = timeGetTime ( ) ;
return 0 ;
}
2024-05-27 04:25:53 -03:00
uint32_t now = timeGetTime ( ) ;
2015-05-25 03:48:13 -03:00
last_ret_us + = ( uint64_t ) ( ( now - tPrev ) * 1000UL ) ;
tPrev = now ;
return last_ret_us ;
2021-10-11 02:08:40 -03:00
# elif CONFIG_HAL_BOARD == HAL_BOARD_SITL
2020-02-18 09:42:25 -04:00
struct timespec ts ;
clock_gettime ( CLOCK_MONOTONIC , & ts ) ;
return uint64_t ( ts . tv_sec * 1000000ULL + ts . tv_nsec / 1000ULL ) ;
2021-10-11 02:08:40 -03:00
# else
return AP_HAL : : micros64 ( ) ;
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
2023-10-31 05:09:11 -03:00
void Aircraft : : update_home ( )
2019-08-15 03:53:35 -03:00
{
if ( ! home_is_set ) {
if ( sitl = = nullptr ) {
return ;
}
Location loc ;
loc . lat = sitl - > opos . lat . get ( ) * 1.0e7 ;
loc . lng = sitl - > opos . lng . get ( ) * 1.0e7 ;
loc . alt = sitl - > opos . alt . get ( ) * 1.0e2 ;
set_start_location ( loc , sitl - > opos . hdg . get ( ) ) ;
}
2023-10-31 05:09:11 -03:00
}
void Aircraft : : update_model ( const struct sitl_input & input )
{
2021-02-08 08:13:19 -04:00
local_ground_level = 0.0f ;
2023-12-29 17:36:18 -04:00
if ( sitl ! = nullptr ) {
update ( input ) ;
} else {
time_advance ( ) ;
}
2019-08-15 03:53:35 -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 )
{
2024-04-28 00:21:41 -03:00
// update eas2tas and air density
# if AP_AHRS_ENABLED
eas2tas = AP : : ahrs ( ) . get_EAS2TAS ( ) ;
# endif
air_density = SSL_AIR_DENSITY / sq ( eas2tas ) ;
2016-12-19 05:48:27 -04:00
const float delta_time = frame_time_us * 1.0e-6 f ;
2024-04-28 04:11:56 -03:00
// update eas2tas and air density
eas2tas = AP_Baro : : get_EAS2TAS_for_alt_amsl ( location . alt * 0.01 ) ;
air_density = AP_Baro : : get_air_density_for_alt_amsl ( location . alt * 0.01 ) ;
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
2024-04-26 05:47:28 -03:00
// limit body accel to 64G
const float accel_limit = 64 * GRAVITY_MSS ;
accel_body . x = constrain_float ( accel_body . x , - accel_limit , accel_limit ) ;
accel_body . y = constrain_float ( accel_body . y , - accel_limit , accel_limit ) ;
accel_body . z = constrain_float ( accel_body . z , - accel_limit , accel_limit ) ;
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
2021-06-20 23:59:02 -03:00
position + = ( velocity_ef * delta_time ) . todouble ( ) ;
2016-01-01 00:11:55 -04:00
2016-04-19 22:48:37 -03:00
// velocity relative to air mass, in earth frame
2022-11-28 18:36:25 -04: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
2024-04-28 04:11:56 -03:00
update_eas_airspeed ( ) ;
2016-12-19 05:48:27 -04:00
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 ) {
2020-11-05 19:36:08 -04:00
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " SIM Hit ground at %f m/s " , 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
2020-03-17 20:07:11 -03:00
// get speed of ground movement (for ship takeoff/landing)
float yaw_rate = 0 ;
2021-10-11 02:05:28 -03:00
# if AP_SIM_SHIP_ENABLED
2024-04-26 05:47:28 -03:00
const Vector2f ship_movement = sitl - > models . shipsim . get_ground_speed_adjustment ( location , yaw_rate ) ;
2020-03-17 20:07:11 -03:00
const Vector3f gnd_movement ( ship_movement . x , ship_movement . y , 0 ) ;
2021-10-11 02:05:28 -03:00
# else
const Vector3f gnd_movement ;
# endif
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 ) ;
2020-03-17 20:07:11 -03:00
y = y + yaw_rate * delta_time ;
2016-12-19 05:48:27 -04:00
dcm . from_euler ( 0.0f , 0.0f , y ) ;
2020-03-17 20:07:11 -03:00
// X, Y movement tracks ground movement
velocity_ef . x = gnd_movement . x ;
velocity_ef . y = gnd_movement . y ;
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 ( ) ;
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 ) ;
2019-07-05 06:17:30 -03:00
if ( velocity_ef . length ( ) < 5 ) {
// at high speeds don't constrain pitch, otherwise we
// can get stuck in takeoff
p = 0 ;
} else {
p = MAX ( p , 0 ) ;
}
2020-03-17 20:07:11 -03:00
y = y + yaw_rate * delta_time ;
2019-07-05 06:17:30 -03:00
dcm . from_euler ( 0.0f , p , 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
}
2020-03-17 20:07:11 -03:00
Vector3f gnd_movement_bf = dcm . transposed ( ) * gnd_movement ;
// lateral speed equals ground movement
v_bf . y = gnd_movement_bf . y ;
if ( ! gnd_movement_bf . is_zero ( ) ) {
// fwd speed slowly approaches ground movement to simulate wheel friction
const float tconst = 20 ; // seconds
const float alpha = delta_time / ( delta_time + tconst / M_2PI ) ;
v_bf . x + = ( gnd_movement . x - v_bf . x ) * alpha ;
}
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 ( ) ;
2020-03-17 20:07:11 -03:00
gyro . z = yaw_rate ;
2017-02-11 07:30:42 -04:00
use_smoothing = true ;
break ;
}
case GROUND_BEHAVIOR_TAILSITTER : {
2021-10-22 19:57:06 -03:00
// rotate normal refernce frame to get yaw angle, then rotate back
Matrix3f rot ;
rot . from_rotation ( ROTATION_PITCH_270 ) ;
2017-02-11 07:30:42 -04:00
float r , p , y ;
2021-10-22 19:57:06 -03:00
( dcm * rot ) . to_euler ( & r , & p , & y ) ;
2020-03-17 20:07:11 -03:00
y = y + yaw_rate * delta_time ;
2021-10-22 19:57:06 -03:00
dcm . from_euler ( 0.0 , 0.0 , y ) ;
rot . from_rotation ( ROTATION_PITCH_90 ) ;
dcm * = rot ;
2020-03-17 20:07:11 -03:00
// X, Y movement tracks ground movement
velocity_ef . x = gnd_movement . x ;
velocity_ef . y = gnd_movement . y ;
2021-10-22 19:57:06 -03:00
if ( velocity_ef . z > 0.0f ) {
velocity_ef . z = 0.0f ;
}
2017-02-11 07:30:42 -04:00
gyro . zero ( ) ;
2021-10-22 19:57:06 -03:00
gyro . x = yaw_rate ;
use_smoothing = true ;
2016-07-19 01:42:31 -03:00
break ;
}
}
2016-01-01 00:11:55 -04:00
}
2020-06-03 01:34:23 -03:00
// allow for changes in physics step
adjust_frame_time ( constrain_float ( sitl - > loop_rate_hz , rate_hz - 1 , rate_hz + 1 ) ) ;
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
2021-07-10 03:10:54 -03:00
wind_ef . z + = get_local_updraft ( position + home . get_distance_NED_double ( origin ) ) ;
2019-05-26 06:56:10 -03:00
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
}
2022-11-28 18:36:25 -04:00
// the AHRS wants wind with opposite sense
wind_ef = - wind_ef ;
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 ;
2021-06-20 23:59:02 -03:00
Vector3d delta_pos = position - smoothing . position ;
2016-07-19 08:38:16 -03:00
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-6 f ) ;
return ;
}
2016-12-19 05:48:27 -04:00
const float delta_time = ( now - smoothing . last_update_us ) * 1.0e-6 f ;
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 ;
2021-06-20 23:59:02 -03:00
Vector3f dvel = ( velocity_ef - smoothing . velocity_ef ) + ( delta_pos / time_constant ) . tofloat ( ) ;
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
2020-04-14 22:54:10 -03:00
// @LoggerMessage: SMOO
// @Description: Smoothed sensor data fed to EKF to avoid inconsistencies
// @Field: TimeUS: Time since system startup
// @Field: AEx: Angular Velocity (around x-axis)
// @Field: AEy: Angular Velocity (around y-axis)
// @Field: AEz: Angular Velocity (around z-axis)
// @Field: DPx: Velocity (along x-axis)
// @Field: DPy: Velocity (along y-axis)
// @Field: DPz: Velocity (along z-axis)
// @Field: R: Roll
// @Field: P: Pitch
// @Field: Y: Yaw
// @Field: R2: DCM Roll
// @Field: P2: DCM Pitch
// @Field: Y2: DCM Yaw
2021-08-17 06:57:41 -03:00
AP : : logger ( ) . WriteStreaming ( " SMOO " , " TimeUS,AEx,AEy,AEz,DPx,DPy,DPz,R,P,Y,R2,P2,Y2 " ,
2016-07-19 08:38:16 -03:00
" 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 ;
2021-06-20 23:59:02 -03:00
smoothing . position + = ( smoothing . velocity_ef * delta_time ) . todouble ( ) ;
2016-07-19 08:38:16 -03:00
2021-07-10 03:10:54 -03:00
smoothing . location = origin ;
smoothing . location . offset ( 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 ;
}
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 )
{
2024-04-28 00:21:41 -03:00
return servo_filter [ idx ] . filter_angle ( input . servos [ idx ] , frame_time_us * 1.0e-6 ) ;
2016-10-25 05:54:56 -03:00
}
/*
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 )
{
2024-04-28 00:21:41 -03:00
return servo_filter [ idx ] . filter_range ( input . servos [ idx ] , frame_time_us * 1.0e-6 ) ;
}
// setup filtering for servo
void Aircraft : : filtered_servo_setup ( uint8_t idx , uint16_t pwm_min , uint16_t pwm_max , float deflection_deg )
{
servo_filter [ idx ] . set_pwm_range ( pwm_min , pwm_max ) ;
servo_filter [ idx ] . set_deflection ( deflection_deg ) ;
2016-10-25 05:54:56 -03:00
}
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 ;
2021-06-20 23:59:02 -03:00
position + = ( velocity_ef * delta_time ) . todouble ( ) ;
2022-11-28 18:36:25 -04:00
velocity_air_ef = velocity_ef - wind_ef ;
2017-10-20 21:57:59 -03:00
velocity_air_bf = dcm . transposed ( ) * velocity_air_ef ;
}
2024-06-07 00:43:50 -03:00
bool Aircraft : : Clamp : : clamped ( Aircraft & aircraft , const struct sitl_input & input )
{
const auto clamp_ch = AP : : sitl ( ) - > clamp_ch ;
if ( clamp_ch < 1 ) {
return false ;
}
const uint32_t clamp_idx = clamp_ch - 1 ;
if ( clamp_idx > ARRAY_SIZE ( input . servos ) ) {
return false ;
}
const uint16_t servo_pos = input . servos [ clamp_idx ] ;
bool new_clamped = currently_clamped ;
if ( servo_pos < 1200 ) {
if ( currently_clamped ) {
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " SITL: Clamp: released vehicle " ) ;
new_clamped = false ;
}
grab_attempted = false ;
} else {
// re-clamp if < 10cm from home
if ( servo_pos > 1800 & & ! grab_attempted ) {
const Vector3d pos = aircraft . get_position_relhome ( ) ;
const float distance_from_home = pos . length ( ) ;
// GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SITL: Clamp: dist=%f", distance_from_home);
if ( distance_from_home < 0.5 ) {
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " SITL: Clamp: grabbed vehicle " ) ;
new_clamped = true ;
} else if ( ! grab_attempted ) {
GCS_SEND_TEXT ( MAV_SEVERITY_INFO , " SITL: Clamp: missed vehicle " ) ;
}
grab_attempted = true ;
}
}
currently_clamped = new_clamped ;
return currently_clamped ;
}
2018-07-31 09:33:23 -03:00
void Aircraft : : update_external_payload ( const struct sitl_input & input )
{
external_payload_mass = 0 ;
// update sprayer
if ( sprayer & & sprayer - > is_enabled ( ) ) {
sprayer - > update ( input ) ;
external_payload_mass + = sprayer - > payload_mass ( ) ;
}
2017-10-20 21:57:59 -03:00
2022-05-23 06:27:58 -03:00
{
const float range = rangefinder_range ( ) ;
2022-10-02 05:21:54 -03:00
for ( uint8_t i = 0 ; i < ARRAY_SIZE ( rangefinder_m ) ; i + + ) {
2022-05-23 06:27:58 -03:00
rangefinder_m [ i ] = range ;
}
}
2020-08-03 00:24:27 -03:00
// update i2c
if ( i2c ) {
i2c - > update ( * this ) ;
}
2019-10-07 04:30:22 -03:00
// update buzzer
if ( buzzer & & buzzer - > is_enabled ( ) ) {
buzzer - > update ( input ) ;
}
2018-07-31 09:33:23 -03:00
// update grippers
if ( gripper & & gripper - > is_enabled ( ) ) {
gripper - > set_alt ( hagl ( ) ) ;
gripper - > update ( input ) ;
external_payload_mass + = gripper - > payload_mass ( ) ;
}
if ( gripper_epm & & gripper_epm - > is_enabled ( ) ) {
gripper_epm - > update ( input ) ;
external_payload_mass + = gripper_epm - > payload_mass ( ) ;
}
2019-01-08 21:39:44 -04:00
// update parachute
if ( parachute & & parachute - > is_enabled ( ) ) {
parachute - > update ( input ) ;
// TODO: add drag to vehicle, presumably proportional to velocity
}
2018-08-03 07:52:20 -03:00
if ( precland & & precland - > is_enabled ( ) ) {
2024-03-07 03:05:30 -04:00
precland - > update ( get_location ( ) ) ;
2021-02-08 08:13:19 -04:00
if ( precland - > _over_precland_base ) {
2022-08-02 07:08:49 -03:00
local_ground_level + = precland - > _device_height ;
2021-02-08 08:13:19 -04:00
}
2018-08-03 07:52:20 -03:00
}
2019-09-28 08:32:57 -03:00
// update RichenPower generator
if ( richenpower ) {
richenpower - > update ( input ) ;
}
2020-03-17 20:07:11 -03:00
2022-01-06 21:36:48 -04:00
# if AP_SIM_LOWEHEISER_ENABLED
// update Loweheiser generator
if ( loweheiser ) {
loweheiser - > update ( ) ;
}
# endif
2021-06-28 19:24:15 -03:00
if ( fetteconewireesc ) {
fetteconewireesc - > update ( * this ) ;
}
2021-10-11 02:05:28 -03:00
# if AP_SIM_SHIP_ENABLED
2024-04-26 05:47:28 -03:00
sitl - > models . shipsim . update ( ) ;
2021-10-11 02:05:28 -03:00
# endif
2020-09-22 22:03:38 -03:00
// update IntelligentEnergy 2.4kW generator
if ( ie24 ) {
ie24 - > update ( input ) ;
}
2023-01-22 03:35:53 -04:00
# if AP_TEST_DRONECAN_DRIVERS
if ( dronecan ) {
dronecan - > update ( ) ;
}
# endif
2024-07-10 21:26:42 -03:00
2024-07-11 09:25:32 -03:00
# if AP_SIM_GPIO_LED_1_ENABLED
sim_led1 . update ( * this ) ;
# endif
2024-07-10 21:26:42 -03:00
# if AP_SIM_GPIO_LED_2_ENABLED
sim_led2 . update ( * this ) ;
# endif
# if AP_SIM_GPIO_LED_3_ENABLED
sim_led3 . update ( * this ) ;
# endif
# if AP_SIM_GPIO_LED_RGB_ENABLED
sim_ledrgb . update ( * this ) ;
# endif
2018-07-31 09:33:23 -03:00
}
2017-11-27 06:45:23 -04:00
void Aircraft : : add_shove_forces ( Vector3f & rot_accel , Vector3f & body_accel )
{
const uint32_t now = AP_HAL : : millis ( ) ;
2019-04-08 22:11:38 -03:00
if ( sitl = = nullptr ) {
return ;
}
2017-11-27 06:45:23 -04:00
if ( sitl - > shove . t = = 0 ) {
return ;
}
if ( sitl - > shove . start_ms = = 0 ) {
sitl - > shove . start_ms = now ;
}
if ( now - sitl - > shove . start_ms < uint32_t ( sitl - > shove . t ) ) {
// FIXME: can we get a vector operation here instead?
body_accel . x + = sitl - > shove . x ;
body_accel . y + = sitl - > shove . y ;
body_accel . z + = sitl - > shove . z ;
} else {
sitl - > shove . start_ms = 0 ;
2022-07-20 06:41:54 -03:00
sitl - > shove . t . set ( 0 ) ;
2017-11-27 06:45:23 -04:00
}
}
2019-04-10 22:55:04 -03:00
2021-06-20 23:59:02 -03:00
float Aircraft : : get_local_updraft ( const Vector3d & currentPos )
2019-05-26 06:56:10 -03:00
{
int scenario = sitl - > thermal_scenario ;
# define MAX_THERMALS 10
float thermals_w [ MAX_THERMALS ] ;
float thermals_r [ MAX_THERMALS ] ;
float thermals_x [ MAX_THERMALS ] ;
float thermals_y [ MAX_THERMALS ] ;
int n_thermals = 0 ;
switch ( scenario ) {
2022-01-28 00:56:24 -04:00
case 0 :
return 0 ;
2019-05-26 06:56:10 -03:00
case 1 :
n_thermals = 1 ;
thermals_w [ 0 ] = 2.0 ;
thermals_r [ 0 ] = 80.0 ;
thermals_x [ 0 ] = - 180.0 ;
thermals_y [ 0 ] = - 260.0 ;
break ;
case 2 :
n_thermals = 1 ;
thermals_w [ 0 ] = 4.0 ;
thermals_r [ 0 ] = 30.0 ;
thermals_x [ 0 ] = - 180.0 ;
thermals_y [ 0 ] = - 260.0 ;
break ;
case 3 :
n_thermals = 1 ;
thermals_w [ 0 ] = 2.0 ;
thermals_r [ 0 ] = 30.0 ;
thermals_x [ 0 ] = - 180.0 ;
thermals_y [ 0 ] = - 260.0 ;
break ;
2023-06-13 19:37:40 -03:00
case 4 :
n_thermals = 1 ;
thermals_w [ 0 ] = 5.0 ;
thermals_r [ 0 ] = 30.0 ;
thermals_x [ 0 ] = 0 ;
thermals_y [ 0 ] = 0 ;
break ;
2022-01-28 00:56:24 -04:00
default :
AP_BoardConfig : : config_error ( " Bad thermal scenario " ) ;
2019-05-26 06:56:10 -03:00
}
2019-06-07 03:40:44 -03:00
// Wind drift at this altitude
2019-06-22 17:09:50 -03:00
float driftX = sitl - > wind_speed * ( currentPos . z + 100 ) * cosf ( sitl - > wind_direction * DEG_TO_RAD ) ;
float driftY = sitl - > wind_speed * ( currentPos . z + 100 ) * sinf ( sitl - > wind_direction * DEG_TO_RAD ) ;
2019-06-07 03:40:44 -03:00
2019-05-26 06:56:10 -03:00
int iThermal ;
float w = 0.0f ;
float r2 ;
for ( iThermal = 0 ; iThermal < n_thermals ; iThermal + + ) {
2021-06-20 23:59:02 -03:00
Vector3d thermalPos ( thermals_x [ iThermal ] + driftX / thermals_w [ iThermal ] ,
2019-06-07 03:40:44 -03:00
thermals_y [ iThermal ] + driftY / thermals_w [ iThermal ] ,
0 ) ;
2021-06-20 23:59:02 -03:00
Vector3d relVec = currentPos - thermalPos ;
2019-05-26 06:56:10 -03:00
r2 = relVec . x * relVec . x + relVec . y * relVec . y ;
w + = thermals_w [ iThermal ] * exp ( - r2 / ( thermals_r [ iThermal ] * thermals_r [ iThermal ] ) ) ;
}
return w ;
}
2019-04-10 22:55:04 -03:00
void Aircraft : : add_twist_forces ( Vector3f & rot_accel )
{
if ( sitl = = nullptr ) {
return ;
}
if ( sitl - > gnd_behav ! = - 1 ) {
ground_behavior = ( GroundBehaviour ) sitl - > gnd_behav . get ( ) ;
}
const uint32_t now = AP_HAL : : millis ( ) ;
if ( sitl = = nullptr ) {
return ;
}
if ( sitl - > twist . t = = 0 ) {
return ;
}
if ( sitl - > twist . start_ms = = 0 ) {
sitl - > twist . start_ms = now ;
}
if ( now - sitl - > twist . start_ms < uint32_t ( sitl - > twist . t ) ) {
// FIXME: can we get a vector operation here instead?
rot_accel . x + = sitl - > twist . x ;
rot_accel . y + = sitl - > twist . y ;
rot_accel . z + = sitl - > twist . z ;
} else {
sitl - > twist . start_ms = 0 ;
2022-07-20 06:41:54 -03:00
sitl - > twist . t . set ( 0 ) ;
2019-04-10 22:55:04 -03:00
}
}
2021-07-10 03:10:54 -03:00
/*
get position relative to home
*/
Vector3d Aircraft : : get_position_relhome ( ) const
{
Vector3d pos = position ;
pos . xy ( ) + = home . get_distance_NE_double ( origin ) ;
return pos ;
}
2024-04-26 05:47:28 -03:00
// get air density in kg/m^3
float Aircraft : : get_air_density ( float alt_amsl ) const
{
2024-04-28 04:11:56 -03:00
return AP_Baro : : get_air_density_for_alt_amsl ( alt_amsl ) ;
}
2024-04-26 05:47:28 -03:00
2024-04-28 04:11:56 -03:00
/*
update EAS airspeed and pitot speed
*/
void Aircraft : : update_eas_airspeed ( )
{
airspeed = velocity_air_ef . length ( ) / eas2tas ;
/*
airspeed as seen by a fwd pitot tube ( limited to 120 m / s )
*/
airspeed_pitot = airspeed ;
// calculate angle between the local flow vector and a pitot tube aligned with the X body axis
const float pitot_aoa = atan2f ( sqrtf ( sq ( velocity_air_bf . y ) + sq ( velocity_air_bf . z ) ) , velocity_air_bf . x ) ;
/*
assume the pitot can correctly capture airspeed up to 20 degrees off the nose
and follows a cose law outside that range
*/
const float max_pitot_aoa = radians ( 20 ) ;
if ( pitot_aoa > radians ( 90 ) ) {
airspeed_pitot = 0 ;
} else if ( pitot_aoa > max_pitot_aoa ) {
const float gain_factor = M_PI_2 / ( radians ( 90 ) - max_pitot_aoa ) ;
airspeed_pitot * = cosf ( ( pitot_aoa - max_pitot_aoa ) * gain_factor ) ;
}
2024-04-26 05:47:28 -03:00
}