Skip to content

Commit

Permalink
Rename the parameter (x|y|z) to local_(x|y|z)
Browse files Browse the repository at this point in the history
Signed-off-by: yamacir-kit <[email protected]>
  • Loading branch information
yamacir-kit committed Jan 23, 2025
1 parent 24426bb commit 8b0948d
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 12 deletions.
6 changes: 3 additions & 3 deletions external/concealer/include/concealer/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,9 +82,9 @@ struct NormalDistribution<nav_msgs::msg::Odometry>
};

// clang-format off
Error position_x_error,
position_y_error,
position_z_error,
Error position_local_x_error,
position_local_y_error,
position_local_z_error,
orientation_r_error,
orientation_p_error,
orientation_y_error,
Expand Down
12 changes: 6 additions & 6 deletions external/concealer/src/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,9 @@ NormalDistribution<nav_msgs::msg::Odometry>::NormalDistribution(
}
}()),
engine(seed ? seed : device()),
position_x_error(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.x.error"),
position_y_error(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.y.error"),
position_z_error(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.z.error"),
position_local_x_error(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.local_x.error"),
position_local_y_error(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.local_y.error"),
position_local_z_error(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.local_z.error"),
orientation_r_error(node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.r.error"),
orientation_p_error(node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.p.error"),
orientation_y_error(node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.y.error"),
Expand All @@ -57,9 +57,9 @@ auto NormalDistribution<nav_msgs::msg::Odometry>::operator()(nav_msgs::msg::Odom

Eigen::Vector3d local_position = Eigen::Vector3d(0.0, 0.0, 0.0);

local_position.x() = position_x_error.apply(engine, local_position.x());
local_position.y() = position_y_error.apply(engine, local_position.y());
local_position.z() = position_z_error.apply(engine, local_position.z());
local_position.x() = position_local_x_error.apply(engine, local_position.x());
local_position.y() = position_local_y_error.apply(engine, local_position.y());
local_position.z() = position_local_z_error.apply(engine, local_position.z());

const Eigen::Vector3d world_position = orientation.toRotationMatrix() * local_position;

Expand Down
16 changes: 13 additions & 3 deletions test_runner/scenario_test_runner/config/parameters.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,23 +8,33 @@ simulation:
pose:
pose:
position:
x:
# The data members of geometry_msgs::msg::Pose.position are x,
# y, z, which are world coordinates in
# `/localization/kinematic_state`. However, applying error to a
# position in world coordinates is unintuitive and tricky, so
# we accept the parameters as the entity's local coordinates.
# local_x, local_y, local_z express that. The simulator
# calculates the error in the local coordinates. It then
# transforms the error to the world coordinates, adds the error
# to the true position (world coordinates), and publishes it as
# `/localization/kinematic_state`.
local_x:
error:
additive:
mean: 0.0
standard_deviation: 0.0
multiplicative:
mean: 0.0
standard_deviation: 0.0
y:
local_y:
error:
additive:
mean: 0.0
standard_deviation: 0.0
multiplicative:
mean: 0.0
standard_deviation: 0.0
z:
local_z:
error:
additive:
mean: 0.0
Expand Down

0 comments on commit 8b0948d

Please sign in to comment.