Skip to content

Commit

Permalink
rebase to new mode name
Browse files Browse the repository at this point in the history
Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
  • Loading branch information
yuki-takagi-66 committed Aug 14, 2024
1 parent 606267a commit a136f54
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 5 deletions.
10 changes: 7 additions & 3 deletions launch/tier4_simulator_launch/launch/simulator.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -154,7 +154,8 @@
</group>

<group if="$(eval '&quot;$(var localization_sim_mode)&quot;==&quot;pose_twist_estimator&quot;')">
<group> <!-- start name space localization -->
<group>
<!-- start name space localization -->
<push-ros-namespace namespace="localization"/>
<group>
<push-ros-namespace namespace="util"/>
Expand All @@ -180,7 +181,8 @@
<push-ros-namespace namespace="pose_twist_fusion_filter"/>
<include file="$(find-pkg-share tier4_localization_launch)/launch/pose_twist_fusion_filter/pose_twist_fusion_filter.launch.xml"/>
</group>
</group> <!-- end name space localization -->
</group>
<!-- end name space localization -->
<group>
<push-ros-namespace namespace="sensing"/>
<arg name="input_vehicle_velocity_topic" default="/vehicle/status/velocity_status"/>
Expand Down Expand Up @@ -210,12 +212,14 @@
<!-- Simulator model -->
<group if="$(var launch_dummy_vehicle)">
<arg name="simulator_model" default="$(var vehicle_model_pkg)/config/simulator_model.param.yaml" description="path to the file of simulator model"/>
<let name="motion_publish_mode" value="pose_only" if="$(eval '&quot;$(var localization_sim_mode)&quot;==&quot;pose_twist_estimator&quot;')"/>
<let name="motion_publish_mode" value="full_motion" unless="$(eval '&quot;$(var localization_sim_mode)&quot;==&quot;pose_twist_estimator&quot;')"/>
<include file="$(find-pkg-share simple_planning_simulator)/launch/simple_planning_simulator.launch.py">
<arg name="vehicle_info_param_file" value="$(var vehicle_info_param_file)"/>
<arg name="simulator_model_param_file" value="$(var simulator_model)"/>
<arg name="initial_engage_state" value="$(var initial_engage_state)"/>
<arg name="raw_vehicle_cmd_converter_param_path" value="$(var raw_vehicle_cmd_converter_param_path)"/>
<arg name="launch_localization_for_sim_vehicle" value="$(var launch_localization_for_sim_vehicle)"/>
<arg name="motion_publish_mode" value="$(var motion_publish_mode)"/>
</include>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -65,15 +65,15 @@ def launch_setup(context, *args, **kwargs):
]

# Additional remappings
if LaunchConfiguration("launch_localization_for_sim_vehicle").perform(context) == "true":
if LaunchConfiguration("motion_publish_mode").perform(context) == "pose_only":
remappings.extend(
[
("output/odometry", "/simulation/debug/localization/kinematic_state"),
("output/acceleration", "/simulation/debug/localization/acceleration"),
("output/pose", "/localization/pose_estimator/pose_with_covariance"),
]
)
else:
elif LaunchConfiguration("motion_publish_mode").perform(context) == "full_motion":
remappings.extend(
[
("output/odometry", "/localization/kinematic_state"),
Expand All @@ -84,6 +84,10 @@ def launch_setup(context, *args, **kwargs):
),
]
)
else:
raise ValueError(
"Invalid motion_publish_mode specified. Please choose 'pose_only' or 'full_motion'."
)

simple_planning_simulator_node = Node(
package="simple_planning_simulator",
Expand Down

0 comments on commit a136f54

Please sign in to comment.