From 3e26cd7dcd17538b74a75c2000dd1409d1b7e933 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 8 Jan 2025 16:32:24 +0900 Subject: [PATCH 01/18] Add new struct template `concealer::NormalDistribution` Signed-off-by: yamacir-kit --- .../concealer/include/concealer/publisher.hpp | 26 ++++++++++++++++--- 1 file changed, 22 insertions(+), 4 deletions(-) diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index aeb323084e4..dfc5b743d7e 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -20,22 +20,40 @@ namespace concealer { -template +template +struct NormalDistribution +{ + template + explicit NormalDistribution(Ts &&...) + { + } + + template + auto operator()(T && x) const -> decltype(auto) + { + return std::forward(x); + } +}; + +template typename Randomizer = NormalDistribution> class Publisher { typename rclcpp::Publisher::SharedPtr publisher; + Randomizer randomize; + public: template explicit Publisher(const std::string & topic, Node & node) - : publisher(node.template create_publisher(topic, rclcpp::QoS(1).reliable())) + : publisher(node.template create_publisher(topic, rclcpp::QoS(1).reliable())), + randomize(topic) { } template - auto operator()(Ts &&... xs) const -> decltype(auto) + auto operator()(Ts &&... xs) -> decltype(auto) { - return publisher->publish(std::forward(xs)...); + return publisher->publish(randomize(std::forward(xs)...)); } }; } // namespace concealer From a0e554897df158e45ffb19126ba3643ca898ddb9 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 8 Jan 2025 17:35:59 +0900 Subject: [PATCH 02/18] Add template specialization `NormalDistribution` Signed-off-by: yamacir-kit --- external/concealer/CMakeLists.txt | 1 + .../concealer/include/concealer/publisher.hpp | 29 +++++- external/concealer/src/publisher.cpp | 98 +++++++++++++++++++ 3 files changed, 127 insertions(+), 1 deletion(-) create mode 100644 external/concealer/src/publisher.cpp diff --git a/external/concealer/CMakeLists.txt b/external/concealer/CMakeLists.txt index 0c05bfd2e30..c267d3dd5cf 100644 --- a/external/concealer/CMakeLists.txt +++ b/external/concealer/CMakeLists.txt @@ -18,6 +18,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/execute.cpp src/field_operator_application.cpp src/is_package_exists.cpp + src/publisher.cpp src/task_queue.cpp) target_link_libraries(${PROJECT_NAME} diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index dfc5b743d7e..91d108792b2 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -15,7 +15,8 @@ #ifndef CONCEALER__PUBLISHER_HPP_ #define CONCEALER__PUBLISHER_HPP_ -#include +#include +#include #include namespace concealer @@ -35,6 +36,32 @@ struct NormalDistribution } }; +template <> +struct NormalDistribution +{ + std::random_device::result_type seed; + + std::random_device device; + + std::default_random_engine engine; + + std::uniform_real_distribution position_x, position_y, position_z, orientation_r, + orientation_p, orientation_y, linear_x, linear_y, linear_z, angular_x, angular_y, angular_z; + + template + auto getParameter(const std::string & name, T value = {}) + { + auto node = rclcpp::Node("normal_distribution", "simulation"); + node.declare_parameter(name, value); + node.get_parameter(name, value); + return value; + } + + explicit NormalDistribution(const std::string &); + + auto operator()(nav_msgs::msg::Odometry odometry) -> nav_msgs::msg::Odometry; +}; + template typename Randomizer = NormalDistribution> class Publisher { diff --git a/external/concealer/src/publisher.cpp b/external/concealer/src/publisher.cpp new file mode 100644 index 00000000000..9f83e8fd6d8 --- /dev/null +++ b/external/concealer/src/publisher.cpp @@ -0,0 +1,98 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +namespace concealer +{ +NormalDistribution::NormalDistribution(const std::string & topic) +: seed(getParameter(topic + ".seed")), + engine(seed ? seed : device()), + position_x( + getParameter(topic + ".pose.pose.position.x.mean"), + getParameter(topic + ".pose.pose.position.x.standard_deviation")), + position_y( + getParameter(topic + ".pose.pose.position.y.mean"), + getParameter(topic + ".pose.pose.position.y.standard_deviation")), + position_z( + getParameter(topic + ".pose.pose.position.z.mean"), + getParameter(topic + ".pose.pose.position.z.standard_deviation")), + orientation_r( + getParameter(topic + ".pose.pose.orientation.r.mean"), + getParameter(topic + ".pose.pose.orientation.r.standard_deviation")), + orientation_p( + getParameter(topic + ".pose.pose.orientation.p.mean"), + getParameter(topic + ".pose.pose.orientation.p.standard_deviation")), + orientation_y( + getParameter(topic + ".pose.pose.orientation.y.mean"), + getParameter(topic + ".pose.pose.orientation.y.standard_deviation")), + linear_x( + getParameter(topic + ".twist.twist.linear.x.mean"), + getParameter(topic + ".twist.twist.linear.x.standard_deviation")), + linear_y( + getParameter(topic + ".twist.twist.linear.y.mean"), + getParameter(topic + ".twist.twist.linear.y.standard_deviation")), + linear_z( + getParameter(topic + ".twist.twist.linear.z.mean"), + getParameter(topic + ".twist.twist.linear.z.standard_deviation")), + angular_x( + getParameter(topic + ".twist.twist.angular.x.mean"), + getParameter(topic + ".twist.twist.angular.x.standard_deviation")), + angular_y( + getParameter(topic + ".twist.twist.angular.y.mean"), + getParameter(topic + ".twist.twist.angular.y.standard_deviation")), + angular_z( + getParameter(topic + ".twist.twist.angular.z.mean"), + getParameter(topic + ".twist.twist.angular.z.standard_deviation")) +{ +} + +auto NormalDistribution::operator()(nav_msgs::msg::Odometry odometry) + -> nav_msgs::msg::Odometry +{ + odometry.pose.pose.position.x += position_x(engine); + odometry.pose.pose.position.y += position_y(engine); + odometry.pose.pose.position.z += position_z(engine); + + Eigen::Vector3d euler = Eigen::Quaterniond( + odometry.pose.pose.orientation.w, odometry.pose.pose.orientation.x, + odometry.pose.pose.orientation.y, odometry.pose.pose.orientation.z) + .matrix() + .eulerAngles(0, 1, 2); + + euler.x() += orientation_r(engine); + euler.y() += orientation_p(engine); + euler.z() += orientation_y(engine); + + const Eigen::Quaterniond orientation = Eigen::AngleAxisd(euler.x(), Eigen::Vector3d::UnitX()) * + Eigen::AngleAxisd(euler.y(), Eigen::Vector3d::UnitY()) * + Eigen::AngleAxisd(euler.z(), Eigen::Vector3d::UnitZ()); + + odometry.pose.pose.orientation.x = orientation.x(); + odometry.pose.pose.orientation.y = orientation.y(); + odometry.pose.pose.orientation.z = orientation.z(); + odometry.pose.pose.orientation.w = orientation.w(); + + odometry.twist.twist.linear.x += linear_x(engine); + odometry.twist.twist.linear.y += linear_y(engine); + odometry.twist.twist.linear.z += linear_z(engine); + + odometry.twist.twist.angular.x += angular_x(engine); + odometry.twist.twist.angular.y += angular_y(engine); + odometry.twist.twist.angular.z += angular_z(engine); + + return odometry; +} +} // namespace concealer From abbcdc42424cc8c719538ce60ca236c806693f6d Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 8 Jan 2025 18:00:20 +0900 Subject: [PATCH 03/18] Add launch argument `parameter_file_path` to `scenario_test_runner` Signed-off-by: yamacir-kit --- .../launch/mock_test.launch.py | 4 +++ .../config/parameters.yaml | 25 +++++++++++++++++++ .../launch/scenario_test_runner.launch.py | 7 +++++- 3 files changed, 35 insertions(+), 1 deletion(-) create mode 100644 test_runner/scenario_test_runner/config/parameters.yaml diff --git a/mock/cpp_mock_scenarios/launch/mock_test.launch.py b/mock/cpp_mock_scenarios/launch/mock_test.launch.py index 0a1f08e45f4..e5bf9853dd8 100644 --- a/mock/cpp_mock_scenarios/launch/mock_test.launch.py +++ b/mock/cpp_mock_scenarios/launch/mock_test.launch.py @@ -115,6 +115,7 @@ def launch_setup(context, *args, **kwargs): launch_rviz = LaunchConfiguration("launch_rviz", default=False) launch_simple_sensor_simulator = LaunchConfiguration("launch_simple_sensor_simulator", default=True) output_directory = LaunchConfiguration("output_directory", default=Path("/tmp")) + parameter_file_path = LaunchConfiguration("parameter_file_path", default=Path(get_package_share_directory("scenario_test_runner")) / "config/parameters.yaml") port = LaunchConfiguration("port", default=5555) publish_empty_context = LaunchConfiguration("publish_empty_context", default=False) record = LaunchConfiguration("record", default=False) @@ -140,6 +141,7 @@ def launch_setup(context, *args, **kwargs): print(f"launch_autoware := {launch_autoware.perform(context)}") print(f"launch_rviz := {launch_rviz.perform(context)}") print(f"output_directory := {output_directory.perform(context)}") + print(f"parameter_file_path := {parameter_file_path.perform(context)}") print(f"port := {port.perform(context)}") print(f"publish_empty_context := {publish_empty_context.perform(context)}") print(f"record := {record.perform(context)}") @@ -174,6 +176,7 @@ def make_parameters(): {"junit_path": junit_path}, ] parameters += make_vehicle_parameters() + parameters += [parameter_file_path.perform(context)] return parameters def make_vehicle_parameters(): @@ -218,6 +221,7 @@ def description(): DeclareLaunchArgument("global_timeout", default_value=global_timeout ), DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ), DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ), + DeclareLaunchArgument("parameter_file_path", default_value=parameter_file_path ), DeclareLaunchArgument("publish_empty_context", default_value=publish_empty_context ), DeclareLaunchArgument("output_directory", default_value=output_directory ), DeclareLaunchArgument("rviz_config", default_value=rviz_config ), diff --git a/test_runner/scenario_test_runner/config/parameters.yaml b/test_runner/scenario_test_runner/config/parameters.yaml new file mode 100644 index 00000000000..6ae2dc8d6b8 --- /dev/null +++ b/test_runner/scenario_test_runner/config/parameters.yaml @@ -0,0 +1,25 @@ +simulation: + normal_distribution: + ros__parameters: + /localization/kinematic_state: + seed: 0 # If 0 is specified, a random seed value will be generated for each run. + pose: + pose: + position: + x: { mean: 0.0, standard_deviation: 0.0 } + y: { mean: 0.0, standard_deviation: 0.0 } + z: { mean: 0.0, standard_deviation: 0.0 } + orientation: + r: { mean: 0.0, standard_deviation: 0.0 } + p: { mean: 0.0, standard_deviation: 0.0 } + y: { mean: 0.0, standard_deviation: 0.0 } + twist: + twist: + linear: + x: { mean: 0.0, standard_deviation: 0.0 } + y: { mean: 0.0, standard_deviation: 0.0 } + z: { mean: 0.0, standard_deviation: 0.0 } + angular: + x: { mean: 0.0, standard_deviation: 0.0 } + y: { mean: 0.0, standard_deviation: 0.0 } + z: { mean: 0.0, standard_deviation: 0.0 } diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 9ad03b6f027..a5fcd88ed6e 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -80,6 +80,7 @@ def launch_setup(context, *args, **kwargs): launch_rviz = LaunchConfiguration("launch_rviz", default=False) launch_simple_sensor_simulator = LaunchConfiguration("launch_simple_sensor_simulator", default=True) output_directory = LaunchConfiguration("output_directory", default=Path("/tmp")) + parameter_file_path = LaunchConfiguration("parameter_file_path", default=Path(get_package_share_directory("scenario_test_runner")) / "config/parameters.yaml") port = LaunchConfiguration("port", default=5555) publish_empty_context = LaunchConfiguration("publish_empty_context", default=False) record = LaunchConfiguration("record", default=True) @@ -106,6 +107,7 @@ def launch_setup(context, *args, **kwargs): print(f"launch_autoware := {launch_autoware.perform(context)}") print(f"launch_rviz := {launch_rviz.perform(context)}") print(f"output_directory := {output_directory.perform(context)}") + print(f"parameter_file_path := {parameter_file_path.perform(context)}") print(f"port := {port.perform(context)}") print(f"publish_empty_context := {publish_empty_context.perform(context)}") print(f"record := {record.perform(context)}") @@ -164,6 +166,8 @@ def collect_prefixed_parameters(): if (it := collect_prefixed_parameters()) != []: parameters += [{"autoware.": it}] + parameters += [parameter_file_path.perform(context)] + return parameters return [ @@ -180,13 +184,14 @@ def collect_prefixed_parameters(): DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ), DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ), DeclareLaunchArgument("output_directory", default_value=output_directory ), + DeclareLaunchArgument("parameter_file_path", default_value=parameter_file_path ), DeclareLaunchArgument("publish_empty_context", default_value=publish_empty_context ), DeclareLaunchArgument("rviz_config", default_value=rviz_config ), DeclareLaunchArgument("scenario", default_value=scenario ), DeclareLaunchArgument("sensor_model", default_value=sensor_model ), DeclareLaunchArgument("sigterm_timeout", default_value=sigterm_timeout ), DeclareLaunchArgument("simulate_localization", default_value=simulate_localization ), - DeclareLaunchArgument("speed_condition", default_value=speed_condition ), + DeclareLaunchArgument("speed_condition", default_value=speed_condition ), DeclareLaunchArgument("use_sim_time", default_value=use_sim_time ), DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ), # fmt: on From 996bc389eb589a120eada1fee4c0941d049943d5 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 9 Jan 2025 11:57:56 +0900 Subject: [PATCH 04/18] Add new struct template `Identity` Signed-off-by: yamacir-kit --- .../include/concealer/autoware_universe.hpp | 16 ++++++++-------- .../concealer/include/concealer/publisher.hpp | 11 +++++++---- 2 files changed, 15 insertions(+), 12 deletions(-) diff --git a/external/concealer/include/concealer/autoware_universe.hpp b/external/concealer/include/concealer/autoware_universe.hpp index 3e28ffe89c3..6279909f875 100644 --- a/external/concealer/include/concealer/autoware_universe.hpp +++ b/external/concealer/include/concealer/autoware_universe.hpp @@ -62,14 +62,14 @@ class AutowareUniverse : public rclcpp::Node, Subscriber getTurnIndicatorsCommand; Subscriber getPathWithLaneId; - Publisher setAcceleration; - Publisher setOdometry; - Publisher setPose; - Publisher setSteeringReport; - Publisher setGearReport; - Publisher setControlModeReport; - Publisher setVelocityReport; - Publisher setTurnIndicatorsReport; + Publisher setAcceleration; + Publisher setOdometry; + Publisher setPose; + Publisher setSteeringReport; + Publisher setGearReport; + Publisher setControlModeReport; + Publisher setVelocityReport; + Publisher setTurnIndicatorsReport; std::atomic current_acceleration; std::atomic current_pose; diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index 91d108792b2..9d43f3f7910 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -22,20 +22,23 @@ namespace concealer { template -struct NormalDistribution +struct Identity { template - explicit NormalDistribution(Ts &&...) + explicit constexpr Identity(Ts &&...) { } template - auto operator()(T && x) const -> decltype(auto) + constexpr auto operator()(T && x) const -> decltype(auto) { return std::forward(x); } }; +template +struct NormalDistribution; + template <> struct NormalDistribution { @@ -62,7 +65,7 @@ struct NormalDistribution auto operator()(nav_msgs::msg::Odometry odometry) -> nav_msgs::msg::Odometry; }; -template typename Randomizer = NormalDistribution> +template typename Randomizer = Identity> class Publisher { typename rclcpp::Publisher::SharedPtr publisher; From 0caa0ecc1d7c939884311b6bb105bb0b70dccfe2 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 9 Jan 2025 17:00:53 +0900 Subject: [PATCH 05/18] Update randomizer to receive `NodeParametersInterface` Signed-off-by: yamacir-kit --- .../concealer/include/concealer/publisher.hpp | 16 ++-- external/concealer/src/autoware_universe.cpp | 2 +- external/concealer/src/publisher.cpp | 82 +++++++++++++------ .../config/parameters.yaml | 5 +- 4 files changed, 66 insertions(+), 39 deletions(-) diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index 9d43f3f7910..95236fa6123 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -42,6 +42,8 @@ struct NormalDistribution; template <> struct NormalDistribution { + int version; + std::random_device::result_type seed; std::random_device device; @@ -51,16 +53,8 @@ struct NormalDistribution std::uniform_real_distribution position_x, position_y, position_z, orientation_r, orientation_p, orientation_y, linear_x, linear_y, linear_z, angular_x, angular_y, angular_z; - template - auto getParameter(const std::string & name, T value = {}) - { - auto node = rclcpp::Node("normal_distribution", "simulation"); - node.declare_parameter(name, value); - node.get_parameter(name, value); - return value; - } - - explicit NormalDistribution(const std::string &); + explicit NormalDistribution( + const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &, const std::string &); auto operator()(nav_msgs::msg::Odometry odometry) -> nav_msgs::msg::Odometry; }; @@ -76,7 +70,7 @@ class Publisher template explicit Publisher(const std::string & topic, Node & node) : publisher(node.template create_publisher(topic, rclcpp::QoS(1).reliable())), - randomize(topic) + randomize(node.get_node_parameters_interface(), topic) { } diff --git a/external/concealer/src/autoware_universe.cpp b/external/concealer/src/autoware_universe.cpp index b67bdbe7fd1..f4ddac37c0d 100644 --- a/external/concealer/src/autoware_universe.cpp +++ b/external/concealer/src/autoware_universe.cpp @@ -17,7 +17,7 @@ namespace concealer { AutowareUniverse::AutowareUniverse(bool simulate_localization) -: rclcpp::Node("concealer", "simulation", rclcpp::NodeOptions().use_global_arguments(false)), +: rclcpp::Node("AutowareUniverse", "simulation"), getCommand("/control/command/control_cmd", rclcpp::QoS(1), *this), getGearCommand("/control/command/gear_cmd", rclcpp::QoS(1), *this), getTurnIndicatorsCommand("/control/command/turn_indicators_cmd", rclcpp::QoS(1), *this), diff --git a/external/concealer/src/publisher.cpp b/external/concealer/src/publisher.cpp index 9f83e8fd6d8..3ae8e677d15 100644 --- a/external/concealer/src/publisher.cpp +++ b/external/concealer/src/publisher.cpp @@ -14,49 +14,79 @@ #include #include +#include namespace concealer { -NormalDistribution::NormalDistribution(const std::string & topic) -: seed(getParameter(topic + ".seed")), +template +auto getParameter( + const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node, + const std::string & name, T value = {}) +{ + if (not node->has_parameter(name)) { + node->declare_parameter(name, rclcpp::ParameterValue(value)); + } + return node->get_parameter(name).get_value(); +} + +NormalDistribution::NormalDistribution( + const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node, + const std::string & topic) +: version([&]() { + switch (const auto version = getParameter(node, topic + ".type.version"); version) { + case 1: + return version; + default: + throw common::Error( + "An unexpected message version ", version, " was specified for topic ", + std::quoted(topic)); + } + }()), + seed(getParameter(node, topic + ".seed")), engine(seed ? seed : device()), position_x( - getParameter(topic + ".pose.pose.position.x.mean"), - getParameter(topic + ".pose.pose.position.x.standard_deviation")), + getParameter(node, topic + ".pose.pose.position.x.mean"), + getParameter(node, topic + ".pose.pose.position.x.standard_deviation")), position_y( - getParameter(topic + ".pose.pose.position.y.mean"), - getParameter(topic + ".pose.pose.position.y.standard_deviation")), + getParameter(node, topic + ".pose.pose.position.y.mean"), + getParameter(node, topic + ".pose.pose.position.y.standard_deviation")), position_z( - getParameter(topic + ".pose.pose.position.z.mean"), - getParameter(topic + ".pose.pose.position.z.standard_deviation")), + getParameter(node, topic + ".pose.pose.position.z.mean"), + getParameter(node, topic + ".pose.pose.position.z.standard_deviation")), orientation_r( - getParameter(topic + ".pose.pose.orientation.r.mean"), - getParameter(topic + ".pose.pose.orientation.r.standard_deviation")), + getParameter(node, topic + ".pose.pose.orientation.r.mean"), + getParameter(node, topic + ".pose.pose.orientation.r.standard_deviation")), orientation_p( - getParameter(topic + ".pose.pose.orientation.p.mean"), - getParameter(topic + ".pose.pose.orientation.p.standard_deviation")), + getParameter(node, topic + ".pose.pose.orientation.p.mean"), + getParameter(node, topic + ".pose.pose.orientation.p.standard_deviation")), orientation_y( - getParameter(topic + ".pose.pose.orientation.y.mean"), - getParameter(topic + ".pose.pose.orientation.y.standard_deviation")), + getParameter(node, topic + ".pose.pose.orientation.y.mean"), + getParameter(node, topic + ".pose.pose.orientation.y.standard_deviation")), linear_x( - getParameter(topic + ".twist.twist.linear.x.mean"), - getParameter(topic + ".twist.twist.linear.x.standard_deviation")), + getParameter(node, topic + ".twist.twist.linear.x.mean"), + getParameter(node, topic + ".twist.twist.linear.x.standard_deviation")), linear_y( - getParameter(topic + ".twist.twist.linear.y.mean"), - getParameter(topic + ".twist.twist.linear.y.standard_deviation")), + getParameter(node, topic + ".twist.twist.linear.y.mean"), + getParameter(node, topic + ".twist.twist.linear.y.standard_deviation")), linear_z( - getParameter(topic + ".twist.twist.linear.z.mean"), - getParameter(topic + ".twist.twist.linear.z.standard_deviation")), + getParameter(node, topic + ".twist.twist.linear.z.mean"), + getParameter(node, topic + ".twist.twist.linear.z.standard_deviation")), angular_x( - getParameter(topic + ".twist.twist.angular.x.mean"), - getParameter(topic + ".twist.twist.angular.x.standard_deviation")), + getParameter(node, topic + ".twist.twist.angular.x.mean"), + getParameter(node, topic + ".twist.twist.angular.x.standard_deviation")), angular_y( - getParameter(topic + ".twist.twist.angular.y.mean"), - getParameter(topic + ".twist.twist.angular.y.standard_deviation")), + getParameter(node, topic + ".twist.twist.angular.y.mean"), + getParameter(node, topic + ".twist.twist.angular.y.standard_deviation")), angular_z( - getParameter(topic + ".twist.twist.angular.z.mean"), - getParameter(topic + ".twist.twist.angular.z.standard_deviation")) + getParameter(node, topic + ".twist.twist.angular.z.mean"), + getParameter(node, topic + ".twist.twist.angular.z.standard_deviation")) { + if (const auto name = getParameter(node, topic + ".type.name"); + name != "nav_msgs::msg::Odometry") { + throw common::Error( + "An unexpected message type ", std::quoted(name), " was specified for topic ", + std::quoted(topic)); + } } auto NormalDistribution::operator()(nav_msgs::msg::Odometry odometry) diff --git a/test_runner/scenario_test_runner/config/parameters.yaml b/test_runner/scenario_test_runner/config/parameters.yaml index 6ae2dc8d6b8..b81e5253d70 100644 --- a/test_runner/scenario_test_runner/config/parameters.yaml +++ b/test_runner/scenario_test_runner/config/parameters.yaml @@ -1,7 +1,10 @@ simulation: - normal_distribution: + AutowareUniverse: ros__parameters: /localization/kinematic_state: + type: + name: nav_msgs::msg::Odometry + version: 1 seed: 0 # If 0 is specified, a random seed value will be generated for each run. pose: pose: From 5ce7a0aafea0d09bc45c0dd18dcefb91c6ccdc48 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 9 Jan 2025 18:58:06 +0900 Subject: [PATCH 06/18] Update parameter file format Signed-off-by: yamacir-kit --- .../concealer/include/concealer/publisher.hpp | 2 - external/concealer/src/publisher.cpp | 78 +++++++++---------- .../config/parameters.yaml | 41 +++++----- 3 files changed, 57 insertions(+), 64 deletions(-) diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index 95236fa6123..2b29648dc69 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -42,8 +42,6 @@ struct NormalDistribution; template <> struct NormalDistribution { - int version; - std::random_device::result_type seed; std::random_device device; diff --git a/external/concealer/src/publisher.cpp b/external/concealer/src/publisher.cpp index 3ae8e677d15..d6eebda88a0 100644 --- a/external/concealer/src/publisher.cpp +++ b/external/concealer/src/publisher.cpp @@ -32,61 +32,57 @@ auto getParameter( NormalDistribution::NormalDistribution( const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node, const std::string & topic) -: version([&]() { - switch (const auto version = getParameter(node, topic + ".type.version"); version) { - case 1: - return version; - default: - throw common::Error( - "An unexpected message version ", version, " was specified for topic ", - std::quoted(topic)); - } - }()), - seed(getParameter(node, topic + ".seed")), +: seed(getParameter(node, topic + ".seed")), engine(seed ? seed : device()), position_x( - getParameter(node, topic + ".pose.pose.position.x.mean"), - getParameter(node, topic + ".pose.pose.position.x.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.x.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.x.standard_deviation")), position_y( - getParameter(node, topic + ".pose.pose.position.y.mean"), - getParameter(node, topic + ".pose.pose.position.y.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.y.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.y.standard_deviation")), position_z( - getParameter(node, topic + ".pose.pose.position.z.mean"), - getParameter(node, topic + ".pose.pose.position.z.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.z.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.z.standard_deviation")), orientation_r( - getParameter(node, topic + ".pose.pose.orientation.r.mean"), - getParameter(node, topic + ".pose.pose.orientation.r.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.r.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.r.standard_deviation")), orientation_p( - getParameter(node, topic + ".pose.pose.orientation.p.mean"), - getParameter(node, topic + ".pose.pose.orientation.p.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.p.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.p.standard_deviation")), orientation_y( - getParameter(node, topic + ".pose.pose.orientation.y.mean"), - getParameter(node, topic + ".pose.pose.orientation.y.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.y.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.y.standard_deviation")), linear_x( - getParameter(node, topic + ".twist.twist.linear.x.mean"), - getParameter(node, topic + ".twist.twist.linear.x.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.x.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.x.standard_deviation")), linear_y( - getParameter(node, topic + ".twist.twist.linear.y.mean"), - getParameter(node, topic + ".twist.twist.linear.y.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.y.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.y.standard_deviation")), linear_z( - getParameter(node, topic + ".twist.twist.linear.z.mean"), - getParameter(node, topic + ".twist.twist.linear.z.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.z.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.z.standard_deviation")), angular_x( - getParameter(node, topic + ".twist.twist.angular.x.mean"), - getParameter(node, topic + ".twist.twist.angular.x.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.x.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.x.standard_deviation")), angular_y( - getParameter(node, topic + ".twist.twist.angular.y.mean"), - getParameter(node, topic + ".twist.twist.angular.y.standard_deviation")), + getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.y.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.y.standard_deviation")), angular_z( - getParameter(node, topic + ".twist.twist.angular.z.mean"), - getParameter(node, topic + ".twist.twist.angular.z.standard_deviation")) + getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.z.mean"), + getParameter( + node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.z.standard_deviation")) { - if (const auto name = getParameter(node, topic + ".type.name"); - name != "nav_msgs::msg::Odometry") { - throw common::Error( - "An unexpected message type ", std::quoted(name), " was specified for topic ", - std::quoted(topic)); - } } auto NormalDistribution::operator()(nav_msgs::msg::Odometry odometry) diff --git a/test_runner/scenario_test_runner/config/parameters.yaml b/test_runner/scenario_test_runner/config/parameters.yaml index b81e5253d70..597930fb49b 100644 --- a/test_runner/scenario_test_runner/config/parameters.yaml +++ b/test_runner/scenario_test_runner/config/parameters.yaml @@ -2,27 +2,26 @@ simulation: AutowareUniverse: ros__parameters: /localization/kinematic_state: - type: - name: nav_msgs::msg::Odometry - version: 1 + version: 20240605 # architecture_type suffix (mandatory) seed: 0 # If 0 is specified, a random seed value will be generated for each run. - pose: + nav_msgs::msg::Odometry: pose: - position: - x: { mean: 0.0, standard_deviation: 0.0 } - y: { mean: 0.0, standard_deviation: 0.0 } - z: { mean: 0.0, standard_deviation: 0.0 } - orientation: - r: { mean: 0.0, standard_deviation: 0.0 } - p: { mean: 0.0, standard_deviation: 0.0 } - y: { mean: 0.0, standard_deviation: 0.0 } - twist: + pose: + position: + x: { mean: 0.0, standard_deviation: 0.0 } + y: { mean: 0.0, standard_deviation: 0.0 } + z: { mean: 0.0, standard_deviation: 0.0 } + orientation: + r: { mean: 0.0, standard_deviation: 0.0 } + p: { mean: 0.0, standard_deviation: 0.0 } + y: { mean: 0.0, standard_deviation: 0.0 } twist: - linear: - x: { mean: 0.0, standard_deviation: 0.0 } - y: { mean: 0.0, standard_deviation: 0.0 } - z: { mean: 0.0, standard_deviation: 0.0 } - angular: - x: { mean: 0.0, standard_deviation: 0.0 } - y: { mean: 0.0, standard_deviation: 0.0 } - z: { mean: 0.0, standard_deviation: 0.0 } + twist: + linear: + x: { mean: 0.0, standard_deviation: 0.0 } + y: { mean: 0.0, standard_deviation: 0.0 } + z: { mean: 0.0, standard_deviation: 0.0 } + angular: + x: { mean: 0.0, standard_deviation: 0.0 } + y: { mean: 0.0, standard_deviation: 0.0 } + z: { mean: 0.0, standard_deviation: 0.0 } From fc1930d524f8224bfb1268c1fb7f5b62c756c6ec Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 16 Jan 2025 15:37:27 +0900 Subject: [PATCH 07/18] Update `NormalDistribution::device` type to `std::mt19937_64` Signed-off-by: yamacir-kit --- external/concealer/include/concealer/publisher.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index 2b29648dc69..68a8ae9e059 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -46,7 +46,7 @@ struct NormalDistribution std::random_device device; - std::default_random_engine engine; + std::mt19937_64 engine; std::uniform_real_distribution position_x, position_y, position_z, orientation_r, orientation_p, orientation_y, linear_x, linear_y, linear_z, angular_x, angular_y, angular_z; From 35eadb73024b14009d074f06e2d03ae228b7babd Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 16 Jan 2025 16:12:00 +0900 Subject: [PATCH 08/18] Update `NormalDistribution` to use `std::normal_distribution` Signed-off-by: yamacir-kit --- .../concealer/include/concealer/publisher.hpp | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index 68a8ae9e059..533b985370e 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -48,8 +48,20 @@ struct NormalDistribution std::mt19937_64 engine; - std::uniform_real_distribution position_x, position_y, position_z, orientation_r, - orientation_p, orientation_y, linear_x, linear_y, linear_z, angular_x, angular_y, angular_z; + // clang-format off + std::normal_distribution position_x, + position_y, + position_z, + orientation_r, + orientation_p, + orientation_y, + linear_x, + linear_y, + linear_z, + angular_x, + angular_y, + angular_z; + // clang-format on explicit NormalDistribution( const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &, const std::string &); From d3c0dafec3d38042b8548ac68f1fd1061b476e11 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 17 Jan 2025 12:00:18 +0900 Subject: [PATCH 09/18] Add support for multiplicative errors as well as additive errors Signed-off-by: yamacir-kit --- .../concealer/include/concealer/publisher.hpp | 57 +++++++-- external/concealer/src/publisher.cpp | 95 ++++----------- .../config/parameters.yaml | 108 ++++++++++++++++-- 3 files changed, 165 insertions(+), 95 deletions(-) diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index 533b985370e..8c37c8e25bc 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -21,6 +21,17 @@ namespace concealer { +template +auto getParameter( + const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node, + const std::string & name, T value = {}) +{ + if (not node->has_parameter(name)) { + node->declare_parameter(name, rclcpp::ParameterValue(value)); + } + return node->get_parameter(name).get_value(); +} + template struct Identity { @@ -48,19 +59,41 @@ struct NormalDistribution std::mt19937_64 engine; + struct Error + { + std::normal_distribution additive, multiplicative; + + explicit Error( + const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node, + const std::string & prefix) + : additive( + getParameter(node, prefix + ".additive.mean"), + getParameter(node, prefix + ".additive.standard_deviation")), + multiplicative( + getParameter(node, prefix + ".multiplicative.mean"), + getParameter(node, prefix + ".multiplicative.standard_deviation")) + { + } + + auto apply(std::mt19937_64 & engine, double & value) -> decltype(auto) + { + return (value *= (multiplicative(engine) + 1.0)) += additive(engine); + } + }; + // clang-format off - std::normal_distribution position_x, - position_y, - position_z, - orientation_r, - orientation_p, - orientation_y, - linear_x, - linear_y, - linear_z, - angular_x, - angular_y, - angular_z; + Error position_x_error, + position_y_error, + position_z_error, + orientation_r_error, + orientation_p_error, + orientation_y_error, + linear_x_error, + linear_y_error, + linear_z_error, + angular_x_error, + angular_y_error, + angular_z_error; // clang-format on explicit NormalDistribution( diff --git a/external/concealer/src/publisher.cpp b/external/concealer/src/publisher.cpp index d6eebda88a0..2098adfc965 100644 --- a/external/concealer/src/publisher.cpp +++ b/external/concealer/src/publisher.cpp @@ -18,79 +18,32 @@ namespace concealer { -template -auto getParameter( - const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node, - const std::string & name, T value = {}) -{ - if (not node->has_parameter(name)) { - node->declare_parameter(name, rclcpp::ParameterValue(value)); - } - return node->get_parameter(name).get_value(); -} - NormalDistribution::NormalDistribution( const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node, const std::string & topic) : seed(getParameter(node, topic + ".seed")), engine(seed ? seed : device()), - position_x( - getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.x.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.x.standard_deviation")), - position_y( - getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.y.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.y.standard_deviation")), - position_z( - getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.z.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.pose.pose.position.z.standard_deviation")), - orientation_r( - getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.r.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.r.standard_deviation")), - orientation_p( - getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.p.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.p.standard_deviation")), - orientation_y( - getParameter(node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.y.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.pose.pose.orientation.y.standard_deviation")), - linear_x( - getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.x.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.x.standard_deviation")), - linear_y( - getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.y.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.y.standard_deviation")), - linear_z( - getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.z.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.z.standard_deviation")), - angular_x( - getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.x.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.x.standard_deviation")), - angular_y( - getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.y.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.y.standard_deviation")), - angular_z( - getParameter(node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.z.mean"), - getParameter( - node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.z.standard_deviation")) + 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"), + 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"), + linear_x_error(node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.x.error"), + linear_y_error(node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.y.error"), + linear_z_error(node, topic + ".nav_msgs::msg::Odometry.twist.twist.linear.z.error"), + angular_x_error(node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.x.error"), + angular_y_error(node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.y.error"), + angular_z_error(node, topic + ".nav_msgs::msg::Odometry.twist.twist.angular.z.error") { } auto NormalDistribution::operator()(nav_msgs::msg::Odometry odometry) -> nav_msgs::msg::Odometry { - odometry.pose.pose.position.x += position_x(engine); - odometry.pose.pose.position.y += position_y(engine); - odometry.pose.pose.position.z += position_z(engine); + position_x_error.apply(engine, odometry.pose.pose.position.x); + position_y_error.apply(engine, odometry.pose.pose.position.y); + position_z_error.apply(engine, odometry.pose.pose.position.z); Eigen::Vector3d euler = Eigen::Quaterniond( odometry.pose.pose.orientation.w, odometry.pose.pose.orientation.x, @@ -98,9 +51,9 @@ auto NormalDistribution::operator()(nav_msgs::msg::Odom .matrix() .eulerAngles(0, 1, 2); - euler.x() += orientation_r(engine); - euler.y() += orientation_p(engine); - euler.z() += orientation_y(engine); + orientation_r_error.apply(engine, euler.x()); + orientation_p_error.apply(engine, euler.y()); + orientation_y_error.apply(engine, euler.z()); const Eigen::Quaterniond orientation = Eigen::AngleAxisd(euler.x(), Eigen::Vector3d::UnitX()) * Eigen::AngleAxisd(euler.y(), Eigen::Vector3d::UnitY()) * @@ -111,13 +64,13 @@ auto NormalDistribution::operator()(nav_msgs::msg::Odom odometry.pose.pose.orientation.z = orientation.z(); odometry.pose.pose.orientation.w = orientation.w(); - odometry.twist.twist.linear.x += linear_x(engine); - odometry.twist.twist.linear.y += linear_y(engine); - odometry.twist.twist.linear.z += linear_z(engine); + linear_x_error.apply(engine, odometry.twist.twist.linear.x); + linear_y_error.apply(engine, odometry.twist.twist.linear.y); + linear_z_error.apply(engine, odometry.twist.twist.linear.z); - odometry.twist.twist.angular.x += angular_x(engine); - odometry.twist.twist.angular.y += angular_y(engine); - odometry.twist.twist.angular.z += angular_z(engine); + angular_x_error.apply(engine, odometry.twist.twist.angular.x); + angular_y_error.apply(engine, odometry.twist.twist.angular.y); + angular_z_error.apply(engine, odometry.twist.twist.angular.z); return odometry; } diff --git a/test_runner/scenario_test_runner/config/parameters.yaml b/test_runner/scenario_test_runner/config/parameters.yaml index 597930fb49b..6f41f1f16ec 100644 --- a/test_runner/scenario_test_runner/config/parameters.yaml +++ b/test_runner/scenario_test_runner/config/parameters.yaml @@ -8,20 +8,104 @@ simulation: pose: pose: position: - x: { mean: 0.0, standard_deviation: 0.0 } - y: { mean: 0.0, standard_deviation: 0.0 } - z: { mean: 0.0, standard_deviation: 0.0 } + x: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 + y: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 + z: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 orientation: - r: { mean: 0.0, standard_deviation: 0.0 } - p: { mean: 0.0, standard_deviation: 0.0 } - y: { mean: 0.0, standard_deviation: 0.0 } + r: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 + p: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 + y: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 twist: twist: linear: - x: { mean: 0.0, standard_deviation: 0.0 } - y: { mean: 0.0, standard_deviation: 0.0 } - z: { mean: 0.0, standard_deviation: 0.0 } + x: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 + y: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 + z: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 angular: - x: { mean: 0.0, standard_deviation: 0.0 } - y: { mean: 0.0, standard_deviation: 0.0 } - z: { mean: 0.0, standard_deviation: 0.0 } + x: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 + y: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 + z: + error: + additive: + mean: 0.0 + standard_deviation: 0.0 + multiplicative: + mean: 0.0 + standard_deviation: 0.0 From e4f46c6a3a3248a612161e8a9f1f6ab2b44b7943 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 17 Jan 2025 14:52:48 +0900 Subject: [PATCH 10/18] Cleanup Signed-off-by: yamacir-kit --- .../concealer/include/concealer/publisher.hpp | 8 ++--- external/concealer/src/publisher.cpp | 36 ++++++++++++------- 2 files changed, 27 insertions(+), 17 deletions(-) diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index 8c37c8e25bc..7d2c83c63a1 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -35,8 +35,8 @@ auto getParameter( template struct Identity { - template - explicit constexpr Identity(Ts &&...) + explicit constexpr Identity( + const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &, const std::string &) { } @@ -75,9 +75,9 @@ struct NormalDistribution { } - auto apply(std::mt19937_64 & engine, double & value) -> decltype(auto) + auto apply(std::mt19937_64 & engine, double value) -> decltype(auto) { - return (value *= (multiplicative(engine) + 1.0)) += additive(engine); + return value * (multiplicative(engine) + 1.0) + additive(engine); } }; diff --git a/external/concealer/src/publisher.cpp b/external/concealer/src/publisher.cpp index 2098adfc965..426082c74af 100644 --- a/external/concealer/src/publisher.cpp +++ b/external/concealer/src/publisher.cpp @@ -21,7 +21,17 @@ namespace concealer NormalDistribution::NormalDistribution( const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & node, const std::string & topic) -: seed(getParameter(node, topic + ".seed")), +: seed([&]() { + if (const auto value = getParameter(node, topic + ".seed"); + std::random_device::min() <= value and value <= std::random_device::max()) { + return value; + } else { + throw common::scenario_simulator_exception::Error( + "The value of parameter ", std::quoted(topic + ".seed"), + " must be greater than or equal to ", std::random_device::min(), + " and less than or equal to ", std::random_device::max()); + } + }()), 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"), @@ -41,9 +51,9 @@ NormalDistribution::NormalDistribution( auto NormalDistribution::operator()(nav_msgs::msg::Odometry odometry) -> nav_msgs::msg::Odometry { - position_x_error.apply(engine, odometry.pose.pose.position.x); - position_y_error.apply(engine, odometry.pose.pose.position.y); - position_z_error.apply(engine, odometry.pose.pose.position.z); + odometry.pose.pose.position.x = position_x_error.apply(engine, odometry.pose.pose.position.x); + odometry.pose.pose.position.y = position_y_error.apply(engine, odometry.pose.pose.position.y); + odometry.pose.pose.position.z = position_z_error.apply(engine, odometry.pose.pose.position.z); Eigen::Vector3d euler = Eigen::Quaterniond( odometry.pose.pose.orientation.w, odometry.pose.pose.orientation.x, @@ -51,9 +61,9 @@ auto NormalDistribution::operator()(nav_msgs::msg::Odom .matrix() .eulerAngles(0, 1, 2); - orientation_r_error.apply(engine, euler.x()); - orientation_p_error.apply(engine, euler.y()); - orientation_y_error.apply(engine, euler.z()); + euler.x() = orientation_r_error.apply(engine, euler.x()); + euler.y() = orientation_p_error.apply(engine, euler.y()); + euler.z() = orientation_y_error.apply(engine, euler.z()); const Eigen::Quaterniond orientation = Eigen::AngleAxisd(euler.x(), Eigen::Vector3d::UnitX()) * Eigen::AngleAxisd(euler.y(), Eigen::Vector3d::UnitY()) * @@ -64,13 +74,13 @@ auto NormalDistribution::operator()(nav_msgs::msg::Odom odometry.pose.pose.orientation.z = orientation.z(); odometry.pose.pose.orientation.w = orientation.w(); - linear_x_error.apply(engine, odometry.twist.twist.linear.x); - linear_y_error.apply(engine, odometry.twist.twist.linear.y); - linear_z_error.apply(engine, odometry.twist.twist.linear.z); + odometry.twist.twist.linear.x = linear_x_error.apply(engine, odometry.twist.twist.linear.x); + odometry.twist.twist.linear.y = linear_y_error.apply(engine, odometry.twist.twist.linear.y); + odometry.twist.twist.linear.z = linear_z_error.apply(engine, odometry.twist.twist.linear.z); - angular_x_error.apply(engine, odometry.twist.twist.angular.x); - angular_y_error.apply(engine, odometry.twist.twist.angular.y); - angular_z_error.apply(engine, odometry.twist.twist.angular.z); + odometry.twist.twist.angular.x = angular_x_error.apply(engine, odometry.twist.twist.angular.x); + odometry.twist.twist.angular.y = angular_y_error.apply(engine, odometry.twist.twist.angular.y); + odometry.twist.twist.angular.z = angular_z_error.apply(engine, odometry.twist.twist.angular.z); return odometry; } From 24426bb7b5b3a8ea482b2b177e3eefd414698de3 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 23 Jan 2025 15:18:58 +0900 Subject: [PATCH 11/18] Update the position error to apply in the entity's local coordinate Signed-off-by: yamacir-kit --- external/concealer/src/publisher.cpp | 38 +++++++++++-------- .../config/parameters.yaml | 8 ++++ 2 files changed, 31 insertions(+), 15 deletions(-) diff --git a/external/concealer/src/publisher.cpp b/external/concealer/src/publisher.cpp index 426082c74af..a87e00fd987 100644 --- a/external/concealer/src/publisher.cpp +++ b/external/concealer/src/publisher.cpp @@ -51,28 +51,36 @@ NormalDistribution::NormalDistribution( auto NormalDistribution::operator()(nav_msgs::msg::Odometry odometry) -> nav_msgs::msg::Odometry { - odometry.pose.pose.position.x = position_x_error.apply(engine, odometry.pose.pose.position.x); - odometry.pose.pose.position.y = position_y_error.apply(engine, odometry.pose.pose.position.y); - odometry.pose.pose.position.z = position_z_error.apply(engine, odometry.pose.pose.position.z); + const Eigen::Quaterniond orientation = Eigen::Quaterniond( + odometry.pose.pose.orientation.w, odometry.pose.pose.orientation.x, + odometry.pose.pose.orientation.y, odometry.pose.pose.orientation.z); - Eigen::Vector3d euler = Eigen::Quaterniond( - odometry.pose.pose.orientation.w, odometry.pose.pose.orientation.x, - odometry.pose.pose.orientation.y, odometry.pose.pose.orientation.z) - .matrix() - .eulerAngles(0, 1, 2); + 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()); + + const Eigen::Vector3d world_position = orientation.toRotationMatrix() * local_position; + + odometry.pose.pose.position.x += world_position.x(); + odometry.pose.pose.position.y += world_position.y(); + odometry.pose.pose.position.z += world_position.z(); + + Eigen::Vector3d euler = orientation.matrix().eulerAngles(0, 1, 2); euler.x() = orientation_r_error.apply(engine, euler.x()); euler.y() = orientation_p_error.apply(engine, euler.y()); euler.z() = orientation_y_error.apply(engine, euler.z()); - const Eigen::Quaterniond orientation = Eigen::AngleAxisd(euler.x(), Eigen::Vector3d::UnitX()) * - Eigen::AngleAxisd(euler.y(), Eigen::Vector3d::UnitY()) * - Eigen::AngleAxisd(euler.z(), Eigen::Vector3d::UnitZ()); + const Eigen::Quaterniond q = Eigen::AngleAxisd(euler.x(), Eigen::Vector3d::UnitX()) * + Eigen::AngleAxisd(euler.y(), Eigen::Vector3d::UnitY()) * + Eigen::AngleAxisd(euler.z(), Eigen::Vector3d::UnitZ()); - odometry.pose.pose.orientation.x = orientation.x(); - odometry.pose.pose.orientation.y = orientation.y(); - odometry.pose.pose.orientation.z = orientation.z(); - odometry.pose.pose.orientation.w = orientation.w(); + odometry.pose.pose.orientation.x = q.x(); + odometry.pose.pose.orientation.y = q.y(); + odometry.pose.pose.orientation.z = q.z(); + odometry.pose.pose.orientation.w = q.w(); odometry.twist.twist.linear.x = linear_x_error.apply(engine, odometry.twist.twist.linear.x); odometry.twist.twist.linear.y = linear_y_error.apply(engine, odometry.twist.twist.linear.y); diff --git a/test_runner/scenario_test_runner/config/parameters.yaml b/test_runner/scenario_test_runner/config/parameters.yaml index 6f41f1f16ec..c2a53d0236c 100644 --- a/test_runner/scenario_test_runner/config/parameters.yaml +++ b/test_runner/scenario_test_runner/config/parameters.yaml @@ -33,6 +33,14 @@ simulation: mean: 0.0 standard_deviation: 0.0 orientation: + # The type of geometry_msgs::msg::Pose.orientation is + # Quaternion, and the actual orientation data members are x, y, + # z, and w. However, applying error to Quaternions can be + # unintuitive and tricky, so we accept the parameters as Euler + # angles here. The simulator internally converts Quaternion to + # Euler angles and applies the error to them. It then converts + # the error-applied Euler angles back to Quaternion and + # publishes them as `/localization/kinematic_state`. r: error: additive: From 8b0948db86605b25085d8a3499ad5ced96566187 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Thu, 23 Jan 2025 15:56:12 +0900 Subject: [PATCH 12/18] Rename the parameter `(x|y|z)` to `local_(x|y|z)` Signed-off-by: yamacir-kit --- .../concealer/include/concealer/publisher.hpp | 6 +++--- external/concealer/src/publisher.cpp | 12 ++++++------ .../scenario_test_runner/config/parameters.yaml | 16 +++++++++++++--- 3 files changed, 22 insertions(+), 12 deletions(-) diff --git a/external/concealer/include/concealer/publisher.hpp b/external/concealer/include/concealer/publisher.hpp index 7d2c83c63a1..b0cf0b33d00 100644 --- a/external/concealer/include/concealer/publisher.hpp +++ b/external/concealer/include/concealer/publisher.hpp @@ -82,9 +82,9 @@ struct NormalDistribution }; // 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, diff --git a/external/concealer/src/publisher.cpp b/external/concealer/src/publisher.cpp index a87e00fd987..b8efe713a26 100644 --- a/external/concealer/src/publisher.cpp +++ b/external/concealer/src/publisher.cpp @@ -33,9 +33,9 @@ NormalDistribution::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"), @@ -57,9 +57,9 @@ auto NormalDistribution::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; diff --git a/test_runner/scenario_test_runner/config/parameters.yaml b/test_runner/scenario_test_runner/config/parameters.yaml index c2a53d0236c..93d35b0fd37 100644 --- a/test_runner/scenario_test_runner/config/parameters.yaml +++ b/test_runner/scenario_test_runner/config/parameters.yaml @@ -8,7 +8,17 @@ 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 @@ -16,7 +26,7 @@ simulation: multiplicative: mean: 0.0 standard_deviation: 0.0 - y: + local_y: error: additive: mean: 0.0 @@ -24,7 +34,7 @@ simulation: multiplicative: mean: 0.0 standard_deviation: 0.0 - z: + local_z: error: additive: mean: 0.0 From d42f31483fb8a8037456948b4cd1a62f6a6f263e Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 24 Jan 2025 13:37:16 +0900 Subject: [PATCH 13/18] Update `scenario_test_runner` to check the path given as a parameter Signed-off-by: yamacir-kit --- .../launch/scenario_test_runner.launch.py | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index a5fcd88ed6e..75d2319da8b 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -166,7 +166,14 @@ def collect_prefixed_parameters(): if (it := collect_prefixed_parameters()) != []: parameters += [{"autoware.": it}] - parameters += [parameter_file_path.perform(context)] + path = Path(parameter_file_path.perform(context)) + + if not path.is_file(): + raise Exception(f'The value "{path}" given for parameter `parameter_file_path` is not a file.') + elif path.suffix != '.yaml' and path.suffix != '.yml': + raise Exception(f'The value "{path}" given for parameter `parameter_file_path` is not a YAML file.') + else: + parameters += [path] return parameters From 8273b71c1233e0ee2aed1fa4f4f24f6766d6c75f Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 7 Feb 2025 17:00:42 +0900 Subject: [PATCH 14/18] Add new test file `concealer/test/normal_distribution.cpp` Signed-off-by: yamacir-kit --- external/concealer/CMakeLists.txt | 8 + .../concealer/test/normal_distribution.cpp | 393 ++++++++++++++++++ 2 files changed, 401 insertions(+) create mode 100644 external/concealer/test/normal_distribution.cpp diff --git a/external/concealer/CMakeLists.txt b/external/concealer/CMakeLists.txt index 2ea1c7f7e53..4d800bc621e 100644 --- a/external/concealer/CMakeLists.txt +++ b/external/concealer/CMakeLists.txt @@ -28,6 +28,14 @@ target_link_libraries(${PROJECT_NAME} if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() + + file(GLOB ${PROJECT_NAME}_TESTS ${CMAKE_CURRENT_SOURCE_DIR}/test/*.cpp) + + foreach(EACH IN LISTS ${PROJECT_NAME}_TESTS) + get_filename_component(TEST_NAME ${EACH} NAME_WE) + ament_add_gtest(${TEST_NAME} ${EACH}) + target_link_libraries(${TEST_NAME} ${PROJECT_NAME}) + endforeach() endif() ament_auto_package() diff --git a/external/concealer/test/normal_distribution.cpp b/external/concealer/test/normal_distribution.cpp new file mode 100644 index 00000000000..9511b214f84 --- /dev/null +++ b/external/concealer/test/normal_distribution.cpp @@ -0,0 +1,393 @@ +// Copyright 2015 TIER IV, Inc. All rights reserved. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include + +auto rclcpp_initialized = false; + +TEST(NormalDistribution_nav_msgs_msg_Odometry, when_no_parameters_are_given) +{ + if (not std::exchange(rclcpp_initialized, true)) { + rclcpp::init(0, nullptr); + } + + auto node = rclcpp::Node("node_name", "simulation"); + + // clang-format off + ASSERT_FALSE(node.has_parameter("/topic_name.seed")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.multiplicative.standard_deviation")); + // clang-format on + + auto randomize = concealer::NormalDistribution( + node.get_node_parameters_interface(), "/topic_name"); + + ASSERT_EQ(randomize.seed, 0); + ASSERT_EQ(randomize.position_local_x_error.additive.mean(), 0); + ASSERT_EQ(randomize.position_local_x_error.additive.stddev(), 0); + ASSERT_EQ(randomize.position_local_x_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.position_local_x_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.position_local_y_error.additive.mean(), 0); + ASSERT_EQ(randomize.position_local_y_error.additive.stddev(), 0); + ASSERT_EQ(randomize.position_local_y_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.position_local_y_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.position_local_z_error.additive.mean(), 0); + ASSERT_EQ(randomize.position_local_z_error.additive.stddev(), 0); + ASSERT_EQ(randomize.position_local_z_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.position_local_z_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.orientation_r_error.additive.mean(), 0); + ASSERT_EQ(randomize.orientation_r_error.additive.stddev(), 0); + ASSERT_EQ(randomize.orientation_r_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.orientation_r_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.orientation_p_error.additive.mean(), 0); + ASSERT_EQ(randomize.orientation_p_error.additive.stddev(), 0); + ASSERT_EQ(randomize.orientation_p_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.orientation_p_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.orientation_y_error.additive.mean(), 0); + ASSERT_EQ(randomize.orientation_y_error.additive.stddev(), 0); + ASSERT_EQ(randomize.orientation_y_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.orientation_y_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.linear_x_error.additive.mean(), 0); + ASSERT_EQ(randomize.linear_x_error.additive.stddev(), 0); + ASSERT_EQ(randomize.linear_x_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.linear_x_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.linear_y_error.additive.mean(), 0); + ASSERT_EQ(randomize.linear_y_error.additive.stddev(), 0); + ASSERT_EQ(randomize.linear_y_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.linear_y_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.linear_y_error.additive.mean(), 0); + ASSERT_EQ(randomize.linear_y_error.additive.stddev(), 0); + ASSERT_EQ(randomize.linear_y_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.linear_y_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.angular_x_error.additive.mean(), 0); + ASSERT_EQ(randomize.angular_x_error.additive.stddev(), 0); + ASSERT_EQ(randomize.angular_x_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.angular_x_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.angular_y_error.additive.mean(), 0); + ASSERT_EQ(randomize.angular_y_error.additive.stddev(), 0); + ASSERT_EQ(randomize.angular_y_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.angular_y_error.multiplicative.stddev(), 0); + ASSERT_EQ(randomize.angular_z_error.additive.mean(), 0); + ASSERT_EQ(randomize.angular_z_error.additive.stddev(), 0); + ASSERT_EQ(randomize.angular_z_error.multiplicative.mean(), 0); + ASSERT_EQ(randomize.angular_z_error.multiplicative.stddev(), 0); + + const auto odometry = nav_msgs::msg::Odometry(); + + const auto randomized_odometry = randomize(odometry); + + // clang-format off + ASSERT_EQ(randomized_odometry.pose.pose.position.x, 0); + ASSERT_EQ(randomized_odometry.pose.pose.position.y, 0); + ASSERT_EQ(randomized_odometry.pose.pose.position.z, 0); + ASSERT_EQ(randomized_odometry.pose.pose.orientation.x, 0); + ASSERT_EQ(randomized_odometry.pose.pose.orientation.y, 0); + ASSERT_EQ(randomized_odometry.pose.pose.orientation.z, 0); + ASSERT_EQ(randomized_odometry.pose.pose.orientation.w, 1); + ASSERT_EQ(randomized_odometry.twist.twist.linear.x, 0); + ASSERT_EQ(randomized_odometry.twist.twist.linear.y, 0); + ASSERT_EQ(randomized_odometry.twist.twist.linear.z, 0); + ASSERT_EQ(randomized_odometry.twist.twist.angular.x, 0); + ASSERT_EQ(randomized_odometry.twist.twist.angular.y, 0); + ASSERT_EQ(randomized_odometry.twist.twist.angular.z, 0); + // clang-format on +} + +TEST(NormalDistribution_nav_msgs_msg_Odometry, when_all_parameters_are_given) +{ + if (not std::exchange(rclcpp_initialized, true)) { + rclcpp::init(0, nullptr); + } + + auto node = rclcpp::Node("node_name", "simulation"); + + // clang-format off + ASSERT_FALSE(node.has_parameter("/topic_name.seed")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.multiplicative.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.additive.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.additive.standard_deviation")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.multiplicative.mean")); + ASSERT_FALSE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.multiplicative.standard_deviation")); + // clang-format on + + // clang-format off + node.declare_parameter("/topic_name.seed", 1); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.additive.mean", 2); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.additive.standard_deviation", 3); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.multiplicative.mean", 4); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.multiplicative.standard_deviation", 5); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.additive.mean", 6); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.additive.standard_deviation", 7); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.multiplicative.mean", 8); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.multiplicative.standard_deviation", 9); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.additive.mean", 10); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.additive.standard_deviation", 11); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.multiplicative.mean", 12); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.multiplicative.standard_deviation", 13); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.additive.mean", 14); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.additive.standard_deviation", 15); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.multiplicative.mean", 16); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.multiplicative.standard_deviation", 17); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.additive.mean", 18); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.additive.standard_deviation", 19); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.multiplicative.mean", 20); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.multiplicative.standard_deviation", 21); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.additive.mean", 22); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.additive.standard_deviation", 23); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.multiplicative.mean", 24); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.multiplicative.standard_deviation", 25); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.additive.mean", 26); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.additive.standard_deviation", 27); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.multiplicative.mean", 28); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.multiplicative.standard_deviation", 29); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.additive.mean", 30); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.additive.standard_deviation", 31); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.multiplicative.mean", 32); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.multiplicative.standard_deviation", 33); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.additive.mean", 34); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.additive.standard_deviation", 35); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.multiplicative.mean", 36); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.multiplicative.standard_deviation", 37); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.additive.mean", 38); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.additive.standard_deviation", 39); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.multiplicative.mean", 40); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.multiplicative.standard_deviation", 41); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.additive.mean", 42); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.additive.standard_deviation", 43); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.multiplicative.mean", 44); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.multiplicative.standard_deviation", 45); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.additive.mean", 46); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.additive.standard_deviation", 47); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.multiplicative.mean", 48); + node.declare_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.multiplicative.standard_deviation", 49); + // clang-format on + + // clang-format off + ASSERT_TRUE(node.has_parameter("/topic_name.seed")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_x.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_y.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.position.local_z.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.r.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.p.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.pose.pose.orientation.y.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.x.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.y.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.linear.z.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.x.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.y.error.multiplicative.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.additive.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.additive.standard_deviation")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.multiplicative.mean")); + ASSERT_TRUE(node.has_parameter("/topic_name.nav_msgs::msg::Odometry.twist.twist.angular.z.error.multiplicative.standard_deviation")); + // clang-format on + + auto randomize = concealer::NormalDistribution( + node.get_node_parameters_interface(), "/topic_name"); + + // clang-format off + ASSERT_EQ(randomize.seed, 1); + ASSERT_EQ(randomize.position_local_x_error.additive.mean(), 2); + ASSERT_EQ(randomize.position_local_x_error.additive.stddev(), 3); + ASSERT_EQ(randomize.position_local_x_error.multiplicative.mean(), 4); + ASSERT_EQ(randomize.position_local_x_error.multiplicative.stddev(), 5); + ASSERT_EQ(randomize.position_local_y_error.additive.mean(), 6); + ASSERT_EQ(randomize.position_local_y_error.additive.stddev(), 7); + ASSERT_EQ(randomize.position_local_y_error.multiplicative.mean(), 8); + ASSERT_EQ(randomize.position_local_y_error.multiplicative.stddev(), 9); + ASSERT_EQ(randomize.position_local_z_error.additive.mean(), 10); + ASSERT_EQ(randomize.position_local_z_error.additive.stddev(), 11); + ASSERT_EQ(randomize.position_local_z_error.multiplicative.mean(), 12); + ASSERT_EQ(randomize.position_local_z_error.multiplicative.stddev(), 13); + ASSERT_EQ(randomize.orientation_r_error.additive.mean(), 14); + ASSERT_EQ(randomize.orientation_r_error.additive.stddev(), 15); + ASSERT_EQ(randomize.orientation_r_error.multiplicative.mean(), 16); + ASSERT_EQ(randomize.orientation_r_error.multiplicative.stddev(), 17); + ASSERT_EQ(randomize.orientation_p_error.additive.mean(), 18); + ASSERT_EQ(randomize.orientation_p_error.additive.stddev(), 19); + ASSERT_EQ(randomize.orientation_p_error.multiplicative.mean(), 20); + ASSERT_EQ(randomize.orientation_p_error.multiplicative.stddev(), 21); + ASSERT_EQ(randomize.orientation_y_error.additive.mean(), 22); + ASSERT_EQ(randomize.orientation_y_error.additive.stddev(), 23); + ASSERT_EQ(randomize.orientation_y_error.multiplicative.mean(), 24); + ASSERT_EQ(randomize.orientation_y_error.multiplicative.stddev(), 25); + ASSERT_EQ(randomize.linear_x_error.additive.mean(), 26); + ASSERT_EQ(randomize.linear_x_error.additive.stddev(), 27); + ASSERT_EQ(randomize.linear_x_error.multiplicative.mean(), 28); + ASSERT_EQ(randomize.linear_x_error.multiplicative.stddev(), 29); + ASSERT_EQ(randomize.linear_y_error.additive.mean(), 30); + ASSERT_EQ(randomize.linear_y_error.additive.stddev(), 31); + ASSERT_EQ(randomize.linear_y_error.multiplicative.mean(), 32); + ASSERT_EQ(randomize.linear_y_error.multiplicative.stddev(), 33); + ASSERT_EQ(randomize.linear_z_error.additive.mean(), 34); + ASSERT_EQ(randomize.linear_z_error.additive.stddev(), 35); + ASSERT_EQ(randomize.linear_z_error.multiplicative.mean(), 36); + ASSERT_EQ(randomize.linear_z_error.multiplicative.stddev(), 37); + ASSERT_EQ(randomize.angular_x_error.additive.mean(), 38); + ASSERT_EQ(randomize.angular_x_error.additive.stddev(), 39); + ASSERT_EQ(randomize.angular_x_error.multiplicative.mean(), 40); + ASSERT_EQ(randomize.angular_x_error.multiplicative.stddev(), 41); + ASSERT_EQ(randomize.angular_y_error.additive.mean(), 42); + ASSERT_EQ(randomize.angular_y_error.additive.stddev(), 43); + ASSERT_EQ(randomize.angular_y_error.multiplicative.mean(), 44); + ASSERT_EQ(randomize.angular_y_error.multiplicative.stddev(), 45); + ASSERT_EQ(randomize.angular_z_error.additive.mean(), 46); + ASSERT_EQ(randomize.angular_z_error.additive.stddev(), 47); + ASSERT_EQ(randomize.angular_z_error.multiplicative.mean(), 48); + ASSERT_EQ(randomize.angular_z_error.multiplicative.stddev(), 49); + // clang-format on + + const auto odometry = nav_msgs::msg::Odometry(); + + const auto randomized_odometry = randomize(odometry); + + // clang-format off + ASSERT_NEAR(randomized_odometry.pose.pose.position.x, 4.0604709175379767, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.pose.pose.position.y, 19.565623431299677, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.pose.pose.position.z, 2.8688348437534232, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.pose.pose.orientation.x, -0.80099847581632522, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.pose.pose.orientation.y, -0.29036040347964753, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.pose.pose.orientation.z, 0.52344585659820897, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.pose.pose.orientation.w, 0.0098342788870005027, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.twist.twist.linear.x, 13.010296958573839, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.twist.twist.linear.y, 42.186386919810495, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.twist.twist.linear.z, 22.434366843481051, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.twist.twist.angular.x, 41.550077290481802, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.twist.twist.angular.y, 40.801412395444473, std::numeric_limits::epsilon()); + ASSERT_NEAR(randomized_odometry.twist.twist.angular.z, 44.530605885302229, std::numeric_limits::epsilon()); + // clang-format on +} From f15bacd819abd2044c2d6c076530a2c4070ded3d Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 12 Feb 2025 14:37:32 +0900 Subject: [PATCH 15/18] Add new document `ConfiguringLocalizationTopics.md` Signed-off-by: yamacir-kit --- docs/developer_guide/.pages | 23 +++++++++--------- .../ConfiguringLocalizationTopics.md | 24 +++++++++++++++++++ 2 files changed, 36 insertions(+), 11 deletions(-) create mode 100644 docs/developer_guide/ConfiguringLocalizationTopics.md diff --git a/docs/developer_guide/.pages b/docs/developer_guide/.pages index 450f1059bcc..949b856adfc 100644 --- a/docs/developer_guide/.pages +++ b/docs/developer_guide/.pages @@ -1,21 +1,22 @@ +# cspell: ignore TIERIV + nav: - About: About.md - AutowareAPI.md + - BehaviorPlugin.md + - CONTRIBUTING.md + - Communication.md + - ConfiguringLocalizationTopics.md + - ConfiguringPerceptionTopics.md - DistanceCalculation.md + - Lane Pose Calculation: lane_pose_calculation + - ManualOverrideWithFollowTrajectoryAction.md - NPCBehavior.md - - BehaviorPlugin.md - # - ErrorCategories.md - OpenSCENARIOSupport.md - SimpleSensorSimulator.md + - SimulationResultFormat.md - SystemArchitecture.md + - TIERIVScenarioFormatVersion2.md - TrafficSimulator.md - - ZeroMQ.md - VehicleDynamics.md - - SimulationResultFormat.md - - Lane Pose Calculation: lane_pose_calculation - # cspell: ignore TIERIV - - TIERIVScenarioFormatVersion2.md - - CONTRIBUTING.md - - Communication.md - - ConfiguringPerceptionTopics.md - - ManualOverrideWithFollowTrajectoryAction.md + - ZeroMQ.md diff --git a/docs/developer_guide/ConfiguringLocalizationTopics.md b/docs/developer_guide/ConfiguringLocalizationTopics.md new file mode 100644 index 00000000000..c0b8918d859 --- /dev/null +++ b/docs/developer_guide/ConfiguringLocalizationTopics.md @@ -0,0 +1,24 @@ +# Configuring Localization Topics + +This section describes properties for configuring localization topics that +`scenario_simulator_v2` publishes to Autoware. + +## Parameter file + +Localization topics are configurable from the ROS 2 parameter file given to the +launch argument `parameter_file_path` of scenario_test_runner. The default +value of `parameter_file_path` is the path to [a sample parameter +file](test_runner/scenario_test_runner/config/parameters.yaml). + +All parameters that can be specified and their default values are shown in the +sample parameter file. In practice, it is not necessary to specify all +parameters except for some that are mandatory. In that case, the simulator will +behave as if similar default values had been specified. + +Most parameters should have their uses understood just by looking at the sample +parameter file or by reading the comments in the file. Below we discuss some +parameters that require additional detailed explanation. + +| Name | Value | Default | Description | +|------------------------|-----------------------------------------|---------------------|----------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| `.version` | An `int` type value in YYYYYMMDD format | None (**madatory**) | Suffix of `scenario_test_runner` launch argument `architecture_type`, used to maintain backward compatibility of the simulator when changing the Autoware interface. | From 04c76fb62312c08614f83f18c540f7066c080533 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Wed, 12 Feb 2025 14:45:21 +0900 Subject: [PATCH 16/18] Fix broken link Signed-off-by: yamacir-kit --- docs/developer_guide/ConfiguringLocalizationTopics.md | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/docs/developer_guide/ConfiguringLocalizationTopics.md b/docs/developer_guide/ConfiguringLocalizationTopics.md index c0b8918d859..103842a5853 100644 --- a/docs/developer_guide/ConfiguringLocalizationTopics.md +++ b/docs/developer_guide/ConfiguringLocalizationTopics.md @@ -8,7 +8,7 @@ This section describes properties for configuring localization topics that Localization topics are configurable from the ROS 2 parameter file given to the launch argument `parameter_file_path` of scenario_test_runner. The default value of `parameter_file_path` is the path to [a sample parameter -file](test_runner/scenario_test_runner/config/parameters.yaml). +file](https://github.com/tier4/scenario_simulator_v2/blob/f15bacd819abd2044c2d6c076530a2c4070ded3d/test_runner/scenario_test_runner/config/parameters.yaml). All parameters that can be specified and their default values are shown in the sample parameter file. In practice, it is not necessary to specify all @@ -19,6 +19,8 @@ Most parameters should have their uses understood just by looking at the sample parameter file or by reading the comments in the file. Below we discuss some parameters that require additional detailed explanation. -| Name | Value | Default | Description | -|------------------------|-----------------------------------------|---------------------|----------------------------------------------------------------------------------------------------------------------------------------------------------------------| -| `.version` | An `int` type value in YYYYYMMDD format | None (**madatory**) | Suffix of `scenario_test_runner` launch argument `architecture_type`, used to maintain backward compatibility of the simulator when changing the Autoware interface. | + + +| Name | Value | Default | Description | +|------------------------|-----------------------------------------|----------------------|----------------------------------------------------------------------------------------------------------------------------------------------------------------------| +| `.version` | An `int` type value in YYYYMMDD format | None (**mandatory**) | Suffix of `scenario_test_runner` launch argument `architecture_type`, used to maintain backward compatibility of the simulator when changing the Autoware interface. | From ed78cb00b4cbe518d46639d6880234a0d38b40d8 Mon Sep 17 00:00:00 2001 From: yamacir-kit Date: Fri, 14 Feb 2025 11:20:14 +0900 Subject: [PATCH 17/18] Update test `normal_distribution.cpp` to use `ASSERT_DOUBLE_EQ` Signed-off-by: yamacir-kit --- .../concealer/test/normal_distribution.cpp | 26 +++++++++---------- .../launch/scenario_test_runner.launch.py | 2 +- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/external/concealer/test/normal_distribution.cpp b/external/concealer/test/normal_distribution.cpp index 9511b214f84..0adceb31ebf 100644 --- a/external/concealer/test/normal_distribution.cpp +++ b/external/concealer/test/normal_distribution.cpp @@ -376,18 +376,18 @@ TEST(NormalDistribution_nav_msgs_msg_Odometry, when_all_parameters_are_given) const auto randomized_odometry = randomize(odometry); // clang-format off - ASSERT_NEAR(randomized_odometry.pose.pose.position.x, 4.0604709175379767, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.pose.pose.position.y, 19.565623431299677, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.pose.pose.position.z, 2.8688348437534232, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.pose.pose.orientation.x, -0.80099847581632522, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.pose.pose.orientation.y, -0.29036040347964753, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.pose.pose.orientation.z, 0.52344585659820897, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.pose.pose.orientation.w, 0.0098342788870005027, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.twist.twist.linear.x, 13.010296958573839, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.twist.twist.linear.y, 42.186386919810495, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.twist.twist.linear.z, 22.434366843481051, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.twist.twist.angular.x, 41.550077290481802, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.twist.twist.angular.y, 40.801412395444473, std::numeric_limits::epsilon()); - ASSERT_NEAR(randomized_odometry.twist.twist.angular.z, 44.530605885302229, std::numeric_limits::epsilon()); + ASSERT_DOUBLE_EQ(randomized_odometry.pose.pose.position.x, 4.0604709175379767 ); + ASSERT_DOUBLE_EQ(randomized_odometry.pose.pose.position.y, 19.565623431299677 ); + ASSERT_DOUBLE_EQ(randomized_odometry.pose.pose.position.z, 2.8688348437534232 ); + ASSERT_DOUBLE_EQ(randomized_odometry.pose.pose.orientation.x, -0.80099847581632522 ); + ASSERT_DOUBLE_EQ(randomized_odometry.pose.pose.orientation.y, -0.29036040347964753 ); + ASSERT_DOUBLE_EQ(randomized_odometry.pose.pose.orientation.z, 0.52344585659820897 ); + ASSERT_DOUBLE_EQ(randomized_odometry.pose.pose.orientation.w, 0.0098342788870005027); + ASSERT_DOUBLE_EQ(randomized_odometry.twist.twist.linear.x, 13.010296958573839 ); + ASSERT_DOUBLE_EQ(randomized_odometry.twist.twist.linear.y, 42.186386919810495 ); + ASSERT_DOUBLE_EQ(randomized_odometry.twist.twist.linear.z, 22.434366843481051 ); + ASSERT_DOUBLE_EQ(randomized_odometry.twist.twist.angular.x, 41.550077290481802 ); + ASSERT_DOUBLE_EQ(randomized_odometry.twist.twist.angular.y, 40.801412395444473 ); + ASSERT_DOUBLE_EQ(randomized_odometry.twist.twist.angular.z, 44.530605885302229 ); // clang-format on } diff --git a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py index 0dd422a51ea..06ba0a68c3d 100755 --- a/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +++ b/test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py @@ -173,7 +173,7 @@ def collect_prefixed_parameters(): if not path.is_file(): raise Exception(f'The value "{path}" given for parameter `parameter_file_path` is not a file.') - elif path.suffix != '.yaml' and path.suffix != '.yml': + elif path.suffix not in {'.yaml', '.yml'}: raise Exception(f'The value "{path}" given for parameter `parameter_file_path` is not a YAML file.') else: parameters += [path] From 2a94cd81074bedcd93a4a0f2ae4c83326f465989 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Fri, 14 Feb 2025 08:55:42 +0000 Subject: [PATCH 18/18] Bump version of scenario_simulator_v2 from version 10.2.0 to version 10.3.0 --- common/math/arithmetic/CHANGELOG.rst | 16 ++++++++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 16 ++++++++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 16 ++++++++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 16 ++++++++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 16 ++++++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 31 +++++++++++++++++++ external/concealer/package.xml | 2 +- external/embree_vendor/CHANGELOG.rst | 16 ++++++++++ external/embree_vendor/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 16 ++++++++++ map/kashiwanoha_map/package.xml | 2 +- map/simple_cross_map/CHANGELOG.rst | 16 ++++++++++ map/simple_cross_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 19 ++++++++++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 16 ++++++++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 16 ++++++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 16 ++++++++++ .../package.xml | 2 +- .../CHANGELOG.rst | 16 ++++++++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 16 ++++++++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 16 ++++++++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 16 ++++++++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_validator/CHANGELOG.rst | 16 ++++++++++ .../openscenario_validator/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 16 ++++++++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 16 ++++++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 16 ++++++++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 16 ++++++++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 16 ++++++++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 16 ++++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 16 ++++++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 16 ++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 16 ++++++++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 16 ++++++++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 26 ++++++++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 58 files changed, 521 insertions(+), 29 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 60f06ab3b56..d508ac1eb28 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package arithmetic * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index 71ca8f12aa5..2a73f1926dd 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 10.2.0 + 10.3.0 arithmetic library for scenario_simulator_v2 Tatsuya Yamasaki Apache License 2.0 diff --git a/common/math/geometry/CHANGELOG.rst b/common/math/geometry/CHANGELOG.rst index 23ddbcee0a7..ca70fab400e 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package geometry * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index ba4970e0f44..534f38c2445 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 10.2.0 + 10.3.0 geometry math library for scenario_simulator_v2 application Masaya Kataoka Apache License 2.0 diff --git a/common/scenario_simulator_exception/CHANGELOG.rst b/common/scenario_simulator_exception/CHANGELOG.rst index ec2a1544198..d7f86742068 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package scenario_simulator_exception * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 5f4c43ae63a..cceb919cf6e 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 10.2.0 + 10.3.0 Exception types for scenario simulator Tatsuya Yamasaki Apache License 2.0 diff --git a/common/simple_junit/CHANGELOG.rst b/common/simple_junit/CHANGELOG.rst index 434250ed0c1..46a91573a13 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package junit_exporter * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index a522dbe7c63..35086e26f2e 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 10.2.0 + 10.3.0 Lightweight JUnit library for ROS 2 Masaya Kataoka Tatsuya Yamasaki diff --git a/common/status_monitor/CHANGELOG.rst b/common/status_monitor/CHANGELOG.rst index 284f5545b7f..7547c38ec4b 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package status_monitor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 0a7ef4045d5..9054b3da4dd 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 10.2.0 + 10.3.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index f9d9ec55df9..44cae0a843e 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -21,6 +21,37 @@ Changelog for package concealer * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge pull request `#1503 `_ from tier4/feature/publisher-with-customizable-randomizer + Feature/publisher with customizable randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Update test `normal_distribution.cpp` to use `ASSERT_DOUBLE_EQ` +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Add new test file `concealer/test/normal_distribution.cpp` +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Rename the parameter `(x|y|z)` to `local\_(x|y|z)` +* Update the position error to apply in the entity's local coordinate +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Cleanup +* Add support for multiplicative errors as well as additive errors +* Update `NormalDistribution` to use `std::normal_distribution` +* Update `NormalDistribution::device` type to `std::mt19937_64` +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Update parameter file format +* Update randomizer to receive `NodeParametersInterface` +* Add new struct template `Identity` +* Add template specialization `NormalDistribution` +* Add new struct template `concealer::NormalDistribution` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 78f09ea08b8..491f813e4e0 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 10.2.0 + 10.3.0 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/external/embree_vendor/CHANGELOG.rst b/external/embree_vendor/CHANGELOG.rst index 9e8c50719b4..92bf332f5ff 100644 --- a/external/embree_vendor/CHANGELOG.rst +++ b/external/embree_vendor/CHANGELOG.rst @@ -24,6 +24,22 @@ Changelog for package embree_vendor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/external/embree_vendor/package.xml b/external/embree_vendor/package.xml index 0af4b097d57..2984cbf94c9 100644 --- a/external/embree_vendor/package.xml +++ b/external/embree_vendor/package.xml @@ -2,7 +2,7 @@ embree_vendor - 10.2.0 + 10.3.0 vendor packages for intel raytracing kernel library masaya Apache 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index ddf42f52d6c..43bf979d121 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package kashiwanoha_map * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index df919e0c250..4986a844cab 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 10.2.0 + 10.3.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/map/simple_cross_map/CHANGELOG.rst b/map/simple_cross_map/CHANGELOG.rst index 1d41b3923cf..8e78b52f326 100644 --- a/map/simple_cross_map/CHANGELOG.rst +++ b/map/simple_cross_map/CHANGELOG.rst @@ -9,6 +9,22 @@ Changelog for package simple_cross_map * Merge branch 'master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/map/simple_cross_map/package.xml b/map/simple_cross_map/package.xml index 222903cd56a..a768f5b5f59 100644 --- a/map/simple_cross_map/package.xml +++ b/map/simple_cross_map/package.xml @@ -2,7 +2,7 @@ simple_cross_map - 10.2.0 + 10.3.0 map package for simple cross Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 31fb667bf6f..86e61f7be5f 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -21,6 +21,25 @@ Changelog for package cpp_mock_scenarios * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge pull request `#1503 `_ from tier4/feature/publisher-with-customizable-randomizer + Feature/publisher with customizable randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Add launch argument `parameter_file_path` to `scenario_test_runner` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index a52caa549d1..82b8dae4c0f 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 10.2.0 + 10.3.0 C++ mock scenarios masaya Apache License 2.0 diff --git a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst index 2c2dce33fc2..66721f91dc0 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package openscenario_experimental_catalog * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index af46ed555b9..562975568ab 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 10.2.0 + 10.3.0 TIER IV experimental catalogs for OpenSCENARIO Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter/CHANGELOG.rst b/openscenario/openscenario_interpreter/CHANGELOG.rst index 165e2448ca4..70ffd5fc46d 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -32,6 +32,22 @@ Changelog for package openscenario_interpreter * add publish_empty_context parameter * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge pull request `#1524 `_ from tier4/feature/rosbag_storage diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 93b3fc6411c..97b9a82e536 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 10.2.0 + 10.3.0 OpenSCENARIO 1.2.0 interpreter package for Autoware Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_example/CHANGELOG.rst b/openscenario/openscenario_interpreter_example/CHANGELOG.rst index bfb0bd43f71..7fc06069b58 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package openscenario_interpreter_example * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 56398759db2..117f6a1920a 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 10.2.0 + 10.3.0 Examples for some TIER IV OpenSCENARIO Interpreter's features Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst index d1efa786c55..29bd408e932 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package openscenario_interpreter_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index a955b3e2dcf..3efaadee93d 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 10.2.0 + 10.3.0 ROS message types for package openscenario_interpreter Yamasaki Tatsuya Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor/CHANGELOG.rst b/openscenario/openscenario_preprocessor/CHANGELOG.rst index be451a92f88..c26ecd159b6 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package openscenario_preprocessor * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index c209e360b53..8349e6b4831 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 10.2.0 + 10.3.0 Example package for TIER IV OpenSCENARIO Interpreter Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst index 2858dab7edd..d35b269c3f5 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package openscenario_preprocessor_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index 80eb7b2f9ba..6b91d60cfae 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 10.2.0 + 10.3.0 ROS message types for package openscenario_preprocessor Kotaro Yoshimoto Apache License 2.0 diff --git a/openscenario/openscenario_utility/CHANGELOG.rst b/openscenario/openscenario_utility/CHANGELOG.rst index fb8fa15d831..f6fab0c39a4 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -24,6 +24,22 @@ Changelog for package openscenario_utility * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 667587318b6..9cf6de4dfcb 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 10.2.0 + 10.3.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_validator/CHANGELOG.rst b/openscenario/openscenario_validator/CHANGELOG.rst index d89a7ad87f5..3d0ca8739ba 100644 --- a/openscenario/openscenario_validator/CHANGELOG.rst +++ b/openscenario/openscenario_validator/CHANGELOG.rst @@ -10,6 +10,22 @@ Changelog for package openscenario_validator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/openscenario/openscenario_validator/package.xml b/openscenario/openscenario_validator/package.xml index 789278cea74..008e6bc5492 100644 --- a/openscenario/openscenario_validator/package.xml +++ b/openscenario/openscenario_validator/package.xml @@ -2,7 +2,7 @@ openscenario_validator - 10.2.0 + 10.3.0 Validator for OpenSCENARIO 1.3 Kotaro Yoshimoto Apache License 2.0 diff --git a/rviz_plugins/openscenario_visualization/CHANGELOG.rst b/rviz_plugins/openscenario_visualization/CHANGELOG.rst index b5322f7f5b5..2934dc4cdb9 100644 --- a/rviz_plugins/openscenario_visualization/CHANGELOG.rst +++ b/rviz_plugins/openscenario_visualization/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package openscenario_visualization * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/rviz_plugins/openscenario_visualization/package.xml b/rviz_plugins/openscenario_visualization/package.xml index f121a23f68c..763f74ceb83 100644 --- a/rviz_plugins/openscenario_visualization/package.xml +++ b/rviz_plugins/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 10.2.0 + 10.3.0 Visualization tools for simulation results Masaya Kataoka Kyoichi Sugahara diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst index f835fcf51b9..64a84126eb2 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package real_time_factor_control_rviz_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml index ffff7071398..1b70f8e4ecb 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/package.xml @@ -2,7 +2,7 @@ real_time_factor_control_rviz_plugin - 10.2.0 + 10.3.0 Slider controlling real time factor value. Paweł Lech Apache License 2.0 diff --git a/scenario_simulator_v2/CHANGELOG.rst b/scenario_simulator_v2/CHANGELOG.rst index 80743265b71..d323f8d34ec 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package scenario_simulator_v2 * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index bea4e17abbe..ed51847e793 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 10.2.0 + 10.3.0 scenario testing framework for Autoware Masaya Kataoka Apache License 2.0 diff --git a/simulation/behavior_tree_plugin/CHANGELOG.rst b/simulation/behavior_tree_plugin/CHANGELOG.rst index 2506b1739c2..1cc279d8d13 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package behavior_tree_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 822bb8a1b3f..3ffd76edc70 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 10.2.0 + 10.3.0 Behavior tree plugin for traffic_simulator masaya Apache 2.0 diff --git a/simulation/do_nothing_plugin/CHANGELOG.rst b/simulation/do_nothing_plugin/CHANGELOG.rst index 64390eb4ab9..9833f74d29e 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package do_nothing_plugin * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 97a71f33198..dce3c9911dc 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 10.2.0 + 10.3.0 Behavior plugin for do nothing Masaya Kataoka Apache 2.0 diff --git a/simulation/simple_sensor_simulator/CHANGELOG.rst b/simulation/simple_sensor_simulator/CHANGELOG.rst index 2d988f15632..7c13b166e89 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package simple_sensor_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 1080f00849a..7eb097f2c1f 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 10.2.0 + 10.3.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 9373d6ff6ee..113894b906a 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package simulation_interface * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 29aee921296..b9085d4bc2b 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 10.2.0 + 10.3.0 packages to define interface between simulator and scenario interpreter Masaya Kataoka Apache License 2.0 diff --git a/simulation/traffic_simulator/CHANGELOG.rst b/simulation/traffic_simulator/CHANGELOG.rst index efbd662edb2..168802e913b 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package traffic_simulator * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 07b2f173acc..c062f8939b3 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 10.2.0 + 10.3.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 538de991677..7f6a4cead5f 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package openscenario_msgs * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index d58a79ef0d1..455bde6f60d 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 10.2.0 + 10.3.0 ROS messages for openscenario Masaya Kataoka Apache License 2.0 diff --git a/test_runner/random_test_runner/CHANGELOG.rst b/test_runner/random_test_runner/CHANGELOG.rst index dc1e5f306c9..8c1985aeffb 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -21,6 +21,22 @@ Changelog for package random_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge branch 'master' into feature/rosbag_storage diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 5af239022a8..4b2aac7506f 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 10.2.0 + 10.3.0 Random behavior test runner piotr-zyskowski-rai Apache License 2.0 diff --git a/test_runner/scenario_test_runner/CHANGELOG.rst b/test_runner/scenario_test_runner/CHANGELOG.rst index b09accf062d..84edfe18ee9 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -35,6 +35,32 @@ Changelog for package scenario_test_runner * Merge remote-tracking branch 'origin/master' into feature/publish_empty_context * Contributors: Masaya Kataoka +10.3.0 (2025-02-14) +------------------- +* Merge pull request `#1503 `_ from tier4/feature/publisher-with-customizable-randomizer + Feature/publisher with customizable randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Update test `normal_distribution.cpp` to use `ASSERT_DOUBLE_EQ` +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Update `scenario_test_runner` to check the path given as a parameter +* Rename the parameter `(x|y|z)` to `local\_(x|y|z)` +* Update the position error to apply in the entity's local coordinate +* Merge branch 'master' into feature/publisher-with-customizable-randomizer +* Add support for multiplicative errors as well as additive errors +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Merge remote-tracking branch 'origin/master' into feature/publisher-with-customizable-randomizer +* Update parameter file format +* Update randomizer to receive `NodeParametersInterface` +* Add launch argument `parameter_file_path` to `scenario_test_runner` +* Contributors: Tatsuya Yamasaki, yamacir-kit + 10.2.0 (2025-02-14) ------------------- * Merge pull request `#1524 `_ from tier4/feature/rosbag_storage diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 02685cb2068..205ee163800 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 10.2.0 + 10.3.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0