-
Notifications
You must be signed in to change notification settings - Fork 827
Open
Description
I have some doubts regarding how GPS noise is being computed.
PX4-SITL_gazebo-classic/src/gazebo_gps_plugin.cpp
Lines 262 to 272 in f754540
if (gps_noise_) { | |
noise_gps_pos_.X() = gps_xy_noise_density_ * sqrt(dt) * randn_(rand_); | |
noise_gps_pos_.Y() = gps_xy_noise_density_ * sqrt(dt) * randn_(rand_); | |
noise_gps_pos_.Z() = gps_z_noise_density_ * sqrt(dt) * randn_(rand_); | |
noise_gps_vel_.X() = gps_vxy_noise_density_ * sqrt(dt) * randn_(rand_); | |
noise_gps_vel_.Y() = gps_vxy_noise_density_ * sqrt(dt) * randn_(rand_); | |
noise_gps_vel_.Z() = gps_vz_noise_density_ * sqrt(dt) * randn_(rand_); | |
random_walk_gps_.X() = gps_xy_random_walk_ * sqrt(dt) * randn_(rand_); | |
random_walk_gps_.Y() = gps_xy_random_walk_ * sqrt(dt) * randn_(rand_); | |
random_walk_gps_.Z() = gps_z_random_walk_ * sqrt(dt) * randn_(rand_); | |
} |
Noise density for XY has, as unit, (m) / sqrt(hz)
and the noise has as unit (m)
.
static constexpr double kDefaultGpsXYNoiseDensity = 2.0e-4; // (m) / sqrt(hz) |
So, by the current formula, noise_gps_pos_.X() = (m) / sqrt(hz) * (1/sqrt(Hz)) = (m) / (Hz)
.
So, it would make me sense that the formula divides noise density by sqrt(df) [sqrt(s)], so that the result is in (m)
instead of multiplying:
noise_gps_pos_.X() = ((m) / sqrt(hz)) / (1/sqrt(Hz)) = (m)
The formula I referred is also used in other places of the code, like here
double sigma_g_d = 1 / sqrt(dt) * imu_parameters_.gyroscope_noise_density; |
If you could clarify, I would appreciate.
Metadata
Metadata
Assignees
Labels
No labels