Skip to content
This repository has been archived by the owner on Mar 27, 2023. It is now read-only.

Fix ros2 lsim launch #103

Merged
merged 6 commits into from
Apr 7, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
86 changes: 56 additions & 30 deletions autoware_launch/launch/logging_simulator.launch.xml
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>

<!-- Essential parameters -->
<arg name="map_path" doc="point cloud and lanelet2 map directory path"/>
<arg name="vehicle_model"/>
<arg name="sensor_model"/>
<arg name="vehicle_id" default="$(env VEHICLE_ID default)"/>

<!-- Optional parameters -->
<arg name="vehicle" default="true" doc="launch vehicle" />
<arg name="system" default="true" doc="launch system" />
Expand All @@ -20,55 +22,79 @@
<set_env name="AW_ROS2_USE_SIM_TIME" value="true" />

<!-- Vehicle -->
<include file="$(find-pkg-share vehicle_launch)/launch/vehicle_description.launch.xml" if="$(var vehicle)">
<arg name="vehicle_model" value="$(var vehicle_model)"/>
<arg name="sensor_model" value="$(var sensor_model)"/>
<arg name="vehicle_id" value="$(var vehicle_id)"/>
<arg name="vehicle_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/>
</include>
<group>
<include file="$(find-pkg-share vehicle_launch)/launch/vehicle_description.launch.xml" if="$(var vehicle)">
<arg name="vehicle_model" value="$(var vehicle_model)"/>
<arg name="sensor_model" value="$(var sensor_model)"/>
<arg name="vehicle_id" value="$(var vehicle_id)"/>
<arg name="vehicle_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/>
</include>
</group>

<!-- System -->
<include file="$(find-pkg-share system_launch)/launch/system.launch.xml" if="$(var system)">
<arg name="run_mode" value="online"/>
</include>
<group>
<include file="$(find-pkg-share system_launch)/launch/system.launch.xml" if="$(var system)">
<arg name="run_mode" value="online"/>
</include>
</group>


<!-- Map -->
<include file="$(find-pkg-share map_launch)/launch/map.launch.xml" if="$(var map)">
<arg name="lanelet2_map_path" value="$(var map_path)/$(var lanelet2_map_file)" />
<arg name="pointcloud_map_path" value="$(var map_path)/$(var pointcloud_map_file)"/>
</include>
<group>
<include file="$(find-pkg-share map_launch)/launch/map.launch.xml" if="$(var map)">
<arg name="lanelet2_map_path" value="$(var map_path)/$(var lanelet2_map_file)" />
<arg name="pointcloud_map_path" value="$(var map_path)/$(var pointcloud_map_file)"/>
</include>
</group>


<!-- Sensing -->
<include file="$(find-pkg-share sensing_launch)/launch/sensing.launch.xml" if="$(var sensing)">
<arg name="launch_driver" value="false"/>
<arg name="sensor_model" value="$(var sensor_model)"/>
<arg name="vehicle_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/>
<arg name="vehicle_mirror_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/mirror.param.yaml"/>
</include>
<group>
<include file="$(find-pkg-share sensing_launch)/launch/sensing.launch.xml" if="$(var sensing)">
<arg name="launch_driver" value="false"/>
<arg name="sensor_model" value="$(var sensor_model)"/>
<arg name="vehicle_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/vehicle_info.param.yaml"/>
<arg name="vehicle_mirror_param_file" value="$(find-pkg-share $(var vehicle_model)_description)/config/mirror.param.yaml"/>
</include>
</group>


<!-- Localization -->
<include file="$(find-pkg-share localization_launch)/launch/localization.launch.xml" if="$(var localization)">
</include>
<group>
<include file="$(find-pkg-share localization_launch)/launch/localization.launch.xml" if="$(var localization)">
</include>
</group>


<!-- Perception -->
<include file="$(find-pkg-share perception_launch)/launch/perception.launch.xml" if="$(var perception)">
<arg name="mode" value="lidar" doc="options: camera_lidar_fusion, lidar, camera"/>
</include>
<group>
<include file="$(find-pkg-share perception_launch)/launch/perception.launch.xml" if="$(var perception)">
<arg name="mode" value="lidar" doc="options: camera_lidar_fusion, lidar, camera"/>
</include>
</group>


<!-- Planning -->
<include file="$(find-pkg-share planning_launch)/launch/planning.launch.xml" if="$(var planning)">
</include>
<group>
<include file="$(find-pkg-share planning_launch)/launch/planning.launch.xml" if="$(var planning)">
</include>
</group>

<!-- Control -->
<include file="$(find-pkg-share control_launch)/launch/control.launch.xml" if="$(var control)">
<arg name="lateral_controller_mode" value="mpc_follower" doc="options: mpc_follower, pure_pursuit"/>
</include>
<group>
<include file="$(find-pkg-share control_launch)/launch/control.launch.xml" if="$(var control)">
<arg name="lateral_controller_mode" value="mpc_follower" doc="options: mpc_follower, pure_pursuit"/>
</include>
</group>

<!-- Rviz -->
<node pkg="rviz2" exec="rviz2" name="rviz2" output="screen" args="-d $(find-pkg-share autoware_launch)/rviz/autoware.rviz -s $(find-pkg-share autoware_launch)/rviz/image/autoware.png" if="$(var rviz)" >
<param name="use_sim_time" value="$(env AW_ROS2_USE_SIM_TIME false)"/>
</node>

<!-- Web Controller -->
<include file="$(find-pkg-share autoware_web_controller)/launch/autoware_web_controller.launch.xml" />
<group>
<include file="$(find-pkg-share autoware_web_controller)/launch/autoware_web_controller.launch.xml" />
</group>

</launch>
7 changes: 3 additions & 4 deletions localization_launch/launch/util/util.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<launch>

<!-- Topics -->
<arg name="input_sensor_points_topic" default="/sensing/lidar/pointcloud" doc="Sensor points topic"/>
<arg name="input_sensor_points_topic" default="/sensing/lidar/top/rectified/pointcloud" doc="Sensor points topic"/>
<arg name="output_measurement_range_sensor_points_topic" default="measurement_range/pointcloud" doc="Sensor points topic"/>
<arg name="output_voxel_grid_downsample_sensor_points_topic" default="voxel_grid_downsample/pointcloud" doc="Sensor points topic"/>
<arg name="output_downsample_sensor_points_topic" default="downsample/pointcloud" doc="Sensor points topic"/>
Expand All @@ -16,7 +16,7 @@
</include>

<node pkg="pointcloud_preprocessor" exec="crop_box_filter_node" name="crop_box_filter_measurement_range" output="log">
<param name="use_sim_time" value="$(env AW_ROS2_USE_SIM_TIME false)"/>
<param name="use_sim_time" value="$(env AW_ROS2_USE_SIM_TIME false)" />
<remap from="input" to="$(var input_sensor_points_topic)" />
<remap from="output" to="$(var output_measurement_range_sensor_points_topic)" />
<param name="min_x" value="-60.0" />
Expand All @@ -25,12 +25,11 @@
<param name="max_y" value="60.0" />
<param name="min_z" value="-30.0" />
<param name="max_z" value="50.0" />
<param name= "negative" value="False" />
<param name="negative" value="False" />
<param name="input_frame" value="$(var base_frame)" />
<param name="output_frame" value="$(var base_frame)" />
</node>


<!-- Run a VoxelGrid filter to clean NaNs and downsample the data -->
<node pkg="pointcloud_preprocessor" exec="voxel_grid_downsample_filter_node" name="voxel_grid_filter" output="log">
<param name="use_sim_time" value="$(env AW_ROS2_USE_SIM_TIME false)"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
autoware_planning_msgs/msg/LaneChangeCommand 'command: true' -r 10"/>

<node pkg="turn_signal_decider" exec="turn_signal_decider" name="turn_signal_decider" output="screen">
<param name="use_sim_time" value="$(env AW_ROS2_USE_SIM_TIME false)"/>
<param name="use_sim_time" value="$(env AW_ROS2_USE_SIM_TIME false)" />
<remap from="input/path_with_lane_id" to="path_with_lane_id" />
<remap from="input/vector_map" to="$(var map_topic_name)" />
<remap from="output/turn_signal_cmd" to="/planning/turn_signal_decider/turn_signal_cmd" />
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -121,21 +121,6 @@ def launch_setup(context, *args, **kwargs):
}]
)

relay_component = ComposableNode(
package='topic_tools',
plugin='topic_tools::RelayNode',
name='relay',
parameters=[{
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
"history": "keep_last",
"depth": 5,
"reliability": "best_effort",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

# set container to run all required components in the same process
container = ComposableNodeContainer(
name='pointcloud_preprocessor_container',
Expand All @@ -145,7 +130,6 @@ def launch_setup(context, *args, **kwargs):
composable_node_descriptions=[
cropbox_component,
ground_component,
relay_component,
],
output='screen',
parameters=[{
Expand Down
16 changes: 0 additions & 16 deletions sensing_launch/launch/aip_s1/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -121,21 +121,6 @@ def launch_setup(context, *args, **kwargs):
}]
)

relay_component = ComposableNode(
package='topic_tools',
plugin='topic_tools::RelayNode',
name='relay',
parameters=[{
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
"history": "keep_last",
"depth": 5,
"reliability": "best_effort",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

# set container to run all required components in the same process
container = ComposableNodeContainer(
name='pointcloud_preprocessor_container',
Expand All @@ -145,7 +130,6 @@ def launch_setup(context, *args, **kwargs):
composable_node_descriptions=[
cropbox_component,
ground_component,
relay_component,
],
output='screen',
parameters=[{
Expand Down
16 changes: 0 additions & 16 deletions sensing_launch/launch/aip_x2/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -123,21 +123,6 @@ def launch_setup(context, *args, **kwargs):
}]
)

relay_component = ComposableNode(
package='topic_tools',
plugin='topic_tools::RelayNode',
name='relay',
parameters=[{
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
"history": "keep_last",
"depth": 5,
"reliability": "best_effort",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

# set container to run all required components in the same process
container = ComposableNodeContainer(
name='pointcloud_preprocessor_container',
Expand All @@ -148,7 +133,6 @@ def launch_setup(context, *args, **kwargs):
concat_component,
cropbox_component,
ground_component,
relay_component,
],
output='screen',
parameters=[{
Expand Down
16 changes: 0 additions & 16 deletions sensing_launch/launch/aip_xx1/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -121,21 +121,6 @@ def launch_setup(context, *args, **kwargs):
}]
)

relay_component = ComposableNode(
package='topic_tools',
plugin='topic_tools::RelayNode',
name='relay',
parameters=[{
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
"history": "keep_last",
"depth": 5,
"reliability": "best_effort",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

# set container to run all required components in the same process
container = ComposableNodeContainer(
name='pointcloud_preprocessor_container',
Expand All @@ -145,7 +130,6 @@ def launch_setup(context, *args, **kwargs):
composable_node_descriptions=[
cropbox_component,
ground_component,
relay_component,
],
output='screen',
parameters=[{
Expand Down
16 changes: 0 additions & 16 deletions sensing_launch/launch/aip_xx2/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -121,21 +121,6 @@ def launch_setup(context, *args, **kwargs):
}]
)

relay_component = ComposableNode(
package='topic_tools',
plugin='topic_tools::RelayNode',
name='relay',
parameters=[{
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
"history": "keep_last",
"depth": 5,
"reliability": "best_effort",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

# set container to run all required components in the same process
container = ComposableNodeContainer(
name='pointcloud_preprocessor_container',
Expand All @@ -145,7 +130,6 @@ def launch_setup(context, *args, **kwargs):
composable_node_descriptions=[
cropbox_component,
ground_component,
relay_component,
],
output='screen',
parameters=[{
Expand Down