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

[pull] main from autowarefoundation:main #425

Merged
merged 5 commits into from
Nov 24, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
104 changes: 104 additions & 0 deletions control/vehicle_cmd_gate/schema/vehicle_cmd_gate.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for vehicle cmd gate",
"type": "object",
"definitions": {
"vehicle_cmd_gate": {
"type": "object",
"properties": {
"update_rate": {
"type": "number",
"default": 10.0,
"description": "To update period"
},
"use_emergency_handling": {
"type": "boolean",
"default": "false",
"description": "true when emergency handler is used."
},
"use_external_emergency_stop": {
"type": "boolean",
"default": "false",
"description": "true when external emergency stop information is used."
},
"system_emergency_heartbeat_timeout": {
"type": "number",
"default": 0.5,
"description": "timeout for system emergency."
},
"external_emergency_stop_heartbeat_timeout": {
"type": "number",
"default": 0.5,
"description": "timeout for external emergency."
},
"stop_hold_acceleration": {
"type": "number",
"default": -1.5,
"description": "longitudinal acceleration cmd when vehicle should stop"
},
"emergency_acceleration": {
"type": "number",
"default": -2.4,
"description": "longitudinal acceleration cmd when vehicle stop with emergency."
},
"nominal.vel_lim": {
"type": "number",
"default": 25.0,
"description": "limit of longitudinal velocity (activated in AUTONOMOUS operation mode)."
},
"nominal.lon_acc_lim": {
"type": "number",
"default": 5.0,
"description": "limit of longitudinal acceleration (activated in AUTONOMOUS operation mode)."
},
"nominal.lon_jerk_lim": {
"type": "number",
"default": 5.0,
"description": "limit of longitudinal jerk (activated in AUTONOMOUS operation mode)."
},
"nominal.lat_acc_lim": {
"type": "number",
"default": 5.0,
"description": "limit of lateral acceleration (activated in AUTONOMOUS operation mode)."
},
"nominal.lat_jerk_lim": {
"type": "number",
"default": 5.0,
"description": "limit of lateral jerk (activated in AUTONOMOUS operation mode)."
},
"nominal.actual_steer_diff_lim": {
"type": "number",
"default": 1.0,
"description": "limit of actual steer diff (activated in AUTONOMOUS operation mode)."
}
},
"required": [
"update_rate",
"use_emergency_handling",
"use_external_emergency_stop",
"system_emergency_heartbeat_timeout",
"external_emergency_stop_heartbeat_timeout",
"stop_hold_acceleration",
"emergency_acceleration",
"nominal.vel_lim",
"nominal.lon_acc_lim",
"nominal.lon_jerk_lim",
"nominal.lat_acc_lim",
"nominal.lat_jerk_lim",
"nominal.actual_steer_diff_lim"
]
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/vehicle_cmd_gate"
}
},
"required": ["ros__parameters"]
}
},
"required": ["/**"]
}
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<arg name="behavior_velocity_planner_out_of_lane_module_param_path"/>
<arg name="behavior_velocity_planner_no_drivable_lane_module_param_path"/>
<!-- <arg name="behavior_velocity_planner_template_module_param_path"/> -->
<arg name="behavior_velocity_planner_param_file" default="$(find-pkg-share behavior_velocity_planner)/config/behavior_velocity_planner.param.yaml"/>

<node pkg="behavior_velocity_planner" exec="behavior_velocity_planner_node" name="behavior_velocity_planner" output="screen">
<!-- topic remap -->
Expand Down Expand Up @@ -69,5 +70,7 @@
<param from="$(var behavior_velocity_planner_out_of_lane_module_param_path)"/>
<param from="$(var behavior_velocity_planner_no_drivable_lane_module_param_path)"/>
<!-- <param from="$(var behavior_velocity_planner_template_param_path)"/> -->

<param from="$(var behavior_velocity_planner_param_file)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for Behavior Velocity Planner",
"type": "object",
"definitions": {
"behavior_velocity_planner": {
"type": "object",
"properties": {
"forward_path_length": {
"type": "number",
"default": "1000.0",
"description": "forward path"
},
"backward_path_length": {
"type": "number",
"default": "5.0",
"description": "backward path"
},
"max_accel": {
"type": "number",
"default": "-2.8",
"description": "(to be a global parameter) max acceleration of the vehicle"
},
"system_delay": {
"type": "number",
"default": "0.5",
"description": "(to be a global parameter) delay time until output control command"
},
"delay_response_time": {
"type": "number",
"default": "0.5",
"description": "(to be a global parameter) delay time of the vehicle's response to control commands"
},
"stop_line_extend_length": {
"type": "number",
"default": "5.0",
"description": "extend length of stop line"
},
"max_jerk": {
"type": "number",
"default": "-5.0",
"description": "max jerk of the vehicle"
},
"is_publish_debug_path": {
"type": "number",
"default": "false",
"description": "is publish debug path?"
}
},
"required": [
"forward_path_length",
"backward_path_length",
"max_accel",
"system_delay",
"delay_response_time",
"stop_line_extend_length",
"max_jerk",
"is_publish_debug_path"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/behavior_velocity_planner"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
12 changes: 5 additions & 7 deletions planning/behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,16 +136,14 @@ BehaviorVelocityPlannerNode::BehaviorVelocityPlannerNode(const rclcpp::NodeOptio
debug_viz_pub_ = this->create_publisher<visualization_msgs::msg::MarkerArray>("~/debug/path", 1);

// Parameters
forward_path_length_ = this->declare_parameter<double>("forward_path_length");
backward_path_length_ = this->declare_parameter<double>("backward_path_length");
planner_data_.stop_line_extend_length =
this->declare_parameter<double>("stop_line_extend_length");
forward_path_length_ = declare_parameter<double>("forward_path_length");
backward_path_length_ = declare_parameter<double>("backward_path_length");
planner_data_.stop_line_extend_length = declare_parameter<double>("stop_line_extend_length");

// nearest search
planner_data_.ego_nearest_dist_threshold =
this->declare_parameter<double>("ego_nearest_dist_threshold");
planner_data_.ego_nearest_yaw_threshold =
this->declare_parameter<double>("ego_nearest_yaw_threshold");
declare_parameter<double>("ego_nearest_dist_threshold");
planner_data_.ego_nearest_yaw_threshold = declare_parameter<double>("ego_nearest_yaw_threshold");

// Initialize PlannerManager
for (const auto & name : declare_parameter<std::vector<std::string>>("launch_modules")) {
Expand Down
12 changes: 1 addition & 11 deletions planning/external_velocity_limit_selector/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -51,17 +51,7 @@ Example:

## Parameters

| Parameter | Type | Description |
| ----------------- | ------ | ------------------------------------------ |
| `max_velocity` | double | default max velocity [m/s] |
| `normal.min_acc` | double | minimum acceleration [m/ss] |
| `normal.max_acc` | double | maximum acceleration [m/ss] |
| `normal.min_jerk` | double | minimum jerk [m/sss] |
| `normal.max_jerk` | double | maximum jerk [m/sss] |
| `limit.min_acc` | double | minimum acceleration to be observed [m/ss] |
| `limit.max_acc` | double | maximum acceleration to be observed [m/ss] |
| `limit.min_jerk` | double | minimum jerk to be observed [m/sss] |
| `limit.max_jerk` | double | maximum jerk to be observed [m/sss] |
{{ json_to_markdown("planning/external_velocity_limit_selector/schema/external_velocity_limit_selector.schema.json") }}

## Assumptions / Known limits

Expand Down

This file was deleted.

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
/**:
ros__parameters:
# constraints param for normal driving
normal:
min_acc: -0.5 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
min_jerk: -0.5 # min jerk [m/sss]
max_jerk: 1.0 # max jerk [m/sss]

# constraints to be observed
limit:
min_acc: -2.5 # min deceleration limit [m/ss]
max_acc: 1.0 # max acceleration limit [m/ss]
min_jerk: -1.5 # min jerk limit [m/sss]
max_jerk: 1.5 # max jerk limit [m/sss]

# motion state constraints
max_velocity: 20.0 # max velocity limit [m/s]
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
<launch>
<!-- common param -->
<arg name="common_param_path" default="$(find-pkg-share external_velocity_limit_selector)/config/default_common.param.yaml"/>
<arg name="param_path" default="$(find-pkg-share external_velocity_limit_selector)/config/default.param.yaml"/>
<arg name="external_velocity_limit_selector_param_path" default="$(find-pkg-share external_velocity_limit_selector)/config/external_velocity_limit_selector.param.yaml"/>

<!-- input/output -->
<arg name="input_velocity_limit_from_api" default="/planning/scenario_planning/max_velocity_default"/>
Expand All @@ -11,8 +10,7 @@
<arg name="output_debug_string" default="/planning/scenario_planning/external_velocity_limit_selector/debug"/>

<node pkg="external_velocity_limit_selector" exec="external_velocity_limit_selector" name="external_velocity_limit_selector" output="screen">
<param from="$(var common_param_path)"/>
<param from="$(var param_path)"/>
<param from="$(var external_velocity_limit_selector_param_path)"/>
<remap from="input/velocity_limit_from_api" to="$(var input_velocity_limit_from_api)"/>
<remap from="input/velocity_limit_from_internal" to="$(var input_velocity_limit_from_internal)"/>
<remap from="input/velocity_limit_clear_command_from_internal" to="$(var input_velocity_limit_clear_command_from_internal)"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,85 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for external velocity limit selector node",
"type": "object",
"definitions": {
"external_velocity_limit_selector": {
"type": "object",
"properties": {
"max_velocity": {
"type": "number",
"description": "max velocity limit [m/s]",
"default": 20.0
},
"normal": {
"type": "object",
"properties": {
"min_acc": {
"type": "number",
"description": "min deceleration [m/ss]",
"default": -0.5
},
"max_acc": {
"type": "number",
"description": "max acceleration [m/ss]",
"default": 1.0
},
"min_jerk": {
"type": "number",
"description": "min jerk [m/sss]",
"default": -0.5
},
"max_jerk": {
"type": "number",
"description": "max jerk [m/sss]",
"default": 1.0
}
},
"required": ["min_acc", "max_acc", "min_jerk", "max_jerk"]
},
"limit": {
"type": "object",
"properties": {
"min_acc": {
"type": "number",
"description": "min deceleration to be observed [m/ss]",
"default": -2.5
},
"max_acc": {
"type": "number",
"description": "max acceleration to be observed [m/ss]",
"default": 1.0
},
"min_jerk": {
"type": "number",
"description": "min jerk to be observed [m/sss]",
"default": -1.5
},
"max_jerk": {
"type": "number",
"description": "max jerk to be observed [m/sss]",
"default": 1.5
}
},
"required": ["min_acc", "max_acc", "min_jerk", "max_jerk"]
}
},
"required": ["max_velocity", "normal", "limit"],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/external_velocity_limit_selector"
}
},
"required": ["ros__parameters"],
"additionalProperties": false
}
},
"required": ["/**"],
"additionalProperties": false
}
8 changes: 1 addition & 7 deletions sensing/gnss_poser/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,7 @@ The `gnss_poser` is a node that subscribes gnss sensing messages and calculates

### Core Parameters

| Name | Type | Default Value | Description |
| ---------------------- | ------ | ---------------- | ------------------------------------------------------------------------------------------------------ |
| `base_frame` | string | "base_link" | frame id |
| `gnss_frame` | string | "gnss" | frame id |
| `gnss_base_frame` | string | "gnss_base_link" | frame id |
| `map_frame` | string | "map" | frame id |
| `gnss_pose_pub_method` | int | 0 | 0: Instant Value 1: Average Value 2: Median Value. If 0 is chosen buffer_epoch parameter loses affect. |
{{ json_to_markdown("sensing/gnss_poser/schema/gnss_poser.schema.json") }}

## Assumptions / Known limits

Expand Down
Loading