Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(simple_planning_simulator): rework parameters #5446

Open
wants to merge 19 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 14 commits
Commits
Show all changes
19 commits
Select commit Hold shift + click to select a range
2a294ff
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Oct 27, 2023
ab76d5e
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Oct 27, 2023
b4b57d7
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Oct 31, 2023
04cefc6
style(pre-commit): autofix
pre-commit-ci[bot] Oct 31, 2023
33a4fe0
refactor(simple_planning_simulator): rework parameter
PhoebeWu21 Nov 1, 2023
2bb7f8b
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Nov 6, 2023
de9e9f4
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Nov 6, 2023
7efb6e1
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Nov 16, 2023
b57ae14
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Nov 16, 2023
54368bb
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Nov 16, 2023
2f0bb73
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Nov 16, 2023
c52e1e5
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Nov 23, 2023
5199323
Merge branch 'main' into refactor-node-config-simple_planning_simulator
satoshi-ota Nov 23, 2023
391a720
Merge branch 'main' into refactor-node-config-simple_planning_simulator
PhoebeWu21 Nov 27, 2023
090c425
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Nov 27, 2023
617ff95
style(pre-commit): autofix
pre-commit-ci[bot] Nov 27, 2023
986ce1a
refactor(simple_planning_simulator): rework parameters
PhoebeWu21 Nov 30, 2023
c4cffa1
Merge branch 'main' into refactor-node-config-simple_planning_simulator
PhoebeWu21 Nov 30, 2023
3fe5938
Merge branch 'main' into refactor-node-config-simple_planning_simulator
PhoebeWu21 Dec 4, 2023
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion simulator/simple_planning_simulator/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,4 +38,6 @@ if(BUILD_TESTING)
)
endif()

ament_auto_package(INSTALL_TO_SHARE param launch)
ament_auto_package(INSTALL_TO_SHARE
config
launch)
12 changes: 1 addition & 11 deletions simulator/simple_planning_simulator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,27 @@
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
debug_acc_scaling_factor: 1.0
debug_steer_scaling_factor: 1.0
x_stddev: 0.0001 # x standard deviation for dummy covariance in map coordinate
y_stddev: 0.0001 # y standard deviation for dummy covariance in map coordinate

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,17 +23,11 @@


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"]

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)
with open(simulator_model_param_path, "r") as f:
simulator_model_param = yaml.safe_load(f)["/**"]["ros__parameters"]
Expand All @@ -46,11 +40,7 @@ def launch_setup(context, *args, **kwargs):
output="screen",
parameters=[
vehicle_info_param,
vehicle_characteristics_param,
simulator_model_param,
{
"initial_engage_state": LaunchConfiguration("initial_engage_state"),
},
],
remappings=[
("input/vector_map", "/map/vector_map"),
Expand Down Expand Up @@ -111,20 +101,11 @@ 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"),
"/param/vehicle_characteristics.param.yaml",
],
"path to config file for vehicle characteristics",
)

add_launch_arg(
"simulator_model_param_file",
[
FindPackageShare("simple_planning_simulator"),
"/param/simple_planning_simulator_default.param.yaml",
"/config/simple_planning_simulator.param.yaml",
],
"path to config file for simulator_model",
)
Expand Down

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,219 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Simple Planning Simulator Node",
"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.0
},
"vel_noise_stddev": {
"type": "number",
"description": "Standard deviation for longitudinal velocity noise",
"default": "1e-2",
"minimum": 0.0
},
"rpy_noise_stddev": {
"type": "number",
"description": "Standard deviation for Euler angle noise",
"default": "1e-4",
"minimum": 0.0
},
"steer_noise_stddev": {
"type": "number",
"description": "Standard deviation for steering angle noise",
"default": "1e-4",
"minimum": 0.0
},
"vel_lim": {
"type": "number",
"description": "limit of velocity [m/s]",
"default": "30.0",
"exclusiveMinimum": 0.0
},
"vel_rate_lim": {
"type": "number",
"description": "limit of velocity change rate [m/ss]",
"default": "30.0",
"minimum": 0.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.0
},
"acc_time_delay": {
"type": "number",
"description": "dead time for the acceleration input [s]",
"default": "0.1",
"minimum": 0.0
},
"acc_time_constant": {
"type": "number",
"description": "time constant of the 1st-order acceleration dynamics [s]",
"default": "0.1",
"minimum": 0.0
},
"vel_time_delay": {
"type": "number",
"description": "dead time for the velocity input [s]",
"default": "0.25",
"minimum": 0.0
},
"vel_time_constant": {
"type": "number",
"description": "time constant of the 1st-order velocity dynamics [s]",
"default": "0.5",
"minimum": 0.0
},
"steer_time_delay": {
"type": "number",
"description": "dead time for the steering input [s]",
"default": "0.1",
"minimum": 0.0
},
"steer_time_constant": {
"type": "number",
"description": "time constant of the 1st-order steering dynamics [s]",
"default": "0.1",
"minimum": 0.0
},
"steer_dead_band": {
"type": "number",
"description": "dead band for steering angle [rad]",
"default": "0.0",
"maximum": 3.142,
"minimum": -3.142
},
"debug_acc_scaling_factor": {
"type": "number",
"description": "scaling factor for accel command",
"default": "1.0",
"minimum": 0.0
},
"debug_steer_scaling_factor": {
"type": "number",
"description": "scaling factor for steer command",
"default": "1.0",
"minimum": 0.0
},
"x_stddev": {
"type": "number",
"description": "x standard deviation for dummy covariance in map coordinate",
"default": "0.0001",
"minimum": 0.0
},
"y_stddev": {
"type": "number",
"description": "y standard deviation for dummy covariance in map coordinate",
"default": "0.0001",
"minimum": 0.0
}
},
"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",
"steer_dead_band",
"debug_acc_scaling_factor",
"debug_steer_scaling_factor",
"x_stddev",
"y_stddev"
]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/simple_planning_simulator"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
Loading
Loading