diff --git a/planning/autoware_obstacle_cruise_planner/README.md b/planning/autoware_obstacle_cruise_planner/README.md new file mode 100644 index 0000000000000..18391eb919eeb --- /dev/null +++ b/planning/autoware_obstacle_cruise_planner/README.md @@ -0,0 +1,424 @@ +# Obstacle Cruise Planner + +## Overview + +The `autoware_obstacle_cruise_planner` package has following modules. + +- Stop planning + - stop when there is a static obstacle near the trajectory. +- Cruise planning + - cruise a dynamic obstacle in front of the ego. +- Slow down planning + - slow down when there is a static/dynamic obstacle near the trajectory. + +## Interfaces + +### Input topics + +| Name | Type | Description | +| -------------------- | ------------------------------------------ | ---------------- | +| `~/input/trajectory` | autoware_planning_msgs::Trajectory | input trajectory | +| `~/input/objects` | autoware_perception_msgs::PredictedObjects | dynamic objects | +| `~/input/odometry` | nav_msgs::msg::Odometry | ego odometry | + +### Output topics + +| Name | Type | Description | +| ------------------------------- | --------------------------------------------------------------- | -------------------------------- | +| `~/output/trajectory` | autoware_planning_msgs::Trajectory | output trajectory | +| `~/output/velocity_limit` | autoware_internal_planning_msgs::msg::VelocityLimit | velocity limit for cruising | +| `~/output/clear_velocity_limit` | autoware_internal_planning_msgs::msg::VelocityLimitClearCommand | clear command for velocity limit | + +## Design + +Design for the following functions is defined here. + +- Behavior determination against obstacles +- Stop planning +- Cruise planning +- Slow down planning + +A data structure for cruise and stop planning is as follows. +This planner data is created first, and then sent to the planning algorithm. + +```cpp +struct PlannerData +{ + rclcpp::Time current_time; + autoware_planning_msgs::msg::Trajectory traj; + geometry_msgs::msg::Pose current_pose; + double ego_vel; + double current_acc; + std::vector target_obstacles; +}; +``` + +```cpp +struct Obstacle +{ + rclcpp::Time stamp; // This is not the current stamp, but when the object was observed. + geometry_msgs::msg::Pose pose; // interpolated with the current stamp + bool orientation_reliable; + Twist twist; + bool twist_reliable; + ObjectClassification classification; + std::string uuid; + Shape shape; + std::vector predicted_paths; +}; +``` + +### Behavior determination against obstacles + +Obstacles for cruising, stopping and slowing down are selected in this order based on their pose and velocity. +The obstacles not in front of the ego will be ignored. + +![determine_cruise_stop_slow_down](./media/determine_cruise_stop_slow_down.drawio.svg) + +The behavior determination flowchart is shown below. + +![behavior_determination_flowchart](./media/behavior_determination_flowchart.drawio.svg) + +#### Determine cruise vehicles + +The obstacles meeting the following condition are determined as obstacles for cruising. + +- The lateral distance from the object to the ego's trajectory is smaller than `behavior_determination.cruise.max_lat_margin`. + +- The object type is for cruising according to `common.cruise_obstacle_type.*`. +- The object is not crossing the ego's trajectory (\*1). +- If the object is inside the trajectory. + - The object type is for inside cruising according to `common.cruise_obstacle_type.inside.*`. + - The object velocity is larger than `behavior_determination.obstacle_velocity_threshold_from_cruise_to_stop`. +- If the object is outside the trajectory. + - The object type is for outside cruising according to `common.cruise_obstacle_type.outside.*`. + - The object velocity is larger than `behavior_determination.cruise.outside_obstacle.obstacle_velocity_threshold`. + - The highest confident predicted path collides with the ego's trajectory. + - Its collision's period is larger than `behavior_determination.cruise.outside_obstacle.ego_obstacle_overlap_time_threshold`. + +| Parameter | Type | Description | +| ------------------------------------------------------------------------------------ | ------ | -------------------------------------------------------------------- | +| `common.cruise_obstacle_type.inside.unknown` | bool | flag to consider unknown objects for cruising | +| `common.cruise_obstacle_type.inside.car` | bool | flag to consider unknown objects for cruising | +| `common.cruise_obstacle_type.inside.truck` | bool | flag to consider unknown objects for cruising | +| ... | bool | ... | +| `common.cruise_obstacle_type.outside.unknown` | bool | flag to consider unknown objects for cruising | +| `common.cruise_obstacle_type.outside.car` | bool | flag to consider unknown objects for cruising | +| `common.cruise_obstacle_type.outside.truck` | bool | flag to consider unknown objects for cruising | +| ... | bool | ... | +| `behavior_determination.cruise.max_lat_margin` | double | maximum lateral margin for cruise obstacles | +| `behavior_determination.obstacle_velocity_threshold_from_cruise_to_stop` | double | maximum obstacle velocity for cruise obstacle inside the trajectory | +| `behavior_determination.cruise.outside_obstacle.obstacle_velocity_threshold` | double | maximum obstacle velocity for cruise obstacle outside the trajectory | +| `behavior_determination.cruise.outside_obstacle.ego_obstacle_overlap_time_threshold` | double | maximum overlap time of the collision between the ego and obstacle | + +##### Yield for vehicles that might cut in into the ego's lane + +It is also possible to yield (cruise) behind vehicles in neighbor lanes if said vehicles might cut in the ego vehicle's current lane. + +The obstacles meeting the following condition are determined as obstacles for yielding (cruising). + +- The object type is for cruising according to `common.cruise_obstacle_type.*` and it is moving with a speed greater than `behavior_determination.cruise.yield.stopped_obstacle_velocity_threshold`. +- The object is not crossing the ego's trajectory (\*1). +- There is another object of type `common.cruise_obstacle_type.*` stopped in front of the moving obstacle. +- The lateral distance (using the ego's trajectory as reference) between both obstacles is less than `behavior_determination.cruise.yield.max_lat_dist_between_obstacles` +- Both obstacles, moving and stopped, are within `behavior_determination.cruise.yield.lat_distance_threshold` and `behavior_determination.cruise.yield.lat_distance_threshold` + `behavior_determination.cruise.yield.max_lat_dist_between_obstacles` lateral distance from the ego's trajectory respectively. + +If the above conditions are met, the ego vehicle will cruise behind the moving obstacle, yielding to it so it can cut in into the ego's lane to avoid the stopped obstacle. + +#### Determine stop vehicles + +Among obstacles which are not for cruising, the obstacles meeting the following condition are determined as obstacles for stopping. + +- The object type is for stopping according to `common.stop_obstacle_type.*`. +- The lateral distance from the object to the ego's trajectory is smaller than `behavior_determination.stop.max_lat_margin`. +- The object velocity along the ego's trajectory is smaller than `behavior_determination.obstacle_velocity_threshold_from_stop_to_cruise`. +- The object + - does not cross the ego's trajectory (\*1) + - with the velocity smaller than `behavior_determination.crossing_obstacle.obstacle_velocity_threshold` + - and its collision time margin is large enough (\*2). + +| Parameter | Type | Description | +| ------------------------------------------------------------------------ | ------ | --------------------------------------------- | +| `common.stop_obstacle_type.unknown` | bool | flag to consider unknown objects for stopping | +| `common.stop_obstacle_type.car` | bool | flag to consider unknown objects for stopping | +| `common.stop_obstacle_type.truck` | bool | flag to consider unknown objects for stopping | +| ... | bool | ... | +| `behavior_determination.stop.max_lat_margin` | double | maximum lateral margin for stop obstacles | +| `behavior_determination.crossing_obstacle.obstacle_velocity_threshold` | double | maximum crossing obstacle velocity to ignore | +| `behavior_determination.obstacle_velocity_threshold_from_stop_to_cruise` | double | maximum obstacle velocity for stop | + +#### Determine slow down vehicles + +Among obstacles which are not for cruising and stopping, the obstacles meeting the following condition are determined as obstacles for slowing down. + +- The object type is for slowing down according to `common.slow_down_obstacle_type.*`. +- The lateral distance from the object to the ego's trajectory is smaller than `behavior_determination.slow_down.max_lat_margin`. + +| Parameter | Type | Description | +| ------------------------------------------------- | ------ | ------------------------------------------------- | +| `common.slow_down_obstacle_type.unknown` | bool | flag to consider unknown objects for slowing down | +| `common.slow_down_obstacle_type.car` | bool | flag to consider unknown objects for slowing down | +| `common.slow_down_obstacle_type.truck` | bool | flag to consider unknown objects for slowing down | +| ... | bool | ... | +| `behavior_determination.slow_down.max_lat_margin` | double | maximum lateral margin for slow down obstacles | + +#### NOTE + +##### \*1: Crossing obstacles + +Crossing obstacle is the object whose orientation's yaw angle against the ego's trajectory is smaller than `behavior_determination.crossing_obstacle.obstacle_traj_angle_threshold`. + +| Parameter | Type | Description | +| ------------------------------------------------------------------------ | ------ | ------------------------------------------------------------------------------------------------- | +| `behavior_determination.crossing_obstacle.obstacle_traj_angle_threshold` | double | maximum angle against the ego's trajectory to judge the obstacle is crossing the trajectory [rad] | + +##### \*2: Enough collision time margin + +We predict the collision area and its time by the ego with a constant velocity motion and the obstacle with its predicted path. +Then, we calculate a collision time margin which is the difference of the time when the ego will be inside the collision area and the obstacle will be inside the collision area. +When this time margin is smaller than `behavior_determination.stop.crossing_obstacle.collision_time_margin`, the margin is not enough. + +| Parameter | Type | Description | +| --------------------------------------------------------------------- | ------ | ----------------------------------------------------- | +| `behavior_determination.stop.crossing_obstacle.collision_time_margin` | double | maximum collision time margin of the ego and obstacle | + +### Stop planning + +| Parameter | Type | Description | +| -------------------------------------- | ------ | ------------------------------------------------------------------------------------------ | +| `common.min_strong_accel` | double | ego's minimum acceleration to stop [m/ss] | +| `common.safe_distance_margin` | double | distance with obstacles for stop [m] | +| `common.terminal_safe_distance_margin` | double | terminal_distance with obstacles for stop, which cannot be exceed safe distance margin [m] | + +The role of the stop planning is keeping a safe distance with static vehicle objects or dynamic/static non vehicle objects. + +The stop planning just inserts the stop point in the trajectory to keep a distance with obstacles. +The safe distance is parameterized as `common.safe_distance_margin`. +When it stops at the end of the trajectory, and obstacle is on the same point, the safe distance becomes `terminal_safe_distance_margin`. + +When inserting the stop point, the required acceleration for the ego to stop in front of the stop point is calculated. +If the acceleration is less than `common.min_strong_accel`, the stop planning will be cancelled since this package does not assume a strong sudden brake for emergency. + +### Cruise planning + +| Parameter | Type | Description | +| ----------------------------- | ------ | ---------------------------------------------- | +| `common.safe_distance_margin` | double | minimum distance with obstacles for cruise [m] | + +The role of the cruise planning is keeping a safe distance with dynamic vehicle objects with smoothed velocity transition. +This includes not only cruising a front vehicle, but also reacting a cut-in and cut-out vehicle. + +The safe distance is calculated dynamically based on the Responsibility-Sensitive Safety (RSS) by the following equation. + +$$ +d_{rss} = v_{ego} t_{idling} + \frac{1}{2} a_{ego} t_{idling}^2 + \frac{v_{ego}^2}{2 a_{ego}} - \frac{v_{obstacle}^2}{2 a_{obstacle}}, +$$ + +assuming that $d_{rss}$ is the calculated safe distance, $t_{idling}$ is the idling time for the ego to detect the front vehicle's deceleration, $v_{ego}$ is the ego's current velocity, $v_{obstacle}$ is the front obstacle's current velocity, $a_{ego}$ is the ego's acceleration, and $a_{obstacle}$ is the obstacle's acceleration. +These values are parameterized as follows. Other common values such as ego's minimum acceleration is defined in `common.param.yaml`. + +| Parameter | Type | Description | +| --------------------------------- | ------ | ----------------------------------------------------------------------------- | +| `common.idling_time` | double | idling time for the ego to detect the front vehicle starting deceleration [s] | +| `common.min_ego_accel_for_rss` | double | ego's acceleration for RSS [m/ss] | +| `common.min_object_accel_for_rss` | double | front obstacle's acceleration for RSS [m/ss] | + +The detailed formulation is as follows. + +$$ +\begin{align} +d_{error} & = d - d_{rss} \\ +d_{normalized} & = lpf(d_{error} / d_{obstacle}) \\ +d_{quad, normalized} & = sign(d_{normalized}) *d_{normalized}*d_{normalized} \\ +v_{pid} & = pid(d_{quad, normalized}) \\ +v_{add} & = v_{pid} > 0 ? v_{pid}* w_{acc} : v_{pid} \\ +v_{target} & = max(v_{ego} + v_{add}, v_{min, cruise}) +\end{align} +$$ + +| Variable | Description | +| ----------------- | --------------------------------------- | +| `d` | actual distance to obstacle | +| `d_{rss}` | ideal distance to obstacle based on RSS | +| `v_{min, cruise}` | `min_cruise_target_vel` | +| `w_{acc}` | `output_ratio_during_accel` | +| `lpf(val)` | apply low-pass filter to `val` | +| `pid(val)` | apply pid to `val` | + +#### Block diagram + +![cruise_planning_block_diagram](./media/cruise_planning_block_diagram.drawio.svg) + +### Slow down planning + +| Parameter | Type | Description | +| ----------------------------------------------------------------- | -------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| `slow_down.labels` | vector(string) | A vector of labels for customizing obstacle-label-based slow down behavior. Each label represents an obstacle type that will be treated differently when applying slow down. The possible labels are ("default" (Mandatory), "unknown","car","truck","bus","trailer","motorcycle","bicycle" or "pedestrian") | +| `slow_down.default.static.min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.static.max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.static.min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.static.max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be static, or not moving | +| `slow_down.default.moving.min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `slow_down.default.moving.max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `slow_down.default.moving.min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `slow_down.default.moving.max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: This default value will be used when the detected obstacle label does not match any of the slow_down.labels and the obstacle is considered to be moving | +| `(optional) slow_down."label".(static & moving).min_lat_velocity` | double | minimum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | +| `(optional) slow_down."label".(static & moving).max_lat_velocity` | double | maximum velocity to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | +| `(optional) slow_down."label".(static & moving).min_lat_margin` | double | minimum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | +| `(optional) slow_down."label".(static & moving).max_lat_margin` | double | maximum lateral margin to linearly calculate slow down velocity [m]. Note: only for obstacles specified in `slow_down.labels`. Requires a `static` and a `moving` value | + +The role of the slow down planning is inserting slow down velocity in the trajectory where the trajectory points are close to the obstacles. The parameters can be customized depending on the obstacle type (see `slow_down.labels`), making it possible to adjust the slow down behavior depending if the obstacle is a pedestrian, bicycle, car, etc. Each obstacle type has a `static` and a `moving` parameter set, so it is possible to customize the slow down response of the ego vehicle according to the obstacle type and if it is moving or not. If an obstacle is determined to be moving, the corresponding `moving` set of parameters will be used to compute the vehicle slow down, otherwise, the `static` parameters will be used. The `static` and `moving` separation is useful for customizing the ego vehicle slow down behavior to, for example, slow down more significantly when passing stopped vehicles that might cause occlusion or that might suddenly open its doors. + +An obstacle is classified as `static` if its total speed is less than the `moving_object_speed_threshold` parameter. Furthermore, a hysteresis based approach is used to avoid chattering, it uses the `moving_object_hysteresis_range` parameter range and the obstacle's previous state (`moving` or `static`) to determine if the obstacle is moving or not. In other words, if an obstacle was previously classified as `static`, it will not change its classification to `moving` unless its total speed is greater than `moving_object_speed_threshold` + `moving_object_hysteresis_range`. Likewise, an obstacle previously classified as `moving`, will only change to `static` if its speed is lower than `moving_object_speed_threshold` - `moving_object_hysteresis_range`. + +The closest point on the obstacle to the ego's trajectory is calculated. +Then, the slow down velocity is calculated by linear interpolation with the distance between the point and trajectory as follows. + +![slow_down_velocity_calculation](./media/slow_down_velocity_calculation.svg) + +| Variable | Description | +| ---------- | ------------------------------------------------- | +| `v_{out}` | calculated velocity for slow down | +| `v_{min}` | `slow_down.min_lat_velocity` | +| `v_{max}` | `slow_down.max_lat_velocity` | +| `l_{min}` | `slow_down.min_lat_margin` | +| `l_{max}` | `slow_down.max_lat_margin` | +| `l'_{max}` | `behavior_determination.slow_down.max_lat_margin` | + +The calculated velocity is inserted in the trajectory where the obstacle is inside the area with `behavior_determination.slow_down.max_lat_margin`. + +![slow_down_planning](./media/slow_down_planning.drawio.svg) + +## Implementation + +### Flowchart + +Successive functions consist of `autoware_obstacle_cruise_planner` as follows. + +Various algorithms for stop and cruise planning will be implemented, and one of them is designated depending on the use cases. +The core algorithm implementation `generateTrajectory` depends on the designated algorithm. + +```plantuml +@startuml +title onTrajectory +start + +group convertToObstacles + :check obstacle's label; + :check obstacle is in front of ego; + :check obstacle's lateral deviation to trajectory; + :create obstacle instance; +end group + +group determineEgoBehaviorAgainstObstacles + :resampleExtendedTrajectory; + group for each obstacle + :createCruiseObstacle; + :createStopObstacle; + :createSlowDownObstacle; + end group + :update previous obstacles; +end group + +:createPlannerData; + +:generateStopTrajectory; + +:generateCruiseTrajectory; + +:generateSlowDownTrajectory; + +:publish trajectory; + +:publishDebugData; + +:publish and print calculation time; + +stop +@enduml +``` + +### Algorithm selection for cruise planner + +Currently, only a PID-based planner is supported. +Each planner will be explained in the following. + +| Parameter | Type | Description | +| ------------------------ | ------ | ------------------------------------------------------------ | +| `common.planning_method` | string | cruise and stop planning algorithm, selected from "pid_base" | + +### PID-based planner + +#### Stop planning + +In the `pid_based_planner` namespace, + +| Parameter | Type | Description | +| ------------------------------------------------- | ------ | ------------------------------------------------------------ | +| `obstacle_velocity_threshold_from_cruise_to_stop` | double | obstacle velocity threshold to be stopped from cruised [m/s] | + +Only one obstacle is targeted for the stop planning. +It is the obstacle among obstacle candidates whose velocity is less than `obstacle_velocity_threshold_from_cruise_to_stop`, and which is the nearest to the ego along the trajectory. A stop point is inserted keeping`common.safe_distance_margin` distance between the ego and obstacle. + +Note that, as explained in the stop planning design, a stop planning which requires a strong acceleration (less than `common.min_strong_accel`) will be canceled. + +#### Cruise planning + +In the `pid_based_planner` namespace, + +| Parameter | Type | Description | +| --------------------------- | ------ | -------------------------------------------------------------------------------------------------------- | +| `kp` | double | p gain for pid control [-] | +| `ki` | double | i gain for pid control [-] | +| `kd` | double | d gain for pid control [-] | +| `output_ratio_during_accel` | double | The output velocity will be multiplied by the ratio during acceleration to follow the front vehicle. [-] | +| `vel_to_acc_weight` | double | target acceleration is target velocity \* `vel_to_acc_weight` [-] | +| `min_cruise_target_vel` | double | minimum target velocity during cruise [m/s] | + +In order to keep the safe distance, the target velocity and acceleration is calculated and sent as an external velocity limit to the velocity smoothing package (`motion_velocity_smoother` by default). +The target velocity and acceleration is respectively calculated with the PID controller according to the error between the reference safe distance and the actual distance. + +### Optimization-based planner + +under construction + +## Minor functions + +### Prioritization of behavior module's stop point + +When stopping for a pedestrian walking on the crosswalk, the behavior module inserts the zero velocity in the trajectory in front of the crosswalk. +Also `autoware_obstacle_cruise_planner`'s stop planning also works, and the ego may not reach the behavior module's stop point since the safe distance defined in `autoware_obstacle_cruise_planner` may be longer than the behavior module's safe distance. +To resolve this non-alignment of the stop point between the behavior module and `autoware_obstacle_cruise_planner`, `common.min_behavior_stop_margin` is defined. +In the case of the crosswalk described above, `autoware_obstacle_cruise_planner` inserts the stop point with a distance `common.min_behavior_stop_margin` at minimum between the ego and obstacle. + +| Parameter | Type | Description | +| --------------------------------- | ------ | ---------------------------------------------------------------------- | +| `common.min_behavior_stop_margin` | double | minimum stop margin when stopping with the behavior module enabled [m] | + +### A function to keep the closest stop obstacle in target obstacles + +In order to keep the closest stop obstacle in the target obstacles, we check whether it is disappeared or not from the target obstacles in the `checkConsistency` function. +If the previous closest stop obstacle is remove from the lists, we keep it in the lists for `stop_obstacle_hold_time_threshold` seconds. +Note that if a new stop obstacle appears and the previous closest obstacle removes from the lists, we do not add it to the target obstacles again. + +| Parameter | Type | Description | +| ---------------------------------------------------------- | ------ | -------------------------------------------------- | +| `behavior_determination.stop_obstacle_hold_time_threshold` | double | maximum time for holding closest stop obstacle [s] | + +#### Parameters + +{{ json_to_markdown("planning/autoware_obstacle_cruise_planner/schema/default_common.schema.json") }} +{{ json_to_markdown("planning/autoware_obstacle_cruise_planner/schema/obstacle_cruise_planner.schema.json") }} + +## How To Debug + +How to debug can be seen [here](docs/debug.md). + +## Known Limits + +- Common + - When the obstacle pose or velocity estimation has a delay, the ego sometimes will go close to the front vehicle keeping deceleration. + - Current implementation only uses predicted objects message for static/dynamic obstacles and does not use pointcloud. Therefore, if object recognition is lost, the ego cannot deal with the lost obstacle. + - The current predicted paths for obstacle's lane change does not have enough precision for obstacle_cruise_planner. Therefore, we set `rough_detection_area` a small value. +- PID-based planner + - The algorithm strongly depends on the velocity smoothing package (`motion_velocity_smoother` by default) whether or not the ego realizes the designated target speed. If the velocity smoothing package is updated, please take care of the vehicle's behavior as much as possible. diff --git a/planning/autoware_obstacle_cruise_planner/schema/default_common.schema.json b/planning/autoware_obstacle_cruise_planner/schema/default_common.schema.json new file mode 100644 index 0000000000000..ee9f620b2f51c --- /dev/null +++ b/planning/autoware_obstacle_cruise_planner/schema/default_common.schema.json @@ -0,0 +1,125 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_obstacle_cruise_planner parameters", + "type": "object", + "definitions": { + "default_common": { + "type": "object", + "properties": { + "max_vel": { + "type": "number", + "description": "Maximum velocity limit [m/s].", + "default": 11.1, + "minimum": 0.0 + }, + "normal": { + "type": "object", + "properties": { + "min_acc": { + "type": "number", + "description": "Minimum deceleration for normal driving [m/s²].", + "default": -1.0, + "minimum": -10.0, + "maximum": 0.0 + }, + "max_acc": { + "type": "number", + "description": "Maximum acceleration for normal driving [m/s²].", + "default": 1.0, + "minimum": 0.0, + "maximum": 10.0 + }, + "min_jerk": { + "type": "number", + "description": "Minimum jerk for normal driving [m/s³].", + "default": -1.0, + "minimum": -10.0, + "maximum": 0.0 + }, + "max_jerk": { + "type": "number", + "description": "Maximum jerk for normal driving [m/s³].", + "default": 1.0, + "minimum": 0.0, + "maximum": 10.0 + } + }, + "required": ["min_acc", "max_acc", "min_jerk", "max_jerk"], + "additionalProperties": false + }, + "slow_down": { + "type": "object", + "properties": { + "min_acc": { + "type": "number", + "description": "Minimum deceleration for slowing down [m/s²].", + "default": -1.0, + "minimum": -10.0, + "maximum": 0.0 + }, + "min_jerk": { + "type": "number", + "description": "Minimum jerk for slowing down [m/s³].", + "default": -1.0, + "minimum": -10.0, + "maximum": 0.0 + } + }, + "required": ["min_acc", "min_jerk"], + "additionalProperties": false + }, + "limit": { + "type": "object", + "properties": { + "min_acc": { + "type": "number", + "description": "Minimum deceleration limit [m/s²].", + "default": -2.5, + "minimum": -10.0, + "maximum": 0.0 + }, + "max_acc": { + "type": "number", + "description": "Maximum acceleration limit [m/s²].", + "default": 1.0, + "minimum": 0.0, + "maximum": 10.0 + }, + "min_jerk": { + "type": "number", + "description": "Minimum jerk limit [m/s³].", + "default": -1.5, + "minimum": -10.0, + "maximum": 0.0 + }, + "max_jerk": { + "type": "number", + "description": "Maximum jerk limit [m/s³].", + "default": 1.5, + "minimum": 0.0, + "maximum": 10.0 + } + }, + "required": ["min_acc", "max_acc", "min_jerk", "max_jerk"], + "additionalProperties": false + } + }, + "required": ["max_vel", "normal", "slow_down", "limit"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/default_common" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/planning/autoware_obstacle_cruise_planner/schema/obstacle_cruise_planner.schema.json b/planning/autoware_obstacle_cruise_planner/schema/obstacle_cruise_planner.schema.json new file mode 100644 index 0000000000000..1e96448cd349d --- /dev/null +++ b/planning/autoware_obstacle_cruise_planner/schema/obstacle_cruise_planner.schema.json @@ -0,0 +1,1248 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "autoware_obstacle_cruise_planner parameters", + "type": "object", + "definitions": { + "obstacle_cruise_planner": { + "type": "object", + "properties": { + "common": { + "type": "object", + "properties": { + "planning_algorithm": { + "type": "string", + "default": "pid_base", + "description": "currently supported algorithm is \"pid_base\"" + }, + "enable_debug_info": { + "type": "boolean", + "default": false, + "description": "" + }, + "enable_calculation_time_info": { + "type": "boolean", + "default": false, + "description": "" + }, + "enable_slow_down_planning": { + "type": "boolean", + "default": true, + "description": "" + }, + "idling_time": { + "type": "number", + "default": 2.0, + "description": "idling time to detect front vehicle starting deceleration [s]" + }, + "min_ego_accel_for_rss": { + "type": "number", + "default": -1.0, + "description": "ego's acceleration to calculate RSS distance [m/ss]" + }, + "min_object_accel_for_rss": { + "type": "number", + "default": -1.0, + "description": "front obstacle's acceleration to calculate RSS distance [m/ss]" + }, + "safe_distance_margin": { + "type": "number", + "default": 5.0, + "description": "This is also used as a stop margin [m]" + }, + "terminal_safe_distance_margin": { + "type": "number", + "default": 3.0, + "description": "Stop margin at the goal. This value cannot exceed safe distance margin. [m]" + }, + "hold_stop_velocity_threshold": { + "type": "number", + "default": 0.01, + "description": "The maximum ego velocity to hold stopping [m/s]" + }, + "hold_stop_distance_threshold": { + "type": "number", + "default": 0.3, + "description": "The ego keeps stopping if the distance to stop changes within the threshold [m]" + }, + "slow_down_min_acc": { + "type": "number", + "default": -1.0, + "description": "slow down min deceleration [m/ss]" + }, + "slow_down_min_jerk": { + "type": "number", + "default": -1.0, + "description": "slow down min jerk [m/sss]" + }, + "nearest_dist_deviation_threshold": { + "type": "number", + "default": 3.0, + "description": "[m] for finding nearest index" + }, + "nearest_yaw_deviation_threshold": { + "type": "number", + "default": 1.57, + "description": "[rad] for finding nearest index" + }, + "min_behavior_stop_margin": { + "type": "number", + "default": 3.0, + "description": "[m]" + }, + "stop_on_curve": { + "type": "object", + "properties": { + "enable_approaching": { + "type": "boolean", + "default": false, + "description": "" + }, + "additional_safe_distance_margin": { + "type": "number", + "default": 3.0, + "description": "[m]" + }, + "min_safe_distance_margin": { + "type": "number", + "default": 3.0, + "description": "[m]" + } + }, + "required": [ + "enable_approaching", + "additional_safe_distance_margin", + "min_safe_distance_margin" + ], + "additionalProperties": false + }, + "suppress_sudden_obstacle_stop": { + "type": "boolean", + "default": false, + "description": "" + }, + "stop_obstacle_type": { + "type": "object", + "properties": { + "pointcloud": { + "type": "boolean", + "default": false, + "description": "" + }, + "inside": { + "type": "object", + "properties": { + "unknown": { + "type": "boolean", + "default": true, + "description": "" + }, + "car": { + "type": "boolean", + "default": true, + "description": "" + }, + "truck": { + "type": "boolean", + "default": true, + "description": "" + }, + "bus": { + "type": "boolean", + "default": true, + "description": "" + }, + "trailer": { + "type": "boolean", + "default": true, + "description": "" + }, + "motorcycle": { + "type": "boolean", + "default": true, + "description": "" + }, + "bicycle": { + "type": "boolean", + "default": true, + "description": "" + }, + "pedestrian": { + "type": "boolean", + "default": true, + "description": "" + } + }, + "required": [ + "unknown", + "car", + "truck", + "bus", + "trailer", + "motorcycle", + "bicycle", + "pedestrian" + ], + "additionalProperties": false + }, + "outside": { + "type": "object", + "properties": { + "unknown": { + "type": "boolean", + "default": false, + "description": "" + }, + "car": { + "type": "boolean", + "default": true, + "description": "" + }, + "truck": { + "type": "boolean", + "default": true, + "description": "" + }, + "bus": { + "type": "boolean", + "default": true, + "description": "" + }, + "trailer": { + "type": "boolean", + "default": true, + "description": "" + }, + "motorcycle": { + "type": "boolean", + "default": true, + "description": "" + }, + "bicycle": { + "type": "boolean", + "default": true, + "description": "" + }, + "pedestrian": { + "type": "boolean", + "default": true, + "description": "" + } + }, + "required": [ + "unknown", + "car", + "truck", + "bus", + "trailer", + "motorcycle", + "bicycle", + "pedestrian" + ], + "additionalProperties": false + } + }, + "required": ["pointcloud", "inside", "outside"], + "additionalProperties": false + }, + "cruise_obstacle_type": { + "type": "object", + "properties": { + "inside": { + "type": "object", + "properties": { + "unknown": { + "type": "boolean", + "default": true, + "description": "" + }, + "car": { + "type": "boolean", + "default": true, + "description": "" + }, + "truck": { + "type": "boolean", + "default": true, + "description": "" + }, + "bus": { + "type": "boolean", + "default": true, + "description": "" + }, + "trailer": { + "type": "boolean", + "default": true, + "description": "" + }, + "motorcycle": { + "type": "boolean", + "default": true, + "description": "" + }, + "bicycle": { + "type": "boolean", + "default": true, + "description": "" + }, + "pedestrian": { + "type": "boolean", + "default": false, + "description": "" + } + }, + "required": [ + "unknown", + "car", + "truck", + "bus", + "trailer", + "motorcycle", + "bicycle", + "pedestrian" + ], + "additionalProperties": false + }, + "outside": { + "type": "object", + "properties": { + "unknown": { + "type": "boolean", + "default": false, + "description": "" + }, + "car": { + "type": "boolean", + "default": true, + "description": "" + }, + "truck": { + "type": "boolean", + "default": true, + "description": "" + }, + "bus": { + "type": "boolean", + "default": true, + "description": "" + }, + "trailer": { + "type": "boolean", + "default": true, + "description": "" + }, + "motorcycle": { + "type": "boolean", + "default": true, + "description": "" + }, + "bicycle": { + "type": "boolean", + "default": false, + "description": "" + }, + "pedestrian": { + "type": "boolean", + "default": false, + "description": "" + } + }, + "required": [ + "unknown", + "car", + "truck", + "bus", + "trailer", + "motorcycle", + "bicycle", + "pedestrian" + ], + "additionalProperties": false + } + }, + "required": ["inside", "outside"], + "additionalProperties": false + }, + "slow_down_obstacle_type": { + "type": "object", + "properties": { + "unknown": { + "type": "boolean", + "default": false, + "description": "" + }, + "car": { + "type": "boolean", + "default": true, + "description": "" + }, + "truck": { + "type": "boolean", + "default": true, + "description": "" + }, + "bus": { + "type": "boolean", + "default": true, + "description": "" + }, + "trailer": { + "type": "boolean", + "default": true, + "description": "" + }, + "motorcycle": { + "type": "boolean", + "default": true, + "description": "" + }, + "bicycle": { + "type": "boolean", + "default": true, + "description": "" + }, + "pedestrian": { + "type": "boolean", + "default": true, + "description": "" + }, + "pointcloud": { + "type": "boolean", + "default": false, + "description": "" + } + }, + "required": [ + "unknown", + "car", + "truck", + "bus", + "trailer", + "motorcycle", + "bicycle", + "pedestrian", + "pointcloud" + ], + "additionalProperties": false + } + }, + "required": [ + "planning_algorithm", + "enable_debug_info", + "enable_calculation_time_info", + "enable_slow_down_planning", + "idling_time", + "min_ego_accel_for_rss", + "min_object_accel_for_rss", + "safe_distance_margin", + "terminal_safe_distance_margin", + "hold_stop_velocity_threshold", + "hold_stop_distance_threshold", + "slow_down_min_acc", + "slow_down_min_jerk", + "nearest_dist_deviation_threshold", + "nearest_yaw_deviation_threshold", + "min_behavior_stop_margin", + "stop_on_curve", + "suppress_sudden_obstacle_stop", + "stop_obstacle_type", + "cruise_obstacle_type", + "slow_down_obstacle_type" + ], + "additionalProperties": false + }, + "behavior_determination": { + "type": "object", + "properties": { + "pointcloud_search_radius": { + "type": "number", + "default": 5.0, + "description": "" + }, + "pointcloud_voxel_grid_x": { + "type": "number", + "default": 0.05, + "description": "" + }, + "pointcloud_voxel_grid_y": { + "type": "number", + "default": 0.05, + "description": "" + }, + "pointcloud_voxel_grid_z": { + "type": "number", + "default": 100000.0, + "description": "" + }, + "pointcloud_cluster_tolerance": { + "type": "number", + "default": 1.0, + "description": "" + }, + "pointcloud_min_cluster_size": { + "type": "integer", + "default": 1, + "description": "" + }, + "pointcloud_max_cluster_size": { + "type": "integer", + "default": 100000, + "description": "" + }, + "decimate_trajectory_step_length": { + "type": "number", + "default": 2.0, + "description": "longitudinal step length to calculate trajectory polygon for collision checking" + }, + "prediction_resampling_time_interval": { + "type": "number", + "default": 0.1, + "description": "" + }, + "prediction_resampling_time_horizon": { + "type": "number", + "default": 10.0, + "description": "" + }, + "stop_obstacle_hold_time_threshold": { + "type": "number", + "default": 1.0, + "description": "maximum time for holding closest stop obstacle" + }, + "obstacle_velocity_threshold_from_cruise_to_stop": { + "type": "number", + "default": 3.0, + "description": "stop planning is executed to the obstacle whose velocity is less than this value [m/s]" + }, + "obstacle_velocity_threshold_from_stop_to_cruise": { + "type": "number", + "default": 3.5, + "description": "stop planning is executed to the obstacle whose velocity is less than this value [m/s]" + }, + "crossing_obstacle": { + "type": "object", + "properties": { + "obstacle_velocity_threshold": { + "type": "number", + "default": 3.0, + "description": "" + }, + "obstacle_traj_angle_threshold": { + "type": "number", + "default": 1.22, + "description": "[rad] = 70 [deg], yaw threshold of crossing obstacle against the nearest trajectory point for cruise or stop" + } + }, + "required": ["obstacle_velocity_threshold", "obstacle_traj_angle_threshold"], + "additionalProperties": false + }, + "stop": { + "type": "object", + "properties": { + "max_lat_margin": { + "type": "number", + "default": 0.3, + "description": "" + }, + "max_lat_margin_against_unknown": { + "type": "number", + "default": 0.3, + "description": "" + }, + "min_velocity_to_reach_collision_point": { + "type": "number", + "default": 2.0, + "description": "" + }, + "outside_obstacle": { + "type": "object", + "properties": { + "max_lateral_time_margin": { + "type": "number", + "default": 4.0, + "description": "" + }, + "num_of_predicted_paths": { + "type": "integer", + "default": 3, + "description": "" + }, + "pedestrian_deceleration_rate": { + "type": "number", + "default": 0.5, + "description": "" + }, + "bicycle_deceleration_rate": { + "type": "number", + "default": 0.5, + "description": "" + } + }, + "required": [ + "max_lateral_time_margin", + "num_of_predicted_paths", + "pedestrian_deceleration_rate", + "bicycle_deceleration_rate" + ], + "additionalProperties": false + }, + "crossing_obstacle": { + "type": "object", + "properties": { + "collision_time_margin": { + "type": "number", + "default": 4.0, + "description": "" + } + }, + "required": ["collision_time_margin"], + "additionalProperties": false + } + }, + "required": [ + "max_lat_margin", + "max_lat_margin_against_unknown", + "min_velocity_to_reach_collision_point", + "outside_obstacle", + "crossing_obstacle" + ], + "additionalProperties": false + }, + "cruise": { + "type": "object", + "properties": { + "max_lat_margin": { + "type": "number", + "default": 1.0, + "description": "" + }, + "outside_obstacle": { + "type": "object", + "properties": { + "obstacle_velocity_threshold": { + "type": "number", + "default": 3.5, + "description": "" + }, + "ego_obstacle_overlap_time_threshold": { + "type": "number", + "default": 2.0, + "description": "" + }, + "max_prediction_time_for_collision_check": { + "type": "number", + "default": 20.0, + "description": "" + }, + "max_lateral_time_margin": { + "type": "number", + "default": 5.0, + "description": "" + }, + "num_of_predicted_paths": { + "type": "integer", + "default": 3, + "description": "" + } + }, + "required": [ + "obstacle_velocity_threshold", + "ego_obstacle_overlap_time_threshold", + "max_prediction_time_for_collision_check", + "max_lateral_time_margin", + "num_of_predicted_paths" + ], + "additionalProperties": false + }, + "yield": { + "type": "object", + "properties": { + "enable_yield": { + "type": "boolean", + "default": true, + "description": "" + }, + "lat_distance_threshold": { + "type": "number", + "default": 5.0, + "description": "" + }, + "max_lat_dist_between_obstacles": { + "type": "number", + "default": 2.5, + "description": "" + }, + "max_obstacles_collision_time": { + "type": "number", + "default": 10.0, + "description": "" + }, + "stopped_obstacle_velocity_threshold": { + "type": "number", + "default": 0.5, + "description": "" + } + }, + "required": [ + "enable_yield", + "lat_distance_threshold", + "max_lat_dist_between_obstacles", + "max_obstacles_collision_time", + "stopped_obstacle_velocity_threshold" + ], + "additionalProperties": false + } + }, + "required": ["max_lat_margin", "outside_obstacle", "yield"], + "additionalProperties": false + }, + "slow_down": { + "type": "object", + "properties": { + "max_lat_margin": { + "type": "number", + "default": 1.1, + "description": "" + }, + "lat_hysteresis_margin": { + "type": "number", + "default": 0.2, + "description": "" + }, + "successive_num_to_entry_slow_down_condition": { + "type": "integer", + "default": 5, + "description": "" + }, + "successive_num_to_exit_slow_down_condition": { + "type": "integer", + "default": 5, + "description": "" + } + }, + "required": [ + "max_lat_margin", + "lat_hysteresis_margin", + "successive_num_to_entry_slow_down_condition", + "successive_num_to_exit_slow_down_condition" + ], + "additionalProperties": false + }, + "consider_current_pose": { + "type": "object", + "properties": { + "enable_to_consider_current_pose": { + "type": "boolean", + "default": true, + "description": "" + }, + "time_to_convergence": { + "type": "number", + "default": 1.5, + "description": "" + } + }, + "required": ["enable_to_consider_current_pose", "time_to_convergence"], + "additionalProperties": false + } + }, + "required": [ + "pointcloud_search_radius", + "pointcloud_voxel_grid_x", + "pointcloud_voxel_grid_y", + "pointcloud_voxel_grid_z", + "pointcloud_cluster_tolerance", + "pointcloud_min_cluster_size", + "pointcloud_max_cluster_size", + "decimate_trajectory_step_length", + "prediction_resampling_time_interval", + "prediction_resampling_time_horizon", + "stop_obstacle_hold_time_threshold", + "obstacle_velocity_threshold_from_cruise_to_stop", + "obstacle_velocity_threshold_from_stop_to_cruise", + "crossing_obstacle", + "stop", + "cruise", + "slow_down", + "consider_current_pose" + ], + "additionalProperties": false + }, + "cruise": { + "type": "object", + "properties": { + "pid_based_planner": { + "type": "object", + "properties": { + "use_velocity_limit_based_planner": { + "type": "boolean", + "default": true, + "description": "" + }, + "error_function_type": { + "type": "string", + "default": "quadratic", + "description": "choose from linear, quadratic" + }, + "velocity_limit_based_planner": { + "type": "object", + "properties": { + "kp": { + "type": "number", + "default": 10.0, + "description": "" + }, + "ki": { + "type": "number", + "default": 0.0, + "description": "" + }, + "kd": { + "type": "number", + "default": 2.0, + "description": "" + }, + "output_ratio_during_accel": { + "type": "number", + "default": 0.6, + "description": "target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]" + }, + "vel_to_acc_weight": { + "type": "number", + "default": 12.0, + "description": "target acceleration is calculated by (target_velocity - current_velocity) * vel_to_acc_weight [-]" + }, + "enable_jerk_limit_to_output_acc": { + "type": "boolean", + "default": false, + "description": "" + }, + "disable_target_acceleration": { + "type": "boolean", + "default": true, + "description": "" + } + }, + "required": [ + "kp", + "ki", + "kd", + "output_ratio_during_accel", + "vel_to_acc_weight", + "enable_jerk_limit_to_output_acc", + "disable_target_acceleration" + ], + "additionalProperties": false + }, + "velocity_insertion_based_planner": { + "type": "object", + "properties": { + "kp_acc": { + "type": "number", + "default": 6.0, + "description": "" + }, + "ki_acc": { + "type": "number", + "default": 0.0, + "description": "" + }, + "kd_acc": { + "type": "number", + "default": 2.0, + "description": "" + }, + "kp_jerk": { + "type": "number", + "default": 20.0, + "description": "" + }, + "ki_jerk": { + "type": "number", + "default": 0.0, + "description": "" + }, + "kd_jerk": { + "type": "number", + "default": 0.0, + "description": "" + }, + "output_acc_ratio_during_accel": { + "type": "number", + "default": 0.6, + "description": "target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]" + }, + "output_jerk_ratio_during_accel": { + "type": "number", + "default": 1.0, + "description": "target acceleration is multiplied with this value while ego accelerates to catch up the front vehicle [-]" + }, + "enable_jerk_limit_to_output_acc": { + "type": "boolean", + "default": true, + "description": "" + } + }, + "required": [ + "kp_acc", + "ki_acc", + "kd_acc", + "kp_jerk", + "ki_jerk", + "kd_jerk", + "output_acc_ratio_during_accel", + "output_jerk_ratio_during_accel", + "enable_jerk_limit_to_output_acc" + ], + "additionalProperties": false + }, + "min_accel_during_cruise": { + "type": "number", + "default": -2.0, + "description": "minimum acceleration during cruise to slow down [m/ss]" + }, + "min_cruise_target_vel": { + "type": "number", + "default": 0.0, + "description": "minimum target velocity during slow down [m/s]" + }, + "time_to_evaluate_rss": { + "type": "number", + "default": 0.0, + "description": "" + }, + "lpf_normalized_error_cruise_dist_gain": { + "type": "number", + "default": 0.2, + "definitions": {} + } + }, + "required": [ + "use_velocity_limit_based_planner", + "error_function_type", + "velocity_limit_based_planner", + "velocity_insertion_based_planner", + "min_accel_during_cruise", + "min_cruise_target_vel", + "time_to_evaluate_rss", + "lpf_normalized_error_cruise_dist_gain" + ], + "additionalProperties": false + }, + "optimization_based_planner": { + "type": "object", + "properties": { + "dense_resampling_time_interval": { + "type": "number", + "default": 0.2, + "description": "" + }, + "sparse_resampling_time_interval": { + "type": "number", + "default": 2.0, + "description": "" + }, + "dense_time_horizon": { + "type": "number", + "default": 5.0, + "description": "" + }, + "max_time_horizon": { + "type": "number", + "default": 25.0, + "description": "" + }, + "velocity_margin": { + "type": "number", + "default": 0.2, + "description": "[m/s]" + }, + "t_dangerous": { + "type": "number", + "default": 0.5, + "description": "" + }, + "replan_vel_deviation": { + "type": "number", + "default": 5.0, + "description": "velocity deviation to replan initial velocity [m/s]" + }, + "engage_velocity": { + "type": "number", + "default": 0.25, + "description": "engage velocity threshold [m/s]" + }, + "engage_acceleration": { + "type": "number", + "default": 0.1, + "description": "engage acceleration [m/ss]" + }, + "engage_exit_ratio": { + "type": "number", + "default": 0.5, + "description": "exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity" + }, + "stop_dist_to_prohibit_engage": { + "type": "number", + "default": 0.5, + "description": "if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m]" + }, + "max_s_weight": { + "type": "number", + "default": 100.0, + "description": "" + }, + "max_v_weight": { + "type": "number", + "default": 1.0, + "description": "" + }, + "over_s_safety_weight": { + "type": "number", + "default": 1000000.0, + "description": "" + }, + "over_s_ideal_weight": { + "type": "number", + "default": 50.0, + "description": "" + }, + "over_v_weight": { + "type": "number", + "default": 500000.0, + "description": "" + }, + "over_a_weight": { + "type": "number", + "default": 5000.0, + "description": "" + }, + "over_j_weight": { + "type": "number", + "default": 10000.0, + "description": "" + } + }, + "required": [ + "dense_resampling_time_interval", + "sparse_resampling_time_interval", + "dense_time_horizon", + "max_time_horizon", + "velocity_margin", + "t_dangerous", + "replan_vel_deviation", + "engage_velocity", + "engage_acceleration", + "engage_exit_ratio", + "stop_dist_to_prohibit_engage", + "max_s_weight", + "max_v_weight", + "over_s_safety_weight", + "over_s_ideal_weight", + "over_v_weight", + "over_a_weight", + "over_j_weight" + ], + "additionalProperties": false + } + }, + "required": ["pid_based_planner", "optimization_based_planner"], + "additionalProperties": false + }, + "slow_down": { + "type": "object", + "properties": { + "labels": { + "type": "array", + "items": { + "type": "string" + }, + "default": ["default"] + }, + "default": { + "type": "object", + "properties": { + "moving": { + "type": "object", + "properties": { + "min_lat_margin": { + "type": "number", + "default": 0.2, + "description": "" + }, + "max_lat_margin": { + "type": "number", + "default": 1.0, + "description": "" + }, + "min_ego_velocity": { + "type": "number", + "default": 2.0, + "description": "" + }, + "max_ego_velocity": { + "type": "number", + "default": 8.0, + "description": "" + } + }, + "required": [ + "min_lat_margin", + "max_lat_margin", + "min_ego_velocity", + "max_ego_velocity" + ], + "additionalProperties": false + }, + "static": { + "type": "object", + "properties": { + "min_lat_margin": { + "type": "number", + "default": 0.2, + "description": "" + }, + "max_lat_margin": { + "type": "number", + "default": 1.0, + "description": "" + }, + "min_ego_velocity": { + "type": "number", + "default": 4.0, + "description": "" + }, + "max_ego_velocity": { + "type": "number", + "default": 8.0, + "description": "" + } + }, + "required": [ + "min_lat_margin", + "max_lat_margin", + "min_ego_velocity", + "max_ego_velocity" + ], + "additionalProperties": false + } + }, + "required": ["moving", "static"], + "additionalProperties": false + }, + "moving_object_speed_threshold": { + "type": "number", + "default": 0.5, + "description": "" + }, + "moving_object_hysteresis_range": { + "type": "number", + "default": 0.1, + "description": "" + }, + "time_margin_on_target_velocity": { + "type": "number", + "default": 1.5, + "description": "" + }, + "lpf_gain_slow_down_vel": { + "type": "number", + "default": 0.99, + "description": "" + }, + "lpf_gain_lat_dist": { + "type": "number", + "default": 0.999, + "description": "" + }, + "lpf_gain_dist_to_slow_down": { + "type": "number", + "default": 0.7, + "description": "" + } + }, + "required": [ + "labels", + "default", + "moving_object_speed_threshold", + "moving_object_hysteresis_range", + "time_margin_on_target_velocity", + "lpf_gain_slow_down_vel", + "lpf_gain_lat_dist", + "lpf_gain_dist_to_slow_down" + ], + "additionalProperties": false + }, + "stop": { + "type": "object", + "properties": { + "type_specified_params": { + "type": "object", + "properties": { + "labels": { + "type": "array", + "items": { + "type": "string" + }, + "default": ["default", "unknown"] + }, + "unknown": { + "type": "object", + "properties": { + "limit_min_acc": { + "type": "number", + "default": -1.2, + "description": "" + }, + "sudden_object_acc_threshold": { + "type": "number", + "default": -1.1, + "description": "" + }, + "sudden_object_dist_threshold": { + "type": "number", + "default": 1000.0, + "description": "" + }, + "abandon_to_stop": { + "type": "boolean", + "default": false, + "description": "" + } + }, + "required": [ + "limit_min_acc", + "sudden_object_acc_threshold", + "sudden_object_dist_threshold", + "abandon_to_stop" + ], + "additionalProperties": false + } + }, + "required": ["labels", "unknown"], + "additionalProperties": false + } + }, + "required": ["type_specified_params"], + "additionalProperties": false + } + }, + "required": ["common", "behavior_determination", "cruise", "slow_down", "stop"], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/obstacle_cruise_planner" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +}