Skip to content

Commit

Permalink
Merge pull request #44 from tier4/sync-upstream
Browse files Browse the repository at this point in the history
chore: sync upstream
  • Loading branch information
tier4-autoware-public-bot[bot] authored May 18, 2022
2 parents 65e6d7b + f1d2b9e commit 0621852
Show file tree
Hide file tree
Showing 132 changed files with 2,941 additions and 1,282 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/github-release.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ jobs:
- name: Select verb
id: select-verb
run: |
has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}")
has_previous_draft=$(gh release view --json isDraft -q ".isDraft" "${{ steps.set-tag-name.outputs.tag-name }}") || true
verb=create
if [ "$has_previous_draft" = "true" ]; then
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_auto_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ include_directories(SYSTEM ${EIGEN3_INCLUDE_DIR})

if(BUILD_TESTING)
set(TEST_COMMON test_common_gtest)
ament_add_gtest(${TEST_COMMON}
ament_add_ros_isolated_gtest(${TEST_COMMON}
test/gtest_main.cpp
test/test_bool_comparisons.cpp
test/test_byte_reader.cpp
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_auto_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<depend>builtin_interfaces</depend>
<depend>eigen</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
<test_depend>geometry_msgs</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_auto_geometry/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ if(BUILD_TESTING)
test/src/test_common_2d.cpp
test/src/test_intersection.cpp
)
ament_add_gtest(${GEOMETRY_GTEST} ${GEOMETRY_SRC})
ament_add_ros_isolated_gtest(${GEOMETRY_GTEST} ${GEOMETRY_SRC})
target_compile_options(${GEOMETRY_GTEST} PRIVATE -Wno-conversion -Wno-sign-conversion)
target_include_directories(${GEOMETRY_GTEST} PRIVATE "test/include" "include")
ament_target_dependencies(${GEOMETRY_GTEST}
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_auto_geometry/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
<depend>autoware_auto_vehicle_msgs</depend>
<depend>geometry_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
<test_depend>osrf_testing_tools_cpp</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_auto_tf2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ find_package(autoware_cmake REQUIRED)
autoware_package()

if(BUILD_TESTING)
ament_add_gtest(test_tf2_autoware_auto_msgs test/test_tf2_autoware_auto_msgs.cpp)
ament_add_ros_isolated_gtest(test_tf2_autoware_auto_msgs test/test_tf2_autoware_auto_msgs.cpp)
target_include_directories(test_tf2_autoware_auto_msgs PRIVATE "include")
ament_target_dependencies(test_tf2_autoware_auto_msgs
"autoware_auto_common"
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_auto_tf2/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<depend>tf2_geometry_msgs</depend>
<depend>tf2_ros</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

Expand Down
2 changes: 1 addition & 1 deletion common/autoware_point_types/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ include_directories(
)

if(BUILD_TESTING)
ament_add_gtest(test_autoware_point_types
ament_add_ros_isolated_gtest(test_autoware_point_types
test/test_point_types.cpp
)
target_include_directories(test_autoware_point_types
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_point_types/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
<depend>pcl_ros</depend>
<depend>point_cloud_msg_wrapper</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
<test_depend>point_cloud_msg_wrapper</test_depend>
Expand Down
39 changes: 27 additions & 12 deletions common/autoware_testing/autoware_testing/smoke_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

import os
import shlex
import time
import unittest

from ament_index_python import get_package_share_directory
Expand All @@ -26,21 +27,24 @@
from launch_ros.actions import Node
import launch_testing
import pytest
import rclpy


def resolve_node(context, *args, **kwargs):
parameters = [
os.path.join(
get_package_share_directory(LaunchConfiguration("arg_package").perform(context)),
"param",
file_name,
)
for file_name in shlex.split(LaunchConfiguration("arg_param_filenames").perform(context))
]

smoke_test_node = Node(
package=LaunchConfiguration("arg_package"),
executable=LaunchConfiguration("arg_package_exe"),
namespace="test",
parameters=[
os.path.join(
get_package_share_directory(LaunchConfiguration("arg_package").perform(context)),
"param",
LaunchConfiguration("arg_param_filename").perform(context),
)
],
parameters=parameters,
arguments=shlex.split(LaunchConfiguration("arg_executable_arguments").perform(context)),
)
return [smoke_test_node]
Expand All @@ -55,8 +59,8 @@ def generate_test_description():
arg_package_exe = DeclareLaunchArgument(
"arg_package_exe", default_value=["default"], description="Tested executable"
)
arg_param_filename = DeclareLaunchArgument(
"arg_param_filename", default_value=["test.param.yaml"], description="Test param file"
arg_param_filenames = DeclareLaunchArgument(
"arg_param_filenames", default_value=["test.param.yaml"], description="Test param file"
)
arg_executable_arguments = DeclareLaunchArgument(
"arg_executable_arguments", default_value=[""], description="Tested executable arguments"
Expand All @@ -66,16 +70,27 @@ def generate_test_description():
[
arg_package,
arg_package_exe,
arg_param_filename,
arg_param_filenames,
arg_executable_arguments,
OpaqueFunction(function=resolve_node),
launch_testing.actions.ReadyToTest(),
]
)


class DummyTest(unittest.TestCase):
def test_wait_for_node_ready(self):
"""Waiting for the node is ready."""
rclpy.init()
test_node = rclpy.create_node("test_node")
while len(test_node.get_node_names()) == 0:
time.sleep(0.1)
print("waiting for Node to be ready")
rclpy.shutdown()


@launch_testing.post_shutdown_test()
class TestProcessOutput(unittest.TestCase):
def test_exit_code(self, proc_output, proc_info):
# Check that process exits with code -15 code: termination request, sent to the program
launch_testing.asserts.assertExitCodes(proc_info, [-15])
# Check that process exits with code 0
launch_testing.asserts.assertExitCodes(proc_info)
10 changes: 5 additions & 5 deletions common/autoware_testing/cmake/add_smoke_test.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -19,18 +19,18 @@
# :type package_name: string
# :param package_exec: package executable to run during smoke test
# :type executable_name: string
# :param PARAM_FILENAME: yaml filename containing test parameters
# :type PARAM_FILENAME: string
# :param PARAM_FILENAMES: yaml filenames containing test parameters
# :type PARAM_FILENAMES: string
# :param EXECUTABLE_ARGUMENTS: arguments passed to tested executable
# :type EXECUTABLE_ARGUMENTS: string

function(add_smoke_test package_name executable_name)
cmake_parse_arguments(PARSE_ARGV 2 smoke_test "" "PARAM_FILENAME;EXECUTABLE_ARGUMENTS" "")
cmake_parse_arguments(PARSE_ARGV 2 smoke_test "" "PARAM_FILENAMES;EXECUTABLE_ARGUMENTS" "")

set(ARGUMENTS "arg_package:=${package_name}" "arg_package_exe:=${executable_name}")

if(smoke_test_PARAM_FILENAME)
list(APPEND ARGUMENTS "arg_param_filename:=${smoke_test_PARAM_FILENAME}")
if(smoke_test_PARAM_FILENAMES)
list(APPEND ARGUMENTS "arg_param_filenames:=${smoke_test_PARAM_FILENAMES}")
endif()

if(smoke_test_EXECUTABLE_ARGUMENTS)
Expand Down
2 changes: 1 addition & 1 deletion common/fake_test_node/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ autoware_package()
ament_auto_add_library(fake_test_node SHARED src/fake_test_node.cpp)

if(BUILD_TESTING)
ament_add_gtest(test_fake_test_node
ament_add_ros_isolated_gtest(test_fake_test_node
test/test_fake_test_node.cpp
)
add_dependencies(test_fake_test_node fake_test_node)
Expand Down
2 changes: 1 addition & 1 deletion common/fake_test_node/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@

<build_depend>autoware_cmake</build_depend>

<depend>ament_cmake_gtest</depend>
<depend>ament_cmake_ros</depend>
<depend>autoware_auto_common</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
2 changes: 1 addition & 1 deletion common/had_map_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
<depend>lanelet2_io</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

Expand Down
2 changes: 1 addition & 1 deletion common/interpolation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ ament_auto_add_library(interpolation SHARED
if(BUILD_TESTING)
file(GLOB_RECURSE test_files test/**/*.cpp)

ament_add_gtest(test_interpolation ${test_files})
ament_add_ros_isolated_gtest(test_interpolation ${test_files})

target_link_libraries(test_interpolation
interpolation
Expand Down
2 changes: 1 addition & 1 deletion common/interpolation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

<depend>tier4_autoware_utils</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

Expand Down
2 changes: 1 addition & 1 deletion common/motion_testing/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ autoware_package()
ament_auto_add_library(${PROJECT_NAME} SHARED src/motion_testing/motion_testing.cpp)

if(BUILD_TESTING)
ament_add_gtest(motion_testing_unit_tests
ament_add_ros_isolated_gtest(motion_testing_unit_tests
test/gtest_main.cpp
test/constant_trajectory.cpp
test/trajectory_checks.cpp)
Expand Down
2 changes: 1 addition & 1 deletion common/motion_testing/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
<build_export_depend>autoware_auto_planning_msgs</build_export_depend>
<build_export_depend>autoware_auto_vehicle_msgs</build_export_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

Expand Down
2 changes: 1 addition & 1 deletion common/osqp_interface/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ if(BUILD_TESTING)
test/test_csc_matrix_conv.cpp
)
set(TEST_OSQP_INTERFACE_EXE test_osqp_interface)
ament_add_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES})
ament_add_ros_isolated_gtest(${TEST_OSQP_INTERFACE_EXE} ${TEST_SOURCES})
target_link_libraries(${TEST_OSQP_INTERFACE_EXE} ${PROJECT_NAME})
endif()

Expand Down
2 changes: 1 addition & 1 deletion common/osqp_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
<test_depend>eigen</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion common/signal_processing/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ ament_auto_add_library(lowpass_filter_1d SHARED
)

if(BUILD_TESTING)
ament_add_gtest(test_signal_processing
ament_add_ros_isolated_gtest(test_signal_processing
test/src/lowpass_filter_1d_test.cpp
)
target_link_libraries(test_signal_processing
Expand Down
2 changes: 1 addition & 1 deletion common/signal_processing/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

<buildtool_depend>ament_cmake_auto</buildtool_depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

Expand Down
2 changes: 1 addition & 1 deletion common/tier4_api_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ autoware_package()

if(BUILD_TESTING)
include_directories(include)
ament_add_gtest(${PROJECT_NAME}_test test/test.cpp)
ament_add_ros_isolated_gtest(${PROJECT_NAME}_test test/test.cpp)
ament_target_dependencies(${PROJECT_NAME}_test rclcpp tier4_external_api_msgs)
endif()

Expand Down
2 changes: 1 addition & 1 deletion common/tier4_api_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<depend>rclcpp</depend>
<depend>tier4_external_api_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
<test_depend>rclcpp</test_depend>
Expand Down
4 changes: 2 additions & 2 deletions common/tier4_autoware_utils/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -12,11 +12,11 @@ ament_auto_add_library(tier4_autoware_utils SHARED
)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_ros REQUIRED)

file(GLOB_RECURSE test_files test/**/*.cpp)

ament_add_gtest(test_tier4_autoware_utils ${test_files})
ament_add_ros_isolated_gtest(test_tier4_autoware_utils ${test_files})

target_link_libraries(test_tier4_autoware_utils
tier4_autoware_utils
Expand Down
2 changes: 1 addition & 1 deletion common/tier4_autoware_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
<depend>tier4_debug_msgs</depend>
<depend>visualization_msgs</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ void AccelBrakeMapCalibratorButtonPanel::onInitialize()
&AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest, this, std::placeholders::_1));

client_ = raw_node->create_client<tier4_vehicle_msgs::srv::UpdateAccelBrakeMap>(
"/vehicle/calibration/accel_brake_map_calibrator/update_map_dir");
"/accel_brake_map_calibrator/update_map_dir");
}

void AccelBrakeMapCalibratorButtonPanel::callbackUpdateSuggest(
Expand Down
1 change: 1 addition & 0 deletions common/tier4_state_rviz_plugin/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<depend>rviz_common</depend>
<depend>tier4_control_msgs</depend>
<depend>tier4_external_api_msgs</depend>
<depend>tier4_planning_msgs</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
Expand Down
Loading

0 comments on commit 0621852

Please sign in to comment.