Skip to content

Commit

Permalink
Merge branch 'main' into feat/lidar_transfusion
Browse files Browse the repository at this point in the history
  • Loading branch information
knzo25 authored Jun 3, 2024
2 parents e6a657d + dfd3c13 commit 5b9bf5c
Show file tree
Hide file tree
Showing 1,113 changed files with 152,284 additions and 23,092 deletions.
64 changes: 31 additions & 33 deletions .github/CODEOWNERS

Large diffs are not rendered by default.

4 changes: 4 additions & 0 deletions .github/PULL_REQUEST_TEMPLATE/small-change.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,10 @@ Not applicable.

Not applicable.

## Interface changes

<!-- Describe any changed interfaces, such as topics, services, or parameters, including debugging interfaces -->

## Pre-review checklist for the PR author

The PR author **must** check the checkboxes below when creating the PR.
Expand Down
13 changes: 13 additions & 0 deletions .github/PULL_REQUEST_TEMPLATE/standard-change.md
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,19 @@

<!-- Describe any changed interfaces, such as topics, services, or parameters. -->

### ROS Topic Changes

<!-- | Topic Name | Type | Direction | Update Description | -->
<!-- | ---------------- | ------------------- | --------- | ------------------------------------------------------------- | -->
<!-- | `/example_topic` | `std_msgs/String` | Subscribe | Description of what the topic is used for in the system | -->
<!-- | `/another_topic` | `sensor_msgs/Image` | Publish | Also explain if it is added / modified / deleted with the PR | -->

### ROS Parameter Changes

<!-- | Parameter Name | Default Value | Update Description | -->
<!-- | -------------------- | ------------- | --------------------------------------------------- | -->
<!-- | `example_parameters` | `1.0` | Describe the parameter and also explain the updates | -->

## Effects on system behavior

<!-- Describe how this PR affects the system behavior. -->
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/build-and-test-arm64.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ jobs:
- -cuda
include:
- rosdistro: humble
container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt
container: ghcr.io/autowarefoundation/autoware:latest-prebuilt
build-depends-repos: build_depends.repos
steps:
- name: Check out repository
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/build-and-test-differential-arm64.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ jobs:
- -cuda
include:
- rosdistro: humble
container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt
container: ghcr.io/autowarefoundation/autoware:latest-prebuilt
build-depends-repos: build_depends.repos
steps:
- name: Check out repository
Expand Down
4 changes: 2 additions & 2 deletions .github/workflows/build-and-test-differential.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ jobs:
- -cuda
include:
- rosdistro: humble
container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt
container: ghcr.io/autowarefoundation/autoware:latest-prebuilt
build-depends-repos: build_depends.repos
steps:
- name: Check out repository
Expand Down Expand Up @@ -77,7 +77,7 @@ jobs:

clang-tidy-differential:
runs-on: ubuntu-latest
container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt-cuda
container: ghcr.io/autowarefoundation/autoware:latest-prebuilt-cuda
steps:
- name: Check out repository
uses: actions/checkout@v4
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/build-and-test.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ jobs:
- -cuda
include:
- rosdistro: humble
container: ghcr.io/autowarefoundation/autoware-openadk:latest-prebuilt
container: ghcr.io/autowarefoundation/autoware:latest-prebuilt
build-depends-repos: build_depends.repos
steps:
- name: Check out repository
Expand Down
4 changes: 4 additions & 0 deletions build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -41,3 +41,7 @@ repositories:
type: git
url: https://github.com/MORAI-Autonomous/MORAI-ROS2_morai_msgs.git
version: main
universe/external/glog: # TODO: to use isGoogleInitialized() API in v0.6.0. Remove when the rosdep glog version is updated to v0.6.0 (already updated in Ubuntu 24.04)
type: git
url: https://github.com/tier4/glog.git
version: v0.6.0_t4-ros
58 changes: 58 additions & 0 deletions common/.pages
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
nav:
- 'Introduction': common
- 'Testing Libraries':
- 'autoware_testing': common/autoware_testing/design/autoware_testing-design
- 'fake_test_node': common/fake_test_node/design/fake_test_node-design
- 'Common Libraries':
- 'autoware_auto_common':
- 'comparisons': common/autoware_auto_common/design/comparisons
- 'autoware_auto_tf2': common/autoware_auto_tf2/design/autoware-auto-tf2-design
- 'autoware_point_types': common/autoware_point_types
- 'Cuda Utils': common/cuda_utils
- 'Geography Utils': common/geography_utils
- 'Global Parameter Loader': common/global_parameter_loader/Readme
- 'Glog Component': common/glog_component
- 'grid_map_utils': common/grid_map_utils
- 'interpolation': common/interpolation
- 'Kalman Filter': common/kalman_filter
- 'Motion Utils': common/motion_utils
- 'Vehicle Utils': common/motion_utils/docs/vehicle/vehicle
- 'Object Recognition Utils': common/object_recognition_utils
- 'OSQP Interface': common/osqp_interface/design/osqp_interface-design
- 'Perception Utils': common/perception_utils
- 'QP Interface': common/qp_interface/design/qp_interface-design
- 'Signal Processing':
- 'Introduction': common/signal_processing
- 'Butterworth Filter': common/signal_processing/documentation/ButterworthFilter
- 'TensorRT Common': common/tensorrt_common
- 'tier4_autoware_utils': common/tier4_autoware_utils
- 'traffic_light_utils': common/traffic_light_utils
- 'TVM Utility':
- 'Introduction': common/tvm_utility
- 'YOLOv2 Tiny Example': common/tvm_utility/tvm-utility-yolo-v2-tiny-tests
- 'RVIZ2 Plugins':
- 'autoware_auto_perception_rviz_plugin': common/autoware_auto_perception_rviz_plugin
- 'autoware_overlay_rviz_plugin': common/autoware_overlay_rviz_plugin/autoware_overlay_rviz_plugin
- 'autoware_mission_details_overlay_rviz_plugin': common/autoware_overlay_rviz_plugin/autoware_mission_details_overlay_rviz_plugin
- 'bag_time_manager_rviz_plugin': common/bag_time_manager_rviz_plugin
- 'polar_grid': common/polar_grid/Readme
- 'tier4_adapi_rviz_plugin': common/tier4_adapi_rviz_plugin
- 'tier4_api_utils': common/tier4_api_utils
- 'tier4_camera_view_rviz_plugin': common/tier4_camera_view_rviz_plugin
- 'tier4_datetime_rviz_plugin': common/tier4_datetime_rviz_plugin
- 'tier4_localization_rviz_plugin': common/tier4_localization_rviz_plugin
- 'tier4_perception_rviz_plugin': common/tier4_perception_rviz_plugin
- 'tier4_planning_rviz_plugin': common/tier4_planning_rviz_plugin
- 'tier4_state_rviz_plugin': common/tier4_state_rviz_plugin
- 'tier4_system_rviz_plugin': common/tier4_system_rviz_plugin
- 'tier4_traffic_light_rviz_plugin': common/tier4_traffic_light_rviz_plugin
- 'tier4_vehicle_rviz_plugin': common/tier4_vehicle_rviz_plugin
- 'traffic_light_recognition_marker_publisher': common/traffic_light_recognition_marker_publisher/Readme
- 'Node':
- 'Goal Distance Calculator': common/goal_distance_calculator/Readme
- 'Path Distance Calculator': common/path_distance_calculator/Readme
- 'Others':
- 'autoware_ad_api_specs': common/autoware_ad_api_specs
- 'component_interface_specs': common/component_interface_specs
- 'component_interface_tools': common/component_interface_tools
- 'component_interface_utils': common/component_interface_utils
16 changes: 16 additions & 0 deletions common/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
# Common

## Getting Started

The Autoware.Universe Common folder consists of common and testing libraries that are used by other Autoware components, as well as useful plugins for visualization in RVIZ2.

!!! note

In addition to the ones listed in this folder, users can also have a look at some of the add-ons in the `autoware_tools/common` documentation [page](https://autowarefoundation.github.io/autoware_tools/main/common/mission_planner_rviz_plugin/).

## Highlights

Some of the commonly used libraries are:

1. `tier4_autoware_utils`
2. `motion_utils`
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
// Copyright 2024 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.

#ifndef AUTOWARE_AD_API_SPECS__SYSTEM_HPP_
#define AUTOWARE_AD_API_SPECS__SYSTEM_HPP_

#include <rclcpp/qos.hpp>

#include <autoware_adapi_v1_msgs/msg/heartbeat.hpp>

namespace autoware_ad_api::system
{

struct Heartbeat
{
using Message = autoware_adapi_v1_msgs::msg::Heartbeat;
static constexpr char name[] = "/api/system/heartbeat";
static constexpr size_t depth = 10;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

} // namespace autoware_ad_api::system

#endif // AUTOWARE_AD_API_SPECS__SYSTEM_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,9 @@ namespace types
// We don't currently require code to comply to MISRA, but we should try to where it is
// easily possible.
using bool8_t = bool;
#if __cplusplus < 201811L || !__cpp_char8_t
using char8_t = char;
#endif
using uchar8_t = unsigned char;
// If we ever compile on a platform where this is not true, float32_t and float64_t definitions
// need to be adjusted.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ using TimeStamp = builtin_interfaces::msg::Time;

/// \brief Helper class to check existence of header file in compile time:
/// https://stackoverflow.com/a/16000226/2325407
template <typename T, typename = nullptr_t>
template <typename T, typename = std::nullptr_t>
struct HasHeader : std::false_type
{
};
Expand All @@ -48,60 +48,60 @@ struct HasHeader<T, decltype((void)T::header, nullptr)> : std::true_type

/////////// Template declarations

/// Get frame id from message. nullptr_t is used to prevent template ambiguity on
/// Get frame id from message. std::nullptr_t is used to prevent template ambiguity on
/// SFINAE specializations. Provide a default value on specializations for a friendly API.
/// \tparam T Message type.
/// \param msg Message.
/// \return Frame id of the message.
template <typename T, nullptr_t>
template <typename T, std::nullptr_t>
const std::string & get_frame_id(const T & msg) noexcept;

/// Get a reference to the frame id from message. nullptr_t is used to prevent
/// Get a reference to the frame id from message. std::nullptr_t is used to prevent
/// template ambiguity on SFINAE specializations. Provide a default value on
/// specializations for a friendly API.
/// \tparam T Message type.
/// \param msg Message.
/// \return Frame id of the message.
template <typename T, nullptr_t>
template <typename T, std::nullptr_t>
std::string & get_frame_id(T & msg) noexcept;

/// Get stamp from message. nullptr_t is used to prevent template ambiguity on
/// Get stamp from message. std::nullptr_t is used to prevent template ambiguity on
/// SFINAE specializations. Provide a default value on specializations for a friendly API.
/// \tparam T Message type.
/// \param msg Message.
/// \return Frame id of the message.
template <typename T, nullptr_t>
template <typename T, std::nullptr_t>
const TimeStamp & get_stamp(const T & msg) noexcept;

/// Get a reference to the stamp from message. nullptr_t is used to prevent
/// Get a reference to the stamp from message. std::nullptr_t is used to prevent
/// template ambiguity on SFINAE specializations. Provide a default value on
/// specializations for a friendly API.
/// \tparam T Message type.
/// \param msg Message.
/// \return Frame id of the message.
template <typename T, nullptr_t>
template <typename T, std::nullptr_t>
TimeStamp & get_stamp(T & msg) noexcept;

/////////////// Default specializations for message types that contain a header.
template <class T, typename std::enable_if<HasHeader<T>::value, nullptr_t>::type = nullptr>
template <class T, typename std::enable_if<HasHeader<T>::value, std::nullptr_t>::type = nullptr>
const std::string & get_frame_id(const T & msg) noexcept
{
return msg.header.frame_id;
}

template <class T, typename std::enable_if<HasHeader<T>::value, nullptr_t>::type = nullptr>
template <class T, typename std::enable_if<HasHeader<T>::value, std::nullptr_t>::type = nullptr>
std::string & get_frame_id(T & msg) noexcept
{
return msg.header.frame_id;
}

template <class T, typename std::enable_if<HasHeader<T>::value, nullptr_t>::type = nullptr>
template <class T, typename std::enable_if<HasHeader<T>::value, std::nullptr_t>::type = nullptr>
TimeStamp & get_stamp(T & msg) noexcept
{
return msg.header.stamp;
}

template <class T, typename std::enable_if<HasHeader<T>::value, nullptr_t>::type = nullptr>
template <class T, typename std::enable_if<HasHeader<T>::value, std::nullptr_t>::type = nullptr>
TimeStamp get_stamp(const T & msg) noexcept
{
return msg.header.stamp;
Expand Down
39 changes: 0 additions & 39 deletions common/autoware_auto_geometry/CMakeLists.txt

This file was deleted.

Loading

0 comments on commit 5b9bf5c

Please sign in to comment.