Exemplo n.º 1
0
def generate_test_description(ready_fn):
    PORT = lidar_integration.get_open_port()

    # The node under test and the checker node that will pass/fail our tests:
    test_topic = "veloyne_cloud_node_test_topic"
    velodyne_cloud_node = launch_ros.actions.LifecycleNode(
        package="velodyne_node",
        node_executable="velodyne_cloud_node_exe",
        node_name="vlp16_driver_node",
        node_namespace="lidar_front",
        parameters=[
            "{}/param/vlp16_test.param.yaml".format(
                ament_index_python.get_package_share_directory(
                    "velodyne_node")), {
                        "port": PORT,
                        "cloud_size": 10700,
                        "expected_num_subscribers": 1,
                    }
        ],
        remappings=[("points_raw", test_topic)],
        arguments=["--model", "vlp16"])

    pcl_checker = lidar_integration.make_pcl_checker(
        topic=test_topic,
        size=10700,
        period=50,
    )

    return lidar_integration.get_lidar_launch_description(
        test_nodes=[velodyne_cloud_node],
        checkers=[pcl_checker],
        other_actions=[
            launch.actions.OpaqueFunction(function=lambda context: ready_fn())
        ],
        port=PORT)
Exemplo n.º 2
0
def generate_test_description(ready_fn):
    PORT = lidar_integration.get_open_port()

    # The nodes under test:
    velodyne_block_node = launch_ros.actions.Node(
        package="velodyne_node",
        node_executable="velodyne_cloud_node_exe",
        node_name="vlp16_test_node",
        node_namespace="lidar_front",
        parameters=[
            os.path.join(
                ament_index_python.get_package_share_directory("velodyne_node"),
                "vlp16_test.param.yaml"
            ),
            {
                "port": PORT,
            }
        ]
    )

    point_cloud_filter_transform_node = launch_ros.actions.Node(
        package="point_cloud_filter_transform_nodes",
        node_executable="point_cloud_filter_transform_node_exe",
        node_name="point_cloud_filter_transform_node",
        node_namespace="lidar_front",
        parameters=[
            os.path.join(
                ament_index_python.get_package_share_directory(
                    "point_cloud_filter_transform_nodes"),
                "param",
                "test.param.yaml"
            ),
            {
                "expected_num_ground_subscribers": 1,
                "expected_num_nonground_subscribers": 1,
            }
        ],
        remappings=[("points_in", "points_raw")]
    )

    filtered_points_checker = lidar_integration.make_pcl_checker(
        topic="points_filtered",
        size=16930,
        period=100,
        period_tolerance=1.0
    )

    return lidar_integration.get_lidar_launch_description(
        test_nodes=[velodyne_block_node, point_cloud_filter_transform_node],
        checkers=[filtered_points_checker],
        other_actions=[
            launch.actions.OpaqueFunction(function=lambda context: ready_fn())
        ],
        port=PORT
    )