Skip to content
This repository has been archived by the owner on Nov 22, 2024. It is now read-only.

Commit

Permalink
feat: use autoware project rviz (#516)
Browse files Browse the repository at this point in the history
  • Loading branch information
hayato-m126 authored Jul 10, 2024
1 parent 3dcf0ae commit 2c55e4f
Show file tree
Hide file tree
Showing 12 changed files with 0 additions and 4,685 deletions.
4,664 changes: 0 additions & 4,664 deletions driving_log_replayer/config/dlr.rviz

This file was deleted.

1 change: 0 additions & 1 deletion driving_log_replayer/driving_log_replayer/launch_common.py
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,6 @@ def get_autoware_launch(
"perception": perception,
"planning": planning,
"control": control,
"rviz": "false",
"scenario_simulation": scenario_simulation,
}
if isinstance(pose_source, str):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,6 @@ def generate_launch_description() -> launch.LaunchDescription:
localization="false",
use_perception_online_evaluator="true",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node(
"annotationless_perception",
addition_parameter={
Expand Down Expand Up @@ -81,7 +80,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
evaluator_node,
player_normal,
Expand Down
2 changes: 0 additions & 2 deletions driving_log_replayer/launch/ar_tag_based_localizer.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@ def generate_launch_description() -> launch.LaunchDescription:
pose_source="artag",
twist_source="gyro_odom",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node("ar_tag_based_localizer")
player = cmn.get_player()
recorder, recorder_override = cmn.get_regex_recorders(
Expand All @@ -42,7 +41,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
fitter_launch,
evaluator_node,
Expand Down
2 changes: 0 additions & 2 deletions driving_log_replayer/launch/eagleye.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ def generate_launch_description() -> launch.LaunchDescription:
pose_source="eagleye",
twist_source="eagleye",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node("eagleye")
player = cmn.get_player()
recorder, recorder_override = cmn.get_regex_recorders(
Expand All @@ -45,7 +44,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
fitter_launch,
evaluator_node,
Expand Down
2 changes: 0 additions & 2 deletions driving_log_replayer/launch/localization.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,6 @@ def generate_launch_description() -> launch.LaunchDescription:
pose_source="ndt",
twist_source="gyro_odom",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node("localization")
player = cmn.get_player()
recorder, recorder_override = cmn.get_regex_recorders(
Expand All @@ -51,7 +50,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
fitter_launch,
evaluator_node,
Expand Down
2 changes: 0 additions & 2 deletions driving_log_replayer/launch/obstacle_segmentation.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ def generate_launch_description() -> launch.LaunchDescription:
control="true",
scenario_simulation="true",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node(
"obstacle_segmentation",
addition_parameter={
Expand All @@ -57,7 +56,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
evaluator_node,
player,
Expand Down
2 changes: 0 additions & 2 deletions driving_log_replayer/launch/perception.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ def generate_launch_description() -> launch.LaunchDescription:
sensing=LaunchConfiguration("sensing"),
localization="false",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node("perception")

player_normal = cmn.get_player(
Expand All @@ -62,7 +61,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
evaluator_node,
player_normal,
Expand Down
2 changes: 0 additions & 2 deletions driving_log_replayer/launch/perception_2d.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,6 @@ def generate_launch_description() -> launch.LaunchDescription:
localization="false",
perception_mode="camera_lidar_fusion",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node("perception_2d")

player_normal = cmn.get_player(
Expand All @@ -62,7 +61,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
evaluator_node,
player_normal,
Expand Down
2 changes: 0 additions & 2 deletions driving_log_replayer/launch/performance_diag.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@ def generate_launch_description() -> launch.LaunchDescription:
localization=LaunchConfiguration("localization"),
perception="false",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node(
"performance_diag",
addition_parameter={"localization": LaunchConfiguration("localization")},
Expand Down Expand Up @@ -83,7 +82,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
fitter_launch,
evaluator_node,
Expand Down
2 changes: 0 additions & 2 deletions driving_log_replayer/launch/traffic_light.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,6 @@ def generate_launch_description() -> launch.LaunchDescription:
sensing=LaunchConfiguration("sensing"),
localization="false",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node(
"traffic_light",
addition_parameter={"map_path": LaunchConfiguration("map_path")},
Expand All @@ -61,7 +60,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
evaluator_node,
player_normal,
Expand Down
2 changes: 0 additions & 2 deletions driving_log_replayer/launch/yabloc.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ def generate_launch_description() -> launch.LaunchDescription:
pose_source="yabloc",
twist_source="gyro_odom",
)
rviz_node = cmn.get_rviz()
evaluator_node = cmn.get_evaluator_node("yabloc")
player = cmn.get_player()
recorder, recorder_override = cmn.get_regex_recorders(
Expand All @@ -45,7 +44,6 @@ def generate_launch_description() -> launch.LaunchDescription:
return launch.LaunchDescription(
[
*launch_arguments,
rviz_node,
autoware_launch,
fitter_launch,
evaluator_node,
Expand Down

0 comments on commit 2c55e4f

Please sign in to comment.