You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
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
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
Noise density for XY has, as unit,
(m) / sqrt(hz)
and the noise has as unit(m)
.PX4-SITL_gazebo-classic/include/gazebo_gps_plugin.h
Line 57 in f754540
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
PX4-SITL_gazebo-classic/src/gazebo_imu_plugin.cpp
Line 198 in f754540
If you could clarify, I would appreciate.
The text was updated successfully, but these errors were encountered: