Package Summary
Tags | No category tags. |
Version | 0.43.0 |
License | Apache License 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
VCS Type | git |
VCS Version | main |
Last Updated | 2025-04-03 |
Dev Status | UNMAINTAINED |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Takamasa Horibe
- Tomoya Kimura
- Maxime Clement
- Mamoru Sobue
- Zulfaqar Azmi
- Temkei Kem
- Junya Sasaki
- Kotaro Yoshimoto
Authors
autoware_simple_planning_simulator
Purpose / Use cases
This node simulates the vehicle motion for a vehicle command in 2D using a simple vehicle model.
Design
The purpose of this simulator is for the integration test of planning and control modules. This does not simulate sensing or perception, but is implemented in pure c++ only and works without GPU.
Assumptions / Known limits
- It simulates only in 2D motion.
- It does not perform physical operations such as collision and sensing, but only calculates the integral results of vehicle dynamics.
Inputs / Outputs / API
input
- input/initialpose [
geometry_msgs/msg/PoseWithCovarianceStamped
] : for initial pose - input/ackermann_control_command [
autoware_control_msgs/msg/Control
] : target command to drive a vehicle - input/manual_ackermann_control_command [
autoware_control_msgs/msg/Control
] : manual target command to drive a vehicle (used when control_mode_request = Manual) - input/gear_command [
autoware_vehicle_msgs/msg/GearCommand
] : target gear command. - input/manual_gear_command [
autoware_vehicle_msgs/msg/GearCommand
] : target gear command (used when control_mode_request = Manual) - input/turn_indicators_command [
autoware_vehicle_msgs/msg/TurnIndicatorsCommand
] : target turn indicator command - input/hazard_lights_command [
autoware_vehicle_msgs/msg/HazardLightsCommand
] : target hazard lights command - input/control_mode_request [
tier4_vehicle_msgs::srv::ControlModeRequest
] : mode change for Auto/Manual driving
output
- /tf [
tf2_msgs/msg/TFMessage
] : simulated vehicle pose (base_link) - /output/odometry [
nav_msgs/msg/Odometry
] : simulated vehicle pose and twist - /output/steering [
autoware_vehicle_msgs/msg/SteeringReport
] : simulated steering angle - /output/control_mode_report [
autoware_vehicle_msgs/msg/ControlModeReport
] : current control mode (Auto/Manual) - /output/gear_report [
autoware_vehicle_msgs/msg/ControlModeReport
] : simulated gear - /output/turn_indicators_report [
autoware_vehicle_msgs/msg/ControlModeReport
] : simulated turn indicator status - /output/hazard_lights_report [
autoware_vehicle_msgs/msg/ControlModeReport
] : simulated hazard lights status
Inner-workings / Algorithms
Common Parameters
Name | Type | Description | Default value |
---|---|---|---|
simulated_frame_id | string | set to the child_frame_id in output tf | “base_link” |
origin_frame_id | string | set to the frame_id in output tf | “odom” |
initialize_source | string | If “ORIGIN”, the initial pose is set at (0,0,0). If “INITIAL_POSE_TOPIC”, node will wait until the input/initialpose topic is published. |
“INITIAL_POSE_TOPIC” |
add_measurement_noise | bool | If true, the Gaussian noise is added to the simulated results. | true |
pos_noise_stddev | double | Standard deviation for position noise | 0.01 |
rpy_noise_stddev | double | Standard deviation for Euler angle noise | 0.0001 |
vel_noise_stddev | double | Standard deviation for longitudinal velocity noise | 0.0 |
angvel_noise_stddev | double | Standard deviation for angular velocity noise | 0.0 |
steer_noise_stddev | double | Standard deviation for steering angle noise | 0.0001 |
Vehicle Model Parameters
vehicle_model_type options
IDEAL_STEER_VEL
IDEAL_STEER_ACC
IDEAL_STEER_ACC_GEARED
DELAY_STEER_VEL
DELAY_STEER_ACC
DELAY_STEER_ACC_GEARED
DELAY_STEER_ACC_GEARED_WO_FALL_GUARD
-
DELAY_STEER_MAP_ACC_GEARED
: applies 1D dynamics and time delay to the steering and acceleration commands. The simulated acceleration is determined by a value converted through the provided acceleration map. This model is valuable for an accurate simulation with acceleration deviations in a real vehicle. -
LEARNED_STEER_VEL
: launches learned python models. More about this here.
The following models receive ACTUATION_CMD
generated from raw_vehicle_cmd_converter
. Therefore, when these models are selected, the raw_vehicle_cmd_converter
is also launched.
-
ACTUATION_CMD
: This model only converts accel/brake commands and use steer command as it is. -
ACTUATION_CMD_STEER_MAP
: The steer command is converted to the steer rate command using the steer map. -
ACTUATION_CMD_VGR
: The steer command is converted to the steer rate command using the variable gear ratio. -
ACTUATION_CMD_MECHANICAL
: This model has mechanical dynamics and controller for that.
The IDEAL
model moves ideally as commanded, while the DELAY
model moves based on a 1st-order with time delay model. The STEER
means the model receives the steer command. The VEL
means the model receives the target velocity command, while the ACC
model receives the target acceleration command. The GEARED
suffix means that the motion will consider the gear command: the vehicle moves only one direction following the gear.
The table below shows which models correspond to what parameters. The model names are written in abbreviated form (e.g. IDEAL_STEER_VEL = I_ST_V).
Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_A_G_WO_FG | D_ST_M_ACC_G | L_S_V | A_C | Default value | unit |
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | o | x | x | 0.1 | [s] |
steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | o | x | o | 0.24 | [s] |
vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | x | x | 0.25 | [s] |
acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | o | x | x | 0.1 | [s] |
steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | o | x | o | 0.27 | [s] |
steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | o | x | x | o | 0.0 | [rad] |
vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | x | x | 0.5 | [s] |
vel_lim | double | limit of velocity | x | x | x | o | o | o | o | o | x | x | 50.0 | [m/s] |
vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | o | x | x | 7.0 | [m/ss] |
steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | o | x | o | 1.0 | [rad] |
steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | o | x | o | 5.0 | [rad/s] |
steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | o | x | o | 0.0 | [rad] |
debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | o | x | x | x | 1.0 | [-] |
debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | o | x | x | x | 1.0 | [-] |
acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | x | o | x | x | - | [-] |
model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | x | o | x | - | [-] |
model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | x | o | x | - | [-] |
model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | x | o | x | - | [-] |
Note: Parameters model_module_paths
, model_param_paths
, and model_class_names
need to have the same length.
The acceleration_map
is used only for DELAY_STEER_MAP_ACC_GEARED
and it shows the acceleration command on the vertical axis and the current velocity on the horizontal axis, with each cell representing the converted acceleration command that is actually used in the simulator’s motion calculation. Values in between are linearly interpolated.
Example of acceleration_map.csv
default, 0.00, 1.39, 2.78, 4.17, 5.56, 6.94, 8.33, 9.72, 11.11, 12.50, 13.89, 15.28, 16.67
-4.0, -4.40, -4.36, -4.38, -4.12, -4.20, -3.94, -3.98, -3.80, -3.77, -3.76, -3.59, -3.50, -3.40
-3.5, -4.00, -3.91, -3.85, -3.64, -3.68, -3.55, -3.42, -3.24, -3.25, -3.00, -3.04, -2.93, -2.80
-3.0, -3.40, -3.37, -3.33, -3.00, -3.00, -2.90, -2.88, -2.65, -2.43, -2.44, -2.43, -2.39, -2.30
-2.5, -2.80, -2.72, -2.72, -2.62, -2.41, -2.43, -2.26, -2.18, -2.11, -2.03, -1.96, -1.91, -1.85
-2.0, -2.30, -2.24, -2.12, -2.02, -1.92, -1.81, -1.67, -1.58, -1.51, -1.49, -1.40, -1.35, -1.30
-1.5, -1.70, -1.61, -1.47, -1.46, -1.40, -1.37, -1.29, -1.24, -1.10, -0.99, -0.83, -0.80, -0.78
-1.0, -1.30, -1.28, -1.10, -1.09, -1.04, -1.02, -0.98, -0.89, -0.82, -0.61, -0.52, -0.54, -0.56
-0.8, -0.96, -0.90, -0.82, -0.74, -0.70, -0.65, -0.63, -0.59, -0.55, -0.44, -0.39, -0.39, -0.35
-0.6, -0.77, -0.71, -0.67, -0.65, -0.58, -0.52, -0.51, -0.50, -0.40, -0.33, -0.30, -0.31, -0.30
-0.4, -0.45, -0.40, -0.45, -0.44, -0.38, -0.35, -0.31, -0.30, -0.26, -0.30, -0.29, -0.31, -0.25
-0.2, -0.24, -0.24, -0.25, -0.22, -0.23, -0.25, -0.27, -0.29, -0.24, -0.22, -0.17, -0.18, -0.12
0.0, 0.00, 0.00, -0.05, -0.05, -0.05, -0.05, -0.08, -0.08, -0.08, -0.08, -0.10, -0.10, -0.10
0.2, 0.16, 0.12, 0.02, 0.02, 0.00, 0.00, -0.05, -0.05, -0.05, -0.05, -0.08, -0.08, -0.08
0.4, 0.38, 0.30, 0.22, 0.25, 0.24, 0.23, 0.20, 0.16, 0.16, 0.14, 0.10, 0.05, 0.05
0.6, 0.52, 0.52, 0.51, 0.49, 0.43, 0.40, 0.35, 0.33, 0.33, 0.33, 0.32, 0.34, 0.34
0.8, 0.82, 0.81, 0.78, 0.68, 0.63, 0.56, 0.53, 0.48, 0.43, 0.41, 0.37, 0.38, 0.40
1.0, 1.00, 1.08, 1.01, 0.88, 0.76, 0.69, 0.66, 0.58, 0.54, 0.49, 0.45, 0.40, 0.40
1.5, 1.52, 1.50, 1.38, 1.26, 1.14, 1.03, 0.91, 0.82, 0.67, 0.61, 0.51, 0.41, 0.41
2.0, 1.80, 1.80, 1.64, 1.43, 1.25, 1.11, 0.96, 0.81, 0.70, 0.59, 0.51, 0.42, 0.42
ACTUATION_CMD model
The simple_planning_simulator usually operates by receiving Control commands, but when the ACTUATION_CMD*
model is selected, it receives Actuation commands instead of Control commands. This model can simulate the motion using the vehicle command that is actually sent to the real vehicle. Therefore, when this model is selected, the raw_vehicle_cmd_converter
is also launched.
Please refer to the actuation_cmd_sim.md for more details.
Note: The steering/velocity/acceleration dynamics is modeled by a first order system with a deadtime in a delay model. The definition of the time constant is the time it takes for the step response to rise up to 63% of its final value. The deadtime is a delay in the response to a control input.
Example of LEARNED_STEER_VEL model
We created a few basic models to showcase how LEARNED_STEER_VEL
works.
-
Install a library that contains basic Python models. (branch:
v0.1_autoware
) -
In a file
src/vehicle/sample_vehicle_launch/sample_vehicle_description/config/simulator_model.param.yaml
setvehicle_model_type
toLEARNED_STEER_VEL
. In the same file set the following parameters. These models are for testing and do not require any parameter file.
model_module_paths:
[
"control_analysis_pipeline.autoware_models.vehicle.kinematic",
"control_analysis_pipeline.autoware_models.steering.steer_example",
"control_analysis_pipeline.autoware_models.drive.drive_example",
]
model_param_paths: ["", "", ""]
model_class_names: ["KinematicModel", "SteerExample", "DriveExample"]
Default TF configuration
Since the vehicle outputs odom
->base_link
tf, this simulator outputs the tf with the same frame_id configuration.
In the simple_planning_simulator.launch.py, the node that outputs the map
->odom
tf, that usually estimated by the localization module (e.g. NDT), will be launched as well. Since the tf output by this simulator module is an ideal value, odom
->map
will always be 0.
(Caveat) Pitch calculation
Ego vehicle pitch angle is calculated in the following manner.
NOTE: driving against the line direction (as depicted in image’s bottom row) is not supported and only shown for illustration purposes.
Error detection and handling
The only validation on inputs being done is testing for a valid vehicle model type.
Security considerations
References / External links
This is originally developed in the Autoware.AI. See the link below.
https://github.com/Autoware-AI/simulation/tree/master/wf_simulator
Future extensions / Unimplemented parts
- Improving the accuracy of vehicle models (e.g., adding steering dead zones and slip behavior)
- Cooperation with modules that output pseudo pointcloud or pseudo perception results
\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^ Changelog for package autoware_simple_planning_simulator \^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^\^
0.43.0 (2025-03-21)
- Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
- chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
- Contributors: Hayato Mizushima, Yutaka Kondo
0.42.0 (2025-03-03)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- feat(autoware_utils): replace autoware_universe_utils with autoware_utils (#10191)
- Contributors: Fumiya Watanabe, 心刚
0.41.2 (2025-02-19)
- chore: bump version to 0.41.1 (#10088)
- Contributors: Ryohsuke Mitsudome
0.41.1 (2025-02-10)
0.41.0 (2025-01-29)
- Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
- feat: apply [autoware_]{.title-ref} prefix for [learning_based_vehicle_model]{.title-ref} (#9991)
- feat: apply [autoware_]{.title-ref} prefix for
[simple_planning_simulator]{.title-ref}
(#9995)
* feat(simple_planning_simulator): apply [autoware_]{.title-ref}
prefix (see below): Note:
* In this commit, I did not organize a folder structure. The folder
structure will be organized in the next some commits.
- The changes will follow the Autoware's guideline as below:
- https://autowarefoundation.github.io/autoware-documentation/main/contributing/coding-guidelines/ros-nodes/directory-structure/#package-folder
- rename(simple_planning_simulator): move headers under `include/autoware`:
- Fixes due to this changes for .hpp/.cpp files will be applied in the next commit
- fix(simple_planning_simulator): fix include header paths
- To follow the previous commit
- rename: [simple_planning_simulator]{.title-ref} => [autoware_simple_planning_simulator]{.title-ref}
- bug(autoware_simple_planning_simulator): fix missing changes
- style(pre-commit): autofix
- bug(autoware_simple_planning_simulator): fix errors in build and tests
- I had to run after [rm -rf install build]{.title-ref}, ... sorry
- style(pre-commit): autofix
- Fixed NOLINT
- Added NOLINT
* Fixed to autoware_simple_planning_simulator ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Shintaro Sakoda <<shintaro.sakoda@tier4.jp>>
- Contributors: Fumiya Watanabe, Junya Sasaki
0.40.0 (2024-12-12)
- Merge branch 'main' into release-0.40.0
- Revert "chore(package.xml): bump version to 0.39.0 (#9587)" This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5.
- fix: fix ticket links in CHANGELOG.rst (#9588)
- chore(package.xml): bump version to 0.39.0
(#9587)
- chore(package.xml): bump version to 0.39.0
- fix: fix ticket links in CHANGELOG.rst
* fix: remove unnecessary diff ---------Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>
- fix: fix ticket links in CHANGELOG.rst (#9588)
- fix(cpplint): include what you use - simulator (#9572)
- fix(simple_planning_simulator): fix clang-diagnostic-delete-non-abstract-non-virtual-dtor (#9448)
- 0.39.0
- update changelog
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- feat(simple_planning_simulator): add mechanical actuaion sim model
(#9300)
* feat(simple_planning_simulator): add mechanical actuaion sim
model update docs
- update from suggestions
* calc internal state using RK4 results ---------
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- Contributors: Esteve Fernandez, Fumiya Watanabe, Kosuke Takeuchi, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, Yutaka Kondo
0.39.0 (2024-11-25)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
- chore(package.xml): bump version to 0.38.0
(#9266)
(#9284)
- unify package.xml version to 0.37.0
- remove system_monitor/CHANGELOG.rst
- add changelog
* 0.38.0
- Contributors: Esteve Fernandez, Yutaka Kondo
0.38.0 (2024-11-08)
- unify package.xml version to 0.37.0
- fix(simple_planning_simulator): change orger of IDX in SimModelDelayS… (#9128)
- fix(simple_planning_simulator, raw_vehicle_cmd_converter): swap row index and column index for csv loader (#8963) swap row and column
- chore(simple_planning_simulator): remove unnecessary lines (#8932) remove unnecessary semicolons
- refactor(autoware_interpolation): prefix package and namespace with autoware (#8088) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- fix(simple_planning_simulator): delete velocity dead band for
brake
(#8685)
- delete dead band
- fix(simple_planning_simulator): increase test_steer_map values (#8631)
- feat(simple_planning_simulator): print actual and expected value in test (#8630)
- fix(simple_planning_simulator): fix dimension (#8629)
- fix(simple_planning_simulator): fix acc output for the model sim_model_delay_steer_acc_geared_wo_fall_guard (#8607) fix acceleration output
- feat(simple_planning_simulator): add VGR sim model
(#8415)
- feat(simple_planning_simulator): add VGR sim model
- Update simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp
- move to interface
* add const ---------
- feat(psim)!: preapre settings to launch localization modules on psim (#8212)
- fix(simple_planning_simulator): fix publised acc of actuation simulator (#8169)
- feat(simple_planning_simulator): add actuation command simulator
(#8065)
* feat(simple_planning_simulator): add actuation command
simulator tmp add
- remove unused functions
- common map
- pre-commit
- update readme
* add test install test dir fix test
- pre-commit
- clean up test for for scalability parameter
* fix typo ---------Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>>
- feat: add [autoware_]{.title-ref} prefix to [lanelet2_extension]{.title-ref} (#7640)
- feat(simple_planning_simulator): add new vehicle model with
falling down
(#7651)
- add new vehicle model
- refactor(universe_utils/motion_utils)!: add autoware namespace (#7594)
- fix(simple_planning_simulator): fix duplicateBranch warnings
(#7574)
- fix(simple_planning_simulator): fix duplicateBranch warnings
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- refactor(motion_utils)!: add autoware prefix and include dir (#7539) refactor(motion_utils): add autoware prefix and include dir
- feat(autoware_universe_utils)!: rename from tier4_autoware_utils (#7538) Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- refactor(vehicle_info_utils)!: prefix package and namespace with
autoware
(#7353)
- chore(autoware_vehicle_info_utils): rename header
- chore(bpp-common): vehicle info
- chore(path_optimizer): vehicle info
- chore(velocity_smoother): vehicle info
- chore(bvp-common): vehicle info
- chore(static_centerline_generator): vehicle info
- chore(obstacle_cruise_planner): vehicle info
- chore(obstacle_velocity_limiter): vehicle info
- chore(mission_planner): vehicle info
- chore(obstacle_stop_planner): vehicle info
- chore(planning_validator): vehicle info
- chore(surround_obstacle_checker): vehicle info
- chore(goal_planner): vehicle info
- chore(start_planner): vehicle info
- chore(control_performance_analysis): vehicle info
- chore(lane_departure_checker): vehicle info
- chore(predicted_path_checker): vehicle info
- chore(vehicle_cmd_gate): vehicle info
- chore(obstacle_collision_checker): vehicle info
- chore(operation_mode_transition_manager): vehicle info
- chore(mpc): vehicle info
- chore(control): vehicle info
- chore(common): vehicle info
- chore(perception): vehicle info
- chore(evaluator): vehicle info
- chore(freespace): vehicle info
- chore(planning): vehicle info
- chore(vehicle): vehicle info
- chore(simulator): vehicle info
- chore(launch): vehicle info
- chore(system): vehicle info
- chore(sensing): vehicle info
* fix(autoware_joy_controller): remove unused deps ---------
- refactor(simple_planning_simulator): remove static odom tf publisher (#7265)
- feat!: replace autoware_auto_msgs with autoware_msgs for simulator modules (#7248) Co-authored-by: Cynthia Liu <<cynthia.liu@autocore.ai>> Co-authored-by: NorahXiong <<norah.xiong@autocore.ai>> Co-authored-by: beginningfan <<beginning.fan@autocore.ai>>
- feat!: remove autoware_auto_tf2 package
(#7218)
- feat!: remove autoware_auto_geometry package
- docs: remove autoware_auto_geometry package from docs
- feat!: remove autoware_auto_tf2 package
* fix: remove from autoware_auto_tf2 packages from docs page ---------
- chore(simple_planning_simulator): add maintainer (#7026)
- chore(simple_planning_simulator): publish control mode before the self-position is given (#7008)
- feat(learned_model): create package (#6395) Co-authored-by: Tomas Nagy <<tomas@pmc.sk>>
- Contributors: Autumn60, Dawid Moszyński, Esteve Fernandez, Go Sakayori, Kosuke Takeuchi, Maxime CLEMENT, Ryohsuke Mitsudome, Ryuta Kambe, Satoshi OTA, Takayuki Murooka, Tomas Nagy, Tomoya Kimura, Yuki TAKAGI, Yutaka Kondo, Zulfaqar Azmi
0.26.0 (2024-04-03)
- feat(simple_planning_simulator): add enable_road_slope_simulation param (#5933)
- fix(log-messages): reduce excessive log messages (#5971)
- fix(simple_planning_simulator): fix steering bias model
(#6240)
- fix(simple_planning_simulator): fix steering bias model
- remove old implementation
- fix initialize order
- fix yawrate measurement
- remove unused code
- add bias to steer rate
- add comments
- fix getWz()
- Update simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_acc.cpp
- Update simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp
* Update simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_vel.cpp ---------Co-authored-by: kosuke55 <<kosuke.tnp@gmail.com>>
- feat(simple_planning_simulator): add option to use initialpose for
z position
(#4256)
- feat(simple_planning_simulator): add option to use initialpose for z position
* Revert "feat(simple_planning_simulator): add option to use initialpose for z position" This reverts commit a3e2779cd38841ba49e063c42fc3a2366c176ad6. * update initial z logic ---------Co-authored-by: Takagi, Isamu <<43976882+isamu-takagi@users.noreply.github.com>>
- fix(autoware_auto_common): move headers to a separate directory
(#5919)
- fix(autoware_auto_common): move headers to a separate directory
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat(simple_planning_simulator): add mesurent_steer_bias
(#5868)
- feat(simple_planning_simulator): add mesurent_steer_bias
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat(simple_plannign_simulator): add map acc model
(#5688)
- (simple_planning_simulator):add delay converter model
* refactoring rename and format read acc map path from config
- update docs
- remove noisy print
- update map
- fix pre-commit
- update acc map
* fix pre-commit and typo typo typo * Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> * Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> * Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> * Update simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.hpp Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>>
- update error message
- simplify map exmaple
- use double
- style(pre-commit): autofix
* Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>>
- add csv loader im sim pacakges
- revert raw vehicle cmd converter
* Update simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> * Update simulator/simple_planning_simulator/include/simple_planning_simulator/utils/csv_loader.hpp Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> * Update simulator/simple_planning_simulator/src/simple_planning_simulator/utils/csv_loader.cpp Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> ---------Co-authored-by: Takumi Ito <<takumi.ito@tier4.jp>> Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- fix(simple_planning_simulator): fix ego sign pitch problem
(#5616)
- fix ego sign pitch problem
- change variable name for clarity
* update documentation to clarify that driving against the lane is not supported ---------
- fix(simple_planning_simulator): change default value of manual gear, DRIVE -> PARK (#5563)
- feat(simple_planning_simulator): add acceleration and steer
command scaling factor for debug
(#5534)
- feat(simple_planning_simulator): add acceleration and steer command scaling factor
* update params as debug ---------
- fix(simple_planning_simulator): set ego pitch to 0 if road slope is not simulated (#5501) set ego pitch to 0 if road slope is not simulated
- feat(simple_planning_simulator): add steer dead band
(#5477)
- feat(simple_planning_simulator): add steer dead band
* Update simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> * Update simulator/simple_planning_simulator/README.md Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> * update params ---------Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>>
- fix(simple_planning_simulator): initialize variables (#5460)
- feat(simple_planning_sim): publish lateral acceleration (#5307)
- fix(simulator, controller): fix inverse pitch calculation (#5199) Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>>
- fix(simple_planning_simulator): fix build error (#5062)
- feat(simple_planning_simulator): consider ego pitch angle for
simulation
(#4941)
- feat(simple_planning_simulator): consider ego pitch angle for simulation
- update
- fix spell
* update
- chore(build): remove tier4_autoware_utils.hpp evaluator/ simulator/ (#4839)
- docs(simple_planning_simulator): rename docs to readme (#4221)
- fix(simple_planning_simulator): old style arg for
static_tf_publisher
(#3736)
- fix(simple_planning_simulator): old style arg for static_tf_publisher
* Update simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>> ---------Co-authored-by: Maxime CLEMENT <<78338830+maxime-clem@users.noreply.github.com>>
- build: proper eigen deps and include
(#3615)
- build: proper eigen deps and include
* style(pre-commit): autofix ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- build: mark autoware_cmake as <buildtool_depend>
(#3616)
* build: mark autoware_cmake as <buildtool_depend> with
<build_depend>, autoware_cmake is automatically exported with
ament_target_dependencies() (unecessary)
- style(pre-commit): autofix
* chore: fix pre-commit errors ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Kenji Miyake <<kenji.miyake@tier4.jp>>
- chore: sync files
(#3227)
- chore: sync files
* style(pre-commit): autofix ---------Co-authored-by: kenji-miyake <<kenji-miyake@users.noreply.github.com>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat(simple_planning_sim): publish sensing interface imu data
(#2843)
- feat(simple_planning_sim): publish sensing interface imu data
* fix covariance index ---------
- chore(planning-sim): change debug topic name (#2610)
- fix(simple_planning_simulator): fix ideal steer acc calc (#2595)
- refactor(simple_planning_simulator): make function for duplicated code (#2502)
- feat(simple_planning_simulator): add initial twist for debug purpose (#2268)
- chore(simple_planning_simulator): add maintainer (#2444) chore(simple_planning_simulator): add maintainer Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>>
- fix(simple_planning_simulator): sim model with gear acc (#2437)
- chore: remove autoware_auto_common dependency from simple_planning_simulator and osqp_interface (#2233) remove autoware_auto_common dependency from simple_planning_simulator, osqp_interface
- chore: remove motion_common dependency
(#2231)
- remove motion_common from smoother
- remove motion_common from control_performance_analysis and simple_planning_simualtor
- fix include
- add include
- refactor!: remove tier4 control mode msg
(#1533)
- [simple_planning_simulator] replace T4 ControlMode msg too auto_msg
- [operation_mode_transition_manager] replace T4 ControlMode msg too auto_msg
- refactor(simple_planning_simulator): refactor covariance index (#1972)
- feat(pose_initializer)!: support ad api
(#1500)
- feat(pose_initializer): support ad api
- docs: update readme
- fix: build error
- fix: test
- fix: auto format
- fix: auto format
- feat(autoware_ad_api_msgs): define localization interface
- feat: update readme
- fix: copyright
- fix: main function
- Add readme of localization message
- feat: modify stop check time
- fix: fix build error
* ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- fix(simple_planning_simulator): fix param file levels (#1612)
- chore(planning/control packages): organized authors and maintainers
(#1610)
- organized planning authors and maintainers
- organized control authors and maintainers
- fix typo
- fix colcon test
* fix Update control/external_cmd_selector/package.xml Update control/vehicle_cmd_gate/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Update planning/motion_velocity_smoother/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Update planning/planning_debug_tools/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Update control/shift_decider/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Update control/pure_pursuit/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Update planning/freespace_planner/package.xml Co-authored-by: Hiroki OTA <<hiroki.ota@tier4.jp>> Update control/operation_mode_transition_manager/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Update planning/planning_debug_tools/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Update control/shift_decider/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Update control/pure_pursuit/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Update control/operation_mode_transition_manager/package.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>>
- fix
* fix Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Co-authored-by: Kenji Miyake <<kenji.miyake@tier4.jp>>
- fix(simple_planning_simulator): fix timer type (#1538)
- feat(operation_mode_transition_manager): add package to manage
vehicle autonomous mode change
(#1246)
- add engage_transition_manager
- rename to operation mode transition manager
- fix precommit
- fix cpplint
- fix topic name & vehicle_info
- update launch
- update default param
- add allow_autonomous_in_stopped
- fix typo
- fix precommit
- feat(simple_planning_simulator): add acceleration publisher
(#1214)
- feat(simple_planning_simulator): add acceleration publisher
- add cov
- feat(simple_planning_simulator): add control_mode server
(#1061)
- add control-mode in simulator
- precommit
- update
- update readme
- update simulator
- fix typo
- fix(simple_planning_simlator): keep alive tf
(#1175)
- fix(simple_planning_simlator): keep alive tf
* ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- docs(simulator): fixed simple_planning_simulator table (#1025)
- docs: update link style and fix typos
(#950)
- feat(state_rviz_plugin): add GateMode and PathChangeApproval Button (#894)
- feat(state_rviz_plugin): add GateMode and PathChangeApproval Button
* ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- docs: update link style
- chore: fix link
- feat(map_tf_generator): accelerate the 'viewer' coordinate calculation (#890)
* add random point sampling function to quickly calculate the 'viewer' coordinate Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>>
- docs(obstacle_stop_planner): update documentation (#880)
- docs(tier4_traffic_light_rviz_plugin): update documentation (#905)
- fix(accel_brake_map_calibrator): rviz panel type (#895)
- fixed panel type
- modified instruction for rosbag replay case
- modified update_map_dir service name
- fix(behavior velocity planner): skipping emplace back stop reason if it is empty (#898)
- skipping emplace back stop reason if it is empty
- add braces
* ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Takagi, Isamu <<43976882+isamu-takagi@users.noreply.github.com>>
- feat(behavior_path_planner): weakened noise filtering of drivable area (#838)
- feat(behavior_path_planner): Weakened noise filtering of drivable area
- fix lanelet's longitudinal disconnection
- add comments of erode/dilate process
- refactor(vehicle-cmd-gate): using namespace for msgs (#913)
- refactor(vehicle-cmd-gate): using namespace for msgs
- for clang
* feat(pose_initializer): introduce an array copy function (#900) Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat: add lidar point filter when debug (#865)
- feat: add lidar point filter when debug
* ci(pre-commit): autofix Co-authored-by: suchang <<chang.su@autocore.ai>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat(component_interface_utils): add interface classes (#899)
- feat(component_interface_utils): add interface classes
- feat(default_ad_api): apply the changes of interface utils
- fix(component_interface_utils): remove old comment
- fix(component_interface_utils): add client log
- fix(component_interface_utils): remove unimplemented message
- docs(component_interface_utils): add design policy
- docs(component_interface_utils): add comment
* refactor(vehicle_cmd_gate): change namespace in launch file (#927) Co-authored-by: Berkay <<berkay@leodrive.ai>>
- feat: visualize lane boundaries (#923)
- feat: visualize lane boundaries
- fix: start_bound
* ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- fix(system_monitor): fix truncation warning in strncpy (#872)
- fix(system_monitor): fix truncation warning in strncpy
- Use std::string constructor to copy char array
- Fixed typo
- fix(behavior_velocity_planner.stopline): extend following and previous search range to avoid no collision (#917)
- fix: extend following and previous search range to avoid no collision
- chore: add debug marker
- fix: simplify logic
- chore: update debug code
- fix: delete space
- fix: some fix
- ci(pre-commit): autofix
* fix: delete debug code Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- docs(surround obstacle checker): update documentation (#878)
- docs(surround_obstacle_checker): update pub/sub topics & params
- docs(surround_obstacle_checker): remove unused files
- docs(surround_obstacke_checker): update purpose
- feat(tier4_autoware_utils): add vehicle state checker (#896)
- feat(tier4_autoware_utils): add vehicle state checker
- fix(tier4_autoware_utils): use absolute value
- feat(tier4_autoware_utils): divide into two classies
- test(tier4_autoware_utils): add unit test for vehicle_state checker
- fix(tier4_autoware_utils): impl class inheritance
- docs(tier4_autoware_utils): add vehicle_state_checker document
- fix(tier4_autoware_utils): into same loop
- fix(tier4_autoware_utils): fix variables name
- fix(tier4_autoware_utils): remove redundant codes
- fix(motion_velocity_smoother): fix overwriteStopPoint using backward point (#816)
- fix(motion_velocity_smoother): fix overwriteStopPoint using backward point
- Modify overwriteStopPoint input and output
- feat(obstacle_avoidance_planner): explicitly insert zero velocity (#906)
- feat(obstacle_avoidance_planner) fix bug of stop line unalignment
- fix bug of unsorted output points
- move calcVelocity in node.cpp
- fix build error
- feat(behavior_velocity): find occlusion more efficiently (#829)
- fix(system_monitor): add some smart information to diagnostics (#708)
- feat(obstacle_avoidance_planner): dealt with close lane change (#921)
- feat(obstacle_avoidance_planner): dealt with close lane change
- fix bug of right lane change
- feat(obstacle_avoidance_planner): some fix for narrow driving (#916)
- use car like constraints in mpt
- use not widest bounds for the first bounds
- organized params
- fix format
- prepare rear_drive and uniform_circle constraints
- fix param callback
- update config
- remove unnecessary files
- update tier4_planning_launch params
- chore(obstacle_avoidance_planner): removed obsolete obstacle_avoidance_planner doc in Japanese (#919)
- chore(behavior_velocity_planner.stopline): add debug marker for stopline collision check (#932)
- chore(behavior_velocity_planner.stopline): add debug marker for stopline collision check
- feat: use marker helper
- feat(map_loader): visualize center line by points (#931)
- feat: visualize center line points
- fix: delete space
- feat: visualize center line by arrow
- revert insertMarkerArray
- fix: delete space
- feat: add RTC interface (#765)
- feature(rtc_interface): add files
- feature(rtc_interface): implement functions
- feature(rtc_interface): reimprement functions to use CooperateCommands and write README.md
- feature(rtc_interface): fix README
- feature(rtc_interface): add getModuleType()
- feature(rtc_interface): fix definition of constructor
- feature(rtc_interface): fix time stamp
- feature(rtc_interface): fix README
- feature(rtc_interface): add isRegistered and clearCooperateStatus
* ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> * chore: sync files (#911) Co-authored-by: kenji-miyake <<kenji-miyake@users.noreply.github.com>>
- fix: replace boost::mutex::scoped_lock to std::scoped_lock (#907)
- fix: replace boost::mutex::scoped_lock to std::scoped_lock
- fix: replace boost::mutex to std::mutex
- feat(tensorrt_yolo): add multi gpu support to tensorrt_yolo node (#885)
- feat(tensorrt_yolo): add multi gpu support to tensorrt_yolo node
* feat(tensorrt_yolo): update arg Co-authored-by: Kaan Colak <<kcolak@leodrive.ai>>
- feat(tier4_planning_launch): create parameter yaml for behavior_velocity_planner (#887)
- feat(tier4_planning_launch): create parameter yaml for behavior_velocity_planner
* Update launch/tier4_planning_launch/config/scenario_planning/lane_driving/behavior_planning/behavior_velocity_planner/behavior_velocity_planner.param.yaml Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>>
- feat: add param.yaml in behavior_velocity_planner package
* some fix Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>>
- fix(map_loader): use std::filesystem to load pcd files in pointcloud_map_loader (#942)
- fix(map_loader): use std::filesystem to load pcd files in pointcloud_map_loader
- fix(map_loader): remove c_str
- fix(map_loader): replace c_str to string
- fix: relative link
- fix: relative links
- fix: relative links
- fix: relative links
- fix: typo
- fix relative links
- docs: ignore rare unknown words
- ci(pre-commit): autofix
- docs: ignore unknown words one by one
* ci(pre-commit): autofix Co-authored-by: Hiroki OTA <<hiroki.ota@tier4.jp>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Takeshi Ishita <<ishitah.takeshi@gmail.com>> Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Co-authored-by: Satoshi OTA <<44889564+satoshi-ota@users.noreply.github.com>> Co-authored-by: Mamoru Sobue <<hilo.soblin@gmail.com>> Co-authored-by: TakumiKozaka-T4 <<70260442+TakumiKozaka-T4@users.noreply.github.com>> Co-authored-by: Takagi, Isamu <<43976882+isamu-takagi@users.noreply.github.com>> Co-authored-by: Takayuki Murooka <<takayuki5168@gmail.com>> Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> Co-authored-by: storrrrrrrrm <<103425473+storrrrrrrrm@users.noreply.github.com>> Co-authored-by: suchang <<chang.su@autocore.ai>> Co-authored-by: Berkay <<brkay54@gmail.com>> Co-authored-by: Berkay <<berkay@leodrive.ai>> Co-authored-by: ito-san <<57388357+ito-san@users.noreply.github.com>> Co-authored-by: Kosuke Takeuchi <<kosuke.tnp@gmail.com>> Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>> Co-authored-by: kk-inoue-esol <<76925382+kk-inoue-esol@users.noreply.github.com>> Co-authored-by: Fumiya Watanabe <<rej55.g@gmail.com>> Co-authored-by: awf-autoware-bot[bot] <94889083+awf-autoware-bot[bot]\@users.noreply.github.com> Co-authored-by: kenji-miyake <<kenji-miyake@users.noreply.github.com>> Co-authored-by: RyuYamamoto <<ryu.yamamoto@tier4.jp>> Co-authored-by: Kaan Çolak <<kaancolak95@gmail.com>> Co-authored-by: Kaan Colak <<kcolak@leodrive.ai>> Co-authored-by: Kenji Miyake <<kenji.miyake@tier4.jp>>
- feat(vehicle_info_util): add max_steer_angle
(#740)
- feat(vehicle_info_util): add max_steer_angle
- applied pre-commit
* Added max_steer_angle in test config Co-authored-by: Tomoya Kimura <<tomoya.kimura@tier4.jp>>
- feat: isolate gtests in all packages (#693)
- chore: upgrade cmake_minimum_required to 3.14 (#856)
- refactor: simplify Rolling support (#854)
- refactor: use autoware cmake
(#849)
- remove autoware_auto_cmake
- add build_depend of autoware_cmake
- use autoware_cmake in CMakeLists.txt
- fix bugs
- fix cmake lint errors
- chore: remove bad chars (#845)
- fix: suppress compiler warnings (#852)
- style: fix format of package.xml (#844)
- fix(autoware_auto_tf2): modify build error in rolling
(#718)
- fix(autoware_auto_common): modify build error in rolling
- fix(autoware_auto_tf2): modify build error in rolling
- fix(autoware_auto_geometry): modify build error in rolling
- fix(simple_planning_simulator): add compile definition for geometry2
- fix(motion_common): add compile definition for geometry2
- fix(motion_testing): add compile definition for geometry2
- fix(simple_planning_simulator): modify build error in rolling
* ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- ci(pre-commit): clear the exclude option
(#426)
- ci(pre-commit): remove unnecessary excludes
- ci(pre-commit): autofix
- ci(pre-commit): autofix
- address pre-commit for Markdown files
- fix Python imports
- address cpplint errors
- fix broken package.xml
- rename ROS parameter files
- fix build
* use autoware_lint_common Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- fix(simple_planning_simulator): fix bug in function to apply noise (#665)
- test(simple_planning_simulator): add node test
(#422)
- test(simple_planning_simulator): add node test
- use TEST_P
- fix(simple psim): gear bug to update state in simple psim
(#370)
- fix(simple psim): gear bug to update state in simple psim
- upadte ideal acc geared model as well
- fix: simple psim with vehicle engage
(#301)
- feat: add initial_engage_state for /vehicle/engage sub result
- feat: simulating only when vehicle engage is true
- feat(simple_planning_simulator): add delay model of velocity and
steering
(#235)
- add delay steer vel in psim
- change wz to steer
- fix param description
- modify readme
- modify cmake
- ci: change file URL
* fix: order to create callback (#220) Co-authored-by: Takeshi Miura <<57553950+1222-takeshi@users.noreply.github.com>>
- chore: remove unnecessary depends (#227)
- ci: add check-build-depends.yaml
- chore: simplify build_depends.repos
- chore: remove exec_depend
- chore: use register-autonomoustuff-repository
- chore: add setup tasks to other workflows
- ci: update .yamllint.yaml (#229)
- ci: update .yamllint.yaml
- chore: fix for yamllint
- fix: remove warning for compile error (#198)
- fix: fix compile error of pointcloud preprocessor
- fix: fix compiler warning for had map utils
- fix: fix compiler warning for behavior velocity planner
- fix: fix compiler warning for compare map segmentation
- fix: fix compiler warning for occupancy grid map outlier filter
- fix: fix compiler warning for detection by tracker
- fix: restore comment
- fix: set control_mode false before autoware engage (#232)
- fix: set control_mode false before autoware engage
- add input/engage remap in launch
* fix: library path (#225) Co-authored-by: taikitanaka3 <<taiki.tanaka@tier4.jp>> * fix: interpolation (#791) (#218) Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>>
- add missing function definition in .cpp
- set input and state for DELAY_STEER_VEL model
* fix: fix typo Co-authored-by: Kenji Miyake <<kenji.miyake@tier4.jp>> Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>> Co-authored-by: Takeshi Miura <<57553950+1222-takeshi@users.noreply.github.com>> Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Co-authored-by: Daisuke Nishimatsu <<42202095+wep21@users.noreply.github.com>> Co-authored-by: Takayuki Murooka <<takayuki5168@gmail.com>> Co-authored-by: taikitanaka3 <<taiki.tanaka@tier4.jp>> Co-authored-by: Tomoya Kimura <<tomoya.kimura@tier4.jp>>
- fix: set control_mode false before autoware engage
(#232)
- fix: set control_mode false before autoware engage
- add input/engage remap in launch
- feat: replace VehicleStateCommand with GearCommand (#217) Co-authored-by: Tomoya Kimura <<tomoya.kimura@tier4.jp>>
- fix: fix typo and url
(#201)
- fix typo
* fix url (jp -> en) Co-authored-by: Takeshi Miura <<57553950+1222-takeshi@users.noreply.github.com>>
- feat: rename existing packages name starting with autoware to
different names
(#180)
- autoware_api_utils -> tier4_api_utils
- autoware_debug_tools -> tier4_debug_tools
- autoware_error_monitor -> system_error_monitor
- autoware_utils -> tier4_autoware_utils
- autoware_global_parameter_loader -> global_parameter_loader
- autoware_iv_auto_msgs_converter -> tier4_auto_msgs_converter
- autoware_joy_controller -> joy_controller
- autoware_error_monitor -> system_error_monitor(launch)
- autoware_state_monitor -> ad_service_state_monitor
- autoware_web_controller -> web_controller
- remove autoware_version
- remove autoware_rosbag_recorder
- autoware__rviz_plugin -> tier4__rviz_plugin
- fix ad_service_state_monitor
* ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- fix: update simple planning simulator param file (#179) Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>>
- feat: add simulator_launch package
(#166)
- Add simulator_launch package (#459)
- Add simulator_launch package
- add argument
- fix depend order
- add argument
- move dummy_perception_publisher
- add arg for dummy_perception_publisher
* Update simulator_launch/launch/simulator.launch.xml Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>>
- Move simple_planning_simulator to simulator_launch (#462)
- move simple_planning_simulator
- add simulation arg to logging_simulator.launch
- delete unused argument
- add arguments for logging simulation
- change default value
- update README
- add default value to simulator arg
- restore vehicle_simulation arg
- Fix/revert initial engage state (#484)
- Fix args
- Add initial_engage_state to vehicle.launch.xml
- Update vehicle.launch.xml
- 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
- Auto/fix launch (#110)
- fix namespace
- remove dynamic_object_visualization
- fix rviz
- add default vehicle param file
- ci(pre-commit): autofix
* fix typo Co-authored-by: Keisuke Shima <<19993104+KeisukeShima@users.noreply.github.com>> Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Co-authored-by: Kenji Miyake <<kenji.miyake@tier4.jp>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>>
- feat: load vehicle info default param
(#148)
- update global_parameter loader readme
- remove unused dependency
- add default vehicle_info_param to launch files
- fix: import os
* Update simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py Co-authored-by: Takeshi Miura <<57553950+1222-takeshi@users.noreply.github.com>> * Update perception/ground_segmentation/launch/scan_ground_filter.launch.py Co-authored-by: Takeshi Miura <<57553950+1222-takeshi@users.noreply.github.com>>
- fix dependency
- fix scan_ground_filter.launch
* ci(pre-commit): autofix Co-authored-by: Takeshi Miura <<57553950+1222-takeshi@users.noreply.github.com>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- feat: change pachage name: autoware_msgs -> tier4_msgs
(#150)
- change pkg name: autoware__msgs -> tier__msgs
- ci(pre-commit): autofix
- autoware_external_api_msgs -> tier4_external_api_msgs
- ci(pre-commit): autofix
* fix description Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com> Co-authored-by: Takeshi Miura <<57553950+1222-takeshi@users.noreply.github.com>>
- feat: add simple planning simulator package
(#5)
- release v0.4.0
- remove ROS1 packages temporarily
- add sample ros2 packages
- add COLCON_IGNORE to ros1 packages
- Fix simple planning simulator (#26)
- simple planning simulator: fix params & launch file
- remove unused file
- fix timercallback
- [simple_planning_simulator] add rostopic relay in launch file (#117)
- [simple_planning_simulator] add rostopic relay in launch file
- add topic_tools as exec_depend
- Adjust copyright notice on 532 out of 699 source files (#143)
- Use quotes for includes where appropriate (#144)
- Use quotes for includes where appropriate
- Fix lint tests
- Make tests pass hopefully
- Run uncrustify on the entire Pilot.Auto codebase (#151)
- Run uncrustify on the entire Pilot.Auto codebase
- Exclude open PRs
- reduce terminal ouput for better error message visibility (#200)
- reduce terminal ouput for better error message visibility
- [costmap_generator] fix waiting for first transform
- fix tests
- fix test
- Use trajectory for z position source (#243)
- Ros2 v0.8.0 engage (#342)
- [autoware_vehicle_msgs]: Add engage message
- [as]: Update message
- [awapi_awiv_adapter]: Update message
- [web_controller]: Update message
- [vehicle_cmd_gate]: Update message
- [autoware_state_monitor]: Update message
- [autoware_control_msgs]: Remove EngageMode message
- [simple_planning_simulator]: Update message
- Ros2 v0.8.0 fix packages (#351)
- add subscription to QoS
- add vihicle_param _file to simple_planning_sim
- update cmake/packages.xml
- comment out unused parameter
- apply lint
- add vehicle_info_util to lane_change_planner
- add vehicle_info_util to vehicle_cmd_gate
- fix cmake of simple planning simulator
- update cmake/packages.xml of vehicle cmd gate
- apply lint
- apply lint
- add latch option to autoware_state_monitor
- delete unused comment
- Rename ROS-related .yaml to .param.yaml (#352)
- Rename ROS-related .yaml to .param.yaml
- Remove prefix 'default_' of yaml files
- Rename vehicle_info.yaml to vehicle_info.param.yaml
- Rename diagnostic_aggregator's param files
- Fix overlooked parameters
- Fix typo in simulator module (#439)
- add use_sim-time option (#454)
- Format launch files (#1219)
- Fix rolling build errors (#1225)
- Add missing include files
- Replace rclcpp::Duration
- Use reference for exceptions
- Use from_seconds
- Sync public repo (#1228)
- [simple_planning_simulator] add readme (#424)
- add readme of simple_planning_simulator
- Update simulator/simple_planning_simulator/README.md
- set transit_margin_time to intersect. planner (#460)
- Fix pose2twist (#462)
- Ros2 vehicle info param server (#447)
- add vehicle_info_param_server
- update vehicle info
- apply format
- fix bug
- skip unnecessary search
- delete vehicle param file
- fix bug
- Ros2 fix topic name part2 (#425)
- Fix topic name of traffic_light_classifier
- Fix topic name of traffic_light_visualization
- Fix topic name of traffic_light_ssd_fine_detector
- Fix topic name of traffic_light_map_based_detector
- Fix lint traffic_light_recognition
- Fix lint traffic_light_ssd_fine_detector
- Fix lint traffic_light_classifier
- Fix lint traffic_light_classifier
- Fix lint traffic_light_ssd_fine_detector
- Fix issues in hdd_reader (#466)
- Fix some issues detected by Coverity Scan and Clang-Tidy
- Update launch command
- Add more [close(new_sock)]{.title-ref}
- Simplify the definitions of struct
- fix: re-construct laneletMapLayer for reindex RTree (#463)
- Rviz overlay render fix (#461)
- Moved painiting in SteeringAngle plugin to update()
- super class now back to MFD
- uncrustified
- acquire data in mutex
- back to RTD as superclass
- Rviz overlay render in update (#465)
- Moved painiting in SteeringAngle plugin to update()
- super class now back to MFD
- uncrustified
- acquire data in mutex
- removed unnecessary includes and some dead code
- Adepted remaining vehicle plugin classes to render-in-update concept. Returned to MFD superclass
* restored RTD superclass Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> Co-authored-by: tkimura4 <<tomoya.kimura@tier4.jp>> Co-authored-by: Takagi, Isamu <<43976882+isamu-takagi@users.noreply.github.com>> Co-authored-by: Kazuki Miyahara <<kmiya@outlook.com>> Co-authored-by: Makoto Tokunaga <<vios-fish@users.noreply.github.com>> Co-authored-by: Adam Dąbrowski <<adam.dabrowski@robotec.ai>>
- Remove use_sim_time for set_parameter (#1260)
- Refactor vehicle info util (#1305)
- Update license
- Refactor vehicle_info_util
- Rename and split files
- Fix interfaces
- Fix bug and add error handling
- Add "// namespace"
- Add missing include
- Fix lint errors (#1378)
- Fix lint errors
- Fix variable names
- Add pre-commit (#1560)
- add pre-commit
- add pre-commit-config
- add additional settings for private repository
- use default pre-commit-config
- update pre-commit setting
- Ignore whitespace for line breaks in markdown
* Update .github/workflows/pre-commit.yml Co-authored-by: Kazuki Miyahara <<kmiya@outlook.com>>
- exclude svg
- remove pretty-format-json
- add double-quote-string-fixer
- consider COLCON_IGNORE file when seaching modified package
- format file
- pre-commit fixes
- Update pre-commit.yml
* Update .pre-commit-config.yaml Co-authored-by: Kazuki Miyahara <<kmiya@outlook.com>> Co-authored-by: pre-commit <<pre-commit@example.com>> Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>>
- Add markdownlint and prettier (#1661)
- Add markdownlint and prettier
- Ignore .param.yaml
- Apply format
- add cov pub in psim (#1732)
- Fix -Wunused-parameter (#1836)
- Fix -Wunused-parameter
- Fix mistake
- fix spell
- Fix lint issues
* Ignore flake8 warnings Co-authored-by: Hiroki OTA <<hiroki.ota@tier4.jp>>
- fix some typos (#1941)
- fix some typos
- fix typo
* Fix typo Co-authored-by: Kenji Miyake <<kenji.miyake@tier4.jp>>
- Add autoware api (#1979)
- add sort-package-xml hook in pre-commit (#1881)
- add sort xml hook in pre-commit
- change retval to exit_status
- rename
- add prettier plugin-xml
- use early return
- add license note
- add tier4 license
- restore prettier
- change license order
- move local hooks to public repo
- move prettier-xml to pre-commit-hooks-ros
- update version for bug-fix
- apply pre-commit
- Feature/add ideal accel model interface (#1894)
- Add IDEAL_ACCEL model interface for simple planning simulator
- Add IDEAL_ACCEL model descriptions
- Fix format
- Change vehicle model type description at config file
- Change formatter to clang-format and black (#2332)
* Revert "Temporarily comment out pre-commit hooks" This reverts commit 748e9cdb145ce12f8b520bcbd97f5ff899fc28a3.
- Replace ament_lint_common with autoware_lint_common
- Remove ament_cmake_uncrustify and ament_clang_format
- Apply Black
- Apply clang-format
- Fix build errors
- Fix for cpplint
- Fix include double quotes to angle brackets
- Apply clang-format
- Fix build errors
- Add COLCON_IGNORE (#500)
- Back port .auto control packages (#571)
- Implement Lateral and Longitudinal Control Muxer
- [#570] Porting wf_simulator
- [#1189] Deactivate flaky test in 'trajectory_follower_nodes'
- [#1189] Fix flacky test in 'trajectory_follower_nodes/latlon_muxer'
- [#1057] Add osqp_interface package
- [#1057] Add library code for MPC-based lateral control
- [#1271] Use std::abs instead of abs
- [#1057] Implement Lateral Controller for Cargo ODD
- [#1246] Resolve "Test case names currently use snake_case but should be CamelCase"
- [#1325] Deactivate flaky smoke test in 'trajectory_follower_nodes'
- [#1058] Add library code of longitudinal controller
- Fix build error for trajectory follower
- Fix build error for trajectory follower nodes
- [#1272] Add AckermannControlCommand support to simple_planning_simulator
- [#1058] Add Longitudinal Controller node
- [#1058] Rename velocity_controller -> longitudinal_controller
- [#1058] Update CMakeLists.txt for the longitudinal_controller_node
- [#1058] Add smoke test python launch file
- [#1058] Use LowPassFilter1d from trajectory_follower
- [#1058] Use autoware_auto_msgs
- [#1058] Changes for .auto (debug msg tmp fix, common func, tf listener)
- [#1058] Remove unused parameters
- [#1058] Fix ros test
- [#1058] Rm default params from declare_parameters + use autoware types
- [#1058] Use default param file to setup NodeOptions in the ros test
- [#1058] Fix docstring
- [#1058] Replace receiving a Twist with a VehicleKinematicState
- [#1058] Change class variables format to m_ prefix
- [#1058] Fix plugin name of LongitudinalController in CMakeLists.txt
- [#1058] Fix copyright dates
- [#1058] Reorder includes
- [#1058] Add some tests (~89% coverage without disabling flaky tests)
- [#1058] Add more tests (90+% coverage without disabling flaky tests)
- [#1058] Use Float32MultiArrayDiagnostic message for debug and slope
- [#1058] Calculate wheel_base value from vehicle parameters
- [#1058] Cleanup redundant logger setting in tests
- [#1058] Set ROS_DOMAIN_ID when running tests to prevent CI failures
- [#1058] Remove TF listener and use published vehicle state instead
- [#1058] Change smoke tests to use autoware_testing
- [#1058] Add plotjuggler cfg for both lateral and longitudinal control
- [#1058] Improve design documents
- [#1058] Disable flaky test
- [#1058] Properly transform vehicle state in longitudinal node
- [#1058] Fix TF buffer of lateral controller
- [#1058] Tuning of lateral controller for LGSVL
- [#1058] Fix formating
- [#1058] Fix /tf_static sub to be transient_local
- [#1058] Fix yaw recalculation of reverse trajs in the lateral controller
- modify trajectory_follower for galactic build
- [#1379] Update trajectory_follower
- [#1379] Update simple_planning_simulator
- [#1379] Update trajectory_follower_nodes
- apply trajectory msg modification in control
- move directory
- remote control/trajectory_follower level dorectpry
- remove .iv trajectory follower
- use .auto trajectory_follower
- remove .iv simple_planning_simulator & osqp_interface
- use .iv simple_planning_simulator & osqp_interface
- add tmp_autoware_auto_dependencies
- tmporally add autoware_auto_msgs
- apply .auto message split
- fix build depend
- fix packages using osqp
- fix autoware_auto_geometry
- ignore lint of some packages
- ignore ament_lint of some packages
- ignore lint/pre-commit of trajectory_follower_nodes
* disable unit tests of some packages Co-authored-by: Maxime CLEMENT <<maxime.clement@tier4.jp>> Co-authored-by: Joshua Whitley <<josh.whitley@autoware.org>> Co-authored-by: Igor Bogoslavskyi <<igor.bogoslavskyi@gmail.com>> Co-authored-by: MIURA Yasuyuki <<kokosabu@gmail.com>> Co-authored-by: wep21 <<border_goldenmarket@yahoo.co.jp>> Co-authored-by: tomoya.kimura <<tomoya.kimura@tier4.jp>>
- [simple planning simulator]change type of msg (#590)
- remove kinematic_state
- remove vehicle_state_command/report
- get z-position from trajectory
- set topic name of trajectory
- twist -> velocity report
- change default param
* Update simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>> * Update simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>> * fix typo Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>>
- [autoware_vehicle_rviz_plugin/route_handler/simple_planning_simulator]fix some packages (#606)
- fix console meter
- fix velocity_history
- fix route handler
- change topic name
- update to support velocity report header (#655)
- update to support velocity report header
* Update simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp Co-authored-by: tkimura4 <<tomoya.kimura@tier4.jp>>
- use maybe_unused
* fix precommit Co-authored-by: tkimura4 <<tomoya.kimura@tier4.jp>>
- adapt to actuation cmd/status as control msg (#646)
- adapt to actuation cmd/status as control msg
- fix readme
- fix topics
- fix remaing topics
- as to pacmod interface
- fix vehicle status
- add header to twist
- revert gyro_odometer_change
- revert twist topic change
- revert unchanged package
- FIx vehicle status topic name/type (#658)
- shift -> gear_status
- twist -> velocity_status
- fix topic name (#674)
- fix topic name
- fix gear message name
- Fix psim param path (#696)
- Fix/psim topics emergency handler awapi (#702)
- fix emergency handler
- fix awapi
- remove unused topic
- remove duplecated vehicle cmd
- Auto/add turn indicators and hazards (#717)
- add turn indicators
- add hazard light
- omit name space
- remap topic name
- delete unnecessary blank line
- [simple_planning_simulator]fix bug (#727)
- input z-axis of trajectory to pose(tf/odometry)
- output 0 velocity when invalid gear is input
- fix gear process in sim (#728)
- Fix for integration test (#732)
- Add backward compatibility of autoware state
- Add simulator initial pose service
- Fix pre-commit
- Fix pre-commit
- Simple planning simulator update for latest develop (#735)
- Refactor vehicle info util (#1305)
- add cov pub in psim (#1732)
- remove pose_with_covariance publisher and add covariance information in Odometry
- Fix acceleration for reverse (#737)
- Fix acceleration for reverse
- Fix acceleration in set_input
- remove unused using
- Fix code
- ci(pre-commit): autofix
* remove tests Co-authored-by: mitsudome-r <<ryohsuke.mitsudome@tier4.jp>> Co-authored-by: Takamasa Horibe <<horibe.takamasa@gmail.com>> Co-authored-by: Ryohsuke Mitsudome <<43976834+mitsudome-r@users.noreply.github.com>> Co-authored-by: Nikolai Morin <<nnmmgit@gmail.com>> Co-authored-by: Daisuke Nishimatsu <<42202095+wep21@users.noreply.github.com>> Co-authored-by: Kenji Miyake <<31987104+kenji-miyake@users.noreply.github.com>> Co-authored-by: Kazuki Miyahara <<kmiya@outlook.com>> Co-authored-by: Takagi, Isamu <<43976882+isamu-takagi@users.noreply.github.com>> Co-authored-by: Makoto Tokunaga <<vios-fish@users.noreply.github.com>> Co-authored-by: Adam Dąbrowski <<adam.dabrowski@robotec.ai>> Co-authored-by: Keisuke Shima <<19993104+KeisukeShima@users.noreply.github.com>> Co-authored-by: pre-commit <<pre-commit@example.com>> Co-authored-by: Kosuke Murakami <<kosuke.murakami@tier4.jp>> Co-authored-by: Hiroki OTA <<hiroki.ota@tier4.jp>> Co-authored-by: Kenji Miyake <<kenji.miyake@tier4.jp>> Co-authored-by: Makoto Kurihara <<mkuri8m@gmail.com>> Co-authored-by: Maxime CLEMENT <<maxime.clement@tier4.jp>> Co-authored-by: Joshua Whitley <<josh.whitley@autoware.org>> Co-authored-by: Igor Bogoslavskyi <<igor.bogoslavskyi@gmail.com>> Co-authored-by: MIURA Yasuyuki <<kokosabu@gmail.com>> Co-authored-by: wep21 <<border_goldenmarket@yahoo.co.jp>> Co-authored-by: taikitanaka3 <<65527974+taikitanaka3@users.noreply.github.com>> Co-authored-by: Sugatyon <<32741405+Sugatyon@users.noreply.github.com>> Co-authored-by: Fumiya Watanabe <<rej55.g@gmail.com>> Co-authored-by: Takeshi Miura <<57553950+1222-takeshi@users.noreply.github.com>> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>
- Contributors: Ahmed Ebrahim, Daisuke Nishimatsu, Esteve Fernandez, Haoru Xue, Hiroki OTA, Kenji Miyake, Kosuke Takeuchi, Mamoru Sobue, Maxime CLEMENT, Satoshi OTA, Satoshi Tanaka, Shumpei Wakabayashi, Takagi, Isamu, Takamasa Horibe, Takayuki Murooka, Tomoya Kimura, Vincent Richard, Yukihiro Saito, awf-autoware-bot[bot], danielsanchezaran, kyoichi-sugahara, taikitanaka3
Wiki Tutorials
Package Dependencies
System Dependencies
Dependant Packages
Name | Deps |
---|---|
tier4_simulator_launch |