From 66e9e7710803ac898d2ab2d424e511223cc7f97f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 31 Jan 2024 15:17:46 +0900 Subject: [PATCH 01/24] doc: add memos to code Signed-off-by: Kotaro Yoshimoto --- external/concealer/src/autoware_universe.cpp | 2 ++ .../src/vehicle_simulation/ego_entity_simulation.cpp | 4 ++-- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/external/concealer/src/autoware_universe.cpp b/external/concealer/src/autoware_universe.cpp index de8ed46b214..dce5f359825 100644 --- a/external/concealer/src/autoware_universe.cpp +++ b/external/concealer/src/autoware_universe.cpp @@ -156,6 +156,8 @@ auto AutowareUniverse::getGearCommand() const -> autoware_auto_vehicle_msgs::msg auto AutowareUniverse::getGearSign() const -> double { using autoware_auto_vehicle_msgs::msg::GearCommand; + // TODO: Add support for GearCommand::NONE to return 0.0 + // ref: https://github.com/autowarefoundation/autoware.universe/blob/main/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp#L475 return getGearCommand().command == GearCommand::REVERSE or getGearCommand().command == GearCommand::REVERSE_2 ? -1.0 diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 428ca770686..35097e1fca8 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -105,8 +105,8 @@ auto EgoEntitySimulation::makeSimulationModel( const auto steer_time_delay = getParameter("steer_time_delay", 0.24); const auto vel_lim = getParameter("vel_lim", parameters.performance.max_speed); // 50.0 const auto vel_rate_lim = getParameter("vel_rate_lim", parameters.performance.max_acceleration); // 7.0 - const auto vel_time_constant = getParameter("vel_time_constant", 0.1); - const auto vel_time_delay = getParameter("vel_time_delay", 0.1); + const auto vel_time_constant = getParameter("vel_time_constant", 0.1); // 0.5 is default value on simple_planning_simulator + const auto vel_time_delay = getParameter("vel_time_delay", 0.1); // 0.25 is default value on simple_planning_simulator const auto wheel_base = getParameter("wheel_base", parameters.axles.front_axle.position_x - parameters.axles.rear_axle.position_x); // clang-format on From defed9e8da4fb7fe2f310fe6bbdbbb18c3465e3d Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 31 Jan 2024 17:50:00 +0900 Subject: [PATCH 02/24] feat(ego_entity_simulation): consider slope in ego entity simulation Signed-off-by: Kotaro Yoshimoto --- .../ego_entity_simulation.hpp | 4 +- .../ego_entity_simulation.cpp | 81 ++++++++++++++++++- 2 files changed, 80 insertions(+), 5 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp index 3d306a67f29..625a595ebd7 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp @@ -64,7 +64,9 @@ class EgoEntitySimulation const std::shared_ptr hdmap_utils_ptr_; private: - auto getCurrentPose() const -> geometry_msgs::msg::Pose; + auto calculateEgoPitch() const -> double; + + auto getCurrentPose(const double pitch_angle) const -> geometry_msgs::msg::Pose; auto getCurrentTwist() const -> geometry_msgs::msg::Twist; diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 35097e1fca8..3743e5002da 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -263,13 +263,22 @@ void EgoEntitySimulation::update( } else { auto input = Eigen::VectorXd(vehicle_model_ptr_->getDimU()); + auto acceleration_by_slope = not consider_road_slope_ ? 0.0 : [this]() { + // calculate longitudinal acceleration by slope + constexpr double gravity_acceleration = -9.81; + const double ego_pitch_angle = calculateEgoPitch(); + const double slope_angle = -ego_pitch_angle; + return gravity_acceleration * std::sin(slope_angle); + }(); + switch (vehicle_model_type_) { case VehicleModelType::DELAY_STEER_ACC: case VehicleModelType::DELAY_STEER_ACC_GEARED: case VehicleModelType::DELAY_STEER_MAP_ACC_GEARED: case VehicleModelType::IDEAL_STEER_ACC: case VehicleModelType::IDEAL_STEER_ACC_GEARED: - input(0) = autoware->getGearSign() * autoware->getAcceleration(); + input(0) = + autoware->getGearSign() * (autoware->getAcceleration() + acceleration_by_slope); input(1) = autoware->getSteeringAngle(); break; @@ -294,6 +303,69 @@ void EgoEntitySimulation::update( updatePreviousValues(); } +auto EgoEntitySimulation::calculateEgoPitch() const -> double +{ + const double ego_x = vehicle_model_ptr_->getX(); + const double ego_y = vehicle_model_ptr_->getY(); + const double ego_yaw = vehicle_model_ptr_->getYaw(); + + geometry_msgs::msg::Pose ego_pose; + ego_pose.position.x = ego_x; + ego_pose.position.y = ego_y; + ego_pose.orientation = quaternion_operation::convertEulerAngleToQuaternion( + traffic_simulator::helper::constructRPY(0., 0., ego_yaw)); + + // calculate prev/next point of lanelet centerline nearest to ego pose. + auto ego_lanelet_id = hdmap_utils_ptr_->getClosestLaneletId(ego_pose, 2.0); + if (not ego_lanelet_id) { + return 0.0; + } + + auto centerline_points = hdmap_utils_ptr_->getCenterPoints(ego_lanelet_id.value()); + + // copied from motion_util::findNearestSegmentIndex + auto find_nearest_segment_index = []( + const std::vector & points, + const geometry_msgs::msg::Point & point) { + assert(not points.empty()); + + double min_dist = std::numeric_limits::max(); + size_t min_idx = 0; + + for (size_t i = 0; i < points.size(); ++i) { + const auto dist = [](const auto point1, const auto point2) { + const auto dx = point1.x - point2.x; + const auto dy = point1.y - point2.y; + return dx * dx + dy * dy; + }(points.at(i), point); + + if (dist < min_dist) { + min_dist = dist; + min_idx = i; + } + } + return min_idx; + }; + + const size_t ego_seg_idx = find_nearest_segment_index(centerline_points, ego_pose.position); + + const auto & prev_point = centerline_points.at(ego_seg_idx); + const auto & next_point = centerline_points.at(ego_seg_idx + 1); + + // calculate ego yaw angle on lanelet coordinates + const double lanelet_yaw = std::atan2(next_point.y - prev_point.y, next_point.x - prev_point.x); + const double ego_yaw_against_lanelet = ego_yaw - lanelet_yaw; + + // calculate ego pitch angle considering ego yaw. + const double diff_z = next_point.z - prev_point.z; + const double diff_xy = std::hypot(next_point.x - prev_point.x, next_point.y - prev_point.y) / + std::cos(ego_yaw_against_lanelet); + const bool reverse_sign = std::cos(ego_yaw_against_lanelet) < 0.0; + const double ego_pitch_angle = + reverse_sign ? -std::atan2(-diff_z, -diff_xy) : -std::atan2(diff_z, diff_xy); + return ego_pitch_angle; +} + auto EgoEntitySimulation::getCurrentTwist() const -> geometry_msgs::msg::Twist { geometry_msgs::msg::Twist current_twist; @@ -302,7 +374,8 @@ auto EgoEntitySimulation::getCurrentTwist() const -> geometry_msgs::msg::Twist return current_twist; } -auto EgoEntitySimulation::getCurrentPose() const -> geometry_msgs::msg::Pose +auto EgoEntitySimulation::getCurrentPose(const double pitch_angle = 0.) const + -> geometry_msgs::msg::Pose { Eigen::VectorXd relative_position(3); relative_position(0) = vehicle_model_ptr_->getX(); @@ -315,10 +388,10 @@ auto EgoEntitySimulation::getCurrentPose() const -> geometry_msgs::msg::Pose current_pose.position.x = initial_pose_.position.x + relative_position(0); current_pose.position.y = initial_pose_.position.y + relative_position(1); current_pose.position.z = initial_pose_.position.z + relative_position(2); - current_pose.orientation = [this]() { + current_pose.orientation = [&]() { geometry_msgs::msg::Vector3 rpy; rpy.x = 0; - rpy.y = 0; + rpy.y = pitch_angle; rpy.z = vehicle_model_ptr_->getYaw(); return initial_pose_.orientation * quaternion_operation::convertEulerAngleToQuaternion(rpy); }(); From ada5f90b047e06cba1eac0899fef069a9caf41fa Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 31 Jan 2024 17:50:30 +0900 Subject: [PATCH 03/24] feat(ego_entity_simulation): add flog for considering slope in ego entity simulation Signed-off-by: Kotaro Yoshimoto --- .../vehicle_simulation/ego_entity_simulation.hpp | 2 ++ .../src/vehicle_simulation/ego_entity_simulation.cpp | 3 ++- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp index 625a595ebd7..4cc63686d8c 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp @@ -60,6 +60,8 @@ class EgoEntitySimulation traffic_simulator_msgs::msg::EntityStatus status_; + bool consider_road_slope_ = false; + public: const std::shared_ptr hdmap_utils_ptr_; diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 3743e5002da..628416da5a9 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -38,7 +38,8 @@ EgoEntitySimulation::EgoEntitySimulation( : autoware(std::make_unique()), vehicle_model_type_(getVehicleModelType()), vehicle_model_ptr_(makeSimulationModel(vehicle_model_type_, step_time, parameters)), - hdmap_utils_ptr_(hdmap_utils) + hdmap_utils_ptr_(hdmap_utils), + consider_road_slope_(getParameter("consider_road_slope", false)) { } From a4ef2cdada30a6a2eca3bf08bb88d2a725fb000e Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 2 Feb 2024 15:02:51 +0900 Subject: [PATCH 04/24] refactor(ego_entity_simulation): rename flag name for considering slope in ego entity simulation Signed-off-by: Kotaro Yoshimoto --- .../vehicle_simulation/ego_entity_simulation.hpp | 2 +- .../src/vehicle_simulation/ego_entity_simulation.cpp | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp index 4cc63686d8c..2c53e1369a9 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp @@ -60,7 +60,7 @@ class EgoEntitySimulation traffic_simulator_msgs::msg::EntityStatus status_; - bool consider_road_slope_ = false; + const bool consider_acceleration_by_road_slope_; public: const std::shared_ptr hdmap_utils_ptr_; diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 628416da5a9..fc92eade932 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -39,7 +39,8 @@ EgoEntitySimulation::EgoEntitySimulation( vehicle_model_type_(getVehicleModelType()), vehicle_model_ptr_(makeSimulationModel(vehicle_model_type_, step_time, parameters)), hdmap_utils_ptr_(hdmap_utils), - consider_road_slope_(getParameter("consider_road_slope", false)) + consider_acceleration_by_road_slope_( + getParameter("consider_acceleration_by_road_slope", false)) { } @@ -264,7 +265,7 @@ void EgoEntitySimulation::update( } else { auto input = Eigen::VectorXd(vehicle_model_ptr_->getDimU()); - auto acceleration_by_slope = not consider_road_slope_ ? 0.0 : [this]() { + auto acceleration_by_slope = not consider_acceleration_by_road_slope_ ? 0.0 : [this]() { // calculate longitudinal acceleration by slope constexpr double gravity_acceleration = -9.81; const double ego_pitch_angle = calculateEgoPitch(); From f390e2219aa0df907c84666b8ee7320863fdbb88 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Fri, 2 Feb 2024 15:11:33 +0900 Subject: [PATCH 05/24] feat(scenario_test_runner): add consider_acceleration_by_road_slope for simple_sensor_simulator Signed-off-by: Kotaro Yoshimoto --- .../launch/scenario_test_runner.launch.py | 117 +++++++++--------- 1 file changed, 60 insertions(+), 57 deletions(-) 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 047b9515896..36d6a688fbb 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 @@ -60,45 +60,47 @@ def default_autoware_launch_file_of(architecture_type): def launch_setup(context, *args, **kwargs): # fmt: off - architecture_type = LaunchConfiguration("architecture_type", default="awf/universe") - autoware_launch_file = LaunchConfiguration("autoware_launch_file", default=default_autoware_launch_file_of(architecture_type.perform(context))) - autoware_launch_package = LaunchConfiguration("autoware_launch_package", default=default_autoware_launch_package_of(architecture_type.perform(context))) - global_frame_rate = LaunchConfiguration("global_frame_rate", default=30.0) - global_real_time_factor = LaunchConfiguration("global_real_time_factor", default=1.0) - global_timeout = LaunchConfiguration("global_timeout", default=180) - initialize_duration = LaunchConfiguration("initialize_duration", default=30) - launch_autoware = LaunchConfiguration("launch_autoware", default=True) - 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")) - port = LaunchConfiguration("port", default=5555) - record = LaunchConfiguration("record", default=True) - rviz_config = LaunchConfiguration("rviz_config", default="") - scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) - sensor_model = LaunchConfiguration("sensor_model", default="") - sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) - vehicle_model = LaunchConfiguration("vehicle_model", default="") - workflow = LaunchConfiguration("workflow", default=Path("/dev/null")) + architecture_type = LaunchConfiguration("architecture_type", default="awf/universe") + autoware_launch_file = LaunchConfiguration("autoware_launch_file", default=default_autoware_launch_file_of(architecture_type.perform(context))) + autoware_launch_package = LaunchConfiguration("autoware_launch_package", default=default_autoware_launch_package_of(architecture_type.perform(context))) + consider_acceleration_by_road_slope = LaunchConfiguration("consider_acceleration_by_road_slope", default=False) + global_frame_rate = LaunchConfiguration("global_frame_rate", default=30.0) + global_real_time_factor = LaunchConfiguration("global_real_time_factor", default=1.0) + global_timeout = LaunchConfiguration("global_timeout", default=180) + initialize_duration = LaunchConfiguration("initialize_duration", default=30) + launch_autoware = LaunchConfiguration("launch_autoware", default=True) + 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")) + port = LaunchConfiguration("port", default=5555) + record = LaunchConfiguration("record", default=True) + rviz_config = LaunchConfiguration("rviz_config", default="") + scenario = LaunchConfiguration("scenario", default=Path("/dev/null")) + sensor_model = LaunchConfiguration("sensor_model", default="") + sigterm_timeout = LaunchConfiguration("sigterm_timeout", default=8) + vehicle_model = LaunchConfiguration("vehicle_model", default="") + workflow = LaunchConfiguration("workflow", default=Path("/dev/null")) # fmt: on - print(f"architecture_type := {architecture_type.perform(context)}") - print(f"autoware_launch_file := {autoware_launch_file.perform(context)}") - print(f"autoware_launch_package := {autoware_launch_package.perform(context)}") - print(f"global_frame_rate := {global_frame_rate.perform(context)}") - print(f"global_real_time_factor := {global_real_time_factor.perform(context)}") - print(f"global_timeout := {global_timeout.perform(context)}") - print(f"initialize_duration := {initialize_duration.perform(context)}") - 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"port := {port.perform(context)}") - print(f"record := {record.perform(context)}") - print(f"rviz_config := {rviz_config.perform(context)}") - print(f"scenario := {scenario.perform(context)}") - print(f"sensor_model := {sensor_model.perform(context)}") - print(f"sigterm_timeout := {sigterm_timeout.perform(context)}") - print(f"vehicle_model := {vehicle_model.perform(context)}") - print(f"workflow := {workflow.perform(context)}") + print(f"architecture_type := {architecture_type.perform(context)}") + print(f"autoware_launch_file := {autoware_launch_file.perform(context)}") + print(f"autoware_launch_package := {autoware_launch_package.perform(context)}") + print(f"consider_acceleration_by_road_slope := {consider_acceleration_by_road_slope.perform(context)}") + print(f"global_frame_rate := {global_frame_rate.perform(context)}") + print(f"global_real_time_factor := {global_real_time_factor.perform(context)}") + print(f"global_timeout := {global_timeout.perform(context)}") + print(f"initialize_duration := {initialize_duration.perform(context)}") + 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"port := {port.perform(context)}") + print(f"record := {record.perform(context)}") + print(f"rviz_config := {rviz_config.perform(context)}") + print(f"scenario := {scenario.perform(context)}") + print(f"sensor_model := {sensor_model.perform(context)}") + print(f"sigterm_timeout := {sigterm_timeout.perform(context)}") + print(f"vehicle_model := {vehicle_model.perform(context)}") + print(f"workflow := {workflow.perform(context)}") def make_parameters(): parameters = [ @@ -115,7 +117,7 @@ def make_parameters(): ] parameters += make_vehicle_parameters() return parameters - + def make_vehicle_parameters(): parameters = [] @@ -131,21 +133,21 @@ def description(): return [ # fmt: off - DeclareLaunchArgument("architecture_type", default_value=architecture_type ), - DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file ), + DeclareLaunchArgument("architecture_type", default_value=architecture_type), + DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file), DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package), - DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate ), + DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate), DeclareLaunchArgument("global_real_time_factor", default_value=global_real_time_factor), - DeclareLaunchArgument("global_timeout", default_value=global_timeout ), - DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ), - DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ), - DeclareLaunchArgument("output_directory", default_value=output_directory ), - 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("vehicle_model", default_value=vehicle_model ), - DeclareLaunchArgument("workflow", default_value=workflow ), + DeclareLaunchArgument("global_timeout", default_value=global_timeout), + DeclareLaunchArgument("launch_autoware", default_value=launch_autoware), + DeclareLaunchArgument("launch_rviz", default_value=launch_rviz), + DeclareLaunchArgument("output_directory", default_value=output_directory), + 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("vehicle_model", default_value=vehicle_model), + DeclareLaunchArgument("workflow", default_value=workflow), # fmt: on Node( package="scenario_test_runner", @@ -156,12 +158,12 @@ def description(): on_exit=ShutdownOnce(), arguments=[ # fmt: off - "--global-frame-rate", global_frame_rate, + "--global-frame-rate", global_frame_rate, "--global-real-time-factor", global_real_time_factor, - "--global-timeout", global_timeout, - "--output-directory", output_directory, - "--scenario", scenario, - "--workflow", workflow, + "--global-timeout", global_timeout, + "--output-directory", output_directory, + "--scenario", scenario, + "--workflow", workflow, # fmt: on ], ), @@ -171,7 +173,8 @@ def description(): namespace="simulation", output="screen", on_exit=ShutdownOnce(), - parameters=[{"port": port}]+make_vehicle_parameters(), + parameters=[{"port": port}, {"consider_acceleration_by_road_slope", + consider_acceleration_by_road_slope}] + make_vehicle_parameters(), condition=IfCondition(launch_simple_sensor_simulator), ), # The `name` keyword overrides the name for all created nodes, so duplicated nodes appear. From 184ee8e46e4b9024a9f68206b800d307851a8864 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Thu, 15 Feb 2024 14:51:00 +0900 Subject: [PATCH 06/24] chore: format Signed-off-by: Kotaro Yoshimoto --- .../src/vehicle_simulation/ego_entity_simulation.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index a608735fbba..4083b616e55 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -42,7 +42,7 @@ EgoEntitySimulation::EgoEntitySimulation( hdmap_utils_ptr_(hdmap_utils), vehicle_parameters(parameters), consider_acceleration_by_road_slope_( - getParameter("consider_acceleration_by_road_slope", false)) + getParameter("consider_acceleration_by_road_slope", false)) { autoware->set_parameter(use_sim_time); } From 3871e2068058e04e9a2b9eae337f200f9683ae55 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 19 Feb 2024 10:20:34 +0900 Subject: [PATCH 07/24] chore: format Signed-off-by: Kotaro Yoshimoto --- .../launch/scenario_test_runner.launch.py | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) 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 eb2b069adfa..69dc42ddaaf 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 @@ -136,22 +136,22 @@ def description(): return [ # fmt: off - DeclareLaunchArgument("architecture_type", default_value=architecture_type), - DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file), + DeclareLaunchArgument("architecture_type", default_value=architecture_type ), + DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file ), DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package), - DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate), + DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate ), DeclareLaunchArgument("global_real_time_factor", default_value=global_real_time_factor), - DeclareLaunchArgument("global_timeout", default_value=global_timeout), - DeclareLaunchArgument("launch_autoware", default_value=launch_autoware), - DeclareLaunchArgument("launch_rviz", default_value=launch_rviz), - DeclareLaunchArgument("output_directory", default_value=output_directory), - 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("global_timeout", default_value=global_timeout ), + DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ), + DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ), + DeclareLaunchArgument("output_directory", default_value=output_directory ), + 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("use_sim_time", default_value=use_sim_time ), - DeclareLaunchArgument("vehicle_model", default_value=vehicle_model), - DeclareLaunchArgument("workflow", default_value=workflow), + DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ), + DeclareLaunchArgument("workflow", default_value=workflow ), # fmt: on Node( package="scenario_test_runner", From 4e7f42feb646a6af1d3e3cac5d39c4f6ab2cdbf3 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Mon, 19 Feb 2024 10:27:14 +0900 Subject: [PATCH 08/24] doc: add notification to duplicated lane matching algorithm Signed-off-by: Kotaro Yoshimoto --- .../src/vehicle_simulation/ego_entity_simulation.cpp | 1 + simulation/traffic_simulator/src/entity/ego_entity.cpp | 2 ++ 2 files changed, 3 insertions(+) diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 4083b616e55..3d09f35dcca 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -473,6 +473,7 @@ auto EgoEntitySimulation::fillLaneletDataAndSnapZToLanelet( traffic_simulator::helper::getUniqueValues(autoware->getRouteLanelets()); std::optional lanelet_pose; + // the lanelet matching algorithm should be equivalent to the one used in EgoEntity::setMapPose const auto get_matching_length = [&] { return std::max( vehicle_parameters.axles.front_axle.track_width, diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index a9fb5ac3fc1..aea0e89b002 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -275,6 +275,8 @@ auto EgoEntity::setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void { const auto unique_route_lanelets = traffic_simulator::helper::getUniqueValues(getRouteLanelets()); std::optional lanelet_pose; + + // the lanelet matching algorithm should be equivalent to the one used in EgoEntitySimulation::fillLaneletDataAndSnapZToLanelet const auto get_matching_length = [&] { return std::max( vehicle_parameters.axles.front_axle.track_width, From 54faa275e75e01f24527492c430c631bd6e309de Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Fri, 16 Feb 2024 19:12:55 +0900 Subject: [PATCH 09/24] change example Signed-off-by: Masaya Kataoka Signed-off-by: Kotaro Yoshimoto --- .github/pull_request_samples/example_detail.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/pull_request_samples/example_detail.md b/.github/pull_request_samples/example_detail.md index c31fe9672cd..a9beca2f5d2 100644 --- a/.github/pull_request_samples/example_detail.md +++ b/.github/pull_request_samples/example_detail.md @@ -28,8 +28,8 @@ This PR fixes how the length of the curve is computed ## References -- [determine-arc-length-of-a-catmull-rom-spline-to-move-at-a-constant-speed](https://gamedev.stackexchange.com/questions/14985/determine-arc-length-of-a-catmull-rom-spline-to-move-at-a-constant-speed) - - This link is an example and is not directly related to this sample. +Please check [this document about spline curve.](https://people.computing.clemson.edu/~dhouse/courses/405/notes/splines.pdf) +This link is an example and is not directly related to this sample. # Destructive Changes From 2bf107c7df60faef60de2665e586ab0c5138bc71 Mon Sep 17 00:00:00 2001 From: Masaya Kataoka Date: Fri, 16 Feb 2024 19:16:42 +0900 Subject: [PATCH 10/24] change link Signed-off-by: Masaya Kataoka --- .github/pull_request_samples/example_detail.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/pull_request_samples/example_detail.md b/.github/pull_request_samples/example_detail.md index a9beca2f5d2..caea007de38 100644 --- a/.github/pull_request_samples/example_detail.md +++ b/.github/pull_request_samples/example_detail.md @@ -28,7 +28,7 @@ This PR fixes how the length of the curve is computed ## References -Please check [this document about spline curve.](https://people.computing.clemson.edu/~dhouse/courses/405/notes/splines.pdf) +See also [this document.](https://tier4.github.io/scenario_simulator_v2-docs/) This link is an example and is not directly related to this sample. # Destructive Changes From 8e18decbbd14ebe418583a9e7846f38e14210d1a Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 20 Feb 2024 21:21:02 +0900 Subject: [PATCH 11/24] fix: pass consider_acceleration_by_road_slope to inside of EgoEntitySimulator --- .../vehicle_simulation/ego_entity_simulation.hpp | 4 +++- .../src/simple_sensor_simulator.cpp | 9 ++++++++- .../src/vehicle_simulation/ego_entity_simulation.cpp | 5 ++--- .../launch/scenario_test_runner.launch.py | 5 +++-- 4 files changed, 16 insertions(+), 7 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp index 47a0c644f9b..c55c0b82f34 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp @@ -64,6 +64,7 @@ class EgoEntitySimulation public: const std::shared_ptr hdmap_utils_ptr_; + const traffic_simulator_msgs::msg::VehicleParameters vehicle_parameters; private: @@ -84,7 +85,8 @@ class EgoEntitySimulation explicit EgoEntitySimulation( const traffic_simulator_msgs::msg::VehicleParameters &, double, - const std::shared_ptr &, const rclcpp::Parameter & use_sim_time); + const std::shared_ptr &, const rclcpp::Parameter & use_sim_time, + const bool consider_acceleration_by_road_slope); auto update(double time, double step_time, bool npc_logic_started) -> void; diff --git a/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp b/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp index 798c9871a25..9a5253c5304 100644 --- a/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp +++ b/simulation/simple_sensor_simulator/src/simple_sensor_simulator.cpp @@ -207,9 +207,16 @@ auto ScenarioSimulator::spawnVehicleEntity( ego_vehicles_.emplace_back(req.parameters()); traffic_simulator_msgs::msg::VehicleParameters parameters; simulation_interface::toMsg(req.parameters(), parameters); + auto get_consider_acceleration_by_road_slope = [&]() { + if (!has_parameter("consider_acceleration_by_road_slope")) { + declare_parameter("consider_acceleration_by_road_slope", false); + } + return get_parameter("consider_acceleration_by_road_slope").as_bool(); + }; ego_entity_simulation_ = std::make_shared( parameters, step_time_, hdmap_utils_, - get_parameter_or("use_sim_time", rclcpp::Parameter("use_sim_time", false))); + get_parameter_or("use_sim_time", rclcpp::Parameter("use_sim_time", false)), + get_consider_acceleration_by_road_slope()); traffic_simulator_msgs::msg::EntityStatus initial_status; initial_status.name = parameters.name; simulation_interface::toMsg(req.pose(), initial_status.pose); diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 3d09f35dcca..197723ba3af 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -35,14 +35,13 @@ static auto getParameter(const std::string & name, T value = {}) EgoEntitySimulation::EgoEntitySimulation( const traffic_simulator_msgs::msg::VehicleParameters & parameters, double step_time, const std::shared_ptr & hdmap_utils, - const rclcpp::Parameter & use_sim_time) + const rclcpp::Parameter & use_sim_time, const bool consider_acceleration_by_road_slope) : autoware(std::make_unique()), vehicle_model_type_(getVehicleModelType()), vehicle_model_ptr_(makeSimulationModel(vehicle_model_type_, step_time, parameters)), hdmap_utils_ptr_(hdmap_utils), vehicle_parameters(parameters), - consider_acceleration_by_road_slope_( - getParameter("consider_acceleration_by_road_slope", false)) + consider_acceleration_by_road_slope_(consider_acceleration_by_road_slope) { autoware->set_parameter(use_sim_time); } 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 69dc42ddaaf..60350e296cb 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 @@ -109,6 +109,7 @@ def make_parameters(): {"architecture_type": architecture_type}, {"autoware_launch_file": autoware_launch_file}, {"autoware_launch_package": autoware_launch_package}, + {"consider_acceleration_by_road_slope": consider_acceleration_by_road_slope}, {"initialize_duration": initialize_duration}, {"launch_autoware": launch_autoware}, {"port": port}, @@ -139,6 +140,7 @@ def description(): DeclareLaunchArgument("architecture_type", default_value=architecture_type ), DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file ), DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package), + DeclareLaunchArgument("consider_acceleration_by_road_slope", default_value=consider_acceleration_by_road_slope), DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate ), DeclareLaunchArgument("global_real_time_factor", default_value=global_real_time_factor), DeclareLaunchArgument("global_timeout", default_value=global_timeout ), @@ -177,8 +179,7 @@ def description(): namespace="simulation", output="screen", on_exit=ShutdownOnce(), - parameters=make_parameters() + [{"use_sim_time": True}, {"consider_acceleration_by_road_slope", - consider_acceleration_by_road_slope}], + parameters=make_parameters() + [{"use_sim_time": True}], condition=IfCondition(launch_simple_sensor_simulator), ), # The `name` keyword overrides the name for all created nodes, so duplicated nodes appear. From 5bf7dc9df3abd69f35fc7c9474b373a087abf652 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 20 Feb 2024 21:23:21 +0900 Subject: [PATCH 12/24] refactor(EgoEntitySimulation): convert lane pose matching processing to getMatchedLaneletPoseFromEntityStatus function --- .../ego_entity_simulation.hpp | 2 + .../ego_entity_simulation.cpp | 84 +++++++++---------- .../src/entity/ego_entity.cpp | 2 +- 3 files changed, 45 insertions(+), 43 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp index c55c0b82f34..9fcd5d40197 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp @@ -78,6 +78,8 @@ class EgoEntitySimulation auto getLinearJerk(double step_time) -> double; + auto getMatchedLaneletPoseFromEntityStatus(const traffic_simulator_msgs::msg::EntityStatus & status, const double entity_width) const -> std::optional; + auto updatePreviousValues() -> void; public: diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 197723ba3af..3e9c6fa6131 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -307,21 +307,39 @@ void EgoEntitySimulation::update( updatePreviousValues(); } -auto EgoEntitySimulation::calculateEgoPitch() const -> double +auto EgoEntitySimulation::getMatchedLaneletPoseFromEntityStatus( + const traffic_simulator_msgs::msg::EntityStatus & status, const double entity_width) const + -> std::optional { - const double ego_x = vehicle_model_ptr_->getX(); - const double ego_y = vehicle_model_ptr_->getY(); - const double ego_yaw = vehicle_model_ptr_->getYaw(); + // the lanelet matching algorithm should be equivalent to the one used in EgoEntity::setMapPose + const auto unique_route_lanelets = + traffic_simulator::helper::getUniqueValues(autoware->getRouteLanelets()); + const auto matching_length = [entity_width] { return entity_width * 0.5 + 1.0; }(); - geometry_msgs::msg::Pose ego_pose; - ego_pose.position.x = ego_x; - ego_pose.position.y = ego_y; - ego_pose.orientation = quaternion_operation::convertEulerAngleToQuaternion( - traffic_simulator::helper::constructRPY(0., 0., ego_yaw)); + std::optional lanelet_pose; + + if (unique_route_lanelets.empty()) { + lanelet_pose = + hdmap_utils_ptr_->toLaneletPose(status.pose, status.bounding_box, false, matching_length); + } else { + lanelet_pose = + hdmap_utils_ptr_->toLaneletPose(status.pose, unique_route_lanelets, matching_length); + if (!lanelet_pose) { + lanelet_pose = + hdmap_utils_ptr_->toLaneletPose(status.pose, status.bounding_box, false, matching_length); + } + } + return lanelet_pose; +} +auto EgoEntitySimulation::calculateEgoPitch() const -> double +{ // calculate prev/next point of lanelet centerline nearest to ego pose. - auto ego_lanelet_id = hdmap_utils_ptr_->getClosestLaneletId(ego_pose, 2.0); - if (not ego_lanelet_id) { + auto ego_lanelet = getMatchedLaneletPoseFromEntityStatus( + status_, std::max( + vehicle_parameters.axles.front_axle.track_width, + vehicle_parameters.axles.rear_axle.track_width)); + if (not ego_lanelet) { return 0.0; } @@ -351,14 +369,17 @@ auto EgoEntitySimulation::calculateEgoPitch() const -> double return min_idx; }; - const size_t ego_seg_idx = find_nearest_segment_index(centerline_points, ego_pose.position); + geometry_msgs::msg::Point ego_point; + ego_point.x = vehicle_model_ptr_->getX(); + ego_point.y = vehicle_model_ptr_->getY(); + const size_t ego_seg_idx = find_nearest_segment_index(centerline_points, ego_point); const auto & prev_point = centerline_points.at(ego_seg_idx); const auto & next_point = centerline_points.at(ego_seg_idx + 1); // calculate ego yaw angle on lanelet coordinates const double lanelet_yaw = std::atan2(next_point.y - prev_point.y, next_point.x - prev_point.x); - const double ego_yaw_against_lanelet = ego_yaw - lanelet_yaw; + const double ego_yaw_against_lanelet = vehicle_model_ptr_->getYaw() - lanelet_yaw; // calculate ego pitch angle considering ego yaw. const double diff_z = next_point.z - prev_point.z; @@ -468,41 +489,20 @@ auto EgoEntitySimulation::updateStatus(double current_scenario_time, double step auto EgoEntitySimulation::fillLaneletDataAndSnapZToLanelet( traffic_simulator_msgs::msg::EntityStatus & status) -> void { - const auto unique_route_lanelets = - traffic_simulator::helper::getUniqueValues(autoware->getRouteLanelets()); - std::optional lanelet_pose; - - // the lanelet matching algorithm should be equivalent to the one used in EgoEntity::setMapPose - const auto get_matching_length = [&] { - return std::max( - vehicle_parameters.axles.front_axle.track_width, - vehicle_parameters.axles.rear_axle.track_width) * - 0.5 + - 1.0; - }; - - if (unique_route_lanelets.empty()) { - lanelet_pose = hdmap_utils_ptr_->toLaneletPose( - status.pose, status.bounding_box, false, get_matching_length()); - } else { - lanelet_pose = - hdmap_utils_ptr_->toLaneletPose(status.pose, unique_route_lanelets, get_matching_length()); - if (!lanelet_pose) { - lanelet_pose = hdmap_utils_ptr_->toLaneletPose( - status.pose, status.bounding_box, false, get_matching_length()); - } - } - if (lanelet_pose) { + if ( + auto lanelet_pose = getMatchedLaneletPoseFromEntityStatus( + status, std::max( + vehicle_parameters.axles.front_axle.track_width, + vehicle_parameters.axles.rear_axle.track_width))) { math::geometry::CatmullRomSpline spline( hdmap_utils_ptr_->getCenterPoints(lanelet_pose->lanelet_id)); if (const auto s_value = spline.getSValue(status.pose)) { status.pose.position.z = spline.getPoint(s_value.value()).z; } - } - - status.lanelet_pose_valid = static_cast(lanelet_pose); - if (status.lanelet_pose_valid) { + status.lanelet_pose_valid = true; status.lanelet_pose = lanelet_pose.value(); + } else { + status.lanelet_pose_valid = false; } } } // namespace vehicle_simulation diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index aea0e89b002..523c37a61dd 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -276,7 +276,7 @@ auto EgoEntity::setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void const auto unique_route_lanelets = traffic_simulator::helper::getUniqueValues(getRouteLanelets()); std::optional lanelet_pose; - // the lanelet matching algorithm should be equivalent to the one used in EgoEntitySimulation::fillLaneletDataAndSnapZToLanelet + // the lanelet matching algorithm should be equivalent to the one used in EgoEntitySimulation::getMatchedLaneletPoseFromEntityStatus const auto get_matching_length = [&] { return std::max( vehicle_parameters.axles.front_axle.track_width, From 1bbc4860f3e6bffd9b8cab3245adbb5148faffd7 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 20 Feb 2024 21:24:36 +0900 Subject: [PATCH 13/24] fix(EgoEntitySimulation) --- .../ego_entity_simulation.cpp | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 3e9c6fa6131..e9c7c182a48 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -267,12 +267,16 @@ void EgoEntitySimulation::update( } else { auto input = Eigen::VectorXd(vehicle_model_ptr_->getDimU()); - auto acceleration_by_slope = not consider_acceleration_by_road_slope_ ? 0.0 : [this]() { - // calculate longitudinal acceleration by slope - constexpr double gravity_acceleration = -9.81; - const double ego_pitch_angle = calculateEgoPitch(); - const double slope_angle = -ego_pitch_angle; - return gravity_acceleration * std::sin(slope_angle); + auto acceleration_by_slope = [this]() { + if (consider_acceleration_by_road_slope_) { + // calculate longitudinal acceleration by slope + constexpr double gravity_acceleration = -9.81; + const double ego_pitch_angle = calculateEgoPitch(); + const double slope_angle = -ego_pitch_angle; + return gravity_acceleration * std::sin(slope_angle); + } else { + return 0.0; + } }(); switch (vehicle_model_type_) { @@ -343,7 +347,7 @@ auto EgoEntitySimulation::calculateEgoPitch() const -> double return 0.0; } - auto centerline_points = hdmap_utils_ptr_->getCenterPoints(ego_lanelet_id.value()); + auto centerline_points = hdmap_utils_ptr_->getCenterPoints(ego_lanelet.value().lanelet_id); // copied from motion_util::findNearestSegmentIndex auto find_nearest_segment_index = []( From 881fc3a2879acc53fc7ab2ecc87bd28dfe000757 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Tue, 20 Feb 2024 21:28:45 +0900 Subject: [PATCH 14/24] chore: format --- .../ego_entity_simulation.hpp | 4 ++- .../launch/scenario_test_runner.launch.py | 32 +++++++++---------- 2 files changed, 19 insertions(+), 17 deletions(-) diff --git a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp index 9fcd5d40197..bd0b234b291 100644 --- a/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp +++ b/simulation/simple_sensor_simulator/include/simple_sensor_simulator/vehicle_simulation/ego_entity_simulation.hpp @@ -78,7 +78,9 @@ class EgoEntitySimulation auto getLinearJerk(double step_time) -> double; - auto getMatchedLaneletPoseFromEntityStatus(const traffic_simulator_msgs::msg::EntityStatus & status, const double entity_width) const -> std::optional; + auto getMatchedLaneletPoseFromEntityStatus( + const traffic_simulator_msgs::msg::EntityStatus & status, const double entity_width) const + -> std::optional; auto updatePreviousValues() -> void; 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 60350e296cb..674f01d8666 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 @@ -137,23 +137,23 @@ def description(): return [ # fmt: off - DeclareLaunchArgument("architecture_type", default_value=architecture_type ), - DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file ), - DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package), + DeclareLaunchArgument("architecture_type", default_value=architecture_type ), + DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file ), + DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package ), DeclareLaunchArgument("consider_acceleration_by_road_slope", default_value=consider_acceleration_by_road_slope), - DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate ), - DeclareLaunchArgument("global_real_time_factor", default_value=global_real_time_factor), - DeclareLaunchArgument("global_timeout", default_value=global_timeout ), - DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ), - DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ), - DeclareLaunchArgument("output_directory", default_value=output_directory ), - 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("use_sim_time", default_value=use_sim_time ), - DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ), - DeclareLaunchArgument("workflow", default_value=workflow ), + DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate ), + DeclareLaunchArgument("global_real_time_factor", default_value=global_real_time_factor ), + DeclareLaunchArgument("global_timeout", default_value=global_timeout ), + DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ), + DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ), + DeclareLaunchArgument("output_directory", default_value=output_directory ), + 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("use_sim_time", default_value=use_sim_time ), + DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ), + DeclareLaunchArgument("workflow", default_value=workflow ), # fmt: on Node( package="scenario_test_runner", From ecec2419a23ef83b5d0591e5bb8bfb49c807c44b Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Feb 2024 16:14:25 +0900 Subject: [PATCH 15/24] Update external/concealer/src/autoware_universe.cpp Co-authored-by: Masaya Kataoka --- external/concealer/src/autoware_universe.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/external/concealer/src/autoware_universe.cpp b/external/concealer/src/autoware_universe.cpp index dce5f359825..11174493820 100644 --- a/external/concealer/src/autoware_universe.cpp +++ b/external/concealer/src/autoware_universe.cpp @@ -156,8 +156,8 @@ auto AutowareUniverse::getGearCommand() const -> autoware_auto_vehicle_msgs::msg auto AutowareUniverse::getGearSign() const -> double { using autoware_auto_vehicle_msgs::msg::GearCommand; - // TODO: Add support for GearCommand::NONE to return 0.0 - // ref: https://github.com/autowarefoundation/autoware.universe/blob/main/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp#L475 + // @todo Add support for GearCommand::NONE to return 0.0 + // @sa https://github.com/autowarefoundation/autoware.universe/blob/main/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp#L475 return getGearCommand().command == GearCommand::REVERSE or getGearCommand().command == GearCommand::REVERSE_2 ? -1.0 From c0809e281fc79f02da2e5038bbd41c93c6d48413 Mon Sep 17 00:00:00 2001 From: Shota Minami Date: Wed, 21 Feb 2024 07:16:35 +0000 Subject: [PATCH 16/24] Update release.yaml to avoid command substitution on Markdown --- .github/workflows/Release.yaml | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/workflows/Release.yaml b/.github/workflows/Release.yaml index f0328615ccb..baed581a687 100644 --- a/.github/workflows/Release.yaml +++ b/.github/workflows/Release.yaml @@ -13,7 +13,7 @@ on: - synchronize - unlabeled concurrency: release - + jobs: release: name: Release @@ -97,8 +97,10 @@ jobs: format: ExternalIssueRef continue-on-error: true - name: Update release description + env: + PULL_REQUEST_BODY: ${{ github.event.pull_request.body }} run: | - echo "${{ github.event.pull_request.body }}" >> release_description.txt + echo "$PULL_REQUEST_BODY" >> release_description.txt echo "" >> release_description.txt echo "# Related Issues " >> release_description.txt echo "${{ steps.linked_issues.outputs.issues }}" >> release_description.txt From f16fddab2db7677fb0be12742dad61565b1adb5f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Feb 2024 16:23:35 +0900 Subject: [PATCH 17/24] Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp Co-authored-by: Masaya Kataoka --- .../src/vehicle_simulation/ego_entity_simulation.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index e9c7c182a48..897afb3a2ff 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -349,7 +349,7 @@ auto EgoEntitySimulation::calculateEgoPitch() const -> double auto centerline_points = hdmap_utils_ptr_->getCenterPoints(ego_lanelet.value().lanelet_id); - // copied from motion_util::findNearestSegmentIndex + // @note Copied from motion_util::findNearestSegmentIndex auto find_nearest_segment_index = []( const std::vector & points, const geometry_msgs::msg::Point & point) { From cfed6252419da41d47cbcb201c89edd3cd251640 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Feb 2024 16:23:52 +0900 Subject: [PATCH 18/24] Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp Co-authored-by: Masaya Kataoka --- .../src/vehicle_simulation/ego_entity_simulation.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 897afb3a2ff..ef538dcac78 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -109,8 +109,8 @@ auto EgoEntitySimulation::makeSimulationModel( const auto steer_time_delay = getParameter("steer_time_delay", 0.24); const auto vel_lim = getParameter("vel_lim", parameters.performance.max_speed); // 50.0 const auto vel_rate_lim = getParameter("vel_rate_lim", parameters.performance.max_acceleration); // 7.0 - const auto vel_time_constant = getParameter("vel_time_constant", 0.1); // 0.5 is default value on simple_planning_simulator - const auto vel_time_delay = getParameter("vel_time_delay", 0.1); // 0.25 is default value on simple_planning_simulator + const auto vel_time_constant = getParameter("vel_time_constant", 0.1); // @note 0.5 is default value on simple_planning_simulator + const auto vel_time_delay = getParameter("vel_time_delay", 0.1); // @note 0.25 is default value on simple_planning_simulator const auto wheel_base = getParameter("wheel_base", parameters.axles.front_axle.position_x - parameters.axles.rear_axle.position_x); // clang-format on From 445030b6f8bd7e5d3a34233b4f479c60970c869f Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Feb 2024 16:23:57 +0900 Subject: [PATCH 19/24] Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp Co-authored-by: Masaya Kataoka --- .../src/vehicle_simulation/ego_entity_simulation.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index ef538dcac78..e0ae1aca47c 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -315,7 +315,7 @@ auto EgoEntitySimulation::getMatchedLaneletPoseFromEntityStatus( const traffic_simulator_msgs::msg::EntityStatus & status, const double entity_width) const -> std::optional { - // the lanelet matching algorithm should be equivalent to the one used in EgoEntity::setMapPose + // @note The lanelet matching algorithm should be equivalent to the one used in EgoEntity::setMapPose const auto unique_route_lanelets = traffic_simulator::helper::getUniqueValues(autoware->getRouteLanelets()); const auto matching_length = [entity_width] { return entity_width * 0.5 + 1.0; }(); From fd9659312425d506694cf49f2f1b3a730f2c435a Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Feb 2024 16:24:05 +0900 Subject: [PATCH 20/24] Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp Co-authored-by: Masaya Kataoka --- .../src/vehicle_simulation/ego_entity_simulation.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index e0ae1aca47c..168ec3321a3 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -381,7 +381,7 @@ auto EgoEntitySimulation::calculateEgoPitch() const -> double const auto & prev_point = centerline_points.at(ego_seg_idx); const auto & next_point = centerline_points.at(ego_seg_idx + 1); - // calculate ego yaw angle on lanelet coordinates + // @note Calculate ego yaw angle on lanelet coordinates const double lanelet_yaw = std::atan2(next_point.y - prev_point.y, next_point.x - prev_point.x); const double ego_yaw_against_lanelet = vehicle_model_ptr_->getYaw() - lanelet_yaw; From bc70e40d47400ff41ad5d1b404ca3af6dfafca8c Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Feb 2024 16:24:12 +0900 Subject: [PATCH 21/24] Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp Co-authored-by: Masaya Kataoka --- .../src/vehicle_simulation/ego_entity_simulation.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp index 168ec3321a3..c88290c5975 100644 --- a/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp +++ b/simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp @@ -385,7 +385,7 @@ auto EgoEntitySimulation::calculateEgoPitch() const -> double const double lanelet_yaw = std::atan2(next_point.y - prev_point.y, next_point.x - prev_point.x); const double ego_yaw_against_lanelet = vehicle_model_ptr_->getYaw() - lanelet_yaw; - // calculate ego pitch angle considering ego yaw. + // @note calculate ego pitch angle considering ego yaw. const double diff_z = next_point.z - prev_point.z; const double diff_xy = std::hypot(next_point.x - prev_point.x, next_point.y - prev_point.y) / std::cos(ego_yaw_against_lanelet); From 1ad085ef11dffcd9a87e1b35177698b439dad5d1 Mon Sep 17 00:00:00 2001 From: Kotaro Yoshimoto Date: Wed, 21 Feb 2024 16:24:43 +0900 Subject: [PATCH 22/24] Update simulation/traffic_simulator/src/entity/ego_entity.cpp Co-authored-by: Masaya Kataoka --- simulation/traffic_simulator/src/entity/ego_entity.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulation/traffic_simulator/src/entity/ego_entity.cpp b/simulation/traffic_simulator/src/entity/ego_entity.cpp index 523c37a61dd..cf59bb9dfa4 100644 --- a/simulation/traffic_simulator/src/entity/ego_entity.cpp +++ b/simulation/traffic_simulator/src/entity/ego_entity.cpp @@ -276,7 +276,7 @@ auto EgoEntity::setMapPose(const geometry_msgs::msg::Pose & map_pose) -> void const auto unique_route_lanelets = traffic_simulator::helper::getUniqueValues(getRouteLanelets()); std::optional lanelet_pose; - // the lanelet matching algorithm should be equivalent to the one used in EgoEntitySimulation::getMatchedLaneletPoseFromEntityStatus + // @note The lanelet matching algorithm should be equivalent to the one used in EgoEntitySimulation::getMatchedLaneletPoseFromEntityStatus const auto get_matching_length = [&] { return std::max( vehicle_parameters.axles.front_axle.track_width, From 645a0afaee5539d855fa0269031bb317f5a37fe8 Mon Sep 17 00:00:00 2001 From: Release Bot Date: Wed, 21 Feb 2024 08:08:20 +0000 Subject: [PATCH 23/24] Bump version of scenario_simulator_v2 from version 1.0.2 to version 1.0.3 --- common/math/arithmetic/CHANGELOG.rst | 5 +++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 5 +++++ common/math/geometry/package.xml | 2 +- common/scenario_simulator_exception/CHANGELOG.rst | 5 +++++ common/scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 5 +++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 5 +++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 5 +++++ external/concealer/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 5 +++++ map/kashiwanoha_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 5 +++++ mock/cpp_mock_scenarios/package.xml | 2 +- openscenario/openscenario_experimental_catalog/CHANGELOG.rst | 5 +++++ openscenario/openscenario_experimental_catalog/package.xml | 2 +- openscenario/openscenario_interpreter/CHANGELOG.rst | 5 +++++ openscenario/openscenario_interpreter/package.xml | 2 +- openscenario/openscenario_interpreter_example/CHANGELOG.rst | 5 +++++ openscenario/openscenario_interpreter_example/package.xml | 2 +- openscenario/openscenario_interpreter_msgs/CHANGELOG.rst | 5 +++++ openscenario/openscenario_interpreter_msgs/package.xml | 2 +- openscenario/openscenario_preprocessor/CHANGELOG.rst | 5 +++++ openscenario/openscenario_preprocessor/package.xml | 2 +- openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst | 5 +++++ openscenario/openscenario_preprocessor_msgs/package.xml | 2 +- openscenario/openscenario_utility/CHANGELOG.rst | 5 +++++ openscenario/openscenario_utility/package.xml | 2 +- openscenario/openscenario_visualization/CHANGELOG.rst | 5 +++++ openscenario/openscenario_visualization/package.xml | 2 +- .../real_time_factor_control_rviz_plugin/CHANGELOG.rst | 5 +++++ .../real_time_factor_control_rviz_plugin/package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 5 +++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 5 +++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 5 +++++ simulation/do_nothing_plugin/package.xml | 2 +- simulation/simple_sensor_simulator/CHANGELOG.rst | 5 +++++ simulation/simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 5 +++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 5 +++++ simulation/traffic_simulator/package.xml | 2 +- simulation/traffic_simulator_msgs/CHANGELOG.rst | 5 +++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 5 +++++ test_runner/random_test_runner/package.xml | 2 +- test_runner/scenario_test_runner/CHANGELOG.rst | 5 +++++ test_runner/scenario_test_runner/package.xml | 2 +- 52 files changed, 156 insertions(+), 26 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index fde5eb9415a..7d38d3c4886 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package arithmetic ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index d1c03a6b550..fd8173c9b45 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 1.0.2 + 1.0.3 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 74171435031..8dd286455f5 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package geometry ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index 8034a4a2e0f..d19a2da6953 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 1.0.2 + 1.0.3 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 055762416a1..6bf230955c7 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package scenario_simulator_exception ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index f2353897eb9..30b67520065 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 1.0.2 + 1.0.3 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 e756537bba1..bfb9d14180c 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package junit_exporter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index fbf8a8668e3..eefb7ef80e6 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 1.0.2 + 1.0.3 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 1574a0b1481..e966fbe538f 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package status_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 8d7f8ceb306..0bcde524ec7 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 1.0.2 + 1.0.3 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 9ba709b5c2f..5b56274d5f5 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package concealer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 55689fece7d..0ebacd44d3c 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 1.0.2 + 1.0.3 Provides a class 'Autoware' to conceal miscellaneous things to simplify Autoware management of the simulator. Tatsuya Yamasaki Apache License 2.0 diff --git a/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index 6c0260d3a0e..c979293788d 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package kashiwanoha_map ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 0e651326d8a..1827c0e54e5 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 1.0.2 + 1.0.3 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 2b89adbb786..53cabe40ba0 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package cpp_mock_scenarios ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index b1200dcc334..03951342ff9 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 1.0.2 + 1.0.3 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 c16454b866d..2be21548ff7 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package openscenario_experimental_catalog ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index ef1ecb51292..549c618a242 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 1.0.2 + 1.0.3 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 04a90a95018..38808b908d8 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package openscenario_interpreter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index 53129e7ff55..fb6ad6ab6fd 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 1.0.2 + 1.0.3 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 81e72b3e4b2..9e8fceb0e89 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package openscenario_interpreter_example ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 257ded32bcf..17b1cf4512f 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 1.0.2 + 1.0.3 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 07e2275bf3e..6b7b4d84502 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package openscenario_interpreter_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index e425e45e9ab..57359d741ef 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 1.0.2 + 1.0.3 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 d9cb9c1e92a..23d0588f1a5 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package openscenario_preprocessor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index fd07807b648..89dc6bc730c 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 1.0.2 + 1.0.3 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 9128a00e006..36c0745c444 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package openscenario_preprocessor_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index ae2b1ab3562..f024a79daeb 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 1.0.2 + 1.0.3 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 fe2dbb98f94..39c1bd0be5f 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package openscenario_utility ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 9597af8fc8b..3baeaf4bea1 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 1.0.2 + 1.0.3 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_visualization/CHANGELOG.rst b/openscenario/openscenario_visualization/CHANGELOG.rst index a42f851f5ba..38c9e7c7ce4 100644 --- a/openscenario/openscenario_visualization/CHANGELOG.rst +++ b/openscenario/openscenario_visualization/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package openscenario_visualization ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/openscenario/openscenario_visualization/package.xml b/openscenario/openscenario_visualization/package.xml index 7ddbfa59c5f..47d2f81597d 100644 --- a/openscenario/openscenario_visualization/package.xml +++ b/openscenario/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 1.0.2 + 1.0.3 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 a528bd95c6b..d11f72301b7 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package real_time_factor_control_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation 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 992ebbed8e2..e51b0ff5b57 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 - 1.0.2 + 1.0.3 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 f9735b62a05..8e030f43942 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package scenario_simulator_v2 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index 27baeb78e87..e90ab179c81 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 1.0.2 + 1.0.3 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 ae10bc780c3..0321d958727 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package behavior_tree_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index d2b5cd0bd85..13dc6afc614 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 1.0.2 + 1.0.3 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 9fed19b616b..b6035eee2c6 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package do_nothing_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index a5f99575bc9..24b5a9b30c8 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 1.0.2 + 1.0.3 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 f57196c7f7b..ccf9c71e20b 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package simple_sensor_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index b060f37c532..0d7cf861044 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 1.0.2 + 1.0.3 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 1a0861a6f3c..1621312a6ff 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package simulation_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 90517779c98..5a8b2422131 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 1.0.2 + 1.0.3 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 8cedfb32785..cf6d8981af2 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package traffic_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * fix CHANGELOG diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 1637408a9ae..4d4b82ba745 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 1.0.2 + 1.0.3 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 8090b5c3333..4f8a73640ff 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package openscenario_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 107386e5aa0..10890398cfb 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 1.0.2 + 1.0.3 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 d35b0f95df8..7e0811d0b88 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package random_test_runner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 14bdf4c464b..9d367cf00bb 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 1.0.2 + 1.0.3 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 3f7101f4050..edc17f3ba11 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package scenario_test_runner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.3 (2024-02-21) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description +* Contributors: Masaya Kataoka + 1.0.2 (2024-02-21) ------------------ * Merge remote-tracking branch 'origin/master' into doc/lane_pose_calculation diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 9da699fbbfd..5444811a891 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 1.0.2 + 1.0.3 scenario test runner package Tatsuya Yamasaki Apache License 2.0 From febce8177d556035750c9c423d48d2692ce329fc Mon Sep 17 00:00:00 2001 From: Release Bot Date: Thu, 22 Feb 2024 02:54:04 +0000 Subject: [PATCH 24/24] Bump version of scenario_simulator_v2 from version 1.0.3 to version 1.1.0 --- common/math/arithmetic/CHANGELOG.rst | 7 ++++ common/math/arithmetic/package.xml | 2 +- common/math/geometry/CHANGELOG.rst | 7 ++++ common/math/geometry/package.xml | 2 +- .../CHANGELOG.rst | 7 ++++ .../scenario_simulator_exception/package.xml | 2 +- common/simple_junit/CHANGELOG.rst | 7 ++++ common/simple_junit/package.xml | 2 +- common/status_monitor/CHANGELOG.rst | 11 +++++++ common/status_monitor/package.xml | 2 +- external/concealer/CHANGELOG.rst | 16 +++++++++ external/concealer/package.xml | 2 +- map/kashiwanoha_map/CHANGELOG.rst | 7 ++++ map/kashiwanoha_map/package.xml | 2 +- mock/cpp_mock_scenarios/CHANGELOG.rst | 7 ++++ mock/cpp_mock_scenarios/package.xml | 2 +- .../CHANGELOG.rst | 7 ++++ .../package.xml | 2 +- .../openscenario_interpreter/CHANGELOG.rst | 11 +++++++ .../openscenario_interpreter/package.xml | 2 +- .../CHANGELOG.rst | 7 ++++ .../package.xml | 2 +- .../CHANGELOG.rst | 7 ++++ .../openscenario_interpreter_msgs/package.xml | 2 +- .../openscenario_preprocessor/CHANGELOG.rst | 7 ++++ .../openscenario_preprocessor/package.xml | 2 +- .../CHANGELOG.rst | 7 ++++ .../package.xml | 2 +- .../openscenario_utility/CHANGELOG.rst | 7 ++++ openscenario/openscenario_utility/package.xml | 2 +- .../openscenario_visualization/CHANGELOG.rst | 7 ++++ .../openscenario_visualization/package.xml | 2 +- .../CHANGELOG.rst | 11 +++++++ .../package.xml | 2 +- scenario_simulator_v2/CHANGELOG.rst | 7 ++++ scenario_simulator_v2/package.xml | 2 +- simulation/behavior_tree_plugin/CHANGELOG.rst | 7 ++++ simulation/behavior_tree_plugin/package.xml | 2 +- simulation/do_nothing_plugin/CHANGELOG.rst | 7 ++++ simulation/do_nothing_plugin/package.xml | 2 +- .../simple_sensor_simulator/CHANGELOG.rst | 33 +++++++++++++++++++ .../simple_sensor_simulator/package.xml | 2 +- simulation/simulation_interface/CHANGELOG.rst | 11 +++++++ simulation/simulation_interface/package.xml | 2 +- simulation/traffic_simulator/CHANGELOG.rst | 17 ++++++++++ simulation/traffic_simulator/package.xml | 2 +- .../traffic_simulator_msgs/CHANGELOG.rst | 7 ++++ simulation/traffic_simulator_msgs/package.xml | 2 +- test_runner/random_test_runner/CHANGELOG.rst | 7 ++++ test_runner/random_test_runner/package.xml | 2 +- .../scenario_test_runner/CHANGELOG.rst | 17 ++++++++++ test_runner/scenario_test_runner/package.xml | 2 +- 52 files changed, 279 insertions(+), 26 deletions(-) diff --git a/common/math/arithmetic/CHANGELOG.rst b/common/math/arithmetic/CHANGELOG.rst index 7d38d3c4886..a1376f1bfca 100644 --- a/common/math/arithmetic/CHANGELOG.rst +++ b/common/math/arithmetic/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package arithmetic ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/common/math/arithmetic/package.xml b/common/math/arithmetic/package.xml index fd8173c9b45..e22342ff44c 100644 --- a/common/math/arithmetic/package.xml +++ b/common/math/arithmetic/package.xml @@ -2,7 +2,7 @@ arithmetic - 1.0.3 + 1.1.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 8dd286455f5..4853d8f0b20 100644 --- a/common/math/geometry/CHANGELOG.rst +++ b/common/math/geometry/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package geometry ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/common/math/geometry/package.xml b/common/math/geometry/package.xml index d19a2da6953..d0580fcea41 100644 --- a/common/math/geometry/package.xml +++ b/common/math/geometry/package.xml @@ -2,7 +2,7 @@ geometry - 1.0.3 + 1.1.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 6bf230955c7..c2aaeadd099 100644 --- a/common/scenario_simulator_exception/CHANGELOG.rst +++ b/common/scenario_simulator_exception/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package scenario_simulator_exception ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/common/scenario_simulator_exception/package.xml b/common/scenario_simulator_exception/package.xml index 30b67520065..4ee1238b99a 100644 --- a/common/scenario_simulator_exception/package.xml +++ b/common/scenario_simulator_exception/package.xml @@ -2,7 +2,7 @@ scenario_simulator_exception - 1.0.3 + 1.1.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 bfb9d14180c..5b33dfd9105 100644 --- a/common/simple_junit/CHANGELOG.rst +++ b/common/simple_junit/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package junit_exporter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/common/simple_junit/package.xml b/common/simple_junit/package.xml index eefb7ef80e6..ab3a05c7221 100644 --- a/common/simple_junit/package.xml +++ b/common/simple_junit/package.xml @@ -2,7 +2,7 @@ simple_junit - 1.0.3 + 1.1.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 e966fbe538f..fef20d8e29a 100644 --- a/common/status_monitor/CHANGELOG.rst +++ b/common/status_monitor/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package status_monitor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model + # Conflicts: + # simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + # test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/common/status_monitor/package.xml b/common/status_monitor/package.xml index 0bcde524ec7..4682e7ba680 100644 --- a/common/status_monitor/package.xml +++ b/common/status_monitor/package.xml @@ -2,7 +2,7 @@ status_monitor - 1.0.3 + 1.1.0 none Tatsuya Yamasaki Apache License 2.0 diff --git a/external/concealer/CHANGELOG.rst b/external/concealer/CHANGELOG.rst index 5b56274d5f5..35f464642d4 100644 --- a/external/concealer/CHANGELOG.rst +++ b/external/concealer/CHANGELOG.rst @@ -2,6 +2,22 @@ Changelog for package concealer ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge pull request `#1182 `_ from tier4/feature/slope_vehicle_model + Consider road slope in ego vehicle simulation +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Update external/concealer/src/autoware_universe.cpp + Co-authored-by: Masaya Kataoka +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model + # Conflicts: + # simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + # test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +* doc: add memos to code +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/external/concealer/package.xml b/external/concealer/package.xml index 0ebacd44d3c..e0956871f3e 100644 --- a/external/concealer/package.xml +++ b/external/concealer/package.xml @@ -2,7 +2,7 @@ concealer - 1.0.3 + 1.1.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/map/kashiwanoha_map/CHANGELOG.rst b/map/kashiwanoha_map/CHANGELOG.rst index c979293788d..4e70985de62 100644 --- a/map/kashiwanoha_map/CHANGELOG.rst +++ b/map/kashiwanoha_map/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package kashiwanoha_map ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/map/kashiwanoha_map/package.xml b/map/kashiwanoha_map/package.xml index 1827c0e54e5..93098cb9de7 100644 --- a/map/kashiwanoha_map/package.xml +++ b/map/kashiwanoha_map/package.xml @@ -2,7 +2,7 @@ kashiwanoha_map - 1.0.3 + 1.1.0 map package for kashiwanoha Masaya Kataoka Apache License 2.0 diff --git a/mock/cpp_mock_scenarios/CHANGELOG.rst b/mock/cpp_mock_scenarios/CHANGELOG.rst index 53cabe40ba0..220a0169388 100644 --- a/mock/cpp_mock_scenarios/CHANGELOG.rst +++ b/mock/cpp_mock_scenarios/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package cpp_mock_scenarios ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/mock/cpp_mock_scenarios/package.xml b/mock/cpp_mock_scenarios/package.xml index 03951342ff9..9e39e1c8ba7 100644 --- a/mock/cpp_mock_scenarios/package.xml +++ b/mock/cpp_mock_scenarios/package.xml @@ -2,7 +2,7 @@ cpp_mock_scenarios - 1.0.3 + 1.1.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 2be21548ff7..c01a5841dd7 100644 --- a/openscenario/openscenario_experimental_catalog/CHANGELOG.rst +++ b/openscenario/openscenario_experimental_catalog/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package openscenario_experimental_catalog ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/openscenario/openscenario_experimental_catalog/package.xml b/openscenario/openscenario_experimental_catalog/package.xml index 549c618a242..6897861bd24 100644 --- a/openscenario/openscenario_experimental_catalog/package.xml +++ b/openscenario/openscenario_experimental_catalog/package.xml @@ -2,7 +2,7 @@ openscenario_experimental_catalog - 1.0.3 + 1.1.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 38808b908d8..bed9b8c2799 100644 --- a/openscenario/openscenario_interpreter/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package openscenario_interpreter ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model + # Conflicts: + # simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + # test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/openscenario/openscenario_interpreter/package.xml b/openscenario/openscenario_interpreter/package.xml index fb6ad6ab6fd..6d5fafd1586 100644 --- a/openscenario/openscenario_interpreter/package.xml +++ b/openscenario/openscenario_interpreter/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter - 1.0.3 + 1.1.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 9e8fceb0e89..fe86902fd0f 100644 --- a/openscenario/openscenario_interpreter_example/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_example/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package openscenario_interpreter_example ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/openscenario/openscenario_interpreter_example/package.xml b/openscenario/openscenario_interpreter_example/package.xml index 17b1cf4512f..9f7453928c6 100644 --- a/openscenario/openscenario_interpreter_example/package.xml +++ b/openscenario/openscenario_interpreter_example/package.xml @@ -3,7 +3,7 @@ openscenario_interpreter_example - 1.0.3 + 1.1.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 6b7b4d84502..6aacfa28716 100644 --- a/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_interpreter_msgs/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package openscenario_interpreter_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/openscenario/openscenario_interpreter_msgs/package.xml b/openscenario/openscenario_interpreter_msgs/package.xml index 57359d741ef..6e438507443 100644 --- a/openscenario/openscenario_interpreter_msgs/package.xml +++ b/openscenario/openscenario_interpreter_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_interpreter_msgs - 1.0.3 + 1.1.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 23d0588f1a5..7572c19f745 100644 --- a/openscenario/openscenario_preprocessor/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package openscenario_preprocessor ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/openscenario/openscenario_preprocessor/package.xml b/openscenario/openscenario_preprocessor/package.xml index 89dc6bc730c..9d0da88d426 100644 --- a/openscenario/openscenario_preprocessor/package.xml +++ b/openscenario/openscenario_preprocessor/package.xml @@ -3,7 +3,7 @@ openscenario_preprocessor - 1.0.3 + 1.1.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 36c0745c444..5a8ce6ed1fd 100644 --- a/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst +++ b/openscenario/openscenario_preprocessor_msgs/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package openscenario_preprocessor_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/openscenario/openscenario_preprocessor_msgs/package.xml b/openscenario/openscenario_preprocessor_msgs/package.xml index f024a79daeb..a5d5b16d283 100644 --- a/openscenario/openscenario_preprocessor_msgs/package.xml +++ b/openscenario/openscenario_preprocessor_msgs/package.xml @@ -2,7 +2,7 @@ openscenario_preprocessor_msgs - 1.0.3 + 1.1.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 39c1bd0be5f..0f3ea7a7b82 100644 --- a/openscenario/openscenario_utility/CHANGELOG.rst +++ b/openscenario/openscenario_utility/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package openscenario_utility ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/openscenario/openscenario_utility/package.xml b/openscenario/openscenario_utility/package.xml index 3baeaf4bea1..d77c7a06960 100644 --- a/openscenario/openscenario_utility/package.xml +++ b/openscenario/openscenario_utility/package.xml @@ -2,7 +2,7 @@ openscenario_utility - 1.0.3 + 1.1.0 Utility tools for ASAM OpenSCENARIO 1.2.0 Tatsuya Yamasaki Apache License 2.0 diff --git a/openscenario/openscenario_visualization/CHANGELOG.rst b/openscenario/openscenario_visualization/CHANGELOG.rst index 38c9e7c7ce4..ed05a0bd951 100644 --- a/openscenario/openscenario_visualization/CHANGELOG.rst +++ b/openscenario/openscenario_visualization/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package openscenario_visualization ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/openscenario/openscenario_visualization/package.xml b/openscenario/openscenario_visualization/package.xml index 47d2f81597d..0e9f16f6905 100644 --- a/openscenario/openscenario_visualization/package.xml +++ b/openscenario/openscenario_visualization/package.xml @@ -2,7 +2,7 @@ openscenario_visualization - 1.0.3 + 1.1.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 d11f72301b7..4037094a5de 100644 --- a/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst +++ b/rviz_plugins/real_time_factor_control_rviz_plugin/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package real_time_factor_control_rviz_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model + # Conflicts: + # simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + # test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description 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 e51b0ff5b57..27cd0e298eb 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 - 1.0.3 + 1.1.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 8e030f43942..1fb76d25317 100644 --- a/scenario_simulator_v2/CHANGELOG.rst +++ b/scenario_simulator_v2/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package scenario_simulator_v2 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/scenario_simulator_v2/package.xml b/scenario_simulator_v2/package.xml index e90ab179c81..1bc907a6775 100644 --- a/scenario_simulator_v2/package.xml +++ b/scenario_simulator_v2/package.xml @@ -2,7 +2,7 @@ scenario_simulator_v2 - 1.0.3 + 1.1.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 0321d958727..2836c67d567 100644 --- a/simulation/behavior_tree_plugin/CHANGELOG.rst +++ b/simulation/behavior_tree_plugin/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package behavior_tree_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/simulation/behavior_tree_plugin/package.xml b/simulation/behavior_tree_plugin/package.xml index 13dc6afc614..3b01d17a49e 100644 --- a/simulation/behavior_tree_plugin/package.xml +++ b/simulation/behavior_tree_plugin/package.xml @@ -2,7 +2,7 @@ behavior_tree_plugin - 1.0.3 + 1.1.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 b6035eee2c6..08ff8646d16 100644 --- a/simulation/do_nothing_plugin/CHANGELOG.rst +++ b/simulation/do_nothing_plugin/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package do_nothing_plugin ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/simulation/do_nothing_plugin/package.xml b/simulation/do_nothing_plugin/package.xml index 24b5a9b30c8..29da2c16716 100644 --- a/simulation/do_nothing_plugin/package.xml +++ b/simulation/do_nothing_plugin/package.xml @@ -2,7 +2,7 @@ do_nothing_plugin - 1.0.3 + 1.1.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 ccf9c71e20b..23ace85da7a 100644 --- a/simulation/simple_sensor_simulator/CHANGELOG.rst +++ b/simulation/simple_sensor_simulator/CHANGELOG.rst @@ -2,6 +2,39 @@ Changelog for package simple_sensor_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge pull request `#1182 `_ from tier4/feature/slope_vehicle_model + Consider road slope in ego vehicle simulation +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + Co-authored-by: Masaya Kataoka +* Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + Co-authored-by: Masaya Kataoka +* Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + Co-authored-by: Masaya Kataoka +* Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + Co-authored-by: Masaya Kataoka +* Update simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + Co-authored-by: Masaya Kataoka +* chore: format +* fix(EgoEntitySimulation) +* refactor(EgoEntitySimulation): convert lane pose matching processing to getMatchedLaneletPoseFromEntityStatus function +* fix: pass consider_acceleration_by_road_slope to inside of EgoEntitySimulator +* doc: add notification to duplicated lane matching algorithm +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* chore: format +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model + # Conflicts: + # simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + # test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +* refactor(ego_entity_simulation): rename flag name for considering slope in ego entity simulation +* feat(ego_entity_simulation): add flog for considering slope in ego entity simulation +* feat(ego_entity_simulation): consider slope in ego entity simulation +* doc: add memos to code +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/simulation/simple_sensor_simulator/package.xml b/simulation/simple_sensor_simulator/package.xml index 0d7cf861044..c1fdf5a209d 100644 --- a/simulation/simple_sensor_simulator/package.xml +++ b/simulation/simple_sensor_simulator/package.xml @@ -1,7 +1,7 @@ simple_sensor_simulator - 1.0.3 + 1.1.0 simple_sensor_simulator package masaya kataoka diff --git a/simulation/simulation_interface/CHANGELOG.rst b/simulation/simulation_interface/CHANGELOG.rst index 1621312a6ff..a462515d2aa 100644 --- a/simulation/simulation_interface/CHANGELOG.rst +++ b/simulation/simulation_interface/CHANGELOG.rst @@ -2,6 +2,17 @@ Changelog for package simulation_interface ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model + # Conflicts: + # simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + # test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/simulation/simulation_interface/package.xml b/simulation/simulation_interface/package.xml index 5a8b2422131..8205b82cf47 100644 --- a/simulation/simulation_interface/package.xml +++ b/simulation/simulation_interface/package.xml @@ -2,7 +2,7 @@ simulation_interface - 1.0.3 + 1.1.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 cf6d8981af2..e6fdc565497 100644 --- a/simulation/traffic_simulator/CHANGELOG.rst +++ b/simulation/traffic_simulator/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package traffic_simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge pull request `#1182 `_ from tier4/feature/slope_vehicle_model + Consider road slope in ego vehicle simulation +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Update simulation/traffic_simulator/src/entity/ego_entity.cpp + Co-authored-by: Masaya Kataoka +* refactor(EgoEntitySimulation): convert lane pose matching processing to getMatchedLaneletPoseFromEntityStatus function +* doc: add notification to duplicated lane matching algorithm +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model + # Conflicts: + # simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + # test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/simulation/traffic_simulator/package.xml b/simulation/traffic_simulator/package.xml index 4d4b82ba745..1145c762ed6 100644 --- a/simulation/traffic_simulator/package.xml +++ b/simulation/traffic_simulator/package.xml @@ -1,7 +1,7 @@ traffic_simulator - 1.0.3 + 1.1.0 control traffic flow masaya kataoka diff --git a/simulation/traffic_simulator_msgs/CHANGELOG.rst b/simulation/traffic_simulator_msgs/CHANGELOG.rst index 4f8a73640ff..4e225744c2f 100644 --- a/simulation/traffic_simulator_msgs/CHANGELOG.rst +++ b/simulation/traffic_simulator_msgs/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package openscenario_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/simulation/traffic_simulator_msgs/package.xml b/simulation/traffic_simulator_msgs/package.xml index 10890398cfb..1c0f593565c 100644 --- a/simulation/traffic_simulator_msgs/package.xml +++ b/simulation/traffic_simulator_msgs/package.xml @@ -2,7 +2,7 @@ traffic_simulator_msgs - 1.0.3 + 1.1.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 7e0811d0b88..4ed34bcd8b2 100644 --- a/test_runner/random_test_runner/CHANGELOG.rst +++ b/test_runner/random_test_runner/CHANGELOG.rst @@ -2,6 +2,13 @@ Changelog for package random_test_runner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/test_runner/random_test_runner/package.xml b/test_runner/random_test_runner/package.xml index 9d367cf00bb..da8cda49517 100644 --- a/test_runner/random_test_runner/package.xml +++ b/test_runner/random_test_runner/package.xml @@ -2,7 +2,7 @@ random_test_runner - 1.0.3 + 1.1.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 edc17f3ba11..533729a5eaf 100644 --- a/test_runner/scenario_test_runner/CHANGELOG.rst +++ b/test_runner/scenario_test_runner/CHANGELOG.rst @@ -2,6 +2,23 @@ Changelog for package scenario_test_runner ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.0 (2024-02-22) +------------------ +* Merge pull request `#1182 `_ from tier4/feature/slope_vehicle_model + Consider road slope in ego vehicle simulation +* Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into feature/slope_vehicle_model +* chore: format +* fix: pass consider_acceleration_by_road_slope to inside of EgoEntitySimulator +* chore: format +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model +* Merge remote-tracking branch 'origin/master' into feature/slope_vehicle_model + # Conflicts: + # simulation/simple_sensor_simulator/src/vehicle_simulation/ego_entity_simulation.cpp + # test_runner/scenario_test_runner/launch/scenario_test_runner.launch.py +* feat(scenario_test_runner): add consider_acceleration_by_road_slope for simple_sensor_simulator +* Contributors: Kotaro Yoshimoto, Masaya Kataoka + 1.0.3 (2024-02-21) ------------------ * Merge branch 'master' of https://github.com/tier4/scenario_simulator_v2 into fix/release_description diff --git a/test_runner/scenario_test_runner/package.xml b/test_runner/scenario_test_runner/package.xml index 5444811a891..be4d7cd9d34 100644 --- a/test_runner/scenario_test_runner/package.xml +++ b/test_runner/scenario_test_runner/package.xml @@ -2,7 +2,7 @@ scenario_test_runner - 1.0.3 + 1.1.0 scenario test runner package Tatsuya Yamasaki Apache License 2.0