From f6eb5047c4870941c91dbd50d8428ea2eaaaebe0 Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Fri, 27 Oct 2023 14:05:45 +0800 Subject: [PATCH 01/12] refactor(simple_planning_simulator): rework parameters Signed-off-by: PhoebeWu21 --- simulator/simple_planning_simulator/README.md | 12 +- ...mple_planning_simulator_default.param.yaml | 8 + .../simple_planning_simulator.schema.json | 223 ++++++++++++++++++ .../simple_planning_simulator_core.cpp | 56 ++--- 4 files changed, 260 insertions(+), 39 deletions(-) create mode 100644 simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index cd362c0115358..d47ba7d6383ae 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -40,17 +40,7 @@ The purpose of this simulator is for the integration test of planning and contro ### Common Parameters -| Name | Type | Description | Default value | -| :-------------------- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------- | :------------------- | -| simulated_frame_id | string | set to the child_frame_id in output tf | "base_link" | -| origin_frame_id | string | set to the frame_id in output tf | "odom" | -| initialize_source | string | If "ORIGIN", the initial pose is set at (0,0,0). If "INITIAL_POSE_TOPIC", node will wait until the `input/initialpose` topic is published. | "INITIAL_POSE_TOPIC" | -| add_measurement_noise | bool | If true, the Gaussian noise is added to the simulated results. | true | -| pos_noise_stddev | double | Standard deviation for position noise | 0.01 | -| rpy_noise_stddev | double | Standard deviation for Euler angle noise | 0.0001 | -| vel_noise_stddev | double | Standard deviation for longitudinal velocity noise | 0.0 | -| angvel_noise_stddev | double | Standard deviation for angular velocity noise | 0.0 | -| steer_noise_stddev | double | Standard deviation for steering angle noise | 0.0001 | +{{ json_to_markdown("simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json") }} ### Vehicle Model Parameters diff --git a/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml b/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml index 4bb7dfd84f392..e3fe4ca32e002 100644 --- a/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml +++ b/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml @@ -4,14 +4,22 @@ origin_frame_id: "map" vehicle_model_type: "DELAY_STEER_ACC_GEARED" initialize_source: "INITIAL_POSE_TOPIC" + initial_engage_state: True + enable_road_slope_simulation: False timer_sampling_time_ms: 25 add_measurement_noise: False + pos_noise_stddev: 1e-2 + vel_noise_stddev: 1e-2 + rpy_noise_stddev: 1e-4 + steer_noise_stddev: 1e-4 vel_lim: 30.0 vel_rate_lim: 30.0 steer_lim: 0.6 steer_rate_lim: 6.28 acc_time_delay: 0.1 acc_time_constant: 0.1 + vel_time_delay: 0.25 + vel_time_constant: 0.5 steer_time_delay: 0.1 steer_time_constant: 0.1 steer_dead_band: 0.0 diff --git a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json new file mode 100644 index 0000000000000..881f243de71cd --- /dev/null +++ b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json @@ -0,0 +1,223 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Simple Planning_ Simulator", + "type": "object", + "definitions": { + "simple_planning_simulator": { + "type": "object", + "properties": { + "simulated_frame_id": { + "type": "string", + "description": "set to the child_frame_id in output tf", + "default": "base_link" + }, + "origin_frame_id": { + "type": "string", + "description": "set to the frame_id in output tf", + "default": "map" + }, + "vehicle_model_type": { + "type": "string", + "description": "Vehicle Model Parameters setting.", + "default": "DELAY_STEER_ACC_GEARED", + "enum": [ + "IDEAL_STEER_VEL", + "IDEAL_STEER_ACC", + "IDEAL_STEER_ACC_GEARED", + "DELAY_STEER_VEL", + "DELAY_STEER_ACC", + "DELAY_STEER_ACC_GEARED" + ] + }, + "initialize_source": { + "type": "string", + "description": "If 'ORIGIN', the initial pose is set at (0,0,0). If 'INITIAL_POSE_TOPIC', node will wait until the 'input/initialpose' topic is published.", + "default": "INITIAL_POSE_TOPIC", + "enum": [ + "ORIGIN", + "INITIAL_POSE_TOPIC" + ] + }, + "initial_engage_state": { + "type": "boolean", + "description": "initial engage state setting", + "default": "true" + }, + "enable_road_slope_simulation": { + "type": "boolean", + "description": "Enable road slope simulation or not.", + "default": "false" + }, + "timer_sampling_time_ms": { + "type": "integer", + "description": "Setting timer for sampling time [ms].", + "default": "25", + "exclusiveMinimum": 0 + }, + "add_measurement_noise": { + "type": "boolean", + "description": "If true, the Gaussian noise is added to the simulated results.", + "default": "false" + }, + "pos_noise_stddev": { + "type": "number", + "description": "Standard deviation for position noise", + "default": "1e-2", + "minimum": 0 + }, + "vel_noise_stddev": { + "type": "number", + "description": "Standard deviation for longitudinal velocity noise", + "default": "1e-2", + "minimum": 0 + }, + "rpy_noise_stddev": { + "type": "number", + "description": "Standard deviation for Euler angle noise", + "default": "1e-4", + "minimum": 0 + }, + "steer_noise_stddev": { + "type": "number", + "description": "Standard deviation for steering angle noise", + "default": "1e-4", + "minimum": 0 + }, + "vel_lim": { + "type": "number", + "description": "limit of velocity [m/s]", + "default": "30.0", + "exclusiveMinimum": 0 + }, + "vel_rate_lim": { + "type": "number", + "description": "limit of velocity change rate [m/ss]", + "default": "30.0", + "minimum": 0 + }, + "steer_lim": { + "type": "number", + "description": "limit of steering angle [rad]", + "default": "0.6" + }, + "steer_rate_lim": { + "type": "number", + "description": "limit of steering angle change rate [rad/s]", + "default": "6.28", + "minimum": 0 + }, + "acc_time_delay": { + "type": "number", + "description": "dead time for the acceleration input [s]", + "default": "0.1", + "minimum": 0 + }, + "acc_time_constant": { + "type": "number", + "description": "time constant of the 1st-order acceleration dynamics [s]", + "default": "0.1", + "minimum": 0 + }, + "vel_time_delay": { + "type": "number", + "description": "dead time for the velocity input [s]", + "default": "0.25", + "minimum": 0 + }, + "vel_time_constant": { + "type": "number", + "description": "time constant of the 1st-order velocity dynamics [s]", + "default": "0.5", + "minimum": 0 + }, + "steer_time_delay": { + "type": "number", + "description": "dead time for the steering input [s]", + "default": "0.1", + "minimum": 0 + }, + "steer_time_constant": { + "type": "number", + "description": "time constant of the 1st-order steering dynamics [s]", + "default": "0.1", + "minimum": 0 + }, + "x_stddev": { + "type": "number", + "description": "x standard deviation for dummy covariance in map coordinate", + "default": "0.0001", + "minimum": 0 + }, + "y_stddev": { + "type": "number", + "description": "y standard deviation for dummy covariance in map coordinate", + "default": "0.0001", + "minimum": 0 + }, + "vehicle_characteristics": { + "type": "object", + "properties": { + "INSERT_PARAMETER_1_NAME": { + "type": "INSERT_TYPE", + "description": "INSERT_DESCRIPTION", + "default": "INSERT_DEFAULT", + "INSERT_BOUND_CONDITION(S)": "INSERT_BOUND_VALUE(S)" + }, + "INSERT_PARAMETER_N_NAME": { + "type": "INSERT_TYPE", + "description": "INSERT_DESCRIPTION", + "default": "INSERT_DEFAULT", + "INSERT_BOUND_CONDITION(S)": "INSERT_BOUND_VALUE(S)" + } + }, + "required": [ + "INSERT_PARAMETER_1_NAME", + "INSERT_PARAMETER_N_NAME" + ] + } + }, + "required": [ + "simulated_frame_id", + "origin_frame_id", + "vehicle_model_type", + "initialize_source", + "initial_engage_state", + "enable_road_slope_simulation", + "timer_sampling_time_ms", + "add_measurement_noise", + "pos_noise_stddev", + "vel_noise_stddev", + "rpy_noise_stddev", + "steer_noise_stddev", + "vel_lim", + "vel_rate_lim", + "steer_lim", + "steer_rate_lim", + "acc_time_delay", + "acc_time_constant", + "vel_time_delay", + "vel_time_constant", + "steer_time_delay", + "steer_time_constant", + "x_stddev", + "y_stddev" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/simple_planning_simulator" + } + }, + "required": [ + "ros__parameters" + ] + } + }, + "required": [ + "/**" + ] +} diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 8c95e144b3f8d..9608b1ae5d364 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -101,12 +101,12 @@ namespace simple_planning_simulator SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & options) : Node("simple_planning_simulator", options), tf_buffer_(get_clock()), tf_listener_(tf_buffer_) { - simulated_frame_id_ = declare_parameter("simulated_frame_id", "base_link"); - origin_frame_id_ = declare_parameter("origin_frame_id", "odom"); - add_measurement_noise_ = declare_parameter("add_measurement_noise", false); + simulated_frame_id_ = declare_parameter("simulated_frame_id"); + origin_frame_id_ = declare_parameter("origin_frame_id"); + add_measurement_noise_ = declare_parameter("add_measurement_noise"); simulate_motion_ = declare_parameter("initial_engage_state"); - enable_road_slope_simulation_ = declare_parameter("enable_road_slope_simulation", false); - enable_pub_steer_ = declare_parameter("enable_pub_steer", true); + enable_road_slope_simulation_ = declare_parameter("enable_road_slope_simulation"); + enable_pub_steer_ = declare_parameter("enable_pub_steer"); using rclcpp::QoS; using std::placeholders::_1; @@ -185,7 +185,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt set_param_res_ = this->add_on_set_parameters_callback( std::bind(&SimplePlanningSimulator::on_parameter, this, _1)); - timer_sampling_time_ms_ = static_cast(declare_parameter("timer_sampling_time_ms", 25)); + timer_sampling_time_ms_ = static_cast(declare_parameter("timer_sampling_time_ms")); on_timer_ = rclcpp::create_timer( this, get_clock(), std::chrono::milliseconds(timer_sampling_time_ms_), std::bind(&SimplePlanningSimulator::on_timer, this)); @@ -200,7 +200,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt initialize_vehicle_model(vehicle_model_type_str); // set initialize source - const auto initialize_source = declare_parameter("initialize_source", "INITIAL_POSE_TOPIC"); + const auto initialize_source = declare_parameter("initialize_source"); RCLCPP_DEBUG(this->get_logger(), "initialize_source : %s", initialize_source.c_str()); if (initialize_source == "ORIGIN") { Pose p; @@ -215,17 +215,17 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt std::random_device seed; auto & m = measurement_noise_; m.rand_engine_ = std::make_shared(seed()); - double pos_noise_stddev = declare_parameter("pos_noise_stddev", 1e-2); - double vel_noise_stddev = declare_parameter("vel_noise_stddev", 1e-2); - double rpy_noise_stddev = declare_parameter("rpy_noise_stddev", 1e-4); - double steer_noise_stddev = declare_parameter("steer_noise_stddev", 1e-4); + double pos_noise_stddev = declare_parameter("pos_noise_stddev"); + double vel_noise_stddev = declare_parameter("vel_noise_stddev"); + double rpy_noise_stddev = declare_parameter("rpy_noise_stddev"); + double steer_noise_stddev = declare_parameter("steer_noise_stddev"); m.pos_dist_ = std::make_shared>(0.0, pos_noise_stddev); m.vel_dist_ = std::make_shared>(0.0, vel_noise_stddev); m.rpy_dist_ = std::make_shared>(0.0, rpy_noise_stddev); m.steer_dist_ = std::make_shared>(0.0, steer_noise_stddev); - x_stddev_ = declare_parameter("x_stddev", 0.0001); - y_stddev_ = declare_parameter("y_stddev", 0.0001); + x_stddev_ = declare_parameter("x_stddev"); + y_stddev_ = declare_parameter("y_stddev"); } // control mode @@ -235,21 +235,21 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt void SimplePlanningSimulator::initialize_vehicle_model(const std::string & vehicle_model_type_str) { - const double vel_lim = declare_parameter("vel_lim", 50.0); - const double vel_rate_lim = declare_parameter("vel_rate_lim", 7.0); - const double steer_lim = declare_parameter("steer_lim", 1.0); - const double steer_rate_lim = declare_parameter("steer_rate_lim", 5.0); - const double acc_time_delay = declare_parameter("acc_time_delay", 0.1); - const double acc_time_constant = declare_parameter("acc_time_constant", 0.1); - const double vel_time_delay = declare_parameter("vel_time_delay", 0.25); - const double vel_time_constant = declare_parameter("vel_time_constant", 0.5); - const double steer_time_delay = declare_parameter("steer_time_delay", 0.24); - const double steer_time_constant = declare_parameter("steer_time_constant", 0.27); - const double steer_dead_band = declare_parameter("steer_dead_band", 0.0); - const double steer_bias = declare_parameter("steer_bias", 0.0); - - const double debug_acc_scaling_factor = declare_parameter("debug_acc_scaling_factor", 1.0); - const double debug_steer_scaling_factor = declare_parameter("debug_steer_scaling_factor", 1.0); + const double vel_lim = declare_parameter("vel_lim"); + const double vel_rate_lim = declare_parameter("vel_rate_lim"); + const double steer_lim = declare_parameter("steer_lim"); + const double steer_rate_lim = declare_parameter("steer_rate_lim"); + const double acc_time_delay = declare_parameter("acc_time_delay"); + const double acc_time_constant = declare_parameter("acc_time_constant"); + const double vel_time_delay = declare_parameter("vel_time_delay"); + const double vel_time_constant = declare_parameter("vel_time_constant"); + const double steer_time_delay = declare_parameter("steer_time_delay"); + const double steer_time_constant = declare_parameter("steer_time_constant"); + const double steer_dead_band = declare_parameter("steer_dead_band"); + const double steer_bias = declare_parameter("steer_bias"); + + const double debug_acc_scaling_factor = declare_parameter("debug_acc_scaling_factor"); + const double debug_steer_scaling_factor = declare_parameter("debug_steer_scaling_factor"); const auto vehicle_info = autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo(); const double wheelbase = vehicle_info.wheel_base_m; From d9a5b6dc23e5543379d0d63e1ea29e0f4a4c28ed Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Fri, 27 Oct 2023 14:26:57 +0800 Subject: [PATCH 02/12] refactor(simple_planning_simulator): rework parameters Signed-off-by: PhoebeWu21 --- .../simple_planning_simulator.schema.json | 79 ++++++++++++++++--- 1 file changed, 67 insertions(+), 12 deletions(-) diff --git a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json index 881f243de71cd..b0a28c331f349 100644 --- a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json +++ b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json @@ -157,22 +157,77 @@ "vehicle_characteristics": { "type": "object", "properties": { - "INSERT_PARAMETER_1_NAME": { - "type": "INSERT_TYPE", - "description": "INSERT_DESCRIPTION", - "default": "INSERT_DEFAULT", - "INSERT_BOUND_CONDITION(S)": "INSERT_BOUND_VALUE(S)" + "cg_to_front_m": { + "type": "number", + "description": "center of gravity to vehicle front [m]", + "default": "1.228", + "minimum": 0 }, - "INSERT_PARAMETER_N_NAME": { - "type": "INSERT_TYPE", - "description": "INSERT_DESCRIPTION", - "default": "INSERT_DEFAULT", - "INSERT_BOUND_CONDITION(S)": "INSERT_BOUND_VALUE(S)" + "cg_to_rear_m": { + "type": "number", + "description": "center of gravity to vehicle rear [m]", + "default": "1.5618", + "minimum": 0 + }, + "front_corner_stiffness": { + "type": "number", + "description": "stiffness of vehicle front corner", + "default": "17000.0", + "minimum": 0 + }, + "rear_corner_stiffness": { + "type": "number", + "description": "stiffness of vehicle rear corner", + "default": "20000.0", + "minimum": 0 + }, + "mass_kg": { + "type": "number", + "description": "vehicle weight [kg]", + "default": "1460.0", + "minimum": 0 + }, + "yaw_inertia_kgm2": { + "type": "number", + "description": "yaw inertia [kgm2]", + "default": "2170.0", + "minimum": 0 + }, + "width_m": { + "type": "number", + "description": "vehicle width [m]", + "default": "2.0", + "minimum": 0 + }, + "front_overhang_m": { + "type": "number", + "description": "front overhang [m]", + "default": "0.5", + "minimum": 0 + }, + "rear_overhang_m": { + "type": "number", + "description": "rear overhang [m]", + "default": "0.5", + "minimum": 0 + }, + "max_steer_angle": { + "type": "number", + "description": "max angle of steer [rad]", + "default": "0.70" } }, "required": [ - "INSERT_PARAMETER_1_NAME", - "INSERT_PARAMETER_N_NAME" + "cg_to_front_m", + "cg_to_rear_m", + "front_corner_stiffness", + "rear_corner_stiffness", + "mass_kg", + "yaw_inertia_kgm2", + "width_m", + "front_overhang_m", + "rear_overhang_m", + "max_steer_angle" ] } }, From 4aa9ba50447ff132a2f79f6f40f5299b14ecc714 Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Tue, 31 Oct 2023 10:17:03 +0800 Subject: [PATCH 03/12] refactor(simple_planning_simulator): rework parameters Signed-off-by: PhoebeWu21 --- .../launch/simple_planning_simulator.launch.py | 3 --- .../schema/simple_planning_simulator.schema.json | 5 +++-- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index aed088de9fd22..b3e11f3170b99 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -96,9 +96,6 @@ def launch_setup(context, *args, **kwargs): vehicle_info_param, vehicle_characteristics_param, simulator_model_param, - { - "initial_engage_state": LaunchConfiguration("initial_engage_state"), - }, ], remappings=remappings, ) diff --git a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json index b0a28c331f349..402a57d126ba5 100644 --- a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json +++ b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json @@ -1,6 +1,6 @@ { "$schema": "http://json-schema.org/draft-07/schema#", - "title": "Parameters for Simple Planning_ Simulator", + "title": "Parameters for Simple Planning Simulator Node", "type": "object", "definitions": { "simple_planning_simulator": { @@ -255,7 +255,8 @@ "steer_time_delay", "steer_time_constant", "x_stddev", - "y_stddev" + "y_stddev", + "vehicle_characteristics" ] } }, From 1bc6d6309ab0d879adde3fd7c2c576768b82b8f9 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 31 Oct 2023 02:25:56 +0000 Subject: [PATCH 04/12] style(pre-commit): autofix --- .../schema/simple_planning_simulator.schema.json | 13 +++---------- 1 file changed, 3 insertions(+), 10 deletions(-) diff --git a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json index 402a57d126ba5..78a75875e74fe 100644 --- a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json +++ b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json @@ -33,10 +33,7 @@ "type": "string", "description": "If 'ORIGIN', the initial pose is set at (0,0,0). If 'INITIAL_POSE_TOPIC', node will wait until the 'input/initialpose' topic is published.", "default": "INITIAL_POSE_TOPIC", - "enum": [ - "ORIGIN", - "INITIAL_POSE_TOPIC" - ] + "enum": ["ORIGIN", "INITIAL_POSE_TOPIC"] }, "initial_engage_state": { "type": "boolean", @@ -268,12 +265,8 @@ "$ref": "#/definitions/simple_planning_simulator" } }, - "required": [ - "ros__parameters" - ] + "required": ["ros__parameters"] } }, - "required": [ - "/**" - ] + "required": ["/**"] } From ec6ce42ca58b041caad124bfa6f0f7b93a8987d8 Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Wed, 1 Nov 2023 14:10:08 +0800 Subject: [PATCH 05/12] refactor(simple_planning_simulator): rework parameter Signed-off-by: PhoebeWu21 --- .../simple_planning_simulator.schema.json | 48 +++++++++---------- 1 file changed, 24 insertions(+), 24 deletions(-) diff --git a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json index 78a75875e74fe..47c8135668609 100644 --- a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json +++ b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json @@ -60,37 +60,37 @@ "type": "number", "description": "Standard deviation for position noise", "default": "1e-2", - "minimum": 0 + "minimum": 0.0 }, "vel_noise_stddev": { "type": "number", "description": "Standard deviation for longitudinal velocity noise", "default": "1e-2", - "minimum": 0 + "minimum": 0.0 }, "rpy_noise_stddev": { "type": "number", "description": "Standard deviation for Euler angle noise", "default": "1e-4", - "minimum": 0 + "minimum": 0.0 }, "steer_noise_stddev": { "type": "number", "description": "Standard deviation for steering angle noise", "default": "1e-4", - "minimum": 0 + "minimum": 0.0 }, "vel_lim": { "type": "number", "description": "limit of velocity [m/s]", "default": "30.0", - "exclusiveMinimum": 0 + "exclusiveMinimum": 0.0 }, "vel_rate_lim": { "type": "number", "description": "limit of velocity change rate [m/ss]", "default": "30.0", - "minimum": 0 + "minimum": 0.0 }, "steer_lim": { "type": "number", @@ -101,55 +101,55 @@ "type": "number", "description": "limit of steering angle change rate [rad/s]", "default": "6.28", - "minimum": 0 + "minimum": 0.0 }, "acc_time_delay": { "type": "number", "description": "dead time for the acceleration input [s]", "default": "0.1", - "minimum": 0 + "minimum": 0.0 }, "acc_time_constant": { "type": "number", "description": "time constant of the 1st-order acceleration dynamics [s]", "default": "0.1", - "minimum": 0 + "minimum": 0.0 }, "vel_time_delay": { "type": "number", "description": "dead time for the velocity input [s]", "default": "0.25", - "minimum": 0 + "minimum": 0.0 }, "vel_time_constant": { "type": "number", "description": "time constant of the 1st-order velocity dynamics [s]", "default": "0.5", - "minimum": 0 + "minimum": 0.0 }, "steer_time_delay": { "type": "number", "description": "dead time for the steering input [s]", "default": "0.1", - "minimum": 0 + "minimum": 0.0 }, "steer_time_constant": { "type": "number", "description": "time constant of the 1st-order steering dynamics [s]", "default": "0.1", - "minimum": 0 + "minimum": 0.0 }, "x_stddev": { "type": "number", "description": "x standard deviation for dummy covariance in map coordinate", "default": "0.0001", - "minimum": 0 + "minimum": 0.0 }, "y_stddev": { "type": "number", "description": "y standard deviation for dummy covariance in map coordinate", "default": "0.0001", - "minimum": 0 + "minimum": 0.0 }, "vehicle_characteristics": { "type": "object", @@ -158,55 +158,55 @@ "type": "number", "description": "center of gravity to vehicle front [m]", "default": "1.228", - "minimum": 0 + "minimum": 0.0 }, "cg_to_rear_m": { "type": "number", "description": "center of gravity to vehicle rear [m]", "default": "1.5618", - "minimum": 0 + "minimum": 0.0 }, "front_corner_stiffness": { "type": "number", "description": "stiffness of vehicle front corner", "default": "17000.0", - "minimum": 0 + "minimum": 0.0 }, "rear_corner_stiffness": { "type": "number", "description": "stiffness of vehicle rear corner", "default": "20000.0", - "minimum": 0 + "minimum": 0.0 }, "mass_kg": { "type": "number", "description": "vehicle weight [kg]", "default": "1460.0", - "minimum": 0 + "minimum": 0.0 }, "yaw_inertia_kgm2": { "type": "number", "description": "yaw inertia [kgm2]", "default": "2170.0", - "minimum": 0 + "minimum": 0.0 }, "width_m": { "type": "number", "description": "vehicle width [m]", "default": "2.0", - "minimum": 0 + "minimum": 0.0 }, "front_overhang_m": { "type": "number", "description": "front overhang [m]", "default": "0.5", - "minimum": 0 + "minimum": 0.0 }, "rear_overhang_m": { "type": "number", "description": "rear overhang [m]", "default": "0.5", - "minimum": 0 + "minimum": 0.0 }, "max_steer_angle": { "type": "number", From 429d31cb40ff74e0b66af6ec131cc53a556368f2 Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Mon, 6 Nov 2023 10:05:18 +0800 Subject: [PATCH 06/12] refactor(simple_planning_simulator): rework parameters Signed-off-by: PhoebeWu21 --- simulator/simple_planning_simulator/CMakeLists.txt | 7 ++++++- .../{param => config}/acceleration_map.csv | 0 .../simple_planning_simulator_default.param.yaml | 0 .../simple_planning_simulator_mechanical_sample.param.yaml | 0 .../{param => config}/vehicle_characteristics.param.yaml | 0 .../launch/simple_planning_simulator.launch.py | 6 +++--- 6 files changed, 9 insertions(+), 4 deletions(-) rename simulator/simple_planning_simulator/{param => config}/acceleration_map.csv (100%) rename simulator/simple_planning_simulator/{param => config}/simple_planning_simulator_default.param.yaml (100%) rename simulator/simple_planning_simulator/{param => config}/simple_planning_simulator_mechanical_sample.param.yaml (100%) rename simulator/simple_planning_simulator/{param => config}/vehicle_characteristics.param.yaml (100%) diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index 6acb74342c90f..f77b7dd6b0bcc 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -43,4 +43,9 @@ if(BUILD_TESTING) ) endif() -ament_auto_package(INSTALL_TO_SHARE param data launch test) +ament_auto_package(INSTALL_TO_SHARE + config + data + launch + test +) diff --git a/simulator/simple_planning_simulator/param/acceleration_map.csv b/simulator/simple_planning_simulator/config/acceleration_map.csv similarity index 100% rename from simulator/simple_planning_simulator/param/acceleration_map.csv rename to simulator/simple_planning_simulator/config/acceleration_map.csv diff --git a/simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml b/simulator/simple_planning_simulator/config/simple_planning_simulator_default.param.yaml similarity index 100% rename from simulator/simple_planning_simulator/param/simple_planning_simulator_default.param.yaml rename to simulator/simple_planning_simulator/config/simple_planning_simulator_default.param.yaml diff --git a/simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml b/simulator/simple_planning_simulator/config/simple_planning_simulator_mechanical_sample.param.yaml similarity index 100% rename from simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml rename to simulator/simple_planning_simulator/config/simple_planning_simulator_mechanical_sample.param.yaml diff --git a/simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml b/simulator/simple_planning_simulator/config/vehicle_characteristics.param.yaml similarity index 100% rename from simulator/simple_planning_simulator/param/vehicle_characteristics.param.yaml rename to simulator/simple_planning_simulator/config/vehicle_characteristics.param.yaml diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index b3e11f3170b99..a925c00944c57 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -25,7 +25,7 @@ def launch_setup(context, *args, **kwargs): - # vehicle information param path + # vehicle information config path vehicle_info_param_path = LaunchConfiguration("vehicle_info_param_file").perform(context) with open(vehicle_info_param_path, "r") as f: vehicle_info_param = yaml.safe_load(f)["/**"]["ros__parameters"] @@ -149,7 +149,7 @@ def add_launch_arg(name: str, default_value=None, description=None): "vehicle_characteristics_param_file", [ FindPackageShare("simple_planning_simulator"), - "/param/vehicle_characteristics.param.yaml", + "/config/vehicle_characteristics.param.yaml", ], "path to config file for vehicle characteristics", ) @@ -158,7 +158,7 @@ def add_launch_arg(name: str, default_value=None, description=None): "simulator_model_param_file", [ FindPackageShare("simple_planning_simulator"), - "/param/simple_planning_simulator_default.param.yaml", + "/config/simple_planning_simulator_default.param.yaml", ], "path to config file for simulator_model", ) From 9443ed164fc396e4a8f2ffc50c0218b8eaec3a7a Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Thu, 16 Nov 2023 11:50:54 +0800 Subject: [PATCH 07/12] refactor(simple_planning_simulator): rework parameters Signed-off-by: PhoebeWu21 --- .../simple_planning_simulator.schema.json | 76 --------------- .../vehicle_characteristics.schema.json | 95 +++++++++++++++++++ 2 files changed, 95 insertions(+), 76 deletions(-) create mode 100644 simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json diff --git a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json index 47c8135668609..4ae964b141c89 100644 --- a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json +++ b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json @@ -150,82 +150,6 @@ "description": "y standard deviation for dummy covariance in map coordinate", "default": "0.0001", "minimum": 0.0 - }, - "vehicle_characteristics": { - "type": "object", - "properties": { - "cg_to_front_m": { - "type": "number", - "description": "center of gravity to vehicle front [m]", - "default": "1.228", - "minimum": 0.0 - }, - "cg_to_rear_m": { - "type": "number", - "description": "center of gravity to vehicle rear [m]", - "default": "1.5618", - "minimum": 0.0 - }, - "front_corner_stiffness": { - "type": "number", - "description": "stiffness of vehicle front corner", - "default": "17000.0", - "minimum": 0.0 - }, - "rear_corner_stiffness": { - "type": "number", - "description": "stiffness of vehicle rear corner", - "default": "20000.0", - "minimum": 0.0 - }, - "mass_kg": { - "type": "number", - "description": "vehicle weight [kg]", - "default": "1460.0", - "minimum": 0.0 - }, - "yaw_inertia_kgm2": { - "type": "number", - "description": "yaw inertia [kgm2]", - "default": "2170.0", - "minimum": 0.0 - }, - "width_m": { - "type": "number", - "description": "vehicle width [m]", - "default": "2.0", - "minimum": 0.0 - }, - "front_overhang_m": { - "type": "number", - "description": "front overhang [m]", - "default": "0.5", - "minimum": 0.0 - }, - "rear_overhang_m": { - "type": "number", - "description": "rear overhang [m]", - "default": "0.5", - "minimum": 0.0 - }, - "max_steer_angle": { - "type": "number", - "description": "max angle of steer [rad]", - "default": "0.70" - } - }, - "required": [ - "cg_to_front_m", - "cg_to_rear_m", - "front_corner_stiffness", - "rear_corner_stiffness", - "mass_kg", - "yaw_inertia_kgm2", - "width_m", - "front_overhang_m", - "rear_overhang_m", - "max_steer_angle" - ] } }, "required": [ diff --git a/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json b/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json new file mode 100644 index 0000000000000..37eca4bd96944 --- /dev/null +++ b/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json @@ -0,0 +1,95 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for Vehicle Characteristics in Simple Planning Simulator Node", + "type": "object", + "definitions": { + "vehicle_characteristics": { + "type": "object", + "properties": { + "cg_to_front_m": { + "type": "number", + "description": "center of gravity to vehicle front [m]", + "default": "1.228", + "minimum": 0.0 + }, + "cg_to_rear_m": { + "type": "number", + "description": "center of gravity to vehicle rear [m]", + "default": "1.5618", + "minimum": 0.0 + }, + "front_corner_stiffness": { + "type": "number", + "description": "stiffness of vehicle front corner", + "default": "17000.0", + "minimum": 0.0 + }, + "rear_corner_stiffness": { + "type": "number", + "description": "stiffness of vehicle rear corner", + "default": "20000.0", + "minimum": 0.0 + }, + "mass_kg": { + "type": "number", + "description": "vehicle weight [kg]", + "default": "1460.0", + "minimum": 0.0 + }, + "yaw_inertia_kgm2": { + "type": "number", + "description": "yaw inertia [kgm2]", + "default": "2170.0", + "minimum": 0.0 + }, + "width_m": { + "type": "number", + "description": "vehicle width [m]", + "default": "2.0", + "minimum": 0.0 + }, + "front_overhang_m": { + "type": "number", + "description": "front overhang [m]", + "default": "0.5", + "minimum": 0.0 + }, + "rear_overhang_m": { + "type": "number", + "description": "rear overhang [m]", + "default": "0.5", + "minimum": 0.0 + }, + "max_steer_angle": { + "type": "number", + "description": "max angle of steer [rad]", + "default": "0.70" + } + }, + "required": [ + "cg_to_front_m", + "cg_to_rear_m", + "front_corner_stiffness", + "rear_corner_stiffness", + "mass_kg", + "yaw_inertia_kgm2", + "width_m", + "front_overhang_m", + "rear_overhang_m", + "max_steer_angle" + ] + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/simple_planning_simulator" + } + }, + "required": ["ros__parameters"] + } + }, + "required": ["/**"] +} From ce792ba998b38fefa50c9d7d0272ce5651221bb6 Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Thu, 16 Nov 2023 11:54:00 +0800 Subject: [PATCH 08/12] refactor(simple_planning_simulator): rework parameters Signed-off-by: PhoebeWu21 --- ..._default.param.yaml => simple_planning_simulator.param.yaml} | 0 .../launch/simple_planning_simulator.launch.py | 2 +- .../schema/vehicle_characteristics.schema.json | 2 +- 3 files changed, 2 insertions(+), 2 deletions(-) rename simulator/simple_planning_simulator/config/{simple_planning_simulator_default.param.yaml => simple_planning_simulator.param.yaml} (100%) diff --git a/simulator/simple_planning_simulator/config/simple_planning_simulator_default.param.yaml b/simulator/simple_planning_simulator/config/simple_planning_simulator.param.yaml similarity index 100% rename from simulator/simple_planning_simulator/config/simple_planning_simulator_default.param.yaml rename to simulator/simple_planning_simulator/config/simple_planning_simulator.param.yaml diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index a925c00944c57..16ef5f590fbe8 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -158,7 +158,7 @@ def add_launch_arg(name: str, default_value=None, description=None): "simulator_model_param_file", [ FindPackageShare("simple_planning_simulator"), - "/config/simple_planning_simulator_default.param.yaml", + "/config/simple_planning_simulator.param.yaml", ], "path to config file for simulator_model", ) diff --git a/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json b/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json index 37eca4bd96944..fd2c1d9a80876 100644 --- a/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json +++ b/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json @@ -85,7 +85,7 @@ "type": "object", "properties": { "ros__parameters": { - "$ref": "#/definitions/simple_planning_simulator" + "$ref": "#/definitions/vehicle_characteristics" } }, "required": ["ros__parameters"] From 8bb9675a1e108b2a0b8765761ed623efdcf12626 Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Thu, 16 Nov 2023 15:19:15 +0800 Subject: [PATCH 09/12] refactor(simple_planning_simulator): rework parameters Signed-off-by: PhoebeWu21 --- .../schema/simple_planning_simulator.schema.json | 9 +++++---- .../schema/vehicle_characteristics.schema.json | 6 ++++-- 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json index 4ae964b141c89..d790d64a2a20e 100644 --- a/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json +++ b/simulator/simple_planning_simulator/schema/simple_planning_simulator.schema.json @@ -176,8 +176,7 @@ "steer_time_delay", "steer_time_constant", "x_stddev", - "y_stddev", - "vehicle_characteristics" + "y_stddev" ] } }, @@ -189,8 +188,10 @@ "$ref": "#/definitions/simple_planning_simulator" } }, - "required": ["ros__parameters"] + "required": ["ros__parameters"], + "additionalProperties": false } }, - "required": ["/**"] + "required": ["/**"], + "additionalProperties": false } diff --git a/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json b/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json index fd2c1d9a80876..83097a84f8455 100644 --- a/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json +++ b/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json @@ -88,8 +88,10 @@ "$ref": "#/definitions/vehicle_characteristics" } }, - "required": ["ros__parameters"] + "required": ["ros__parameters"], + "additionalProperties": false } }, - "required": ["/**"] + "required": ["/**"], + "additionalProperties": false } From 6e6aecadc335c6031f8d72d0e43098a012c31a1b Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Thu, 23 Nov 2023 09:02:34 +0800 Subject: [PATCH 10/12] refactor(simple_planning_simulator): rework parameters Signed-off-by: PhoebeWu21 --- .../config/vehicle_characteristics.param.yaml | 12 --- .../simple_planning_simulator.launch.py | 16 --- .../vehicle_characteristics.schema.json | 97 ------------------- 3 files changed, 125 deletions(-) delete mode 100644 simulator/simple_planning_simulator/config/vehicle_characteristics.param.yaml delete mode 100644 simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json diff --git a/simulator/simple_planning_simulator/config/vehicle_characteristics.param.yaml b/simulator/simple_planning_simulator/config/vehicle_characteristics.param.yaml deleted file mode 100644 index 42fd36825d213..0000000000000 --- a/simulator/simple_planning_simulator/config/vehicle_characteristics.param.yaml +++ /dev/null @@ -1,12 +0,0 @@ -/**: - ros__parameters: - cg_to_front_m: 1.228 - cg_to_rear_m: 1.5618 - front_corner_stiffness: 17000.0 - rear_corner_stiffness: 20000.0 - mass_kg: 1460.0 - yaw_inertia_kgm2: 2170.0 - width_m: 2.0 - front_overhang_m: 0.5 - rear_overhang_m: 0.5 - max_steer_angle: 0.70 # [rad] diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index 16ef5f590fbe8..d5634ce841b96 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -30,12 +30,6 @@ def launch_setup(context, *args, **kwargs): with open(vehicle_info_param_path, "r") as f: vehicle_info_param = yaml.safe_load(f)["/**"]["ros__parameters"] - vehicle_characteristics_param_path = LaunchConfiguration( - "vehicle_characteristics_param_file" - ).perform(context) - with open(vehicle_characteristics_param_path, "r") as f: - vehicle_characteristics_param = yaml.safe_load(f)["/**"]["ros__parameters"] - simulator_model_param_path = LaunchConfiguration("simulator_model_param_file").perform(context) simulator_model_param = launch_ros.parameter_descriptions.ParameterFile( param_file=simulator_model_param_path, allow_substs=True @@ -94,7 +88,6 @@ def launch_setup(context, *args, **kwargs): output="screen", parameters=[ vehicle_info_param, - vehicle_characteristics_param, simulator_model_param, ], remappings=remappings, @@ -145,15 +138,6 @@ def add_launch_arg(name: str, default_value=None, description=None): "path to the parameter file of vehicle information", ) - add_launch_arg( - "vehicle_characteristics_param_file", - [ - FindPackageShare("simple_planning_simulator"), - "/config/vehicle_characteristics.param.yaml", - ], - "path to config file for vehicle characteristics", - ) - add_launch_arg( "simulator_model_param_file", [ diff --git a/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json b/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json deleted file mode 100644 index 83097a84f8455..0000000000000 --- a/simulator/simple_planning_simulator/schema/vehicle_characteristics.schema.json +++ /dev/null @@ -1,97 +0,0 @@ -{ - "$schema": "http://json-schema.org/draft-07/schema#", - "title": "Parameters for Vehicle Characteristics in Simple Planning Simulator Node", - "type": "object", - "definitions": { - "vehicle_characteristics": { - "type": "object", - "properties": { - "cg_to_front_m": { - "type": "number", - "description": "center of gravity to vehicle front [m]", - "default": "1.228", - "minimum": 0.0 - }, - "cg_to_rear_m": { - "type": "number", - "description": "center of gravity to vehicle rear [m]", - "default": "1.5618", - "minimum": 0.0 - }, - "front_corner_stiffness": { - "type": "number", - "description": "stiffness of vehicle front corner", - "default": "17000.0", - "minimum": 0.0 - }, - "rear_corner_stiffness": { - "type": "number", - "description": "stiffness of vehicle rear corner", - "default": "20000.0", - "minimum": 0.0 - }, - "mass_kg": { - "type": "number", - "description": "vehicle weight [kg]", - "default": "1460.0", - "minimum": 0.0 - }, - "yaw_inertia_kgm2": { - "type": "number", - "description": "yaw inertia [kgm2]", - "default": "2170.0", - "minimum": 0.0 - }, - "width_m": { - "type": "number", - "description": "vehicle width [m]", - "default": "2.0", - "minimum": 0.0 - }, - "front_overhang_m": { - "type": "number", - "description": "front overhang [m]", - "default": "0.5", - "minimum": 0.0 - }, - "rear_overhang_m": { - "type": "number", - "description": "rear overhang [m]", - "default": "0.5", - "minimum": 0.0 - }, - "max_steer_angle": { - "type": "number", - "description": "max angle of steer [rad]", - "default": "0.70" - } - }, - "required": [ - "cg_to_front_m", - "cg_to_rear_m", - "front_corner_stiffness", - "rear_corner_stiffness", - "mass_kg", - "yaw_inertia_kgm2", - "width_m", - "front_overhang_m", - "rear_overhang_m", - "max_steer_angle" - ] - } - }, - "properties": { - "/**": { - "type": "object", - "properties": { - "ros__parameters": { - "$ref": "#/definitions/vehicle_characteristics" - } - }, - "required": ["ros__parameters"], - "additionalProperties": false - } - }, - "required": ["/**"], - "additionalProperties": false -} From 7afefa1aee044874aa585f97dc6b1a88b3cd8e1e Mon Sep 17 00:00:00 2001 From: PhoebeWu21 Date: Mon, 27 Nov 2023 09:18:22 +0800 Subject: [PATCH 11/12] refactor(simple_planning_simulator): rework parameters Signed-off-by: PhoebeWu21 --- .../launch/simple_planning_simulator.launch.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index d5634ce841b96..50c2c1a2ce49a 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -89,6 +89,9 @@ def launch_setup(context, *args, **kwargs): parameters=[ vehicle_info_param, simulator_model_param, + { + "initial_engage_state": LaunchConfiguration("initial_engage_state"), + } ], remappings=remappings, ) From 323d1e0f7413621a0988676cbf041802a6538620 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Mon, 27 Nov 2023 01:20:32 +0000 Subject: [PATCH 12/12] style(pre-commit): autofix --- .../launch/simple_planning_simulator.launch.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index 50c2c1a2ce49a..29d15e4470237 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -91,7 +91,7 @@ def launch_setup(context, *args, **kwargs): simulator_model_param, { "initial_engage_state": LaunchConfiguration("initial_engage_state"), - } + }, ], remappings=remappings, )