Skip to content

Commit

Permalink
feat: add planning_launch package (#164)
Browse files Browse the repository at this point in the history
* release v0.4.0

* add obstacle avoid param (#62)

* Feature/add stop reason lane change (#69)

* add blocked by obstacle

* add stop reason topic to lane change planner

* Revert "add blocked by obstacle"

This reverts commit 1f5ecdb30c04f7ee70a4b3271bb2099c44752801.

* removed ROS1 package

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* Revert "removed ROS1 package"

This reverts commit c914e2e16fed7726f8748e1f936b061f051eaf8f.

* add COLCON_IGNORE file to all ROS1 packages

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* rename *.launch files to *.launch.xml

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* port planning launch

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* add missing porting

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* replace rostopic pub with executable in behavior_planning.launch.xml

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* fix remapping of topics in launch files

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* modify integer parameters to double parameters

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* fix arguments in parking.launch.xml

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* fix remapping of topics in scenario_planning.launch.xml

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* ROS2 Linting: planning_launch (#38)

* Ros2 port autoware launch (#35)

* [autoware_launch] port CMakelists.txt and remove COLCON_IGNORE

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* [autoware_launch] fix planning_simulator.launch.xml

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* [autoware_launch] add rviz config

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* [autoware_launch] first port of autoware_launch

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* lanuch rviz with config file

Signed-off-by: kosuke murakami <kosuke.murakami@tier4.jp>

* modify launch file for making psim work

Signed-off-by: kosuke murakami <kosuke.murakami@tier4.jp>

* add vehicle model in launch

Signed-off-by: kosuke murakami <kosuke.murakami@tier4.jp>

* change from vehicle_model to vehicle_param_file

Signed-off-by: kosuke murakami <kosuke.murakami@tier4.jp>

* [autoware_launch] add autoware_web_controller and system launch

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* add rosbrdige_suite to build_depends.repos

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* Update rviz

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* update autoware.rviz

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

* remove autoware_ros2.rviz

Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>

Co-authored-by: kosuke murakami <kosuke.murakami@tier4.jp>
Co-authored-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Ros2 v0.8.0 planning launch (#59)

* [planning_launch] restore file name for ros2 porting

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* Add obstacle_stop_planner.yaml (#82)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* add surround obstacle checker options (#86)

* fix slow down param related to tier4/autoware.iv@a9cdcb2 (#91)

* fix parame max_steer_deg (#92)

* add refine_goal_search_radius_range (#93)

* Change default evaluation in motion velocity optimizer (#97)

* Use Linf

* Add new line

* Add maximum_deceleration parameter (#98)

* Add maximum_deceleration parameter

* Change default value

* Unable abort lane change (#102)

* add param stoping velocity and fix typo (#106)

* Add a parameter for minimum velocity for lane change (#109)

* Add parameters for collision check for lane change (#110)

* Add a parameter for disable collision check at prepare phase

* Add parameters for collision check with predicted_path

* Add a parameter for backward buffer for end of lane (#114)

* Add parameters for backward buffer for end of lane

* Remove comment out

* add extend_distance param (#107)

* add parameter of acc (#129)

Signed-off-by: Yuma Nihei <yuma.nihei@tier4.jp>

* fix typo & change static object velocity thres in lane_change_planner (#104)

* change static object velocity thres

Signed-off-by: Kosuke Murakami <kosuke.murakami@tier4.jp>

* fix typo

Signed-off-by: Kosuke Murakami <kosuke.murakami@tier4.jp>

* Change minimum_lane_change_velocity (#131)

* Feature/update avoidance param (#140)

* update avoidance param

Signed-off-by: Kosuke Murakami <kosuke.murakami@tier4.jp>

* disable unnecesarry marker

Signed-off-by: Kosuke Murakami <kosuke.murakami@tier4.jp>

* modify min_behavior_stop_margin (#127)

* modify min_behavior_stop_margin

Signed-off-by: Yamato Ando <yamato.ando@gmail.com>

* Update obstacle_stop_planner.yaml

Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com>

* Add expand_stop_range to obstacle_stop_planner.yaml (#152)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Update obstacle_stop_planner.yaml (#153)

* Visualize echo back goal_pose instead of 2D Nav Goal (#150)

* Visualize echo back goal_pose instead of 2D Nav Goal

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Fix mission_planning.launch

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Add surround_obstacle_checker.yaml (#157)

* Add parameter (#158)

* Revert "[planning_launch] restore file name for ros2 porting"

This reverts commit 275f0df232323bf24627adea9cb08888c250625e.

* fix namespace

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* fix relay

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* [planning_launch]: Add vehicle_param_file for turn signal decider

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* [planning_launch]: Change topic type of lane change approval

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com>
Co-authored-by: tkimura4 <tomoya.kimura@tier4.jp>
Co-authored-by: Taichi Higashide <taichi.higashide@tier4.jp>
Co-authored-by: Satoshi Tanaka <st14.828soccer@gmail.com>
Co-authored-by: Fumiya Watanabe <rej55.g@gmail.com>
Co-authored-by: Yuma Nihei <yuma.nihei@tier4.jp>
Co-authored-by: Kosuke Murakami <kosuke.murakami@tier4.jp>
Co-authored-by: YamatoAndo <yamato.ando@gmail.com>
Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com>
Co-authored-by: hiroaki-ishikawa-t4 <57431939+hiroaki-ishikawa-t4@users.noreply.github.com>
Co-authored-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Ros2 v0.8.0 fix packages (#64)

* add vehicle_param_file to simple planning simulator

* add vehicle_param_file to lane change planner

* Rename ROS-related .yaml to .param.yaml (#65)

* Rename ROS-related .yaml to .param.yaml

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Add missing '--'

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Rename vehicle_info.yaml to vehicle_info.param.yaml

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Fix livox param name

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Ros2 update v0.9.0 (#67)

* Add pose history into rviz config

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* add blocked by obstacle option (#164)

* fix tab name (#166)

* disenable ndt visualization (#169)

* disenable ndt visualization

* change alpha

* dont visualize position covariance

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* change global frame to map (#171)

* add param (#156)

Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com>
Co-authored-by: Taichi Higashide <taichi.higashide@tier4.jp>
Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com>
Co-authored-by: tkimura4 <tomoya.kimura@tier4.jp>

* Ros2 fix topic name part1 (#83)

* Fix topic name for behavior_velocity_planner

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix topic name of lane_change_planner

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix topic name of freespace_planner

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix topic name for freespace_planner

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix typo in planning launch (#92)

* Fix typo in planning launch

* Fix remaining errors

* Fix various typos in launch files (#97)

* add use_sim-time option (#99)

* Format launch files (#178)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Sync public repo (#185)

* add tier4 usbcam (#104)

* add tier4 usbcam

* change version

* tier4/ros2

* Ros2 vehicle info param server (#96)

* add vehicle info param server

* delete vehicle param file

Co-authored-by: taikitanaka <ttatcoder@outlook.jp>

* Ros2 fix topic name part2 (#89)

* Fix topic name for traffic_light_classifier

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix topic name for traffic_light_visualization

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix topic name for traffic_light_ssd_fine_detector

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com>
Co-authored-by: tkimura4 <tomoya.kimura@tier4.jp>
Co-authored-by: taikitanaka <ttatcoder@outlook.jp>
Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com>

* Ros2 lsim test (#186)

* Add group to launch file for var scope

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Remove pointcloud relay for localization

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Add use_sim_time

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Remove pointcloud relay for localization

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

Co-authored-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Use set_parameter for use_sim_time (#198)

* Use set_parameter for use_sim_time

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add default parameter for scenario simulator

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add container launch for planning (#205)

* Add container launch for planning

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* fix porting miss

* fix lane_driving.launch.xml

* Add missing parameters

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

Co-authored-by: taichiH <azumade.30@gmail.com>

* Rename AstarNavi to FreespacePlannerNode (#213)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Fix typos in launch files (#231)

* Fix typos in launch files

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Fix lint

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

Co-authored-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Format launch files (#228)

* Format launch files

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Format launch.py

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Fix lint

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Fix topic name of external traffic light input (#236)

* Add namespace to behavior_velocity_planner (#252)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Fix typo applygin->applying (#304)

Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>

* add description for planning_launch #335

* add README.md and svg files (#328)

* add md and svg

* fix typo

* fix typo

* fix word

* fix typo

* add lack of things

* Update README

* fix depending packages

* fix word

* Add autoware api (#376)

* Add external api adaptor (#267)

* Add external api adaptor

* Add api adaptor to logging simulator

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Add engage status output

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Add internal api adaptor (#273)

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Add map hash generator (#319)

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Add autoware api launch (#326)

* Add autoware api launch

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Apply autoware api launch

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Add deprecated comment

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Remove unused parameter (#325)

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Add api parameter (#341)

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Add start request API (#321)

* Add use start request option

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix lint

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Feature external cmd selector heartbeat (#356)

* Rename external command topic

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Modify command topic name

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix topic name

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Rename remote_cmd_converter

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Remove gate mode from external command

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix latest external command name (#361)

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* Fix merge conflict

Signed-off-by: Takagi, Isamu <isamu.takagi@tier4.jp>

* change external traffic light topic name in behavior velocity planner (#310)

* fix topic

* change internal topic name

Co-authored-by: yabuta <makoto.yabuta@tier4.jp>

* Merge pull request #359 from tier4/feature/add_plannig_error_monitor (#365)

* Feature/add virtual traffic light planner (#317)

* Fix pre-commit (#407)

* Fix pre-commit errors

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Fix package.xml

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* fix parameter name (#470)

* Feature/porting behavior path planner (#300)

* modify behavior_planning launch for behavior_path_planner with lane_c… (#239)

* modify behavior_planning launch for behavior_path_planner with lane_change_only config

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* remove avoidance & side_shift related code

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* Fix launcher and add config files and change obstacle avoid param

* Add new line

* Fix visualization and remove multiple args

* Enable auto approve path change

Co-authored-by: rej55 <rej55.g@gmail.com>
Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* add param in behavior_path_planner (#255)

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* Fix param (#251)

* Fix typo

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com>
Co-authored-by: rej55 <rej55.g@gmail.com>

* Feature/porting motion velocity smoother (#302)

* Launch motion_velocity_smoother (#215)

* Launch motion_velocity_smoother

* Change params

* Fix parameter files

* Fix

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Fix/smoother trajectory ds (#249)

* Add parameter

* Fix

* Fix

* change launcher parameter (#265)

* Feature/smoother resampling (#269)

* change launcher parameter

* add new parameter

Co-authored-by: Fumiya Watanabe <rej55.g@gmail.com>
Co-authored-by: purewater0901 <43805014+purewater0901@users.noreply.github.com>

* Master sync parking module (#303)

* Add namespace

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add freespace planner config file

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Add missing import

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* update rviz config & planner params (#305)

Co-authored-by: satoshi-ota <satoshi.ota@gmail.com>

* Feature/porting occlusion spot (#309)

* add occulusion_spot marker (#266)

* add blindspot marker

* to occlusion spot slow down

* remove debug info from marker (#287)

* remove debug info from marker

* remove debug arrow

* fix format

* update behavior launch

* apply pep8

* fix format

Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com>

* Use multithread for lane driving planning (#327)

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Fix import order of parking.launch.py (#347)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* Add analytical smoother config (#360)

Signed-off-by: Makoto Kurihara <mkuri8m@gmail.com>

* update acc param (#358)

* add rosparam for vehicle center optimization (#362)

* update ros param for .iv (#353)

* update ros param for .iv

* forward fixing mpt time: 3.0->1.0

* Fix/obstacle avoid revert some improvements (#381)

* Revert "update ros param for .iv (#353)"

This reverts commit f7f341a.

* Revert "add rosparam for vehicle center optimization (#362)"

This reverts commit 78bbf70.

* update side shift param (#370)

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* add yaml & load lane following params (#377)

* add pull over/out module (#430)

add yaml file and modify BT tree file path

modify parameter file

add parameter

add use_dynamic_object flag in pull out param

delete unncesarry parameters

delete unnecessary param

merge change for jpntaxi

delete blank line

modify BT file name

modify launch file

* Update behavior path planner launch files (#433)

* update launch parameters for behavior_path_planner

Signed-off-by: TakaHoribe <horibe.takamasa@gmail.com>

* update param at experiment

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* fix typo

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* Fix indent

Co-authored-by: TakaHoribe <horibe.takamasa@gmail.com>

* Fix for pre-commit (437)

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

* change threshold_distance_object_is_on_center to 1.0 (#441)

Signed-off-by: TakaHoribe <horibe.takamasa@gmail.com>

* delete optimizer (#456)

* add params for acceleration prevention (#454) (#457)

Signed-off-by: Takamasa Horibe <horibe.takamasa@gmail.com>

Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com>

* Feature/use external velocity limit selector (#460)

* use external velocity limit selector

* add common planning params

* update yaml params

* Feature/add slow down params (#448)

* add/update slow down params

* topic remap

* update topic name

* Fix/use common param (#465)

* Change formatter to black (#488)

* Update pre-commit settings

* Apply Black

* Replace ament_lint_common with autoware_lint_common

* Update build_depends.repos

* Fix build_depends

* twist -> odometry (#109)

Co-authored-by: Takayuki Murooka <takayuki.murooka@tier4.jp>

* Auto/fix launch (#110)

* fix namespace

* remove dynamic_object_visualization

* fix rviz

* remove unused depend/launcher (#112)

* Fix remapping in control.launch.py (#115)

* Fix remappings

* Add comment

* Sync .auto branch with the latest branch in internal repository (#120)

* Disbale intersection polygon marker (#483)

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Merge pull request #384 from tier4/feature/no_stopping_area

Feature/no stopping area

Signed-off-by: Kenji Miyake <kenji.miyake@tier4.jp>

Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com>
Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com>

* Update traffic light topic name (#131)

* Update traffic light topic name

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Update traffic light topic name in perception

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* Fix no ground pointcloud topic name (#134)

Signed-off-by: j4tfwm6z <proj-jpntaxi@tier4.jp>

Co-authored-by: j4tfwm6z <proj-jpntaxi@tier4.jp>

* auto/fix occupancy grid map topic name (#137)

* fix/rename segmentation namespace (#139)

* fix namespace: rviz config

* fix namespace: planning stack

* rename segmentatino directory

* fix namespace: perception stack

* add vehicle info parameter

Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp>

* ci(pre-commit): autofix

* remove unused import

* remove unused import

Signed-off-by: tomoya.kimura <tomoya.kimura@tier4.jp>

Co-authored-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>
Co-authored-by: Kosuke Murakami <kosuke.murakami@tier4.jp>
Co-authored-by: Takamasa Horibe <horibe.takamasa@gmail.com>
Co-authored-by: Jilada Eccleston <jilada.eccleston@tier4.jp>
Co-authored-by: Ryohsuke Mitsudome <43976834+mitsudome-r@users.noreply.github.com>
Co-authored-by: wep21 <border_goldenmarket@yahoo.co.jp>
Co-authored-by: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com>
Co-authored-by: Taichi Higashide <taichi.higashide@tier4.jp>
Co-authored-by: Satoshi Tanaka <st14.828soccer@gmail.com>
Co-authored-by: Fumiya Watanabe <rej55.g@gmail.com>
Co-authored-by: Yuma Nihei <yuma.nihei@tier4.jp>
Co-authored-by: YamatoAndo <yamato.ando@gmail.com>
Co-authored-by: Yukihiro Saito <yukky.saito@gmail.com>
Co-authored-by: hiroaki-ishikawa-t4 <57431939+hiroaki-ishikawa-t4@users.noreply.github.com>
Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com>
Co-authored-by: taikitanaka3 <65527974+taikitanaka3@users.noreply.github.com>
Co-authored-by: Takagi, Isamu <43976882+isamu-takagi@users.noreply.github.com>
Co-authored-by: Kazuki Miyahara <kmiya@outlook.com>
Co-authored-by: taikitanaka <ttatcoder@outlook.jp>
Co-authored-by: Takagi, Isamu <isamu.takagi@tier4.jp>
Co-authored-by: taichiH <azumade.30@gmail.com>
Co-authored-by: Kosuke Takeuchi <kosuke.tnp@gmail.com>
Co-authored-by: Hiroki OTA <hiroki.ota@tier4.jp>
Co-authored-by: yabuta <makoto.yabuta@tier4.jp>
Co-authored-by: purewater0901 <43805014+purewater0901@users.noreply.github.com>
Co-authored-by: Satoshi OTA <44889564+satoshi-ota@users.noreply.github.com>
Co-authored-by: satoshi-ota <satoshi.ota@gmail.com>
Co-authored-by: Makoto Kurihara <mkuri8m@gmail.com>
Co-authored-by: Takayuki Murooka <takayuki5168@gmail.com>
Co-authored-by: kyoichi sugahara <81.s.kyo.19@gmail.com>
Co-authored-by: Kenji Miyake <kenji.miyake@tier4.jp>
Co-authored-by: autoware-iv-sync-ci[bot] <87871706+autoware-iv-sync-ci[bot]@users.noreply.github.com>
Co-authored-by: Takayuki Murooka <takayuki.murooka@tier4.jp>
Co-authored-by: j4tfwm6z <proj-jpntaxi@tier4.jp>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
1 parent 7b23bdf commit 9c5d9ff
Show file tree
Hide file tree
Showing 35 changed files with 2,014 additions and 0 deletions.
23 changes: 23 additions & 0 deletions launch/planning_launch/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
cmake_minimum_required(VERSION 3.5)
project(planning_launch)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wno-unused-parameter -Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake_auto REQUIRED)
ament_auto_find_build_dependencies()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_auto_package(
INSTALL_TO_SHARE
launch
config
)
16 changes: 16 additions & 0 deletions launch/planning_launch/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
# planning_launch

## Structure

![planning_launch](./planning_launch.drawio.svg)

## Package Dependencies

Please see `<exec_depend>` in `package.xml`.

## Usage

```xml
<include file="$(find-pkg-share planning_launch)/launch/planning.launch.xml">
</include>
```
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
/**:
ros__parameters:
# constraints param for normal driving
normal:
min_acc: -0.5 # min deceleration [m/ss]
max_acc: 1.0 # max acceleration [m/ss]
min_jerk: -0.5 # min jerk [m/sss]
max_jerk: 1.0 # max jerk [m/sss]

# constraints to be observed
limit:
min_acc: -2.5 # min deceleration limit [m/ss]
max_acc: 1.0 # max acceleration limit [m/ss]
min_jerk: -1.5 # min jerk limit [m/sss]
max_jerk: 1.5 # max jerk limit [m/sss]
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
/**:
ros__parameters:
resample:
ds_resample: 0.1
num_resample: 1
delta_yaw_threshold: 0.785

latacc:
enable_constant_velocity_while_turning: false
constant_velocity_dist_threshold: 2.0

forward:
max_acc: 1.0
min_acc: -1.0
max_jerk: 0.3
min_jerk: -0.3
kp: 0.3

backward:
start_jerk: -0.1
min_jerk_mild_stop: -0.3
min_jerk: -1.5
min_acc_mild_stop: -1.0
min_acc: -2.5
span_jerk: -0.01
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
/**:
ros__parameters:
jerk_weight: 0.1 # weight for "smoothness" cost for jerk
over_v_weight: 10000.0 # weight for "over speed limit" cost
over_a_weight: 500.0 # weight for "over accel limit" cost
over_j_weight: 200.0 # weight for "over jerk limit" cost
jerk_filter_ds: 0.1 # resampling ds for jerk filter
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
pseudo_jerk_weight: 100.0 # weight for "smoothness" cost
over_v_weight: 100000.0 # weight for "over speed limit" cost
over_a_weight: 1000.0 # weight for "over accel limit" cost
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
pseudo_jerk_weight: 200.0 # weight for "smoothness" cost
over_v_weight: 100000.0 # weight for "over speed limit" cost
over_a_weight: 5000.0 # weight for "over accel limit" cost
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
/**:
ros__parameters:
# motion state constraints
max_velocity: 20.0 # max velocity limit [m/s]

# external velocity limit parameter
margin_to_insert_external_velocity_limit: 0.3 # margin distance to insert external velocity limit [m]

# curve parameters
max_lateral_accel: 0.8 # max lateral acceleration limit [m/ss]
min_curve_velocity: 2.74 # min velocity at lateral acceleration limit [m/ss]
decel_distance_before_curve: 3.5 # slow speed distance before a curve for lateral acceleration limit
decel_distance_after_curve: 2.0 # slow speed distance after a curve for lateral acceleration limit

# engage & replan parameters
replan_vel_deviation: 5.53 # velocity deviation to replan initial velocity [m/s]
engage_velocity: 0.25 # engage velocity threshold [m/s] (if the trajectory velocity is higher than this value, use this velocity for engage vehicle speed)
engage_acceleration: 0.1 # engage acceleration [m/ss] (use this acceleration when engagement)
engage_exit_ratio: 0.5 # exit engage sequence to normal velocity planning when the velocity exceeds engage_exit_ratio x engage_velocity.
stop_dist_to_prohibit_engage: 0.5 # if the stop point is in this distance, the speed is set to 0 not to move the vehicle [m]

# stop velocity
stopping_velocity: 2.778 # change target velocity to this value before v=0 point [m/s]
stopping_distance: 0.0 # distance for the stopping_velocity [m]. 0 means the stopping velocity is not applied.

# path extraction parameters
extract_ahead_dist: 200.0 # forward trajectory distance used for planning [m]
extract_behind_dist: 5.0 # backward trajectory distance used for planning [m]
delta_yaw_threshold: 1.0472 # Allowed delta yaw between ego pose and trajectory pose [radian]

# resampling parameters for optimization
max_trajectory_length: 200.0 # max trajectory length for resampling [m]
min_trajectory_length: 150.0 # min trajectory length for resampling [m]
resample_time: 5.0 # resample total time for dense sampling [s]
dense_dt: 0.1 # resample time interval for dense sampling [s]
dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m]
sparse_dt: 0.5 # resample time interval for sparse sampling [s]
sparse_min_interval_distance: 4.0 # minimum points-interval length for sparse sampling [m]

# resampling parameters for post process
post_max_trajectory_length: 300.0 # max trajectory length for resampling [m]
post_min_trajectory_length: 30.0 # min trajectory length for resampling [m]
post_resample_time: 10.0 # resample total time for dense sampling [s]
post_dense_dt: 0.1 # resample time interval for dense sampling [s]
post_dense_min_interval_distance: 0.1 # minimum points-interval length for dense sampling [m]
post_sparse_dt: 0.1 # resample time interval for sparse sampling [s]
post_sparse_min_interval_distance: 1.0 # minimum points-interval length for sparse sampling [m]

# system
over_stop_velocity_warn_thr: 1.389 # used to check if the optimization exceeds the input velocity on the stop point
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
# see AvoidanceParameters description in avoidance_module_data.hpp for description.
/**:
ros__parameters:
avoidance:
resample_interval_for_planning: 0.3
resample_interval_for_output: 4.0
detection_area_right_expand_dist: 0.0
detection_area_left_expand_dist: 1.0

threshold_distance_object_is_on_center: 1.0 # [m]
threshold_speed_object_is_stopped: 1.0 # [m/s]
object_check_forward_distance: 150.0 # [m]
object_check_backward_distance: 2.0 # [m]
lateral_collision_margin: 2.0 # [m]

prepare_time: 2.0 # [s]
min_prepare_distance: 1.0 # [m]
min_avoidance_distance: 10.0 # [m]

min_nominal_avoidance_speed: 7.0 # [m/s]
min_sharp_avoidance_speed: 1.0 # [m/s]

max_right_shift_length: 5.0
max_left_shift_length: 5.0

nominal_lateral_jerk: 0.2 # [m/s3]
max_lateral_jerk: 1.0 # [m/s3]

object_hold_max_count: 20

# For prevention of large acceleration while avoidance
min_avoidance_speed_for_acc_prevention: 3.0 # [m/s]
max_avoidance_acceleration: 0.5 # [m/ss]

# for debug
publish_debug_marker: false
print_debug_info: false

# not enabled yet
longitudinal_collision_margin_min_distance: 0.0 # [m]
longitudinal_collision_margin_time: 0.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/**:
ros__parameters:
backward_path_length: 5.0
forward_path_length: 300.0
backward_length_buffer_for_end_of_lane: 5.0
backward_length_buffer_for_end_of_pull_over: 5.0
backward_length_buffer_for_end_of_pull_out: 5.0
minimum_lane_change_length: 12.0
minimum_pull_over_length: 16.0
drivable_area_resolution: 0.1
drivable_area_width: 100.0
drivable_area_height: 50.0
refine_goal_search_radius_range: 7.5
intersection_search_distance: 30.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
/**:
ros__parameters:
lane_change:
min_stop_distance: 5.0
stop_time: 2.0
hysteresis_buffer_distance: 2.0
lane_change_prepare_duration: 4.0
lane_changing_duration: 8.0
lane_change_finish_judge_buffer: 3.0
minimum_lane_change_velocity: 5.6
prediction_duration: 8.0
prediction_time_resolution: 0.5
static_obstacle_velocity_thresh: 1.5
maximum_deceleration: 1.0
enable_abort_lane_change: false
enable_collision_check_at_prepare_phase: false
use_predicted_path_outside_lanelet: false
use_all_predicted_path: false
enable_blocked_by_obstacle: false
lane_change_search_distance: 30.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
/**:
ros__parameters:
lane_following:
expand_drivable_area: false
right_bound_offset: 0.5
left_bound_offset: 0.5
lane_change_prepare_duration: 2.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
/**:
ros__parameters:
pull_out:
min_stop_distance: 2.0
stop_time: 0.0
hysteresis_buffer_distance: 1.0
pull_out_prepare_duration: 4.0
pull_out_duration: 2.0
pull_out_finish_judge_buffer: 1.0
minimum_pull_out_velocity: 2.0
prediction_duration: 30.0
prediction_time_resolution: 0.5
static_obstacle_velocity_thresh: 1.5
maximum_deceleration: 1.0
enable_collision_check_at_prepare_phase: false
use_predicted_path_outside_lanelet: false
use_all_predicted_path: false
use_dynamic_object: true
enable_blocked_by_obstacle: false
pull_out_search_distance: 30.0
before_pull_out_straight_distance: 5.0
after_pull_out_straight_distance: 5.0
maximum_lateral_jerk: 2.0
minimum_lateral_jerk: 0.5
deceleration_interval: 15.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
/**:
ros__parameters:
pull_over:
min_stop_distance: 5.0
stop_time: 2.0
hysteresis_buffer_distance: 2.0
pull_over_prepare_duration: 4.0
pull_over_duration: 2.0
pull_over_finish_judge_buffer: 3.0
minimum_pull_over_velocity: 3.0
prediction_duration: 30.0
prediction_time_resolution: 0.5
static_obstacle_velocity_thresh: 1.5
maximum_deceleration: 1.0
enable_collision_check_at_prepare_phase: false
use_predicted_path_outside_lanelet: false
use_all_predicted_path: false
enable_blocked_by_obstacle: false
pull_over_search_distance: 30.0
after_pull_over_straight_distance: 5.0
before_pull_over_straight_distance: 5.0
margin_from_boundary: 0.5
maximum_lateral_jerk: 2.0
minimum_lateral_jerk: 0.5
deceleration_interval: 15.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
side_shift:
min_distance_to_start_shifting: 5.0
time_to_start_shifting: 1.0
shifting_lateral_jerk: 0.2
min_shifting_distance: 5.0
min_shifting_speed: 5.56
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
/**:
ros__parameters:
min_stop_distance: 5.0
stop_time: 2.0
hysteresis_buffer_distance: 2.0
backward_path_length: 5.0
forward_path_length: 300.0
max_accel: -5.0
lane_change_prepare_duration: 4.0
lane_changing_duration: 8.0
backward_length_buffer_for_end_of_lane: 5.0
lane_change_finish_judge_buffer: 3.0
minimum_lane_change_length: 12.0
minimum_lane_change_velocity: 5.6
prediction_duration: 8.0
prediction_time_resolution: 0.5
drivable_area_resolution: 0.1
drivable_area_width: 100.0
drivable_area_height: 50.0
static_obstacle_velocity_thresh: 1.5
maximum_deceleration: 1.0
refine_goal_search_radius_range: 7.5
Loading

0 comments on commit 9c5d9ff

Please sign in to comment.