Giter VIP home page Giter VIP logo

gnss-ins-sim's Introduction

GNSS-INS-SIM

GNSS-INS-SIM is an GNSS/INS simulation project, which generates reference trajectories, IMU sensor output, GPS output, odometer output and magnetometer output. Users choose/set up the sensor model, define the waypoints and provide algorithms, and gnss-ins-sim can generate required data for the algorithms, run the algorithms, plot simulation results, save simulations results, and generate a brief summary.

Contents


Requirements

  • Numpy ( version>1.10 )
  • Matplotlib

Demos

We provide the following demos to show how to use this tool:

file name description
demo_no_algo.py A demo of generating data, saving generated data to files and plotting (2D/3D)interested data, no user specified algorithm.
demo_allan.py A demo of Allan analysis of gyroscope and accelerometer data. The generated Allan deviation is shown in figures.
demo_free_integration.py A demo of a simple strapdown system. The simulation runs for 1000 times. The statistics of the INS results of the 1000 simulations are generated.
demo_inclinometer_mahony.py A demo of an dynamic inclinometer algorithm based on Mahony's theory. This demo shows how to generate error plot of interested data.
demo_aceinna_vg.py A demo of DMU380 dynamic tilt algorithm. The algorithm is first compiled as a shared library. This demo shows how to call the shared library. This is the algorithm inside Aceinna's VG/MTLT products.
demo_aceinna_ins.py A demo of DMU380 GNSS/INS fusion algorithm. The algorithm is first compiled as a shared library. This demo shows how to call the shared library. This is the algorithm inside Aceinna's INS products.
demo_multiple_algorithms.py A demo of multiple algorithms in a simulation. This demo shows how to compare resutls of multiple algorithm.
demo_gen_data_from_files.py This demo shows how to do simulation from logged data files.

Get started

Step 1 Define the IMU model

Step 1.1 Define the IMU error model

IMU error model can be specified in two ways:

Choose a built-in model

There are three built-in IMU models: 'low-accuracy', 'mid-accuracy' and 'high accuracy'.

Manually define the model

imu_err = {
            # gyro bias, deg/hr
            'gyro_b': np.array([0.0, 0.0, 0.0]),
            # gyro angle random walk, deg/rt-hr
            'gyro_arw': np.array([0.25, 0.25, 0.25]),
            # gyro bias instability, deg/hr
            'gyro_b_stability': np.array([3.5, 3.5, 3.5]),
            # gyro bias instability correlation, sec.
            # set this to 'inf' to use a random walk model
            # set this to a positive real number to use a first-order Gauss-Markkov model
            'gyro_b_corr': np.array([100.0, 100.0, 100.0]),
            # accelerometer bias, m/s^2
            'accel_b': np.array([0.0e-3, 0.0e-3, 0.0e-3]),
            # accelerometer velocity random walk, m/s/rt-hr
            'accel_vrw': np.array([0.03119, 0.03009, 0.04779]),
            # accelerometer bias instability, m/s^2
            'accel_b_stability': np.array([4.29e-5, 5.72e-5, 8.02e-5]),
            # accelerometer bias instability correlation, sec. Similar to gyro_b_corr
            'accel_b_corr': np.array([200.0, 200.0, 200.0]),
            # magnetometer noise std, uT
            'mag_std': np.array([0.2, 0.2, 0.2])
          }

Step 1.2 Create an IMU object

imu = imu_model.IMU(accuracy=imu_err, axis=6, gps=False)
imu = imu_model.IMU(accuracy='low-accuracy', axis=9, gps=True)

axis = 6 to generate only gyro and accelerometer data.

axis = 9 to generate magnetometer data besides gyro and accelerometer data.

gps = True to generate GPS data, gps = False not.

Step 2 Create a motion profile

A motion profile specifies the initial states of the vehicle and motion command that drives the vehicle to move, as shown in the following table.

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 200 1
... ... ... ... ... ... ... ... ...

The initial position should be given in the LLA (latitude, longitude and altitude) form. The initial velocity is specified in the vehicle body frame. The initial attitude is represented by Euler angles of ZYX rotation sequence.

Motion commands define how the vehicle moves from its initial state. The simulation will generate true angular velocity, acceleration, magnetic field, position, velocity and attitude according to the commands. Combined with sensor error models, these true values are used to generate gyroscope, accelerometer, magnetometer and GPS output. There is only one motion command in the above table. Indeed, you can add more motion commands to specify the attitude and velocity of the vehicle. You can also define GPS visibility of the vehicle for each command.

Five command types are supported, as listed below.

Command type Comment
1 Directly define the Euler angles change rate and body frame velocity change rate. The change rates are given by column 2~7. The units are deg/s and m/s/s. Column 8 gives how long the command will last. If you want to fully control execution time of each command by your own, you should always choose the motion type to be 1
2 Define the absolute attitude and absolute velocity to reach. The target attitude and velocity are given by column 2~7. The units are deg and m/s. Column 8 defines the maximum time to execute the command. If actual executing time is less than max time, the remaining time will not be used and the next command will be executed immediately. If the command cannot be finished within max time, the next command will be executed after max time.
3 Define attitude change and velocity change. The attitude and velocity changes are given by column 2~7. The units are deg and m/s. Column 8 defines the maximum time to execute the command.
4 Define absolute attitude and velocity change. The absolute attitude and velocity change are given by column 2~7. The units are deg and m/s. Column 8 defines the maximum time to execute the command.
5 Define attitude change and absolute velocity. The attitude change and absolute velocity are given by column 2~7. The units are deg and m/s. Column 8 defines the maximum time to execute the command.

An example of motion profile

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 200 1
5 0 45 0 10 0 0 250 1
1 0 0 0 0 0 0 10 1
3 90 -45 0 0 0 0 25 1
1 0 0 0 0 0 0 50 1
3 180 0 0 0 0 0 25 1
1 0 0 0 0 0 0 50 1
3 -180 0 0 0 0 0 25 1
1 0 0 0 0 0 0 50 1
3 180 0 0 0 0 0 25 1
1 0 0 0 0 0 0 50 1
3 -180 0 0 0 0 0 25 1
1 0 0 0 0 0 0 50 1
3 180 0 0 0 0 0 25 1
1 0 0 0 0 0 0 50 1
3 -180 0 0 0 0 0 25 1
1 0 0 0 0 0 0 50 1
5 0 0 0 0 0 0 10 1

The initial latitude, longitude and altitude of the vehicle are 32deg, 120deg and 0 meter, respectively. The initial velocity of the vehicle is 0. The initial Euler angles are 0deg pitch, 0deg roll and 0deg yaw, which means the vehicle is level and its x axis points to the north.

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

This command is of type 1. Command type1 directly gives Euler angle change rate and velocity change rate. In this case, they are zeros. That means keep the current state (being static) of the vehicle for 200sec. During this period, GPS is visible.

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
5 0 45 0 10 0 0 250 1

This command is of type 5. Command type 5 defines attitude change and absolute velocity. In this case, the pitch angle will be increased by 45deg, and the velocity along the x axis of the body frame will be accelerated to 10m/s. This command should be executed within 250sec.

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
3 90 -45 0 0 0 0 25 1

This command is of type 3. Command type 3 defines attitude change and velocity change. In this case, the yaw angle will be increased by 90deg, which is a right turn. The pitch angle is decreased by 45deg. The velocity of the vehicle does not change. This command should be executed within 25sec.

The following figure shows the trajectory generated from the motion commands in the above table. The trajectory sections corresponding to the above three commands are marked by command types 1, 5 and 3.

Step 3 Create your algorithm

algo = allan_analysis.Allan() # an Allan analysis demo algorithm

An algorithm is an object of a Python class. It should at least include the following members:

self.input and self.output

The member variable 'input' tells gnss-ins-sim what data the algorithm need. 'input' is a tuple or list of strings.

The member variable 'output' tells gnss-ins-sim what data the algorithm returns. 'output' is a tuple or list of strings.

Each string in 'input' and 'output' corresponds to a set of data supported by gnss-ins-sim. The following is a list of supported data by gnss-ins-sim.

name description
'ref_frame' Reference frame used as the navigation frame and the attitude reference.
0: NED (default), with x axis pointing along geographic north, y axis pointing eastward, z axis pointing downward. Position will be expressed in LLA form, and the velocity of the vehicle relative to the ECEF frame will be expressed in local NED frame.
1: a virtual inertial frame with constant g, x axis pointing along geographic or magnetic north, z axis pointing along g, y axis completing a right-handed coordinate system. Position and velocity will both be in the [x y z] form in this frame.
**Notice: For this virtual inertial frame, position is indeed the sum of the initial position in ecef and the relative position in the virutal inertial frame. Indeed, two vectors expressed in different frames should not be added. This is done in this way here just to preserve all useful information to generate .kml files. Keep this in mind if you use this result.
'fs' Sample frequency of IMU, units: Hz
'fs_gps' Sample frequency of GNSS, units: Hz
'fs_mag' Sample frequency of magnetometer, units: Hz
'time' Time series corresponds to IMU samples, units: sec.
'gps_time' Time series corresponds to GNSS samples, units: sec.
'algo_time' Time series corresponding to algorithm output, units: ['s']. If your algorithm output data rate is different from the input data rate, you should include 'algo_time' in the algorithm output.
'gps_visibility' Indicate if GPS is available. 1 means yes, and 0 means no.
'ref_pos' True position in the navigation frame. When users choose NED (ref_frame=0) as the navigation frame, positions will be given in the form of [Latitude, Longitude, Altitude], units: ['rad', 'rad', 'm']. When users choose the virtual inertial frame, positions (initial position + positions relative to the origin of the frame) will be given in the form of [x, y, z], units: ['m', 'm', 'm'].
'ref_vel' True velocity w.r.t the navigation/reference frame expressed in the NED frame, units: ['m/s', 'm/s', 'm/s'].
'ref_att_euler' True attitude (Euler angles, ZYX rotation sequency), units: ['rad', 'rad', 'rad']
'ref_att_quat' True attitude (quaternions)
'ref_gyro' True angular velocity in the body frame, units: ['rad/s', 'rad/s', 'rad/s']
'ref_accel' True acceleration in the body frame, units: ['m/s^2', 'm/s^2', 'm/s^2']
'ref_mag' True geomagnetic field in the body frame, units: ['uT', 'uT', 'uT'] (only available when axis=9 in IMU object)
'ref_gps' True GPS position/velocity, ['rad', 'rad', 'm', 'm/s', 'm/s', 'm/s'] for NED (LLA), ['m', 'm', 'm', 'm/s', 'm/s', 'm/s'] for virtual inertial frame (xyz) (only available when gps=True in IMU object)
'gyro' Gyroscope measurements, 'ref_gyro' with errors
'accel' Accelerometer measurements, 'ref_accel' with errors
'mag' Magnetometer measurements, 'ref_mag' with errors
'gps' GPS measurements, 'ref_gps' with errors
'ad_gyro' Allan std of gyro, units: ['rad/s', 'rad/s', 'rad/s']
'ad_accel' Allan std of accel, units: ['m/s2', 'm/s2', 'm/s2']
'pos' Simulation position from algo, units: ['rad', 'rad', 'm'] for NED (LLA), ['m', 'm', 'm'] for virtual inertial frame (xyz).
'vel' Simulation velocity from algo, units: ['m/s', 'm/s', 'm/s']
'att_euler' Simulation attitude (Euler, ZYX) from algo, units: ['rad', 'rad', 'rad']
'att_quat' Simulation attitude (quaternion) from algo
'wb' Gyroscope bias estimation, units: ['rad/s', 'rad/s', 'rad/s']
'ab' Accelerometer bias estimation, units: ['m/s^2', 'm/s^2', 'm/s^2']
'gyro_cal' Calibrated gyro output, units: ['rad/s', 'rad/s', 'rad/s']
'accel_cal' Calibrated acceleromter output, units: ['m/s^2', 'm/s^2', 'm/s^2']
'mag_cal' Calibrated magnetometer output, units: ['uT', 'uT', 'uT']
'soft_iron' 3x3 soft iron calibration matrix
'hard_iron' Hard iron calibration, units: ['uT', 'uT', 'uT']

self.run(self, set_of_input)

This is the main procedure of the algorithm. gnss-ins-sim will call this procedure to run the algorithm. 'set_of_input' is a list of data that is consistent with self.input. For example, if you set self.input = ['fs', 'accel', 'gyro'], you should get the corresponding data this way:

  def run(self, set_of_input):
      # get input
      fs = set_of_input[0]
      accel = set_of_input[1]
      gyro = set_of_input[2]

self.get_results(self)

gnss-ins-sim will call this procedure to get resutls from the algorithm. The return should be consistent with self.output. For example, if you set self.output = ['allan_t', 'allan_std_accel', 'allan_std_gyro'], you should return the results this way:

  def get_results(self):
      self.results = [tau,
                      np.array([avar_ax, avar_ay, avar_az]).T,
                      np.array([avar_wx, avar_wy, avar_wz]).T]
      return self.results

self.reset(self)

gnss-ins-sim will call this procedure after run the algorithm. This is necessary when you want to run the algorithm more than one time and some states of the algorithm should be reinitialized.

Step 4 Run the simulation

step 4.1 Create the simulation object

  sim = ins_sim.Sim(
        # sample rate of imu (gyro and accel), GPS and magnetometer
        [fs, fs_gps, fs_mag],
        # initial conditions and motion definition,
        # see IMU in ins_sim.py for details
        data_path+"//motion_def-90deg_turn.csv",
        # reference frame
        ref_frame=1,
        # the imu object created at step 1
        imu,
        # vehicle maneuver capability
        # [max accel, max angular accel, max angular rate]
        mode=np.array([1.0, 0.5, 2.0]),
        # specifies the vibration model for IMU
        env=None,
        #env=np.genfromtxt(data_path+'//vib_psd.csv', delimiter=',', skip_header=1),
        # the algorithm object created at step 2
        algorithm=algo)

gnss-ins-sim supports running multiple algorithms in one simulation. You can refer to demo_multiple_algorihtms.py for example.

There are three kinds of vibration models: random, sinusoidal and PSD.

Acceleration vibration model description
'[nx ny nz]g-random' normal-distribution random vibration, rms is n*9.8 m/s^2
'[nx ny nz]-random' normal-distribution random vibration, rms is n m/s^2
'[nx ny nz]g-mHz-sinusoidal' sinusoidal vibration of m Hz, amplitude is n*9.8 m/s^2
'[nx ny nz]-mHz-sinusoidal' sinusoidal vibration of m Hz, amplitude is n m/s^2
numpy array of size (n,4) single-sided PSD. The four columns are [freqency, x, y, z], in units of (m/s^2)^2/Hz

|

For the vibratoin model of the gyro, it is similar as that of the acceleration except that the unit is default to rad/s and 'd' is used to change the unit to be deg/s.

The following example sets random vibration to accel with RMS for x/y/z axis being 1, 2 and 3 m/s^2, respectively, and sets sinusoidal vibration to gyro with frequency being 0.5Hz and amplitude for x/y/z axis being 6, 5 and 4 deg/s, respectively.

    env = {'acc': '[1 2 3]-random',
           'gyro': '[6 5 4]d-0.5Hz-sinusoidal'}

Step 4.2 Run the simulation

sim.run()     # run for 1 time
sim.run(1)    # run for 1 time
sim.run(100)  # run for 100 times

Step 5 Show results

# generate a simulation summary,
# and save the summary and all data in directory './data'.
# You can specify the directory.
sim.results('./data/')

# generate a simulation summary, do not save any file
sim.results()

# plot interested data
sim.plot(['ref_pos', 'gyro'], opt={'ref_pos': '3d'})

Acknowledgement

gnss-ins-sim's People

Contributors

dinglezhang avatar dxg-aceinna avatar dxglaw avatar hovavalon avatar oscarlundstrom avatar stolpa4 avatar theophilec avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

gnss-ins-sim's Issues

a question for imu model parameter?

hello,dear@Aceinna
i have same question about the imu model?
1.which parameter is the Gaussian white noise ?
2.The imu model parameter which means in discrete sample case or in continuous sample case? thanks alot!

Command Type 1 reference frame

Hello,

Thank you for sharing this toolbox. I was wondering: what are reference frames (world vs body) for command type 1 inputs? It seems to me that the rotation rate inputs are in world frame while the acceleration is in a body-fixed frame; is that correct.

For reference, I am attempting to generate IMU data for a known trajectory, given as NED positions and orientations. I have differentiated to get velocity, acceleration, and rotation rates, and use the attitude to transform the accelerations into body-frame. After disabling the filter on the inputs, this seems to give me the correct reference accelerations (ref_accel), rotation rates (ref_gyro), and attitudes (ref_att_euler) but the outputs for position (ref_pos) and velocity (ref_vel) do not match the source data.

I'm trying to track down what I am doing incorrect, and would appreciate any advice.

I can't run file demo_no_algo.py

when i run file demo_no_algo.py. i have bug "NotImplementedError: It is not currently possible to manually set the aspect on 3D axes"

Different GPS generated using int and float longitude and latitude

Different GPS generated using int and float longitude and latitude.

attitude.D2R: 0.017453292519943295
ini_pos_n: [ 32. 120. 0.]
calculated ini_pos_n: [0.55850536 2.0943951 0. ]

attitude.D2R: 0.017453292519943295
ini_pos_n: [ 32 120 0]
calculated ini_pos_n: [0 2 0]

how to simulate a magnetometer

I am trying to simulate an imu augmented magnetometer based on a motion trajectory. if I can know the magnetic strength and robot pose, I can calculate the mag_x, mag_y,mag_z. But how can I know the magnetic strength? I guess I can get it based on location on earth?
Or could you recommend some papers or tutorials on how to simulate a magnetometer?

UnboundLocalError: local variable 'mobility' referenced before assignment

def __parse_mode(self, mode):
'''
Parse mode. Not completely implemented yet.
Args:
mode: simualtion mode
'''
if mode is not None:
if isinstance(mode, str): # choose built-in mode
mode = mode.lower()
if 'flight' in mode:
mobility = high_mobility
elif 'land' in mode:
mobility = high_mobility
elif 'ship' in mode:
mobility = high_mobility
else:
mobility = high_mobility
elif isinstance(mode, np.ndarray): # customize the sim mode
if mode.shape == (3,):
mobility[0] = mode[0]
mobility[1] = mode[1] * attitude.D2R
mobility[2] = mode[2] * attitude.D2R
else:
raise TypeError('mode should be of size (3,)')
else:
raise TypeError('mode should be a string or a numpy array of size (3,)')
else:
mobility = high_mobility
return mobility

varible mobility not defined

GPS lat and lon remain at their initial values whatever the motion profile and algorithms

I am running simulations and I cannot make GPS positions to show any variations from their initial values, except for the altitude which varies if I make the vz velocity vary.

I have tried a lot of different motion profiles:

  • Various initial states (zero and non-zero velocities; zero and non-zero Euler angles);
  • Various motion commands (zero and non-zero changes in Euler angles or velocities; different command types);
  • I made sure I have gps=True in the IMU model and that GPS visibility is 1;
  • I tried with no algorithms and with different built-in algorithms;
  • I tried with the two reference frames.

In all my experiments, GPS latitude and longitude (gps_lat, gps_lon) stayed at there initial value. I am refering to both the 'ref_gps' results and the 'gps-0' results (with or without GPS uncertainty).
I was expecting the latitude and longitude to vary when for example vx or vy vary, which is not the case.

In addition, in the results with uncertainties, only the altitude has noise, while latitude and longitude are always flat curves.

To reproduce this issue, I am attaching the results I obtain with the motion file motion_def-simple.csv (also attached) and with the main code demo_no_algo.py.

accel-0.csv
att_euler.csv
att_euler
att_quat.csv
gps-0.csv
gps_0
gps_time.csv
gps_visibility.csv
gps_visibility
gyro-0.csv
ref_accel.csv
ref_att_euler.csv
ref_att_euler
ref_att_quat.csv
ref_gps.csv
ref_gps
ref_gyro.csv
ref_pos.csv
ref_pos
ref_vel.csv
summary.txt
time.csv
motion_def-simple.csv

No Rate Random Walk modeled in `pathgen.py`, right?

RE: https://github.com/Aceinna/gnss-ins-sim/blob/master/gnss_ins_sim/pathgen/pathgen.py

It looks like to me you this simulation only considers constant bias (or turn-on bias; static bias in your code at line 520), bias instability (bias drifting in your code at line 522), and angle random walk (white noise in your code at line 524).

I have a question that why rate random walk is not considered in the simulation. Does it have a neglectable effect on the gyro error?
According to these references, it seems rate random walk also has a considerable effect on the simulation of the gyro error:

  1. Jay A. Farrell, Felipe O. Silva, Farzana Rahman, and Jan Wendel, “IMU Error State Modeling for State Estimation and Sensor Calibration: A Tutorial”, May 2019. [Link].
  2. Elder M. Hemerly, “MEMS IMU stochastic error modelling”, Systems Science & Control Engineering, vol. 5, Jan. 2017, pp. 1–8.
  3. Vaibhav Saini, S C Rana, and MM Kuber, “Online Estimation of State Space Error Model for MEMS IMU”, Journal of Modelling and Simulation of Systems, vol. 1, 2010, pp. 219--225.

Also, do you have a good reference to simulate the bias instability as a white noise sequence, rather then a random walk sequence, when there is no correlation input (line 558 in the code)? I think it is improper as suggested by the above references 2 and 3.

Simulate attitude change of IMU sensor

Hello, is it possible to simulate the attitude change of the IMU sensor without changing the attitude and velocity of the vehicle?

For example, I want to simulate that the IMU data would come from a smartphone inside the vehicle and that the attitude of the smartphone could change during the ride.

Thanks!
Oskari

GPS error model dictionary modified in gps_gen

I believe there is an issue in GPS noise generation when multiple runs are used, because of the way the gps_error dictionary is used.

Bug reproduction

Using the demo_no_algo.py:

  1. comment out the plotting line
  2. change sim.run(1) to sim.run(10) (for example)
  3. change ref_frame from 1 to 0

Open gps-0.csv, gps-4.csv and ref_pos.csv. As you can see, the gps-4.csv data is identical to the ref_pos.csv data in the first two columns (lattitude and longitude). However, in the gps-0.csv file, this is not the case, and the noise level is consistent with the GPS error model dictionary (here, the built-in one).

Bug description

In the gps_gen function below, the gps_err dictionary is a class attribute, passed as reference, that is modified at each simulation loop. And so, dividing by the Earth's radii, becomes exponentially small as runs are simulated.

def gps_gen(ref_gps, gps_err, gps_type=0):
    '''
    Add error to true GPS data according to GPS receiver error parameters
    Args:
        ref_gps: If gps_type is 0, [Lat, Lon, Alt, vx, vy, vz], [rad, rad, m].
                 If gps_type is 1, [x, y, z, vx, vy, vz], [m, m, m].
                 ref_gps data are expressed in the navigation frame.
        gps_err: GPS reeceiver parameters.
            'stdp': RMS position error, [m, m, m].
            'stdv': RMS velocity error, [m/s, m/s, m/s].
        gps_type: GPS data type.
            0: default, position is in the form of [Lat, Lon, Alt], rad, m
            1: position is in the form of [x, y, z], m
    Returns:
        gps_mea: ref_gps with error.
    '''
    # total data count
    n = ref_gps.shape[0]
    # If position is in the form of LLA, convert gps_err['stdp'] to LLA error
    if gps_type == 0:   # GPS is in the form of LLA, stdp meter to rad
        earth_param = geoparams.geo_param(ref_gps[0, 1:4])
        gps_err['stdp'][0] = gps_err['stdp'][0] / earth_param[0]
        gps_err['stdp'][1] = gps_err['stdp'][1] / earth_param[1] / earth_param[4]
    ## simulate GPS error
    pos_noise = gps_err['stdp'] * np.random.randn(n, 3)
    vel_noise = gps_err['stdv'] * np.random.randn(n, 3)
    gps_mea = np.hstack([ref_gps[:, 0:3] + pos_noise,
                         ref_gps[:, 3:6] + vel_noise])
    return gps_mea

Fixing the bug

I would like to propose to submit a PR calculating the latitude and longitude standard deviations in local variables. Would you be open to that?

Environment

Cloned master branch in new Python venv with only numpy and matplotlib added.

Running demo_no_algo.py out of the box returns NotImplementedError

Downloaded repo
Opened powershell
ran py -m venv env
ran & env/Scripts/Activate.ps1
ran pip.exe install numpy
ran pip.exe install matplotlib
ran python.exe .\demo_no_algo.py

Got the following error
NotImplementedError: Axes3D currently only supports the aspect argument 'auto'. You passed in 'equal'.

Quick look in code did not show where we set it as equal or where to set it as auto

Strange value in "lat/long to meters"

Hi,

Function: In the function geoparams.py "lla2ecef(lla)"
Data: motion_def-3d.csv, I modify the init lat/long to 1° and 1°.
Function return value: (x,y) = (6.38E+06 , 1.11E+05). Actually you can check in the result txt file: ref_gps.csv.
Thanks very much.

Best Regards
Jun Wang

Free integration calculation issue

I stumble upon an issue in free integration as my program calculated the same problem.

I have the following motion file

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)
0,0,0,100,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,18,0,0,0,0,0,10,0
1,0,0,0,0,0,0,10,0

Basically running North at 100 m/s at init, making a 180 deg turn to go South. After the turn I have a residual 0.314 m/s velocity in the East direction. If I then continue for 10s, my position is off by about 4 m. See the max error in the following output:

The following are error statistics.
-----------statistics for simulation attitude (Euler, ZYX)  from algo (in units of ['deg', 'deg', 'deg'])
        Simulation run algo0_0:
                --Max error: [6.63957329e-09 9.04183229e-06 4.23312952e-05]
                --Avg error: [-1.22998502e-09 -4.51875153e-06  1.69835339e-05]
                --Std of error: [1.92722543e-09 4.93997734e-06 1.31422442e-05]

-----------statistics for simulation position from algo (in units of ['m', 'm', 'm'])
        Simulation run algo0_0:
                --Max error: [1.00223908 4.70682951 0.00532531]
                --Avg error: [ 7.50355098e-01  1.80151065e+00 -1.42031785e-03]
                --Std of error: [0.35447558 1.52014583 0.0015642 ]

-----------statistics for simulation velocity from algo (in units of ['m/s', 'm/s', 'm/s'])
        Simulation run algo0_0:
                --Max error: [0.15715554 0.31415198 0.00068664]
                --Avg error: [ 0.050112    0.23549853 -0.0002667 ]
                --Std of error: [0.06053796 0.11113709 0.00021853]

The position error will obviously grow over time. I run the code as follows for the above result:

                vel_dot_n = c_bn.T.dot(accel[i-1, :]) + g_n -\
                            attitude.cross3(2*w_ie_n + w_en_n, self.vel[i-1, :])
                # Current velosity is previous plus my experienced changed in velocity
                self.vel[i, :] = self.vel[i-1, :] + vel_dot_n * self.dt

                #### propagate position
                lat_dot = self.vel[i-1, 0] / rm_effective
                lon_dot = self.vel[i-1, 1] / rn_effective / cl
                alt_dot = -self.vel[i-1, 2]
                self.pos[i, 0] = self.pos[i-1, 0] + lat_dot * self.dt
                self.pos[i, 1] = self.pos[i-1, 1] + lon_dot * self.dt
                self.pos[i, 2] = self.pos[i-1, 2] + alt_dot * self.dt
                #### output
                c_bn = attitude.euler2dcm(self.att[i, :])

In the free integration file, there was some code commented out that updates the c_bn first, calculates vel_dot_b and then vel_b, then converts the vel_b to vel, and updates the position. If I do the calculation this way around it works out correctly. See the output below:

The following are error statistics.
-----------statistics for simulation attitude (Euler, ZYX)  from algo (in units of ['deg', 'deg', 'deg'])
        Simulation run algo0_0:
                --Max error: [0.00000000e+00 1.32311075e-12 1.01268861e-11]
                --Avg error: [ 0.00000000e+00 -5.00873751e-13 -3.77686476e-12]
                --Std of error: [0.00000000e+00 3.71630599e-13 3.40864583e-12]

-----------statistics for simulation position from algo (in units of ['m', 'm', 'm'])
        Simulation run algo0_0:
                --Max error: [8.41556947e-08 1.12544081e-06 4.64393640e-04]
                --Avg error: [ 2.21354525e-08 -4.37359926e-07 -3.47980894e-04]
                --Std of error: [2.92403334e-08 3.63927099e-07 1.64325317e-04]

-----------statistics for simulation velocity from algo (in units of ['m/s', 'm/s', 'm/s'])
        Simulation run algo0_0:
                --Max error: [1.77236092e-09 7.36129863e-08 7.29224333e-05]
                --Avg error: [-3.67040030e-10 -5.51504148e-08 -2.32196570e-05]
                --Std of error: [6.70454848e-10 2.61383274e-08 2.81123335e-05]

I change the code to the following for this result:

                c_bn = attitude.euler2dcm(self.att[i, :])
                vel_dot_b = accel[i-1, :] + c_bn.T.dot(g_n) -\
                            attitude.cross3(c_bn.dot(w_ie_n)+gyro[i-1,:], self.vel_b[i-1,:])
                self.vel_b[i,:] = self.vel_b[i-1,:] + vel_dot_b*self.dt
                self.vel[i,:] = c_bn.T.dot(self.vel_b[i, :])
                
                # vel_dot_n = c_bn.T.dot(accel[i-1, :]) + g_n -\
                #             attitude.cross3(2*w_ie_n + w_en_n, self.vel[i-1, :])

                # # Current velosity is previous plus my experienced changed in velocity
                # self.vel[i, :] = self.vel[i-1, :] + vel_dot_n * self.dt

                #### propagate position
                lat_dot = self.vel[i-1, 0] / rm_effective
                lon_dot = self.vel[i-1, 1] / rn_effective / cl
                alt_dot = -self.vel[i-1, 2]
                self.pos[i, 0] = self.pos[i-1, 0] + lat_dot * self.dt
                self.pos[i, 1] = self.pos[i-1, 1] + lon_dot * self.dt
                self.pos[i, 2] = self.pos[i-1, 2] + alt_dot * self.dt
                #### output
                # c_bn = attitude.euler2dcm(self.att[i, :])

I made the IMU and GPS noise 0 to remove inconsitancy in the calculation and I am running the sim in
ref_frame=0,
in the demo_free_integraion file.

Is this problem an issue in the simulator generating the data or in the way free integration calculates?

Mahony Algorithm

Hi @dxg-aceinna! Firstly,this library is super useful!! Thank you very much for putting something so comprehensive together!

I have been looking into your Mahony algorithm and was wondering if there was a source you based it on as it is different from the standard implementations in literature. It almost seems like you merged in elements of the Valenti complementary filter. I would be very interested if you had some relevant articles I could read.

Thanks!

真实加速度测量值生成问题

在pathgen.py文件中的函数 def calc_true_sensor_output(pos_n, vel_b, att, c_nb, vel_dot_b, att_dot, ref_frame, g) 中
406~411行代码如下:
# Gyroscope output
gyro = c_nb.T.dot(w_nb_n + w_en_n + w_ie_n)
# Acceleration output
w_ie_b = c_nb.T.dot(w_ie_n)
acc = vel_dot_b + attitude.cross3(w_ie_b+gyro, vel_b) - c_nb.T.dot(gravity)
return acc, gyro, vel_dot_n, pos_dot_n

在计算真实加速度时,这一项

attitude.cross3(w_ie_b+gyro, vel_b)

中的gyro项里面包含了w_nb_n,是否合理?

Constants in geoparams

Hi!

In the context of IMU simulation in a static setting, we've run into issues using the constants in geoparams because of the "hard-coded" values FLATTENING and E_SQR.

I'd change to FLATTENING = 1/298.257223563 and E_SQR = ECCENTRICITY**2?
The first is the WGS-84 definition of flattening. The second removes a 1e-12 error that integrates to small drifts.

Thanks for open-sourcing this simulator: it's great!

Hard dependency on matplotlib even if you don't need to plot graphs

From looking at the code matplotlib is minimally used and only to show graph plots. However matplotlib drags in a lot of dependencies causing issues.

Be good if matplotlib was not referenced directly inside core gnss-ins-sim modules. Maybe a separate graphing module.

position error without any drift

At first, thank you very much!

Could you explain , how the position error results depend on the fs ?
I am trying to set zero error for gyro and acc and get non-zero error when fs=10 (demo_free_integration).
Or am I missing something important?

能否使用ENU坐标系输出?

请问一下可以输出ENU坐标系的数据吗?如果可以的话需要怎么设置呢?

感觉要对加速度计、陀螺仪和磁力计的数据进行坐标变换,交换x和y的数据,并对z轴数据取反。我对导航的理解还很浅,如果不对还望您谅解。

十分感谢!

How to create high freq trajectory from low freq trajectory.

Looking for an example to create high freq trajectory from low freq trajectory.

The most similar example to start from seemed to me to be demo_free_integration.

Running the demo_free_integration.py example produces empty plots.
I modified demo_free_integration.py this way:

>> git diff demo_free_integration.py
diff --git a/demo_free_integration.py b/demo_free_integration.py
index fc2e804..b7274eb 100644
--- a/demo_free_integration.py
+++ b/demo_free_integration.py
@@ -58,8 +58,7 @@ def test_free_integration():
     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)
+    algo = free_integration.FreeIntegration(ini_pos_vel_att)
 
     #### start simulation
     sim = ins_sim.Sim([fs, 0.0, 0.0],
@@ -68,14 +67,14 @@ def test_free_integration():
                       imu=imu,
                       mode=None,
                       env=None,
-                      algorithm=[algo1, algo2])
+                      algorithm=[algo])
     # run the simulation for 1000 times
-    sim.run(10)
+    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(['pos'], opt={'pos':'error'})
+    sim.plot(['ref_pos', 'pos'], opt={'ref_pos': '3d', 'pos':'3d'})
 
 if __name__ == '__main__':
     test_free_integration()

This gives empty plots:

image

Reading the doc, I tried to simplify the case:

>> git diff demo_motion_def_files/motion_def-90deg_turn.csv
diff --git a/demo_motion_def_files/motion_def-90deg_turn.csv b/demo_motion_def_files/motion_def-90deg_turn.csv
index 87caf81..12a3b3a 100644
--- a/demo_motion_def_files/motion_def-90deg_turn.csv
+++ b/demo_motion_def_files/motion_def-90deg_turn.csv
@@ -1,6 +1,4 @@
 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)
 31.9965,120.004,0,10,0,0,315,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,1,0
-1,15,0,0,0,0,0,6,0
-1,0,0,0,0,0,0,3,0
+1,0,0,0,0,0,0,10,1

And still get empty plots.

What did I miss?

My initial need is to create high freq trajectory from low freq trajectory: what is the most similar example? Any advice on how to achieve this would be helpful.

Note: my low freq trajectory is a collection of n-uplets {timestamp, lat, lon, alt, roll, pitch, yaw, ax, ay, az, wx, wy, wz}

Acceleration error

When I get the trayectory and I obtain the accelerometer data and reference quaternion, I've checked the acceleration measurements from the transformation the acceleration measurement. When the quaternion is [1,0,0,0], in this case, the acceleration measurements is [7.328724153415264002e-03,-7.097695153575984614e-04,-9.801918481487374990e+00].
After the transformation, with the quaternion [0.793 +0.609i +0.000j +0.000k] , the acceleration should be [ 7.32872415e-03 9.46751078e+00 -2.53847319e+00], but the acceleration obtained from simulation is [-0.004411866173716657, -9.473102208586964, -2.5396297352216073].
Thanks a lot!
Carlos

Pathgen.py calculation of the gyro output

I've been stuck on this problem for a few weeks now. I'm developing an error state Kalman filter and using the output of this sim as test data.
It never estimates the errors 100% correctly, so I started running my prediction code only, figuring that, if using the ref data, I should get the same answer. I've reduced all variables to only now update my attitude using the gyro reading.
I set ref_frame = 1, so not taking into account earth's rotation etc (which I do calculate exactly the same as the sim). In calc_true_sensor_output I add the following code to test the output of the gyro, just after the line that calcs the gyro reading.

gyro = c_nb.T.dot(w_nb_n + w_en_n + w_ie_n)
q1 = attitude.euler2quat(att)
print(q1)
q2 = attitude.quat_update(q1, gyro, 0.5)
print(q2)
print("_______________________")
global count
count += 1
if count == 3:
    quit()

with a count in the global frame. Basically what I'm trying to do is get the current quaternion, update it with the gyro rate, and print the new quaternion. (Yes I did hardcode dt at 0.5s, and this is also the dt used as input, the error is bigger at larger dt's). My motion file is basically, start at 0, 0, 0 with vel 0,0,0 and attitude 0,0,0. Have the following command

1,0,0.3,0.3,0,0,0,1200,1
so flipping 360 deg in pitch and roll at the same time.

I get the following printout:

[1. 0. 0. 0.]
[9.99999983e-01 1.30899693e-04 1.30899693e-04 0.00000000e+00]


[ 9.99999983e-01 1.30899692e-04 1.30899692e-04 -1.71347298e-08]
[ 9.99999856e-01 3.79609089e-04 3.79609089e-04 -8.22467001e-08]


[ 9.99999856e-01 3.79609076e-04 3.79609076e-04 -1.44103071e-07]
[ 9.99999461e-01 7.34347081e-04 7.34347081e-04 -4.13426700e-07]


So the first is the quat where we start and the second is the quat where we end after applying the gyro rate.
The third is the quat calculated from the att, and that should in theory be the same as the second correct? But it is not, even by a few fractions. In my ESKF I get the same value as the second, so my calculations are done the same as the built-in attitude.quat_update.

I'm I doing something wrong? Is my assumption about how to apply the rate command wrong? Is this just a limitation of double precision?

Computation of w_nb_n in function calc_true_sensor_output

Hello.

I noticed a slight disparity between the computation of vector w_nb_n (angular rotation vector from b to n expressed in n frame) in function calc_true_sensor_output of file pathgen.py comparing to the formulae that I found in various theory sources.

It seems that you are interpreting the result as w_nb_n, but these authors say that this vector is actually w_nb_b (that is, expressed in b frame coordinates).

imagem

Sources:
http://citeseerx.ist.psu.edu/viewdoc/download?doi=10.1.1.668.1629&rep=rep1&type=pdf Eq.9 ,
https://www.atlantis-press.com/article/25897503.pdf Eq. 18,
Springer Handbook of Global Navigation Satellite Systems, Chapter 28, Eqs (28.21)-(28.23)

Am I missing something, or is this correct?

Thank you for your time

A question about GPS measurement

During the simulation, I found a problem. After stdp and stdv are specified as 2.5 and 0.1, respectively, the simulated GPS height may tend to a certain direction of the true value. For example, the average GPS position height of the track is about -1.5m according to the statistics of the simulated GPS data. Even though I didn't do any settings on the height. Is this normal?

Accelerometer coordinate frame

Hi, I have an issue with getting the simulated accelerometer and gyroscope measurements to match with a real life case. I'm trying to replicate IMU data that was recorded during a metro ride that includes 2 approx. 75 deg turns. First left then right. I flipped the IMU with initial pitch of 180 deg to get positive z-acceleration and assigned an initial velocity v_y = 20m/s. Then I simulated these 2 turns with constant yaw rate during 40 sec. (I ignored the acceleration periods in y-direction)

The results match pretty well with the real life case except that the acceleration in x-direction is negative during the left turn and positive during the right turn. I would assume that these should be opposite if the accelerometer coordinate frame follows the right hand convention?

tapiola-acc
tapiola-gyro
tapiola-sim-acc
tapiola-sim-gyro

Error encountered demo_ins_loose

Dear all,

Thank you very much for sharing & contributing the open source implementation.

in function ins_algo_manager()

def run_algo
at line 95 in code:
results[self.output_alloc[i][j]][this_algo_name+'_'+str(key)] = this_results[j]

this_results is list with value [NoneType]

IndexError: list index out of range as j goes from 0 to 4

how this error could be corrected??
Thanks for your help in advance.

Issue with mid-accuracy

If you run " demo_free_integration_long_time.py" with mid-accuracy, you get odd results.

#imu_err = 'low-accuracy'
#imu_err = 'high-accuracy'
imu_err = 'mid-accuracy'

generate GPS and magnetometer data

imu = imu_model.IMU(accuracy=imu_err, axis=6, gps=False)

Generating a circular trajectory

(I don't know if you take this sort of usage question in the issues, I can move it elsewhere if you prefer!)

I would like to generate a circular trajectory (for benchmarking) using the simulator. Ideally, I'd like to have: constant speed in the body frame (say v_x = 1 m/s) and so constant y acceleration.

I can't quite get the motion definition file right. The best I have is using type 3 commands in the motion definition file. While the speed seems constant and position is periodic (lat and long return to the starting point), acceleration in the y direction is not constant and thus the movement is not circular. See attached motion def file.
circle.txt

Generated KML files does not output altitudes <0

I'm not sure if this was done on purpose, but if an altitude is <0 (either reference or algo), the KML altitude is set at 0. The output pos CSV files however state the negative altitudes.

Edit: Actually, it seems that the altitude data is always 0 in display of Google Earth Pro, but when altitude is <0, it shows up as 0 in the KML file.

Ultra-tightly integrated navigation

Hi!
Thank you for your code.
I am doubt whether your code can use to create data for simulation of Ultra-tightly integrated ins/gnss navigation?

bias_drift uses wrong std value?

First, thanks for the amazing tool!

But, I suspect there is a bug here:

Should it be

b = drift[i] * np.sqrt(1. - np.exp(-2/(fs * corr_time[i])))

or am I missing something?

With this scaling, then the drift[i] describes the standard deviation of the output process. Whereas, the original implementation just describes the standard deviation of the discretized white noise. Which means that the noise process will not be consistent if the sampling frequency is changed.

Comments and odd order for function euler_update_zyx

Looking at the function euler_update_zyx, the attitude is fed in and returned as [psi theta phi] (i.e. zyx - yaw, pitch, roll) and not [phi theta psi] as all the comments state. The gyro reading is fed in as [phi theta psi] (i.e. xyz).

The function works and is used 4 times in the project correctly, so no need to fix it, the comments just seem off and it is odd that x and w are in different orders, just something to take note of when using the function.

self.amgr.run_algo error

Hi,
Thanks for the open source algorithm, almost all functioned for me.
I would like bring to your kind attention the following error in demo_ins_loose.py

Traceback (most recent call last): File "C:/gnss_ins_sim/demo_ins_loose.py", line 63, in <module> test_ins_loose() File "C:/gnss_ins_sim/demo_ins_loose.py", line 55, in test_ins_loose sim.run(100) File "C:\gnss_ins_sim\gnss_ins_sim\sim\ins_sim.py", line 177, in run algo_output = self.amgr.run_algo(algo_input, range(self.sim_count)) File "C:\gnss_ins_sim\gnss_ins_sim\sim\ins_algo_manager.py", line 101, in run_algo results[self.output_alloc[i][j]][this_algo_name+'_'+str(key)] = this_results[j] IndexError: list index out of range

After checking, I found that index j is out of range.

Thank you very much for your help in advance!!

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo 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.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.