Skip to content

Commit

Permalink
chore(autoware_velocity_smoother, autoware_path_optimizer): rename pa…
Browse files Browse the repository at this point in the history
…ckages (#7202)

* chore(autoware_path_optimizer): rename package and namespace

Signed-off-by: satoshi-ota <[email protected]>

* chore(autoware_static_centerline_generator): rename package and namespace

Signed-off-by: satoshi-ota <[email protected]>

* chore: update module name

Signed-off-by: satoshi-ota <[email protected]>

* chore(autoware_velocity_smoother): rename package and namespace

Signed-off-by: satoshi-ota <[email protected]>

* chore(tier4_planning_launch): update module name

Signed-off-by: satoshi-ota <[email protected]>

* chore: update module name

Signed-off-by: satoshi-ota <[email protected]>

* fix: test

Signed-off-by: satoshi-ota <[email protected]>

* fix: test

Signed-off-by: satoshi-ota <[email protected]>

* fix: test

Signed-off-by: satoshi-ota <[email protected]>

---------

Signed-off-by: satoshi-ota <[email protected]>
  • Loading branch information
satoshi-ota authored Jun 3, 2024
1 parent 25cf700 commit d2f41bc
Show file tree
Hide file tree
Showing 116 changed files with 492 additions and 502 deletions.
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<launch>
<arg name="input/odometry" default="/localization/kinematic_state"/>
<arg name="input/trajectory" default="/planning/scenario_planning/trajectory"/>
<arg name="input/reference_trajectory" default="/planning/scenario_planning/lane_driving/motion_planning/obstacle_avoidance_planner/trajectory"/>
<arg name="input/reference_trajectory" default="/planning/scenario_planning/lane_driving/motion_planning/path_optimizer/trajectory"/>
<arg name="input/objects" default="/perception/object_recognition/objects"/>
<arg name="input/modified_goal" default="/planning/scenario_planning/modified_goal"/>

Expand Down
2 changes: 1 addition & 1 deletion launch/tier4_planning_launch/launch/planning.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@
<!-- planning validator -->
<group>
<include file="$(find-pkg-share planning_validator)/launch/planning_validator.launch.xml">
<arg name="input_trajectory" value="/planning/scenario_planning/motion_velocity_smoother/trajectory"/>
<arg name="input_trajectory" value="/planning/scenario_planning/velocity_smoother/trajectory"/>
<arg name="output_trajectory" value="/planning/scenario_planning/trajectory"/>
<arg name="planning_validator_param_path" value="$(var planning_validator_param_path)"/>
</include>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,7 @@
<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 velocity_smoother_param_path)"/>
<param from="$(var behavior_velocity_smoother_type_param_path)"/>
<param from="$(var behavior_velocity_planner_common_param_path)"/>
<param name="launch_modules" value="$(var behavior_velocity_planner_launch_modules)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,18 +60,18 @@

<!-- generate kinematic-feasible path -->
<group>
<group if="$(eval &quot;'$(var motion_path_planner_type)' == 'obstacle_avoidance_planner'&quot;)">
<group if="$(eval &quot;'$(var motion_path_planner_type)' == 'path_optimizer'&quot;)">
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
<composable_node pkg="obstacle_avoidance_planner" plugin="obstacle_avoidance_planner::ObstacleAvoidancePlanner" name="obstacle_avoidance_planner" namespace="">
<composable_node pkg="autoware_path_optimizer" plugin="autoware_path_optimizer::PathOptimizer" name="path_optimizer" namespace="">
<!-- topic remap -->
<remap from="~/input/path" to="path_smoother/path"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/output/path" to="obstacle_avoidance_planner/trajectory"/>
<remap from="~/output/path" to="path_optimizer/trajectory"/>
<!-- params -->
<param from="$(var common_param_path)"/>
<param from="$(var vehicle_param_file)"/>
<param from="$(var nearest_search_param_path)"/>
<param from="$(var obstacle_avoidance_planner_param_path)"/>
<param from="$(var path_optimizer_param_path)"/>
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>
Expand All @@ -84,7 +84,7 @@
<!-- topic remap -->
<remap from="~/input/path" to="path_smoother/path"/>
<remap from="~/input/odometry" to="/localization/kinematic_state"/>
<remap from="~/output/path" to="obstacle_avoidance_planner/trajectory"/>
<remap from="~/output/path" to="path_optimizer/trajectory"/>
<!-- params -->
<param from="$(var common_param_path)"/>
<param from="$(var vehicle_param_file)"/>
Expand All @@ -101,7 +101,7 @@
<composable_node pkg="planning_topic_converter" plugin="planning_topic_converter::PathToTrajectory" name="path_to_trajectory_converter" namespace="">
<!-- params -->
<param name="input_topic" value="path_smoother/path"/>
<param name="output_topic" value="obstacle_avoidance_planner/trajectory"/>
<param name="output_topic" value="path_optimizer/trajectory"/>
<!-- composable node config -->
<extra_arg name="use_intra_process_comms" value="false"/>
</composable_node>
Expand All @@ -114,7 +114,7 @@
<load_composable_node target="/planning/scenario_planning/lane_driving/motion_planning/motion_planning_container">
<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/trajectory" to="path_optimizer/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"/>
Expand All @@ -131,8 +131,8 @@
<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 velocity_smoother_param_path)"/>
<param from="$(var motion_velocity_planner_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)"/> -->
Expand All @@ -146,7 +146,7 @@
<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/trajectory" to="path_optimizer/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
Original file line number Diff line number Diff line change
Expand Up @@ -21,22 +21,22 @@
<group>
<include file="$(find-pkg-share external_velocity_limit_selector)/launch/external_velocity_limit_selector.launch.xml">
<arg name="common_param_path" value="$(var common_param_path)"/>
<arg name="param_path" value="$(var motion_velocity_smoother_param_path)"/>
<arg name="param_path" value="$(var velocity_smoother_param_path)"/>
</include>
</group>
<!-- motion velocity smoother -->
<group>
<node_container pkg="rclcpp_components" exec="component_container" name="motion_velocity_smoother_container" namespace="">
<composable_node pkg="motion_velocity_smoother" plugin="motion_velocity_smoother::MotionVelocitySmootherNode" name="motion_velocity_smoother" namespace="">
<param name="algorithm_type" value="$(var motion_velocity_smoother_type)"/>
<node_container pkg="rclcpp_components" exec="component_container" name="velocity_smoother_container" namespace="">
<composable_node pkg="autoware_velocity_smoother" plugin="autoware_velocity_smoother::VelocitySmootherNode" name="velocity_smoother" namespace="">
<param name="algorithm_type" value="$(var velocity_smoother_type)"/>
<param from="$(var common_param_path)"/>
<param from="$(var nearest_search_param_path)"/>
<param from="$(var motion_velocity_smoother_param_path)"/>
<param from="$(var velocity_smoother_param_path)"/>
<param from="$(var velocity_smoother_type_param_path)"/>

<param name="publish_debug_trajs" value="false"/>
<remap from="~/input/trajectory" to="/planning/scenario_planning/scenario_selector/trajectory"/>
<remap from="~/output/trajectory" to="/planning/scenario_planning/motion_velocity_smoother/trajectory"/>
<remap from="~/output/trajectory" to="/planning/scenario_planning/velocity_smoother/trajectory"/>

<remap from="~/input/external_velocity_limit_mps" to="/planning/scenario_planning/max_velocity"/>
<remap from="~/input/acceleration" to="/localization/acceleration"/>
Expand Down
4 changes: 2 additions & 2 deletions launch/tier4_planning_launch/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -58,16 +58,16 @@
<buildtool_depend>autoware_cmake</buildtool_depend>

<exec_depend>autoware_behavior_velocity_planner</exec_depend>
<exec_depend>autoware_path_optimizer</exec_depend>
<exec_depend>autoware_remaining_distance_time_calculator</exec_depend>
<exec_depend>autoware_velocity_smoother</exec_depend>
<exec_depend>behavior_path_planner</exec_depend>
<exec_depend>costmap_generator</exec_depend>
<exec_depend>external_cmd_selector</exec_depend>
<exec_depend>external_velocity_limit_selector</exec_depend>
<exec_depend>freespace_planner</exec_depend>
<exec_depend>glog_component</exec_depend>
<exec_depend>mission_planner</exec_depend>
<exec_depend>motion_velocity_smoother</exec_depend>
<exec_depend>obstacle_avoidance_planner</exec_depend>
<exec_depend>obstacle_cruise_planner</exec_depend>
<exec_depend>obstacle_stop_planner</exec_depend>
<exec_depend>planning_evaluator</exec_depend>
Expand Down
8 changes: 4 additions & 4 deletions planning/.pages
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,10 @@ nav:
- 'RRT*': planning/freespace_planning_algorithms/rrtstar
- 'Mission Planner': planning/mission_planner
- 'Motion Planning':
- 'Obstacle Avoidance Planner':
- 'About Obstacle Avoidance': planning/obstacle_avoidance_planner
- 'Model Predictive Trajectory (MPT)': planning/obstacle_avoidance_planner/docs/mpt
- 'How to Debug': planning/obstacle_avoidance_planner/docs/debug
- 'Path Optimizer':
- 'About Path Optimizer': planning/autoware_path_optimizer
- 'Model Predictive Trajectory (MPT)': planning/autoware_path_optimizer/docs/mpt
- 'How to Debug': planning/autoware_path_optimizer/docs/debug
- 'Obstacle Cruise Planner':
- 'About Obstacle Cruise': planning/obstacle_cruise_planner
- 'How to Debug': planning/obstacle_cruise_planner/docs/debug
Expand Down
2 changes: 1 addition & 1 deletion planning/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -105,7 +105,7 @@ Interested in joining our meetings? We’d love to have you! For more informatio

Occasionally, we publish papers specific to the Planning Component in Autoware. We encourage you to explore these publications and find valuable insights for your work. If you find them useful and incorporate any of our methodologies or algorithms in your projects, citing our papers would be immensely helpful. This support allows us to reach a broader audience and continue contributing to the field.

If you use the Jerk Constrained Velocity Planning algorithm in [Motion Velocity Smoother](./motion_velocity_smoother/README.md) module in the Planning Component, we kindly request you to cite the relevant paper.
If you use the Jerk Constrained Velocity Planning algorithm in [Motion Velocity Smoother](./autoware_velocity_smoother/README.md) module in the Planning Component, we kindly request you to cite the relevant paper.

<!-- cspell:ignore Shimizu, Horibe, Watanabe, Kato -->

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ This module is under development.

## Purpose / Role

This module provides avoidance functions for vehicles, pedestrians, and obstacles in the vicinity of the ego's path in combination with the [obstacle_avoidance_planner](https://autowarefoundation.github.io/autoware.universe/main/planning/obstacle_avoidance_planner/).
This module provides avoidance functions for vehicles, pedestrians, and obstacles in the vicinity of the ego's path in combination with the [autoware_path_optimizer](https://autowarefoundation.github.io/autoware.universe/main/planning/autoware_path_optimizer/).
Each module performs the following roles.
Dynamic Avoidance module cuts off the drivable area according to the position and velocity of the target to be avoided.
Obstacle Avoidance module modifies the path to be followed so that it fits within the received drivable area.
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_behavior_velocity_planner/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -37,14 +37,14 @@
<depend>autoware_auto_mapping_msgs</depend>
<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_velocity_smoother</depend>
<depend>behavior_velocity_planner_common</depend>
<depend>diagnostic_msgs</depend>
<depend>eigen</depend>
<depend>geometry_msgs</depend>
<depend>lanelet2_extension</depend>
<depend>libboost-dev</depend>
<depend>motion_utils</depend>
<depend>motion_velocity_smoother</depend>
<depend>pcl_conversions</depend>
<depend>pluginlib</depend>
<depend>rclcpp</depend>
Expand Down
4 changes: 2 additions & 2 deletions planning/autoware_behavior_velocity_planner/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,11 @@

#include "node.hpp"

#include <autoware_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp>
#include <behavior_velocity_planner_common/utilization/path_utilization.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <motion_utils/trajectory/path_with_lane_id.hpp>
#include <motion_utils/trajectory/trajectory.hpp>
#include <motion_velocity_smoother/smoother/analytical_jerk_constrained_smoother/analytical_jerk_constrained_smoother.hpp>
#include <tier4_autoware_utils/ros/wait_for_param.hpp>
#include <tier4_autoware_utils/transform/transforms.hpp>

Expand Down Expand Up @@ -310,7 +310,7 @@ void BehaviorVelocityPlannerNode::onParam()
// constructed. It would be required if it was a callback. std::lock_guard<std::mutex>
// lock(mutex_);
planner_data_.velocity_smoother_ =
std::make_unique<motion_velocity_smoother::AnalyticalJerkConstrainedSmoother>(*this);
std::make_unique<autoware_velocity_smoother::AnalyticalJerkConstrainedSmoother>(*this);
planner_data_.velocity_smoother_->setWheelBase(planner_data_.vehicle_info_.wheel_base_m);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,8 +51,8 @@ std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
ament_index_cpp::get_package_share_directory("planning_test_utils");
const auto behavior_velocity_planner_dir =
ament_index_cpp::get_package_share_directory("autoware_behavior_velocity_planner");
const auto motion_velocity_smoother_dir =
ament_index_cpp::get_package_share_directory("motion_velocity_smoother");
const auto velocity_smoother_dir =
ament_index_cpp::get_package_share_directory("autoware_velocity_smoother");

const auto get_behavior_velocity_module_config = [](const std::string & module) {
const auto package_name = "behavior_velocity_" + module + "_module";
Expand Down Expand Up @@ -83,27 +83,26 @@ std::shared_ptr<BehaviorVelocityPlannerNode> generateNode()
node_options.parameter_overrides(params);

test_utils::updateNodeOptions(
node_options,
{planning_test_utils_dir + "/config/test_common.param.yaml",
planning_test_utils_dir + "/config/test_nearest_search.param.yaml",
planning_test_utils_dir + "/config/test_vehicle_info.param.yaml",
motion_velocity_smoother_dir + "/config/default_motion_velocity_smoother.param.yaml",
motion_velocity_smoother_dir + "/config/Analytical.param.yaml",
behavior_velocity_planner_dir + "/config/behavior_velocity_planner.param.yaml",
get_behavior_velocity_module_config("blind_spot"),
get_behavior_velocity_module_config("crosswalk"),
get_behavior_velocity_module_config("walkway"),
get_behavior_velocity_module_config("detection_area"),
get_behavior_velocity_module_config("intersection"),
get_behavior_velocity_module_config("no_stopping_area"),
get_behavior_velocity_module_config("occlusion_spot"),
get_behavior_velocity_module_config("run_out"),
get_behavior_velocity_module_config("speed_bump"),
get_behavior_velocity_module_config("stop_line"),
get_behavior_velocity_module_config("traffic_light"),
get_behavior_velocity_module_config("virtual_traffic_light"),
get_behavior_velocity_module_config("out_of_lane"),
get_behavior_velocity_module_config("no_drivable_lane")});
node_options, {planning_test_utils_dir + "/config/test_common.param.yaml",
planning_test_utils_dir + "/config/test_nearest_search.param.yaml",
planning_test_utils_dir + "/config/test_vehicle_info.param.yaml",
velocity_smoother_dir + "/config/default_velocity_smoother.param.yaml",
velocity_smoother_dir + "/config/Analytical.param.yaml",
behavior_velocity_planner_dir + "/config/behavior_velocity_planner.param.yaml",
get_behavior_velocity_module_config("blind_spot"),
get_behavior_velocity_module_config("crosswalk"),
get_behavior_velocity_module_config("walkway"),
get_behavior_velocity_module_config("detection_area"),
get_behavior_velocity_module_config("intersection"),
get_behavior_velocity_module_config("no_stopping_area"),
get_behavior_velocity_module_config("occlusion_spot"),
get_behavior_velocity_module_config("run_out"),
get_behavior_velocity_module_config("speed_bump"),
get_behavior_velocity_module_config("stop_line"),
get_behavior_velocity_module_config("traffic_light"),
get_behavior_velocity_module_config("virtual_traffic_light"),
get_behavior_velocity_module_config("out_of_lane"),
get_behavior_velocity_module_config("no_drivable_lane")});

// TODO(Takagi, Isamu): set launch_modules
// TODO(Kyoichi Sugahara) set to true launch_virtual_traffic_light
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.14)
project(obstacle_avoidance_planner)
project(autoware_path_optimizer)

include(CheckCXXCompilerFlag)

Expand All @@ -17,7 +17,7 @@ autoware_package()

find_package(Eigen3 REQUIRED)

ament_auto_add_library(obstacle_avoidance_planner SHARED
ament_auto_add_library(autoware_path_optimizer SHARED
# node
src/node.cpp
# core algorithms
Expand All @@ -34,20 +34,20 @@ ament_auto_add_library(obstacle_avoidance_planner SHARED
src/utils/geometry_utils.cpp
)

target_include_directories(obstacle_avoidance_planner
target_include_directories(autoware_path_optimizer
SYSTEM PUBLIC
${EIGEN3_INCLUDE_DIR}
)

# register node
rclcpp_components_register_node(obstacle_avoidance_planner
PLUGIN "obstacle_avoidance_planner::ObstacleAvoidancePlanner"
EXECUTABLE obstacle_avoidance_planner_node
rclcpp_components_register_node(autoware_path_optimizer
PLUGIN "autoware_path_optimizer::PathOptimizer"
EXECUTABLE path_optimizer_node
)

if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_${PROJECT_NAME}
test/test_${PROJECT_NAME}_node_interface.cpp
test/test_path_optimizer_node_interface.cpp
)
target_link_libraries(test_${PROJECT_NAME}
${PROJECT_NAME}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# Obstacle Avoidance Planner
# Path optimizer

## Purpose

Expand Down Expand Up @@ -158,7 +158,7 @@ Therefore, we have to make sure that the optimized trajectory is inside the driv

- Computation cost is sometimes high.
- Because of the approximation such as linearization, some narrow roads cannot be run by the planner.
- Roles of planning for `behavior_path_planner` and `obstacle_avoidance_planner` are not decided clearly. Both can avoid obstacles.
- Roles of planning for `behavior_path_planner` and `path_optimizer` are not decided clearly. Both can avoid obstacles.

## Comparison to other methods

Expand Down Expand Up @@ -195,7 +195,7 @@ Although it has a cons to converge to the local minima, it can get a good soluti
- The point on the vehicle, offset forward with this parameter from the base link` tries to follow the reference path.

- change or tune the method to approximate footprints with a set of circles.
- See [here](https://autowarefoundation.github.io/autoware.universe/main/planning/obstacle_avoidance_planner/docs/mpt/#collision-free)
- See [here](https://autowarefoundation.github.io/autoware.universe/main/planning/path_optimizer/docs/mpt/#collision-free)
- Tuning means changing the ratio of circle's radius.

### Computation time
Expand Down
Loading

0 comments on commit d2f41bc

Please sign in to comment.