Skip to content

Commit

Permalink
updated config, currected the modeling of bernoulli distribution nois…
Browse files Browse the repository at this point in the history
…es to Markov process.

rename rho to phi

update description.
  • Loading branch information
xtk8532704 committed Feb 21, 2025
1 parent 962eabd commit b8ae6ca
Show file tree
Hide file tree
Showing 3 changed files with 61 additions and 43 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ class DetectionSensor : public DetectionSensorBase
{
double simulation_time, distance_noise, yaw_noise;

bool mask, flip;
bool tp, flip;

explicit NoiseOutput(double simulation_time = 0.0) : simulation_time(simulation_time) {}
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -358,19 +358,39 @@ auto DetectionSensor<autoware_perception_msgs::msg::DetectedObjects>::update(
};

/*
We use AR(1) model to model noises' autocorrelation coefficients for
all kinds of noises. We define the `tau` used for AR(1) from
`delta_t`, which means the time interval when the autocorrelation
coefficient becomes `correlation_for_delta_t`.
We use AR(1) model to model the autocorrelation coefficients `phi` for
noises(distance_noise, yaw_noise) with Gaussian distribution, by the
following formula:
noise(prev_noise) = mean + phi * (prev_noise - mean) + N(0, 1 - phi^2) * standard_deviation
We use Markov process to model the autocorrelation coefficients `rho`
for noises(flip, tp) with Bernoulli distribution, by the transition matrix:
| p_00 p_01 | == | p0 + rho * p1 p1(1 - rho) |
| p_10 p_11 | == | p0(1 - rho) p1 - rho * p0 |
In the code, we use `phi` for the above autocorrelation coefficients `phi` or `rho`,
Which is calculated from the time_interval `dt` by the following formula:
phi(dt) = amplitude * exp(-decay * dt) + offset
*/
static const auto correlation_for_delta_t = parameter("correlation_for_delta_t");

auto ar1_noise = [this](auto previous_noise, auto mean, auto standard_deviation, auto phi) {
return mean + phi * (previous_noise - mean) +
std::normal_distribution<double>(
0, standard_deviation * std::sqrt(1 - phi * phi))(random_engine_);
};

auto mp_noise = [this](bool is_previous_noise_1, auto p1, auto phi) {
auto rate = (is_previous_noise_1 ? 1.0 : 0.0) * phi + (1 - phi) * p1;
return std::uniform_real_distribution<double>()(random_engine_) < rate;
};

auto get_phi = [&](const auto & interval, const std::string & name) {
static const auto amplitude = parameter(name + ".phi_amplitude");
static const auto decay = parameter(name + ".phi_decay");
static const auto offset = parameter(name + ".phi_offset");
return std::clamp(amplitude * std::exp(-interval * decay) + offset, 0.0, 1.0);
};

auto selector = [&](auto ellipse_normalized_x_radius, const auto & targets) {
static const auto ellipse_y_radii = parameters("ellipse_y_radii");
return [&, ellipse_normalized_x_radius, targets]() {
Expand All @@ -393,50 +413,41 @@ auto DetectionSensor<autoware_perception_msgs::msg::DetectedObjects>::update(
};

noise_output->second.distance_noise = [&]() {
static const auto tau =
-parameter("distance.delta_t") / std::log(correlation_for_delta_t);
static const auto mean = selector(
parameter("distance.ellipse_normalized_x_radius.mean"), parameters("distance.means"));
static const auto standard_deviation = selector(
parameter("distance.ellipse_normalized_x_radius.standard_deviation"),
parameters("distance.standard_deviations"));
const auto phi = std::exp(-interval / tau);
const auto phi = get_phi(interval, "distance");
return ar1_noise(noise_output->second.distance_noise, mean(), standard_deviation(), phi);
}();

noise_output->second.yaw_noise = [&]() {
static const auto tau = -parameter("yaw.delta_t") / std::log(correlation_for_delta_t);
static const auto mean =
selector(parameter("yaw.ellipse_normalized_x_radius.mean"), parameters("yaw.means"));
static const auto standard_deviation = selector(
parameter("yaw.ellipse_normalized_x_radius.standard_deviation"),
parameters("yaw.standard_deviations"));
const auto phi = std::exp(-interval / tau);
const auto phi = get_phi(interval, "yaw");
return ar1_noise(noise_output->second.yaw_noise, mean(), standard_deviation(), phi);
}();

noise_output->second.flip = [&]() {
static const auto tau =
-parameter("yaw_flip.delta_t") / std::log(correlation_for_delta_t);
static const auto velocity_threshold = parameter("yaw_flip.velocity_threshold");
static const auto stop_rate = parameter("yaw_flip.stop_rate");
const auto phi = std::exp(-interval / tau);
const auto rate = (noise_output->second.flip ? 1.0 : 0.0) * phi + (1 - phi) * stop_rate;
static const auto flip_rate = parameter("yaw_flip.flip_rate");
const auto phi = get_phi(interval, "yaw_flip");
return velocity < velocity_threshold and
std::uniform_real_distribution<double>()(random_engine_) < rate;
mp_noise(noise_output->second.flip, flip_rate, phi);
}();

noise_output->second.mask = [&]() {
static const auto tau = -parameter("mask.delta_t") / std::log(correlation_for_delta_t);
static const auto unmask_rate = selector(
parameter("mask.ellipse_normalized_x_radius"), parameters("mask.unmask_rates"));
const auto phi = std::exp(-interval / tau);
const auto rate =
(noise_output->second.mask ? 1.0 : 0.0) * phi + (1 - phi) * (1 - unmask_rate());
return std::uniform_real_distribution()(random_engine_) < rate;
noise_output->second.tp = [&]() {
static const auto tp_rate = selector(
parameter("tp.ellipse_normalized_x_radius"), parameters("tp.tp_rates"));
const auto phi = get_phi(interval, "tp");
return mp_noise(noise_output->second.tp, tp_rate(), phi);
}();

if (noise_output->second.mask) {
if (noise_output->second.tp) {
const auto angle = std::atan2(y, x);

const auto yaw_rotated_orientation =
Expand Down
41 changes: 24 additions & 17 deletions test_runner/scenario_test_runner/config/parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -134,27 +134,34 @@ simulation:
model:
version: 2 # Any of [1, 2].
v2:
correlation_for_delta_t: 0.5
ellipse_y_radii: [10.0, 20.0, 40.0, 60.0, 80.0, 120.0, 150.0, 180.0, 1000.0]
distance:
delta_t: 0.5
phi_amplitude: 0.32
phi_decay: 0.45
phi_offset: 0.26
ellipse_normalized_x_radius:
mean: 1.8
standard_deviation: 1.8
means: [0.25, 0.27, 0.44, 0.67, 1.00, 3.00, 4.09, 3.40, 0.00]
standard_deviations: [0.35, 0.54, 0.83, 1.14, 1.60, 3.56, 4.31, 3.61, 0.00]
mean: 1.1
standard_deviation: 1.0
means: [-0.06, -0.04, -0.04, -0.07, -0.26, -0.56, -1.02, -1.05, 0.0]
standard_deviations: [0.17, 0.20, 0.27, 0.40, 0.67, 0.94, 1.19, 1.17, 0.0]
yaw:
delta_t: 0.3
phi_amplitude: 0.22
phi_decay: 0.52
phi_offset: 0.21
ellipse_normalized_x_radius:
mean: 0.6
standard_deviation: 1.6
means: [0.01, 0.01, 0.00, 0.03, 0.04, 0.00, 0.01, 0.00, 0.00]
standard_deviations: [0.05, 0.1, 0.15, 0.15, 0.2, 0.2, 0.3, 0.4, 0.5]
mean: 1.9
standard_deviation: 0.8
means: [0.0, 0.01, 0.0, 0.0, 0.0, -0.07, 0.18, 0.06, 0.0]
standard_deviations: [0.09, 0.15, 0.21, 0.18, 0.17, 0.19, 0.39, 0.15, 0.0]
yaw_flip:
delta_t: 0.1
phi_amplitude: 0.29
phi_decay: 0.12
phi_offset: 0.49
velocity_threshold: 0.1
stop_rate: 0.3
mask:
delta_t: 0.3
ellipse_normalized_x_radius: 0.6
unmask_rates: [0.92, 0.77, 0.74, 0.66, 0.57, 0.28, 0.09, 0.03, 0.00]
flip_rate: 0.12
tp:
phi_amplitude: 0.32
phi_decay: 0.26
phi_offset: 0.40
ellipse_normalized_x_radius: 0.7
tp_rates: [0.96, 0.78, 0.57, 0.48, 0.27, 0.07, 0.01, 0.0, 0.0]

0 comments on commit b8ae6ca

Please sign in to comment.