Comments (9)
Hi InsJet,
Thank you for your feedback.
There are two algorithms running in this demo. One is free integration with odometer, and the other is pure INS.
For the first one, you need also to set odometer error to be 0.
Even if all sensor errors are eliminated, there is still error from numerical calculations. I just reran the demo. With all IMU errors being zero, the position error for pure INS is about 10^(-8) meters, which I think is mroe than enough.
from gnss-ins-sim.
Hello sir!Thank you so much for your answer! Here is code I got non-zero error ~3х10^-3 deg in position:
motion_def_path = os.path.abspath('.//demo_motion_def_files//')
fs = 10 # IMU sample frequency
def test_free_integration():
'''
test Sim
'''
#### IMU model, typical for IMU381
imu_err = {'gyro_b': np.array([0.005, 0.005, 0.01])*0.0,
'gyro_arw': np.array([0.02, 0.02, 0.25])*0.0,
'gyro_b_stability': np.array([3.5, 3.5, 3.5]) * 0.0,
'gyro_b_corr': np.array([100.0, 100.0, 100.0]),
'accel_b': np.array([0.5e-3, 0.5e-3, 0.5e-3])*0.0,
'accel_vrw': np.array([0.03119, 0.03009, 0.04779]) * 0.0,
'accel_b_stability': np.array([4.29e-5, 5.72e-5, 8.02e-5]) * 0.0,
'accel_b_corr': np.array([200.0, 200.0, 200.0]),
'mag_std': np.array([0.2, 0.2, 0.2]) * 0.0
}
# do not generate GPS and magnetometer data
imu = imu_model.IMU(accuracy=imu_err, axis=6, gps=False)
from gnss-ins-sim.
I think by "~3х10^-3 deg" you actually mean "~3х10^-3 meters".
My results are different from yours. So there might be some differences. Could you provide more details?
I just tried the demo in this repo, and I got the following position error:
The statistics are:
Sample frequency of IMU: [fs] = 10.0 Hz
Reference frame: 1
Simulation time duration: 10.0 s
Simulation runs: 1
Simulation results are saved to E:\Projects\gnss-ins-sim\demo_saved_data\2020-12-16-14-37-06
The following results are saved:
The following are error statistics.
-----------statistics for simulation attitude (Euler, ZYX) from algo (in units of ['deg', 'deg', 'deg'])
--Max error: [2.035555e-13 0.000000e+00 0.000000e+00]
--Avg error: [-2.035555e-13 0.000000e+00 0.000000e+00]
--Std of error: [0. 0. 0.]
-----------statistics for simulation position from algo (in units of ['m', 'm', 'm'])
--Max error: [4.65661287e-10 1.86264515e-09 0.00000000e+00]
--Avg error: [4.65661287e-10 1.86264515e-09 0.00000000e+00]
--Std of error: [0. 0. 0.]
-----------statistics for simulation velocity from algo (in units of ['m/s', 'm/s', 'm/s'])
--Max error: [2.66453526e-14 2.66453526e-14 0.00000000e+00]
--Avg error: [ 2.66453526e-14 -2.66453526e-14 0.00000000e+00]
--Std of error: [0. 0. 0.]
from gnss-ins-sim.
Here is my result (I modified trajectory file to get a long period):
Sample frequency of IMU: [fs] = 10 Hz
Reference frame: 0
Simulation time duration: 3476.5 s
Simulation runs: 1
Simulation results are saved to C:\Users\IIB\Documents\gnss-ins-sim-master\demo_saved_data\2020-12-16-08-53-49
The following results are saved:
time: sample time
ref_pos: true LLA pos in the navigation frame
ref_vel: true vel in the NED frame
ref_att_euler: true attitude (Euler angles, ZYX)
ref_accel: true accel in the body frame
ref_gyro: true angular velocity in the body frame
accel: accel measurements
gyro: gyro measurements
vel: simulation velocity from algo
att_euler: simulation attitude (Euler, ZYX) from algo
pos: simulation position from algo
ref_att_quat: true attitude (quaternion)
att_quat: simulation attitude (quaternion) from algo
The following are error statistics.
-----------statistics for simulation attitude (Euler, ZYX) from algo (in units of ['deg', 'deg', 'deg'])
--Max error: [0.00225529 0.00590184 0.00140033]
--Avg error: [-0.00225529 0.00590184 -0.00140033]
--Std of error: [0. 0. 0.]
-----------statistics for simulation position from algo (in units of ['deg', 'deg', 'm'])
--Max error: [5.88081038e-03 2.69572975e-03 7.52883758e+01]
--Avg error: [-5.88081038e-03 -2.69572975e-03 -7.52883758e+01]
--Std of error: [0. 0. 0.]
-----------statistics for simulation velocity from algo (in units of ['m/s', 'm/s', 'm/s'])
--Max error: [0.78990747 0.64338399 0.12690452]
--Avg error: [-0.78990747 0.64338399 0.12690452]
--Std of error: [0. 0. 0.]
I
from gnss-ins-sim.
Here is the trajectory I used:
ini lat (deg),ini lon (deg),ini alt (m),ini vx_body (m/s),ini vy_body (m/s),ini vz_body (m/s),ini yaw (deg),ini pitch (deg),ini roll (deg)
55.508183,34.401989,0,0,0,0,183,0,0
command type,yaw (deg),pitch (deg),roll (deg),vx_body (m/s),vy_body (m/s),vz_body (m/s),command duration (s),GPS visibility
1,0,0,0,0,0,0,200,1
5,0,0,0,9.5,0,0,20,1
5,-70,0,0,5,0,0,25,1
5,0,0,0,10,0,0,25,1
1,0,0,0,0,0,0,16.8,1
5,-68,0,0,5,0,0,25,1
5,0,0,0,10,0,0,25,1
1,0,0,0,0,0,0,17,1
5,-90,0,0,5,0,0,25,1
5,0,0,0,10,0,0,25,1
1,0,0,0,0,0,0,9,1
3,12,0,0,0,0,0,5,1
1,0,0,0,0,0,0,7,1
5,0,0,0,0,0,0,5,1
5,-112,0,0,10,0,0,10,1
1,0,0,0,0,0,0,8,1
1,10,0,0,0,0,0,1,1
1,2.8,0,0,0,0,0,10,1
1,2,0,0,0,0,0,3,1
1,0,0,0,0,0,0,1,1
5,80,0,0,5,0,0,10,1
5,0,0,0,10,0,0,10,1
1,-4,0,0,0,0,0,5,1
1,0,0,0,0,0,0,6.5,1
5,89,0,0,5,0,0,10,1
5,0,0,0,10,0,0,10,1
1,0,0,0,0,0,0,9,1
5,-94.5,0,0,10,0,0,10,1
1,0,0,0,0,0,0,1053.5,1
5,-88,0,0,10,0,0,10,1
1,0,0,0,0,0,0,20,1
3,-5,0,0,0,0,0,5,1
3,5.6,0,0,0,0,0,5,1
5,0,0,0,20,0,0,40,1
1,0,0,0,0,0,0,13,1
3,3,0,0,0,0,0,5,1
5,0,0,0,0,0,0,40,1
5,0,0,0,5,0,0,20,1
5,-90,0,0,5,0,0,20,1
5,0,0,0,8,0,0,20,1
5,7,0,0,8,0,0,8,1
5,7,0,0,10,0,0,8,1
5,-15,0,0,20,0,0,40,1
1,0,0,0,0,0,0,6,1
5,-0.5,0,0,15,0,0,40,1
1,0,0,0,0,0,0,1600,1
5,-90,0,0,10,0,0,40,1
5,0,0,0,20,0,0,40,1
1,0,0,0,0,0,0,18,1
5,0,0,0,5,0,0,40,1
5,88,0,0,5,0,0,40,1
5,2,0,0,5,0,0,40,1
1,0,0,0,0,0,0,9,1
5,-16,0,0,5,0,0,40,1
1,-1.2,0,0,0,0,0,20,1
1,-0.8,0,0,0,0,0,13,1
5,96,0,0,5,0,0,40,1
5,0,0,0,0,0,0,40,1
from gnss-ins-sim.
Hi,
I think I know what is going on. The simulation time is 3476.5 s, which is too long for free integration. Since the gyro is integrated to get attitude, attitude is used to remove Earth gravity to get accel, and accel is double integrated, the numerical error accumulates. So an error of 10^(-3) meters is as expected.
from gnss-ins-sim.
Dear dxg-aceinna
Thank you for your answer! I thoght I could simulate Schuler's process
from gnss-ins-sim.
Hi InsJet,
I think you can simulate the Schuler's process. The following is what I did. There are a few to notice. First, set all sensor errors to zero. Second, add an initial velocity error. Third, choose a motion definition file which defines a motionless profile. Fourth, set the reference frame to 0 to include the Earth motion. Finally, set the sample frequency to 10Hz. The code is as follow.
- demo_free_integration.py
# -*- coding: utf-8 -*-
# Filename: demo_free_integration.py
"""
A simple free integration (strapdown inertial navigation) demo of Sim.
Created on 2018-01-23
@author: dongxiaoguang
"""
import os
import math
import numpy as np
from gnss_ins_sim.sim import imu_model
from gnss_ins_sim.sim import ins_sim
# globals
D2R = math.pi/180
motion_def_path = os.path.abspath('.//demo_motion_def_files//')
fs = 10.0 # IMU sample frequency
def test_free_integration():
'''
test Sim
'''
#### IMU model, typical for IMU381
imu_err = {'gyro_b': np.array([0.0, 0.0, 0.0]),
'gyro_arw': np.array([0.25, 0.25, 0.25]) * 0.0,
'gyro_b_stability': np.array([3.5, 3.5, 3.5]) * 0.0,
'gyro_b_corr': np.array([100.0, 100.0, 100.0]),
'accel_b': np.array([0.0e-3, 0.0e-3, 0.0e-3]),
'accel_vrw': np.array([0.03119, 0.03009, 0.04779]) * 0.0,
'accel_b_stability': np.array([4.29e-5, 5.72e-5, 8.02e-5]) * 0.0,
'accel_b_corr': np.array([200.0, 200.0, 200.0]),
'mag_std': np.array([0.2, 0.2, 0.2]) * 0.0
}
odo_err = {'scale': 0.999,
'stdv': 0.1}
# do not generate GPS and magnetometer data
imu = imu_model.IMU(accuracy=imu_err, axis=6, gps=False, odo=True, odo_opt=odo_err)
#### Algorithm
# Free integration in a virtual inertial frame
from demo_algorithms import free_integration_odo
from demo_algorithms import free_integration
'''
Free integration requires initial states (position, velocity and attitude). You should provide
theses values when you create the algorithm object.
'''
ini_pos_vel_att = np.genfromtxt(motion_def_path+"//motion_def-Allan.csv",\
delimiter=',', skip_header=1, max_rows=1)
ini_pos_vel_att[0] = ini_pos_vel_att[0] * D2R
ini_pos_vel_att[1] = ini_pos_vel_att[1] * D2R
ini_pos_vel_att[6:9] = ini_pos_vel_att[6:9] * D2R
# add initial states error if needed
ini_vel_err = np.array([1e-3, 0.0, 0.0]) # initial velocity error in the body frame, m/s
ini_att_err = np.array([0.0, 0.0, 0.0]) # initial Euler angles error, deg
ini_pos_vel_att[3:6] += ini_vel_err
ini_pos_vel_att[6:9] += ini_att_err * D2R
# create the algorith object
algo1 = free_integration_odo.FreeIntegration(ini_pos_vel_att)
algo2 = free_integration.FreeIntegration(ini_pos_vel_att)
#### start simulation
sim = ins_sim.Sim([fs, 0.0, 0.0],
motion_def_path+"//motion_def-Allan.csv",
ref_frame=0,
imu=imu,
mode=None,
env=None,
algorithm=[algo2])
# run the simulation for 1000 times
sim.run(1)
# generate simulation results, summary
# do not save data since the simulation runs for 1000 times and generates too many results
sim.results(err_stats_start=-1, gen_kml=True)
# plot postion error
sim.plot(['vel', 'att_euler'], opt={'vel':'error', 'att_euler':'error'})
if __name__ == '__main__':
test_free_integration()
- The motion def file motion_def-Allan.csv.
ini lat (deg),ini lon (deg),ini alt (m),ini vx_body (m/s),ini vy_body (m/s),ini vz_body (m/s),ini yaw (deg),ini pitch (deg),ini roll (deg)
32,120,0,0,0,0,0,0,0
command type,yaw (deg),pitch (deg),roll (deg),vx_body (m/s),vy_body (m/s),vz_body (m/s),command duration (s),GPS visibility
1,0,0,0,0,0,0,18000,0
In the following plots of errors of velocity and Euler angles, we can see an oscilating error of a period around 90min. However, the error diverges eventually. I haven't had time to give that a further analysis. If you are interested, you can do that.
from gnss-ins-sim.
Hello dxg-aceinna! Thank you so much foк this detailed answer!
from gnss-ins-sim.
Related Issues (20)
- how to simulate a magnetometer HOT 3
- a question for imu model parameter? HOT 2
- GPS lat and lon remain at their initial values whatever the motion profile and algorithms HOT 2
- Computation of w_nb_n in function calc_true_sensor_output HOT 3
- Command Type 1 reference frame HOT 1
- Why does ‘g’ need to be multiplied by -1 in the NED coordinate system? HOT 3
- Different GPS generated using int and float longitude and latitude HOT 1
- A question about GPS measurement HOT 2
- How to create high freq trajectory from low freq trajectory. HOT 12
- Pathgen.py calculation of the gyro output HOT 5
- Comments and odd order for function euler_update_zyx HOT 1
- Free integration calculation issue HOT 3
- 真实加速度测量值生成问题 HOT 1
- Lic
- Accelerometer coordinate frame HOT 1
- I can't run file demo_no_algo.py HOT 1
- Issue with mid-accuracy HOT 1
- 能否使用ENU坐标系输出? HOT 4
- Simulate attitude change of IMU sensor HOT 3
- Is there a plan for demo_ins_loose to be completed? HOT 3
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from gnss-ins-sim.