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

Fix default value of use_concat_filter and use_radius_search #90

Merged
merged 2 commits into from
Mar 15, 2021
Merged
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
94 changes: 45 additions & 49 deletions sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,16 +13,12 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import os
import yaml

import launch
from launch.actions import DeclareLaunchArgument, OpaqueFunction
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch.substitutions import EnvironmentVariable, LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer, LoadComposableNodes
from launch_ros.descriptions import ComposableNode
from launch.substitutions import EnvironmentVariable
import yaml


def get_vehicle_info(context):
Expand Down Expand Up @@ -65,7 +61,7 @@ def launch_setup(context, *args, **kwargs):
'/sensing/lidar/front_right/mirror_cropped/pointcloud',
'/sensing/lidar/front_center/mirror_cropped/pointcloud'],
'output_frame': LaunchConfiguration('base_frame'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -82,7 +78,7 @@ def launch_setup(context, *args, **kwargs):
'output_frame': LaunchConfiguration('base_frame'),
'min_z': vehicle_info['min_height_offset'],
'max_z': vehicle_info['max_height_offset'],
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -105,7 +101,7 @@ def launch_setup(context, *args, **kwargs):
'min_z': -0.5,
'max_z': vehicle_info['max_height_offset'],
'negative': False,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -118,18 +114,18 @@ def launch_setup(context, *args, **kwargs):
('output', 'rough/no_ground/pointcloud'),
],
parameters=[{
"initial_max_slope": 10.0,
"general_max_slope": 10.0,
"local_max_slope": 10.0,
"min_height_threshold": 0.3,
"radial_devider_angle": 1.0,
"concentric_devider_distance": 0.0,
"use_vehicle_footprint": True,
"min_x": vehicle_info['min_longitudinal_offset'],
"max_x": vehicle_info['max_longitudinal_offset'],
"min_y": vehicle_info['min_lateral_offset'],
"max_y": vehicle_info['max_lateral_offset'],
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'initial_max_slope': 10.0,
'general_max_slope': 10.0,
'local_max_slope': 10.0,
'min_height_threshold': 0.3,
'radial_devider_angle': 1.0,
'concentric_devider_distance': 0.0,
'use_vehicle_footprint': True,
'min_x': vehicle_info['min_longitudinal_offset'],
'max_x': vehicle_info['max_longitudinal_offset'],
'min_y': vehicle_info['min_lateral_offset'],
'max_y': vehicle_info['max_lateral_offset'],
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -151,7 +147,7 @@ def launch_setup(context, *args, **kwargs):
'min_z': -0.5,
'max_z': 0.5,
'negative': False,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -167,7 +163,7 @@ def launch_setup(context, *args, **kwargs):
parameters=[{
'voxel_size_x': 0.25,
'voxel_size_y': 0.25,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -190,7 +186,7 @@ def launch_setup(context, *args, **kwargs):
'voxel_size_y': 0.2,
'voxel_size_z': 0.2,
'debug': False,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -203,7 +199,7 @@ def launch_setup(context, *args, **kwargs):
'input_topics': ['/sensing/lidar/rough/no_ground/pointcloud',
'/sensing/lidar/short_height/no_ground/pointcloud'],
'output_frame': LaunchConfiguration('base_frame'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -216,12 +212,12 @@ def launch_setup(context, *args, **kwargs):
('output', 'voxel_grid_filtered/pointcloud'),
],
parameters=[{
"input_frame": LaunchConfiguration('base_frame'),
"output_frame": LaunchConfiguration('base_frame'),
"voxel_size_x": 0.04,
"voxel_size_y": 0.04,
"voxel_size_z": 0.08,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'input_frame': LaunchConfiguration('base_frame'),
'output_frame': LaunchConfiguration('base_frame'),
'voxel_size_x': 0.04,
'voxel_size_y': 0.04,
'voxel_size_z': 0.08,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -234,9 +230,9 @@ def launch_setup(context, *args, **kwargs):
('output', 'no_ground/pointcloud'),
],
parameters=[{
"search_radius": 0.2,
"min_neighbors": 5,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'search_radius': 0.2,
'min_neighbors': 5,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -249,11 +245,11 @@ def launch_setup(context, *args, **kwargs):
('output', 'no_ground/pointcloud'),
],
parameters=[{
"voxel_size_x": 0.4,
"voxel_size_y": 0.4,
"voxel_size_z": 100.0,
"voxel_points_threshold": 5,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'voxel_size_x': 0.4,
'voxel_size_y': 0.4,
'voxel_size_z': 100.0,
'voxel_points_threshold': 5,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}]
)

Expand All @@ -262,13 +258,13 @@ def launch_setup(context, *args, **kwargs):
plugin='topic_tools::RelayNode',
name='relay',
parameters=[{
"input_topic": "/sensing/lidar/top/outlier_filtered/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'),
'input_topic': '/sensing/lidar/top/outlier_filtered/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')
}],
)

Expand All @@ -290,7 +286,7 @@ def launch_setup(context, *args, **kwargs):
],
output='screen',
parameters=[{
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False')
}],
)

Expand Down Expand Up @@ -332,8 +328,8 @@ def add_launch_arg(name: str, default_value=None):
launch_arguments.append(DeclareLaunchArgument(name, default_value=default_value))

add_launch_arg('base_frame', 'base_link')
add_launch_arg('use_concat_filter', 'use_concat_filter')
add_launch_arg('use_radius_search', 'use_radius_search')
add_launch_arg('use_concat_filter', 'true')
add_launch_arg('use_radius_search', 'true')
add_launch_arg('vehicle_param_file')

return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)])