Skip to content

Commit

Permalink
style fix
Browse files Browse the repository at this point in the history
  • Loading branch information
robomic committed Dec 18, 2024
1 parent 43f7e10 commit 539580d
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 44 deletions.
54 changes: 12 additions & 42 deletions mock/cpp_mock_scenarios/launch/mock_test.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,13 +30,7 @@
from launch.events import Shutdown
from launch.event_handlers import OnProcessExit, OnProcessIO

from launch.actions import (
EmitEvent,
RegisterEventHandler,
LogInfo,
TimerAction,
OpaqueFunction,
)
from launch.actions import EmitEvent, RegisterEventHandler, LogInfo, TimerAction, OpaqueFunction
from launch.actions.declare_launch_argument import DeclareLaunchArgument
from launch.substitutions.launch_configuration import LaunchConfiguration

Expand All @@ -46,7 +40,6 @@

from pathlib import Path


class Color:
BLACK = "\033[30m"
RED = "\033[31m"
Expand Down Expand Up @@ -104,10 +97,7 @@ def default_autoware_launch_file_of(architecture_type):


def default_rviz_config_file():
return (
Path(get_package_share_directory("traffic_simulator"))
/ "config/scenario_simulator_v2.rviz"
)
return Path(get_package_share_directory("traffic_simulator")) / "config/scenario_simulator_v2.rviz"


def launch_setup(context, *args, **kwargs):
Expand Down Expand Up @@ -138,38 +128,20 @@ def launch_setup(context, *args, **kwargs):
junit_path = LaunchConfiguration("junit_path", default="/tmp/output.xunit.xml")
# fmt: on

print(
f"architecture_type := {architecture_type.perform(context)}"
)
print(
f"autoware_launch_file := {autoware_launch_file.perform(context)}"
)
print(
f"autoware_launch_package := {autoware_launch_package.perform(context)}"
)
print(
f"consider_acceleration_by_road_slope := {consider_acceleration_by_road_slope.perform(context)}"
)
print(
f"consider_pose_by_road_slope := {consider_pose_by_road_slope.perform(context)}"
)
print(
f"global_frame_rate := {global_frame_rate.perform(context)}"
)
print(
f"global_real_time_factor := {global_real_time_factor.perform(context)}"
)
print(f"architecture_type := {architecture_type.perform(context)}")
print(f"autoware_launch_file := {autoware_launch_file.perform(context)}")
print(f"autoware_launch_package := {autoware_launch_package.perform(context)}")
print(f"consider_acceleration_by_road_slope := {consider_acceleration_by_road_slope.perform(context)}")
print(f"consider_pose_by_road_slope := {consider_pose_by_road_slope.perform(context)}")
print(f"global_frame_rate := {global_frame_rate.perform(context)}")
print(f"global_real_time_factor := {global_real_time_factor.perform(context)}")
print(f"global_timeout := {global_timeout.perform(context)}")
print(
f"initialize_duration := {initialize_duration.perform(context)}"
)
print(f"initialize_duration := {initialize_duration.perform(context)}")
print(f"launch_autoware := {launch_autoware.perform(context)}")
print(f"launch_rviz := {launch_rviz.perform(context)}")
print(f"output_directory := {output_directory.perform(context)}")
print(f"port := {port.perform(context)}")
print(
f"publish_empty_context := {publish_empty_context.perform(context)}"
)
print(f"publish_empty_context := {publish_empty_context.perform(context)}")
print(f"record := {record.perform(context)}")
print(f"rviz_config := {rviz_config.perform(context)}")
print(f"scenario := {scenario.perform(context)}")
Expand All @@ -185,9 +157,7 @@ def make_parameters():
{"architecture_type": architecture_type},
{"autoware_launch_file": autoware_launch_file},
{"autoware_launch_package": autoware_launch_package},
{
"consider_acceleration_by_road_slope": consider_acceleration_by_road_slope
},
{"consider_acceleration_by_road_slope": consider_acceleration_by_road_slope},
{"consider_pose_by_road_slope": consider_pose_by_road_slope},
{"initialize_duration": initialize_duration},
{"launch_autoware": launch_autoware},
Expand Down
3 changes: 1 addition & 2 deletions simulation/traffic_simulator/src/traffic/traffic_sink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,7 @@ TrafficSink::TrafficSink(
auto TrafficSink::execute(
[[maybe_unused]] const double current_time, [[maybe_unused]] const double step_time) -> void
{
const auto entity_names = entity_manager_ptr_->getEntityNames();
for (const auto & entity_name : entity_names) {
for (const auto & entity_name : entity_manager_ptr_->getEntityNames()) {
if (isEntitySinkable(entity_name)) {
entity_manager_ptr_->despawnEntity(entity_name);
}
Expand Down

0 comments on commit 539580d

Please sign in to comment.