diff --git a/src/modules/simulator/simulator.h b/src/modules/simulator/simulator.h index 5c8c8b5830..f4ac51a75c 100644 --- a/src/modules/simulator/simulator.h +++ b/src/modules/simulator/simulator.h @@ -285,7 +285,6 @@ private: DEFINE_PARAMETERS( (ParamFloat) _param_sim_bat_drain, ///< battery drain interval (ParamFloat) _param_bat_min_pct, //< minimum battery percentage - (ParamFloat) _param_sim_gps_noise_x, (ParamBool) _param_sim_gps_block, (ParamBool) _param_sim_accel_block, (ParamBool) _param_sim_gyro_block, diff --git a/src/modules/simulator/simulator_mavlink.cpp b/src/modules/simulator/simulator_mavlink.cpp index 6cb59f37b1..ca86d467e2 100644 --- a/src/modules/simulator/simulator_mavlink.cpp +++ b/src/modules/simulator/simulator_mavlink.cpp @@ -309,13 +309,6 @@ void Simulator::handle_message_hil_gps(const mavlink_message_t *msg) gps.satellites_used = hil_gps.satellites_visible; gps.s_variance_m_s = 0.25f; - // use normal distribution for noise - if (_param_sim_gps_noise_x.get() > 0.0f) { - std::normal_distribution normal_distribution(0.0f, 1.0f); - gps.lat += (int32_t)(_param_sim_gps_noise_x.get() * normal_distribution(_gen)); - gps.lon += (int32_t)(_param_sim_gps_noise_x.get() * normal_distribution(_gen)); - } - _vehicle_gps_position_pub.publish(gps); } } diff --git a/src/modules/simulator/simulator_params.c b/src/modules/simulator/simulator_params.c index 4b9033237a..7b66e20a0f 100644 --- a/src/modules/simulator/simulator_params.c +++ b/src/modules/simulator/simulator_params.c @@ -65,18 +65,6 @@ PARAM_DEFINE_FLOAT(SIM_BAT_DRAIN, 60); */ PARAM_DEFINE_FLOAT(SIM_BAT_MIN_PCT, 50.0f); -/** - * Simulator GPS noise multiplier. - * - * @min 0 - * @max 10 - * @increment 0.1 - * @unit % - * - * @group SITL - */ -PARAM_DEFINE_FLOAT(SIM_GPS_NOISE_X, 0.0f); - /** * Simulator block GPS data. *