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

added use_sim_time with AW_ROS2_USE_SIM_TIME envvar for the parameters in the *.launch.py #61

Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import EnvironmentVariable


def get_vehicle_info(context):
Expand Down Expand Up @@ -63,6 +64,7 @@ def launch_setup(context, *args, **kwargs):
'/sensing/lidar/left/outlier_filtered/pointcloud',
'/sensing/lidar/right/outlier_filtered/pointcloud'],
'output_frame': 'base_link',
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)
else:
Expand All @@ -78,6 +80,7 @@ def launch_setup(context, *args, **kwargs):
'output_frame': 'base_link',
'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'),
}]
)

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

Expand All @@ -116,6 +120,7 @@ def launch_setup(context, *args, **kwargs):
"general_max_slope": 10.0,
"local_max_slope": 10.0,
"min_height_threshold": 0.2,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)

Expand All @@ -127,6 +132,7 @@ def launch_setup(context, *args, **kwargs):
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

Expand All @@ -143,6 +149,9 @@ def launch_setup(context, *args, **kwargs):
relay_component,
],
output='screen',
parameters=[{
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

return [container]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import EnvironmentVariable

def get_vehicle_info(context):
path = LaunchConfiguration('vehicle_param_file').perform(context)
Expand Down Expand Up @@ -62,6 +63,7 @@ def launch_setup(context, *args, **kwargs):
'/sensing/lidar/left/outlier_filtered/pointcloud',
'/sensing/lidar/right/outlier_filtered/pointcloud'],
'output_frame': 'base_link',
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)
else:
Expand All @@ -78,6 +80,7 @@ def launch_setup(context, *args, **kwargs):
'output_frame': 'base_link',
'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'),
}]
)

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

Expand All @@ -115,6 +119,7 @@ def launch_setup(context, *args, **kwargs):
"general_max_slope": 10.0,
"local_max_slope": 10.0,
"min_height_threshold": 0.2,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)

Expand All @@ -126,6 +131,7 @@ def launch_setup(context, *args, **kwargs):
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

Expand All @@ -142,6 +148,9 @@ def launch_setup(context, *args, **kwargs):
relay_component,
],
output='screen',
parameters=[{
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

return [container]
Expand Down
12 changes: 12 additions & 0 deletions sensing_launch/launch/aip_x1/pointcloud_preprocessor.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import EnvironmentVariable

def get_vehicle_info(context):
path = LaunchConfiguration('vehicle_param_file').perform(context)
Expand Down Expand Up @@ -63,6 +64,7 @@ def launch_setup(context, *args, **kwargs):
'/sensing/lidar/front_right/mirror_cropped/pointcloud',
'/sensing/lidar/front_center/mirror_cropped/pointcloud'],
'output_frame': 'base_link',
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)
else:
Expand All @@ -79,6 +81,7 @@ def launch_setup(context, *args, **kwargs):
'output_frame': 'base_link',
'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'),
}]
)

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

Expand All @@ -122,6 +126,7 @@ def launch_setup(context, *args, **kwargs):
"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 @@ -139,6 +144,7 @@ def launch_setup(context, *args, **kwargs):
"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 @@ -154,6 +160,7 @@ def launch_setup(context, *args, **kwargs):
parameters=[{
"search_radius": 0.2,
"min_neighbors": 5
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)
else:
Expand All @@ -170,6 +177,7 @@ def launch_setup(context, *args, **kwargs):
"voxel_size_y": 0.4,
"voxel_size_z": 100,
"voxel_points_threshold": 5,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)

Expand All @@ -181,6 +189,7 @@ def launch_setup(context, *args, **kwargs):
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

Expand All @@ -197,6 +206,9 @@ def launch_setup(context, *args, **kwargs):
relay_component,
],
output='screen',
parameters=[{
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

return [container]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import EnvironmentVariable

def get_vehicle_info(context):
path = LaunchConfiguration('vehicle_param_file').perform(context)
Expand Down Expand Up @@ -62,6 +63,7 @@ def launch_setup(context, *args, **kwargs):
'/sensing/lidar/left/outlier_filtered/pointcloud',
'/sensing/lidar/right/outlier_filtered/pointcloud'],
'output_frame': 'base_link',
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)
else:
Expand All @@ -78,6 +80,7 @@ def launch_setup(context, *args, **kwargs):
'output_frame': 'base_link',
'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'),
}]
)

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

Expand All @@ -115,6 +119,7 @@ def launch_setup(context, *args, **kwargs):
"general_max_slope": 10.0,
"local_max_slope": 10.0,
"min_height_threshold": 0.2,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)

Expand All @@ -126,6 +131,7 @@ def launch_setup(context, *args, **kwargs):
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

Expand All @@ -142,6 +148,9 @@ def launch_setup(context, *args, **kwargs):
relay_component,
],
output='screen',
parameters=[{
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

return [container]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import EnvironmentVariable

def get_vehicle_info(context):
path = LaunchConfiguration('vehicle_param_file').perform(context)
Expand Down Expand Up @@ -61,6 +62,7 @@ def launch_setup(context, *args, **kwargs):
'/sensing/lidar/left/outlier_filtered/pointcloud',
'/sensing/lidar/right/outlier_filtered/pointcloud'],
'output_frame': 'base_link',
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)
else:
Expand All @@ -76,6 +78,7 @@ def launch_setup(context, *args, **kwargs):
'output_frame': 'base_link',
'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'),
}]
)

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

Expand All @@ -113,6 +117,7 @@ def launch_setup(context, *args, **kwargs):
"general_max_slope": 10.0,
"local_max_slope": 10.0,
"min_height_threshold": 0.2,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)

Expand All @@ -124,6 +129,7 @@ def launch_setup(context, *args, **kwargs):
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

Expand All @@ -140,6 +146,9 @@ def launch_setup(context, *args, **kwargs):
relay_component,
],
output='screen',
parameters=[{
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

return [container]
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
from launch.substitutions import EnvironmentVariable


def get_vehicle_info(context):
Expand Down Expand Up @@ -62,6 +63,7 @@ def launch_setup(context, *args, **kwargs):
'/sensing/lidar/left/outlier_filtered/pointcloud',
'/sensing/lidar/right/outlier_filtered/pointcloud'],
'output_frame': 'base_link',
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)
else:
Expand All @@ -78,6 +80,7 @@ def launch_setup(context, *args, **kwargs):
'output_frame': 'base_link',
'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'),
}]
)

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

Expand All @@ -115,6 +119,7 @@ def launch_setup(context, *args, **kwargs):
"general_max_slope": 10.0,
"local_max_slope": 10.0,
"min_height_threshold": 0.2,
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}]
)

Expand All @@ -126,6 +131,7 @@ def launch_setup(context, *args, **kwargs):
"input_topic": "/sensing/lidar/top/rectified/pointcloud",
"output_topic": "/sensing/lidar/pointcloud",
"type": "sensor_msgs/msg/PointCloud2",
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

Expand All @@ -142,6 +148,9 @@ def launch_setup(context, *args, **kwargs):
relay_component,
],
output='screen',
parameters=[{
'use_sim_time': EnvironmentVariable(name='AW_ROS2_USE_SIM_TIME', default_value='False'),
}],
)

return [container]
Expand Down
Loading