Skip to content

Commit

Permalink
Merge branch 'main' into feat/update_osqp_iteration_num
Browse files Browse the repository at this point in the history
Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara committed Oct 31, 2023
2 parents 510b6d8 + a2b114d commit 2395d62
Show file tree
Hide file tree
Showing 483 changed files with 22,454 additions and 6,777 deletions.
2 changes: 1 addition & 1 deletion .cspell-partial.json
Original file line number Diff line number Diff line change
Expand Up @@ -5,5 +5,5 @@
"perception/bytetrack/lib/**"
],
"ignoreRegExpList": [],
"words": []
"words": ["dltype", "tvmgen", "quantizer", "imageio", "mimsave"]
}
17 changes: 10 additions & 7 deletions .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ common/traffic_light_recognition_marker_publisher/** [email protected]
common/traffic_light_utils/** [email protected] [email protected]
common/trtexec_vendor/** [email protected] [email protected]
common/tvm_utility/** [email protected] [email protected]
control/autonomous_emergency_braking/** [email protected] [email protected]
control/autonomous_emergency_braking/** [email protected] [email protected] [email protected]
control/control_performance_analysis/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
control/control_validator/** [email protected] [email protected] [email protected]
control/external_cmd_selector/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
Expand All @@ -66,6 +66,7 @@ control/mpc_lateral_controller/** [email protected] takayuki.murooka@tier
control/obstacle_collision_checker/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
control/operation_mode_transition_manager/** [email protected] [email protected]
control/pid_longitudinal_controller/** [email protected] [email protected]
control/predicted_path_checker/** [email protected]
control/pure_pursuit/** [email protected]
control/shift_decider/** [email protected]
control/trajectory_follower_base/** [email protected] [email protected]
Expand All @@ -87,13 +88,15 @@ launch/tier4_system_launch/** [email protected] [email protected]
launch/tier4_vehicle_launch/** [email protected]
localization/ekf_localizer/** [email protected] [email protected] [email protected] [email protected] [email protected]
localization/gyro_odometer/** [email protected] [email protected]
localization/landmark_based_localizer/ar_tag_based_localizer/** [email protected] [email protected]
localization/landmark_based_localizer/landmark_tf_caster/** [email protected] [email protected]
localization/landmark_based_localizer/ar_tag_based_localizer/** [email protected] [email protected] shintaro.sakoda@tier4.jp yamato.ando@tier4.jp
localization/landmark_based_localizer/landmark_parser/** [email protected] [email protected] shintaro.sakoda@tier4.jp yamato.ando@tier4.jp
localization/localization_error_monitor/** [email protected] [email protected] [email protected]
localization/localization_util/** [email protected] [email protected] [email protected] [email protected]
localization/ndt_scan_matcher/** [email protected] [email protected] [email protected] [email protected]
localization/pose2twist/** [email protected] [email protected]
localization/pose_initializer/** [email protected] [email protected] [email protected]
localization/stop_filter/** [email protected] [email protected] [email protected]
localization/tree_structured_parzen_estimator/** [email protected] [email protected] [email protected] [email protected]
localization/twist2accel/** [email protected] [email protected] [email protected]
localization/yabloc/yabloc_common/** [email protected] [email protected]
localization/yabloc/yabloc_image_processing/** [email protected] [email protected]
Expand Down Expand Up @@ -140,6 +143,7 @@ perception/simple_object_merger/** [email protected] shunsuke.miura@tier4.
perception/tensorrt_classifier/** [email protected]
perception/tensorrt_yolo/** [email protected]
perception/tensorrt_yolox/** [email protected] [email protected] [email protected]
perception/tracking_object_merger/** [email protected] [email protected]
perception/traffic_light_arbiter/** [email protected] [email protected]
perception/traffic_light_classifier/** [email protected] [email protected]
perception/traffic_light_fine_detector/** [email protected] [email protected]
Expand All @@ -150,7 +154,7 @@ perception/traffic_light_ssd_fine_detector/** [email protected]
perception/traffic_light_visualization/** [email protected]
planning/behavior_path_planner/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/behavior_velocity_blind_spot_module/** [email protected] [email protected] [email protected]
planning/behavior_velocity_crosswalk_module/** [email protected] [email protected] [email protected] [email protected]
planning/behavior_velocity_crosswalk_module/** [email protected] [email protected] [email protected] [email protected] [email protected]
planning/behavior_velocity_detection_area_module/** [email protected] [email protected] [email protected]
planning/behavior_velocity_intersection_module/** [email protected] [email protected] [email protected] [email protected] [email protected]
planning/behavior_velocity_no_drivable_lane_module/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
Expand All @@ -177,11 +181,10 @@ planning/obstacle_cruise_planner/** [email protected] [email protected]
planning/obstacle_stop_planner/** [email protected] [email protected] [email protected] [email protected] [email protected]
planning/obstacle_velocity_limiter/** [email protected]
planning/path_smoother/** [email protected] [email protected]
planning/planning_debug_tools/** [email protected] [email protected]
planning/planning_debug_tools/** [email protected] [email protected] [email protected]
planning/planning_test_utils/** [email protected] [email protected]
planning/planning_validator/** [email protected] [email protected]
planning/route_handler/** [email protected] [email protected] [email protected] [email protected] [email protected] [email protected]
planning/rtc_auto_mode_manager/** [email protected] [email protected]
planning/rtc_interface/** [email protected] [email protected]
planning/rtc_replayer/** [email protected] [email protected]
planning/sampling_based_planner/bezier_sampler/** [email protected]
Expand Down Expand Up @@ -215,11 +218,11 @@ system/default_ad_api_helpers/ad_api_visualizers/** [email protected] kahhoo
system/default_ad_api_helpers/automatic_pose_initializer/** [email protected] [email protected] [email protected] [email protected] [email protected]
system/dummy_diag_publisher/** [email protected] [email protected]
system/dummy_infrastructure/** [email protected]
system/duplicated_node_checker/** [email protected] [email protected]
system/emergency_handler/** [email protected]
system/mrm_comfortable_stop_operator/** [email protected]
system/mrm_emergency_stop_operator/** [email protected]
system/system_diagnostic_graph/** [email protected]
system/system_diagnostic_monitor/** [email protected]
system/system_error_monitor/** [email protected]
system/system_monitor/** [email protected] [email protected]
system/topic_state_monitor/** [email protected]
Expand Down
14 changes: 0 additions & 14 deletions .github/sync-files.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -42,20 +42,6 @@
- \"\"
- -cuda
include:" {source}
- source: .github/workflows/build-and-test-differential.yaml
pre-commands: |
sd "container: ros:(\w+)" "container: ghcr.io/autowarefoundation/autoware-universe:\$1-latest" {source}
sd -s 'container: ${{ matrix.container }}' 'container: ${{ matrix.container }}${{ matrix.container-suffix }}' {source}
sd -- \
" include:" \
" container-suffix:
- \"\"
- -cuda
include:" {source}
sd "^ container: ghcr.io/autowarefoundation/autoware-universe:(\w+)-latest\$" \
" container: ghcr.io/autowarefoundation/autoware-universe:\$1-latest-cuda" {source}
- source: .github/workflows/build-and-test-differential-self-hosted.yaml
pre-commands: |
sd "container: ros:(\w+)" "container: ghcr.io/autowarefoundation/autoware-universe:\$1-latest" {source}
Expand Down
34 changes: 34 additions & 0 deletions common/component_interface_specs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,38 @@ project(component_interface_specs)
find_package(autoware_cmake REQUIRED)
autoware_package()

include_directories(
include
SYSTEM
${rclcpp_INCLUDE_DIRS}
${rosidl_runtime_cpp_INCLUDE_DIRS}
${rcl_INCLUDE_DIRS}
${autoware_adapi_v1_msgs_INCLUDE_DIRS}
${autoware_auto_planning_msgs_INCLUDE_DIRS}
${autoware_planning_msgs_INCLUDE_DIRS}
${autoware_auto_vehicle_msgs_INCLUDE_DIRS}
${tier4_control_msgs_INCLUDE_DIRS}
${nav_msgs_INCLUDE_DIRS}
${tier4_system_msgs_INCLUDE_DIRS}
${tier4_vehicle_msgs_INCLUDE_DIRS}
${autoware_auto_perception_msgs_INCLUDE_DIRS}
${tier4_map_msgs_INCLUDE_DIRS}
)

if(BUILD_TESTING)
ament_add_ros_isolated_gtest(test_component_interface_specs
test/gtest_main.cpp
test/test_planning.cpp
test/test_control.cpp
test/test_localization.cpp
test/test_system.cpp
test/test_map.cpp
test/test_perception.cpp
test/test_vehicle.cpp
)
target_include_directories(test_component_interface_specs
PRIVATE include
)
endif()

ament_auto_package()
17 changes: 16 additions & 1 deletion common/component_interface_specs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,13 +11,28 @@
<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>ament_cmake_core</buildtool_depend>
<buildtool_depend>ament_cmake_export_dependencies</buildtool_depend>
<buildtool_depend>ament_cmake_test</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<buildtool_export_depend>ament_cmake_core</buildtool_export_depend>
<buildtool_export_depend>ament_cmake_test</buildtool_export_depend>

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_auto_perception_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_auto_vehicle_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>nav_msgs</depend>
<depend>rcl</depend>
<depend>rclcpp</depend>
<depend>rosidl_runtime_cpp</depend>
<depend>tier4_control_msgs</depend>
<depend>tier4_map_msgs</depend>
<depend>tier4_system_msgs</depend>
<depend>tier4_vehicle_msgs</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
@@ -1,4 +1,4 @@
// Copyright 2023 Autoware Foundation
// Copyright 2023 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -12,11 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "landmark_tf_caster/landmark_tf_caster_core.hpp"
#include "gtest/gtest.h"

int main(int argc, char ** argv)
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
rclcpp::spin(std::make_shared<LandmarkTfCaster>());
rclcpp::shutdown();
::testing::InitGoogleTest(&argc, argv);
return RUN_ALL_TESTS();
}
46 changes: 46 additions & 0 deletions common/component_interface_specs/test/test_control.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// Copyright 2023 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "component_interface_specs/control.hpp"
#include "gtest/gtest.h"

TEST(control, interface)
{
{
using control_interface::IsPaused;
IsPaused is_paused;
size_t depth = 1;
EXPECT_EQ(is_paused.depth, depth);
EXPECT_EQ(is_paused.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(is_paused.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
}

{
using control_interface::IsStartRequested;
IsStartRequested is_start_requested;
size_t depth = 1;
EXPECT_EQ(is_start_requested.depth, depth);
EXPECT_EQ(is_start_requested.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(is_start_requested.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
}

{
using control_interface::IsStopped;
IsStopped is_stopped;
size_t depth = 1;
EXPECT_EQ(is_stopped.depth, depth);
EXPECT_EQ(is_stopped.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(is_stopped.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
}
}
46 changes: 46 additions & 0 deletions common/component_interface_specs/test/test_localization.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// Copyright 2023 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "component_interface_specs/localization.hpp"
#include "gtest/gtest.h"

TEST(localization, interface)
{
{
using localization_interface::InitializationState;
InitializationState initialization_state;
size_t depth = 1;
EXPECT_EQ(initialization_state.depth, depth);
EXPECT_EQ(initialization_state.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(initialization_state.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
}

{
using localization_interface::KinematicState;
KinematicState kinematic_state;
size_t depth = 1;
EXPECT_EQ(kinematic_state.depth, depth);
EXPECT_EQ(kinematic_state.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(kinematic_state.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);
}

{
using localization_interface::Acceleration;
Acceleration acceleration;
size_t depth = 1;
EXPECT_EQ(acceleration.depth, depth);
EXPECT_EQ(acceleration.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(acceleration.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);
}
}
28 changes: 28 additions & 0 deletions common/component_interface_specs/test/test_map.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
// Copyright 2023 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "component_interface_specs/map.hpp"
#include "gtest/gtest.h"

TEST(map, interface)
{
{
using map_interface::MapProjectorInfo;
MapProjectorInfo map_projector;
size_t depth = 1;
EXPECT_EQ(map_projector.depth, depth);
EXPECT_EQ(map_projector.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(map_projector.durability, RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL);
}
}
28 changes: 28 additions & 0 deletions common/component_interface_specs/test/test_perception.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
// Copyright 2023 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "component_interface_specs/perception.hpp"
#include "gtest/gtest.h"

TEST(perception, interface)
{
{
using perception_interface::ObjectRecognition;
ObjectRecognition object_recognition;
size_t depth = 1;
EXPECT_EQ(object_recognition.depth, depth);
EXPECT_EQ(object_recognition.reliability, RMW_QOS_POLICY_RELIABILITY_RELIABLE);
EXPECT_EQ(object_recognition.durability, RMW_QOS_POLICY_DURABILITY_VOLATILE);
}
}
Loading

0 comments on commit 2395d62

Please sign in to comment.