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

feat(motion_velocity_planner): add new motion velocity planning #7064

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
cbbbcba
adding new motion_velocity_planner package
maxime-clem Apr 30, 2024
c150d50
Split into _node and _common packages
maxime-clem May 2, 2024
4294db9
fix motion_velocity_planner_node to run without issues
maxime-clem May 2, 2024
2a31557
fix launch file (psim works)
maxime-clem May 2, 2024
6697df1
improve plugin interface
maxime-clem May 2, 2024
c131f0a
initial running out_of_lane module
maxime-clem May 2, 2024
8440695
working out_of_lane module
maxime-clem May 6, 2024
c8ea727
dont update the map at each iteration and properly delete debug markers
maxime-clem May 6, 2024
2be620c
add update of params, small cleanup, update copyrights
maxime-clem May 6, 2024
754643a
motion_velocity_planner: rm launch prefix and switch to composable node
maxime-clem May 7, 2024
6ff2877
remove unused function and function parameters
maxime-clem May 17, 2024
5f1f885
implement velocity factor
maxime-clem May 17, 2024
7c58734
improve velocity factors
maxime-clem May 22, 2024
1e51e1f
add autoware_ prefix to package names
maxime-clem May 23, 2024
7bc236f
cleanup and doc
maxime-clem May 24, 2024
bef6c3e
setup node interface test
maxime-clem May 24, 2024
699f3fe
add initial unit test (for cut_predicted_path_beyond_line)
maxime-clem May 24, 2024
ecdd9e8
remove useless array functiona dded to the velocity factor interface
maxime-clem May 24, 2024
7e4bc26
set the velocity_factors topics and add it to the default_ad_api
maxime-clem May 27, 2024
c05961d
remove not used parameter file path
maxime-clem May 27, 2024
57ee29b
fix spelling and json schema
maxime-clem May 28, 2024
0942524
split big function
maxime-clem May 28, 2024
618b759
add param to active velocity smoothing or not
maxime-clem May 28, 2024
174c933
directly use TrajectoryPoint type
maxime-clem May 29, 2024
feaae47
construct SlowdownInterval's members with copies instead of std::move
maxime-clem May 29, 2024
a4b0cc4
set all points to 0 vel when inserting a stop point
maxime-clem May 30, 2024
2ea5c58
update doc pages
maxime-clem May 30, 2024
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
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@
#include <autoware_adapi_v1_msgs/msg/planning_behavior.hpp>
#include <autoware_adapi_v1_msgs/msg/velocity_factor.hpp>
#include <autoware_adapi_v1_msgs/msg/velocity_factor_array.hpp>
#include <autoware_auto_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <geometry_msgs/msg/pose.hpp>

#include <string>
Expand All @@ -40,10 +39,10 @@ class VelocityFactorInterface
void init(const VelocityFactorBehavior & behavior) { behavior_ = behavior; }
void reset() { velocity_factor_.behavior = PlanningBehavior::UNKNOWN; }

template <class PointType>
void set(
const std::vector<autoware_auto_planning_msgs::msg::PathPointWithLaneId> & points,
const Pose & curr_pose, const Pose & stop_pose, const VelocityFactorStatus status,
const std::string & detail = "");
const std::vector<PointType> & points, const Pose & curr_pose, const Pose & stop_pose,
const VelocityFactorStatus status, const std::string & detail = "");

private:
VelocityFactorBehavior behavior_{VelocityFactor::UNKNOWN};
Expand Down
20 changes: 17 additions & 3 deletions common/motion_utils/src/factor/velocity_factor_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,16 @@
#include <motion_utils/factor/velocity_factor_interface.hpp>
#include <motion_utils/trajectory/trajectory.hpp>

#include <autoware_auto_planning_msgs/msg/path_point.hpp>
#include <autoware_auto_planning_msgs/msg/path_point_with_lane_id.hpp>
#include <autoware_auto_planning_msgs/msg/trajectory_point.hpp>

namespace motion_utils
{
template <class PointType>
void VelocityFactorInterface::set(
const std::vector<autoware_auto_planning_msgs::msg::PathPointWithLaneId> & points,
const Pose & curr_pose, const Pose & stop_pose, const VelocityFactorStatus status,
const std::string & detail)
const std::vector<PointType> & points, const Pose & curr_pose, const Pose & stop_pose,
const VelocityFactorStatus status, const std::string & detail)
{
const auto & curr_point = curr_pose.position;
const auto & stop_point = stop_pose.position;
Expand All @@ -32,4 +36,14 @@ void VelocityFactorInterface::set(
velocity_factor_.detail = detail;
}

template void VelocityFactorInterface::set<autoware_auto_planning_msgs::msg::PathPointWithLaneId>(
const std::vector<autoware_auto_planning_msgs::msg::PathPointWithLaneId> &, const Pose &,
const Pose &, const VelocityFactorStatus, const std::string &);
template void VelocityFactorInterface::set<autoware_auto_planning_msgs::msg::PathPoint>(
const std::vector<autoware_auto_planning_msgs::msg::PathPoint> &, const Pose &, const Pose &,
const VelocityFactorStatus, const std::string &);
template void VelocityFactorInterface::set<autoware_auto_planning_msgs::msg::TrajectoryPoint>(
const std::vector<autoware_auto_planning_msgs::msg::TrajectoryPoint> &, const Pose &,
const Pose &, const VelocityFactorStatus, const std::string &);

} // namespace motion_utils
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,24 @@
<arg name="interface_input_topic" default="/planning/scenario_planning/lane_driving/behavior_planning/path"/>
<arg name="interface_output_topic" default="/planning/scenario_planning/lane_driving/trajectory"/>

<arg name="launch_motion_out_of_lane_module" default="true"/>
<arg name="launch_dynamic_obstacle_stop_module" default="true"/>
<arg name="launch_module_list_end" default="&quot;&quot;]"/>

<!-- assemble launch config for motion velocity planner -->
<arg name="motion_velocity_planner_launch_modules" default="["/>
<let
name="motion_velocity_planner_launch_modules"
value="$(eval &quot;'$(var motion_velocity_planner_launch_modules)' + 'autoware::motion_velocity_planner::OutOfLaneModule, '&quot;)"
if="$(var launch_motion_out_of_lane_module)"
/>
<let
name="motion_velocity_planner_launch_modules"
value="$(eval &quot;'$(var motion_velocity_planner_launch_modules)' + 'motion_velocity_planner::DynamicObstacleStopModule, '&quot;)"
if="$(var launch_dynamic_obstacle_stop_module)"
/>
<let name="motion_velocity_planner_launch_modules" value="$(eval &quot;'$(var motion_velocity_planner_launch_modules)' + '$(var launch_module_list_end)'&quot;)"/>

<node_container pkg="rclcpp_components" exec="$(var container_type)" name="motion_planning_container" namespace="" args="" output="screen">
<composable_node pkg="glog_component" plugin="GlogComponent" name="glog_component" namespace=""/>
</node_container>
Expand Down Expand Up @@ -91,12 +109,44 @@
</group>
</group>

<!-- velocity limiter -->
<!-- plan slowdown or stops on the final trajectory -->
<group>
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
<composable_node pkg="obstacle_velocity_limiter" plugin="obstacle_velocity_limiter::ObstacleVelocityLimiterNode" name="obstacle_velocity_limiter" namespace="">
<composable_node pkg="autoware_motion_velocity_planner_node" plugin="autoware::motion_velocity_planner::MotionVelocityPlannerNode" name="motion_velocity_planner" namespace="">
<!-- topic remap -->
<remap from="~/input/trajectory" to="obstacle_avoidance_planner/trajectory"/>
<remap from="~/input/vector_map" to="/map/vector_map"/>
<remap from="~/input/vehicle_odometry" to="/localization/kinematic_state"/>
<remap from="~/input/accel" to="/localization/acceleration"/>
<remap from="~/input/dynamic_objects" to="/perception/object_recognition/objects"/>
<remap from="~/input/no_ground_pointcloud" to="/perception/obstacle_segmentation/pointcloud"/>
<remap from="~/input/traffic_signals" to="/perception/traffic_light_recognition/traffic_signals"/>
<remap from="~/input/virtual_traffic_light_states" to="/perception/virtual_traffic_light_states"/>
<remap from="~/input/occupancy_grid" to="/perception/occupancy_grid_map/map"/>
<remap from="~/output/trajectory" to="motion_velocity_planner/trajectory"/>
<remap from="~/output/stop_reasons" to="/planning/scenario_planning/status/stop_reasons"/>
<remap from="~/output/velocity_factors" to="/planning/velocity_factors/motion_velocity_planner"/>
<!-- params -->
<param name="launch_modules" value="$(var motion_velocity_planner_launch_modules)"/>
<param from="$(var common_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param from="$(var motion_velocity_smoother_param_path)"/>
<param from="$(var motion_velocity_smoother_type_param_path)"/>
<param from="$(var motion_velocity_planner_param_path)"/>
<param from="$(var motion_velocity_planner_out_of_lane_module_param_path)"/>
<!-- <param from="$(var motion_velocity_planner_template_param_path)"/> -->
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>
</load_composable_node>
</group>
<!-- velocity limiter TODO(Maxime): move this node to the motion_velocity_planner -->
<group>
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
<composable_node pkg="obstacle_velocity_limiter" plugin="obstacle_velocity_limiter::ObstacleVelocityLimiterNode" name="obstacle_velocity_limiter" namespace="">
<!-- topic remap -->
<remap from="~/input/trajectory" to="motion_velocity_planner/trajectory"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/input/dynamic_obstacles" to="/perception/object_recognition/objects"/>
<remap from="~/input/occupancy_grid" to="/perception/occupancy_grid_map/map"/>
Expand Down
4 changes: 4 additions & 0 deletions planning/.pages
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,10 @@ nav:
- 'Surround Obstacle Checker':
- 'About Surround Obstacle Checker': planning/surround_obstacle_checker
- 'About Surround Obstacle Checker (Japanese)': planning/surround_obstacle_checker/surround_obstacle_checker-design.ja
- 'Motion Velocity Planner':
- 'About Motion Velocity Planner': planning/autoware_motion_velocity_planner_node/
- 'Available Modules':
- 'Out of Lane': planning/autoware_motion_velocity_planner_out_of_lane_module/
- 'Motion Velocity Smoother':
- 'About Motion Velocity Smoother': planning/motion_velocity_smoother
- 'About Motion Velocity Smoother (Japanese)': planning/motion_velocity_smoother/README.ja
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
cmake_minimum_required(VERSION 3.14)
project(autoware_motion_velocity_out_of_lane_module)

find_package(autoware_cmake REQUIRED)
autoware_package()
pluginlib_export_plugin_description_file(autoware_motion_velocity_planner_node plugins.xml)

ament_auto_add_library(${PROJECT_NAME} SHARED
DIRECTORY src
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
test/test_filter_predicted_objects.cpp
)
target_link_libraries(test_${PROJECT_NAME}
${PROJECT_NAME}
)
endif()

ament_auto_package(INSTALL_TO_SHARE config)
Original file line number Diff line number Diff line change
@@ -0,0 +1,165 @@
## Out of Lane

### Role

`out_of_lane` is the module that decelerates and stops to prevent the ego vehicle from entering another lane with incoming dynamic objects.

### Activation Timing

This module is activated if `launch_out_of_lane` is set to true.

### Inner-workings / Algorithms

The algorithm is made of the following steps.

1. Calculate the ego path footprints (red).
2. Calculate the other lanes (magenta).
3. Calculate the overlapping ranges between the ego path footprints and the other lanes (green).
4. For each overlapping range, decide if a stop or slow down action must be taken.
5. For each action, insert the corresponding stop or slow down point in the path.

![overview](./docs/out_of_lane-footprints_other_lanes_overlaps_ranges.png)

#### 1. Ego Path Footprints

In this first step, the ego footprint is projected at each path point and are eventually inflated based on the `extra_..._offset` parameters.

#### 2. Other lanes

In the second step, the set of lanes to consider for overlaps is generated.
This set is built by selecting all lanelets within some distance from the ego vehicle, and then removing non-relevant lanelets.
The selection distance is chosen as the maximum between the `slowdown.distance_threshold` and the `stop.distance_threshold`.

A lanelet is deemed non-relevant if it meets one of the following conditions.

- It is part of the lanelets followed by the ego path.
- It contains the rear point of the ego footprint.
- It follows one of the ego path lanelets.

#### 3. Overlapping ranges

In the third step, overlaps between the ego path footprints and the other lanes are calculated.
For each pair of other lane $l$ and ego path footprint $f$, we calculate the overlapping polygons using `boost::geometry::intersection`.
For each overlapping polygon found, if the distance inside the other lane $l$ is above the `overlap.minimum_distance` threshold, then the overlap is ignored.
Otherwise, the arc length range (relative to the ego path) and corresponding points of the overlapping polygons are stored.
Ultimately, for each other lane $l$, overlapping ranges of successive overlaps are built with the following information:

- overlapped other lane $l$.
- start and end ego path indexes.
- start and end ego path arc lengths.
- start and end overlap points.

#### 4. Decisions

In the fourth step, a decision to either slow down or stop before each overlapping range is taken based on the dynamic objects.
The conditions for the decision depend on the value of the `mode` parameter.

Whether it is decided to slow down or stop is determined by the distance between the ego vehicle and the start of the overlapping range (in arc length along the ego path).
If this distance is bellow the `actions.slowdown.threshold`, a velocity of `actions.slowdown.velocity` will be used.
If the distance is bellow the `actions.stop.threshold`, a velocity of `0`m/s will be used.

<table width="100%">
<tr>
<td>
<img src="./docs/out_of_lane_slow.png" width="550px"/>
</td>
<td>
<img src="./docs/out_of_lane_stop.png" width="550px"/>
</td>
</tr>
</table>

##### Threshold

With the `mode` set to `"threshold"`,
a decision to stop or slow down before a range is made if
an incoming dynamic object is estimated to reach the overlap within `threshold.time_threshold`.

##### TTC (time to collision)

With the `mode` set to `"ttc"`,
estimates for the times when ego and the dynamic objects reach the start and end of the overlapping range are calculated.
This is then used to calculate the time to collision over the period where ego crosses the overlap.
If the time to collision is predicted to go bellow the `ttc.threshold`, the decision to stop or slow down is made.

##### Intervals

With the `mode` set to `"intervals"`,
the estimated times when ego and the dynamic objects reach the start and end points of
the overlapping range are used to create time intervals.
These intervals can be made shorter or longer using the
`intervals.ego_time_buffer` and `intervals.objects_time_buffer` parameters.
If the time interval of ego overlaps with the time interval of an object, the decision to stop or slow down is made.

##### Time estimates

###### Ego

To estimate the times when ego will reach an overlap, it is assumed that ego travels along its path
at its current velocity or at half the velocity of the path points, whichever is higher.

###### Dynamic objects

Two methods are used to estimate the time when a dynamic objects with reach some point.
If `objects.use_predicted_paths` is set to `true`, the predicted paths of the dynamic object are used if their confidence value is higher than the value set by the `objects.predicted_path_min_confidence` parameter.
Otherwise, the lanelet map is used to estimate the distance between the object and the point and the time is calculated assuming the object keeps its current velocity.

#### 5. Path update

Finally, for each decision to stop or slow down before an overlapping range,
a point is inserted in the path.
For a decision taken for an overlapping range with a lane $l$ starting at ego path point index $i$,
a point is inserted in the path between index $i$ and $i-1$ such that the ego footprint projected at the inserted point does not overlap $l$.
Such point with no overlap must exist since, by definition of the overlapping range,
we know that there is no overlap at $i-1$.

If the point would cause a higher deceleration than allowed by the `max_accel` parameter (node parameter),
it is skipped.

Moreover, parameter `action.distance_buffer` adds an extra distance between the ego footprint and the overlap when possible.

### Module Parameters

| Parameter | Type | Description |
| ----------------------------- | ------ | --------------------------------------------------------------------------------- |
| `mode` | string | [-] mode used to consider a dynamic object. Candidates: threshold, intervals, ttc |
| `skip_if_already_overlapping` | bool | [-] if true, do not run this module when ego already overlaps another lane |

| Parameter /threshold | Type | Description |
| -------------------- | ------ | ---------------------------------------------------------------- |
| `time_threshold` | double | [s] consider objects that will reach an overlap within this time |

| Parameter /intervals | Type | Description |
| --------------------- | ------ | ------------------------------------------------------- |
| `ego_time_buffer` | double | [s] extend the ego time interval by this buffer |
| `objects_time_buffer` | double | [s] extend the time intervals of objects by this buffer |

| Parameter /ttc | Type | Description |
| -------------- | ------ | ------------------------------------------------------------------------------------------------------ |
| `threshold` | double | [s] consider objects with an estimated time to collision bellow this value while ego is on the overlap |

| Parameter /objects | Type | Description |
| ------------------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
| `minimum_velocity` | double | [m/s] ignore objects with a velocity lower than this value |
| `predicted_path_min_confidence` | double | [-] minimum confidence required for a predicted path to be considered |
| `use_predicted_paths` | bool | [-] if true, use the predicted paths to estimate future positions; if false, assume the object moves at constant velocity along _all_ lanelets it currently is located in |

| Parameter /overlap | Type | Description |
| ------------------ | ------ | ---------------------------------------------------------------------------------------------------- |
| `minimum_distance` | double | [m] minimum distance inside a lanelet for an overlap to be considered |
| `extra_length` | double | [m] extra arc length to add to the front and back of an overlap (used to calculate enter/exit times) |

| Parameter /action | Type | Description |
| ----------------------------- | ------ | ---------------------------------------------------------------------------------------------- |
| `skip_if_over_max_decel` | bool | [-] if true, do not take an action that would cause more deceleration than the maximum allowed |
| `distance_buffer` | double | [m] buffer distance to try to keep between the ego footprint and lane |
| `slowdown.distance_threshold` | double | [m] insert a slow down when closer than this distance from an overlap |
| `slowdown.velocity` | double | [m] slow down velocity |
| `stop.distance_threshold` | double | [m] insert a stop when closer than this distance from an overlap |

| Parameter /ego | Type | Description |
| -------------------- | ------ | ---------------------------------------------------- |
| `extra_front_offset` | double | [m] extra front distance to add to the ego footprint |
| `extra_rear_offset` | double | [m] extra rear distance to add to the ego footprint |
| `extra_left_offset` | double | [m] extra left distance to add to the ego footprint |
| `extra_right_offset` | double | [m] extra right distance to add to the ego footprint |
Loading
Loading