Skip to content

Commit

Permalink
chore: format
Browse files Browse the repository at this point in the history
  • Loading branch information
HansRobo committed Feb 20, 2024
1 parent 1bbc486 commit 881fc3a
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,9 @@ class EgoEntitySimulation

auto getLinearJerk(double step_time) -> double;

auto getMatchedLaneletPoseFromEntityStatus(const traffic_simulator_msgs::msg::EntityStatus & status, const double entity_width) const -> std::optional<traffic_simulator_msgs::msg::LaneletPose>;
auto getMatchedLaneletPoseFromEntityStatus(
const traffic_simulator_msgs::msg::EntityStatus & status, const double entity_width) const
-> std::optional<traffic_simulator_msgs::msg::LaneletPose>;

auto updatePreviousValues() -> void;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -137,23 +137,23 @@ def description():

return [
# fmt: off
DeclareLaunchArgument("architecture_type", default_value=architecture_type ),
DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file ),
DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package),
DeclareLaunchArgument("architecture_type", default_value=architecture_type ),
DeclareLaunchArgument("autoware_launch_file", default_value=autoware_launch_file ),
DeclareLaunchArgument("autoware_launch_package", default_value=autoware_launch_package ),
DeclareLaunchArgument("consider_acceleration_by_road_slope", default_value=consider_acceleration_by_road_slope),
DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate ),
DeclareLaunchArgument("global_real_time_factor", default_value=global_real_time_factor),
DeclareLaunchArgument("global_timeout", default_value=global_timeout ),
DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ),
DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ),
DeclareLaunchArgument("output_directory", default_value=output_directory ),
DeclareLaunchArgument("rviz_config", default_value=rviz_config ),
DeclareLaunchArgument("scenario", default_value=scenario ),
DeclareLaunchArgument("sensor_model", default_value=sensor_model ),
DeclareLaunchArgument("sigterm_timeout", default_value=sigterm_timeout ),
DeclareLaunchArgument("use_sim_time", default_value=use_sim_time ),
DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ),
DeclareLaunchArgument("workflow", default_value=workflow ),
DeclareLaunchArgument("global_frame_rate", default_value=global_frame_rate ),
DeclareLaunchArgument("global_real_time_factor", default_value=global_real_time_factor ),
DeclareLaunchArgument("global_timeout", default_value=global_timeout ),
DeclareLaunchArgument("launch_autoware", default_value=launch_autoware ),
DeclareLaunchArgument("launch_rviz", default_value=launch_rviz ),
DeclareLaunchArgument("output_directory", default_value=output_directory ),
DeclareLaunchArgument("rviz_config", default_value=rviz_config ),
DeclareLaunchArgument("scenario", default_value=scenario ),
DeclareLaunchArgument("sensor_model", default_value=sensor_model ),
DeclareLaunchArgument("sigterm_timeout", default_value=sigterm_timeout ),
DeclareLaunchArgument("use_sim_time", default_value=use_sim_time ),
DeclareLaunchArgument("vehicle_model", default_value=vehicle_model ),
DeclareLaunchArgument("workflow", default_value=workflow ),
# fmt: on
Node(
package="scenario_test_runner",
Expand Down

0 comments on commit 881fc3a

Please sign in to comment.