Skip to content

Commit

Permalink
feat(autoware_universe_utils)!: rename from tier4_autoware_utils (#7538)
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
Co-authored-by: kosuke55 <kosuke.tnp@gmail.com>
  • Loading branch information
takayuki5168 and kosuke55 committed Jun 18, 2024
1 parent d9cf068 commit 7a3e6ed
Show file tree
Hide file tree
Showing 764 changed files with 4,126 additions and 4,011 deletions.
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ common/signal_processing/** ali.boyali@tier4.jp fumiya.watanabe@tier4.jp kyoichi
common/tensorrt_common/** dan.umeda@tier4.jp manato.hirabayashi@tier4.jp
common/tier4_adapi_rviz_plugin/** hiroki.ota@tier4.jp isamu.takagi@tier4.jp kosuke.takeuchi@tier4.jp
common/tier4_api_utils/** isamu.takagi@tier4.jp
common/tier4_autoware_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
common/autoware_universe_utils/** mamoru.sobue@tier4.jp takamasa.horibe@tier4.jp takayuki.murooka@tier4.jp
common/tier4_camera_view_rviz_plugin/** makoto.ybauta@tier4.jp uken.ryu@tier4.jp
common/tier4_datetime_rviz_plugin/** isamu.takagi@tier4.jp
common/tier4_localization_rviz_plugin/** isamu.takagi@tier4.jp takamasa.horibe@tier4.jp
Expand Down
2 changes: 1 addition & 1 deletion common/.pages
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ nav:
- 'Introduction': common/signal_processing
- 'Butterworth Filter': common/signal_processing/documentation/ButterworthFilter
- 'TensorRT Common': common/tensorrt_common
- 'tier4_autoware_utils': common/tier4_autoware_utils
- 'autoware_universe_utils': common/autoware_universe_utils
- 'traffic_light_utils': common/traffic_light_utils
- 'TVM Utility':
- 'Introduction': common/tvm_utility
Expand Down
2 changes: 1 addition & 1 deletion common/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,5 +12,5 @@ The Autoware.Universe Common folder consists of common and testing libraries tha

Some of the commonly used libraries are:

1. `tier4_autoware_utils`
1. `autoware_universe_utils`
2. `motion_utils`
2 changes: 1 addition & 1 deletion common/autoware_grid_map_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,10 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_universe_utils</depend>
<depend>grid_map_core</depend>
<depend>grid_map_cv</depend>
<depend>libopencv-dev</depend>
<depend>tier4_autoware_utils</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
4 changes: 2 additions & 2 deletions common/autoware_grid_map_utils/test/benchmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,13 +17,13 @@
#include "grid_map_cv/GridMapCvConverter.hpp"
#include "grid_map_cv/GridMapCvProcessing.hpp"

#include <autoware/universe_utils/system/stop_watch.hpp>
#include <grid_map_core/iterators/PolygonIterator.hpp>
#include <grid_map_cv/grid_map_cv.hpp>
#include <opencv2/core.hpp>
#include <opencv2/highgui.hpp>
#include <opencv2/imgproc.hpp>
#include <opencv2/opencv.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>

#include <algorithm>
#include <fstream>
Expand All @@ -46,7 +46,7 @@ int main(int argc, char * argv[])
result_file
<< "#Size PolygonVertices PolygonIndexes grid_map_utils_constructor grid_map_utils_iteration "
"grid_map_constructor grid_map_iteration\n";
tier4_autoware_utils::StopWatch<std::chrono::milliseconds> stopwatch;
autoware_universe_utils::StopWatch<std::chrono::milliseconds> stopwatch;

constexpr auto nb_iterations = 10;
constexpr auto polygon_side_vertices =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,8 @@

#include "autoware_grid_map_utils/polygon_iterator.hpp"

#include <autoware/universe_utils/system/stop_watch.hpp>
#include <grid_map_core/iterators/PolygonIterator.hpp>
#include <tier4_autoware_utils/system/stop_watch.hpp>

// gtest
#include <gtest/gtest.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@
#ifndef AUTOWARE_TEST_UTILS__AUTOWARE_TEST_UTILS_HPP_
#define AUTOWARE_TEST_UTILS__AUTOWARE_TEST_UTILS_HPP_

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <component_interface_specs/planning.hpp>
#include <lanelet2_extension/io/autoware_osm_parser.hpp>
#include <lanelet2_extension/projection/mgrs_projector.hpp>
#include <lanelet2_extension/utility/message_conversion.hpp>
#include <lanelet2_extension/utility/utilities.hpp>
#include <tier4_autoware_utils/geometry/geometry.hpp>

#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp>
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
Expand Down Expand Up @@ -62,6 +62,8 @@ using autoware_planning_msgs::msg::Trajectory;
using tier4_planning_msgs::msg::PathPointWithLaneId;
using tier4_planning_msgs::msg::PathWithLaneId;
using RouteSections = std::vector<autoware_planning_msgs::msg::LaneletSegment>;
using autoware_universe_utils::createPoint;
using autoware_universe_utils::createQuaternionFromRPY;
using geometry_msgs::msg::Point;
using geometry_msgs::msg::Pose;
using geometry_msgs::msg::PoseStamped;
Expand All @@ -70,8 +72,6 @@ using nav_msgs::msg::OccupancyGrid;
using nav_msgs::msg::Odometry;
using sensor_msgs::msg::PointCloud2;
using tf2_msgs::msg::TFMessage;
using tier4_autoware_utils::createPoint;
using tier4_autoware_utils::createQuaternionFromRPY;
using tier4_planning_msgs::msg::Scenario;
using unique_identifier_msgs::msg::UUID;

Expand Down
2 changes: 1 addition & 1 deletion common/autoware_test_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>autoware_map_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>component_interface_specs</depend>
<depend>component_interface_utils</depend>
Expand All @@ -29,7 +30,6 @@
<depend>tf2_msgs</depend>
<depend>tf2_ros</depend>
<depend>tier4_api_msgs</depend>
<depend>tier4_autoware_utils</depend>
<depend>tier4_planning_msgs</depend>
<depend>tier4_v2x_msgs</depend>
<depend>unique_identifier_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
cmake_minimum_required(VERSION 3.14)
project(tier4_autoware_utils)
project(autoware_universe_utils)

find_package(autoware_cmake REQUIRED)
autoware_package()

find_package(Boost REQUIRED)

ament_auto_add_library(tier4_autoware_utils SHARED
ament_auto_add_library(autoware_universe_utils SHARED
src/geometry/geometry.cpp
src/geometry/pose_deviation.cpp
src/geometry/boost_polygon_utils.cpp
Expand All @@ -23,10 +23,10 @@ if(BUILD_TESTING)

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

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

target_link_libraries(test_tier4_autoware_utils
tier4_autoware_utils
target_link_libraries(test_autoware_universe_utils
autoware_universe_utils
)
endif()

Expand Down
9 changes: 9 additions & 0 deletions common/autoware_universe_utils/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
# autoware_universe_utils

## Purpose

This package contains many common functions used by other packages, so please refer to them as needed.

## For developers

`autoware_universe_utils.hpp` header file was removed because the source files that directly/indirectly include this file took a long time for preprocessing.
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,8 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
#define TIER4_AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
#ifndef AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_

#include <boost/geometry/core/cs.hpp>
#include <boost/geometry/geometries/geometries.hpp>
Expand All @@ -25,7 +25,7 @@

#include <geometry_msgs/msg/point.hpp>

namespace tier4_autoware_utils
namespace autoware_universe_utils
{
// 2D
struct Point2d;
Expand Down Expand Up @@ -93,12 +93,12 @@ inline Point3d fromMsg(const geometry_msgs::msg::Point & msg)
point.z() = msg.z;
return point;
}
} // namespace tier4_autoware_utils
} // namespace autoware_universe_utils

BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLINT
tier4_autoware_utils::Point2d, double, cs::cartesian, x(), y()) // NOLINT
BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT
tier4_autoware_utils::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT
BOOST_GEOMETRY_REGISTER_RING(tier4_autoware_utils::LinearRing2d) // NOLINT
BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLINT
autoware_universe_utils::Point2d, double, cs::cartesian, x(), y()) // NOLINT
BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT
autoware_universe_utils::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT
BOOST_GEOMETRY_REGISTER_RING(autoware_universe_utils::LinearRing2d) // NOLINT

#endif // TIER4_AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_
#define TIER4_AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_
#ifndef AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_
#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_

#include "tier4_autoware_utils/geometry/boost_geometry.hpp"
#include "autoware/universe_utils/geometry/boost_geometry.hpp"

#include <autoware_perception_msgs/msg/detected_object.hpp>
#include <autoware_perception_msgs/msg/predicted_object.hpp>
Expand All @@ -24,7 +24,7 @@

#include <vector>

namespace tier4_autoware_utils
namespace autoware_universe_utils
{
bool isClockwise(const Polygon2d & polygon);
Polygon2d inverseClockwise(const Polygon2d & polygon);
Expand All @@ -47,6 +47,6 @@ Polygon2d toFootprint(
const double base_to_rear, const double width);
double getArea(const autoware_perception_msgs::msg::Shape & shape);
Polygon2d expandPolygon(const Polygon2d & input_polygon, const double offset);
} // namespace tier4_autoware_utils
} // namespace autoware_universe_utils

#endif // TIER4_AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_
#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_
#define TIER4_AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_
#ifndef AUTOWARE__UNIVERSE_UTILS__GEOMETRY__GEOMETRY_HPP_
#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__GEOMETRY_HPP_

#include "tier4_autoware_utils/geometry/boost_geometry.hpp"
#include "tier4_autoware_utils/math/constants.hpp"
#include "tier4_autoware_utils/math/normalization.hpp"
#include "tier4_autoware_utils/ros/msg_covariance.hpp"
#include "autoware/universe_utils/geometry/boost_geometry.hpp"
#include "autoware/universe_utils/math/constants.hpp"
#include "autoware/universe_utils/math/normalization.hpp"
#include "autoware/universe_utils/ros/msg_covariance.hpp"

#include <exception>
#include <string>
Expand Down Expand Up @@ -96,7 +96,7 @@ inline void doTransform(
#endif
} // namespace tf2

namespace tier4_autoware_utils
namespace autoware_universe_utils
{
template <class T>
geometry_msgs::msg::Point getPoint(const T & p)
Expand Down Expand Up @@ -577,6 +577,6 @@ std::optional<geometry_msgs::msg::Point> intersect(
const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2,
const geometry_msgs::msg::Point & p3, const geometry_msgs::msg::Point & p4);

} // namespace tier4_autoware_utils
} // namespace autoware_universe_utils

#endif // TIER4_AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_
#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__GEOMETRY_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_
#define TIER4_AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_
#ifndef AUTOWARE__UNIVERSE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_
#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_

#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/pose.hpp>

namespace tier4_autoware_utils
namespace autoware_universe_utils
{
struct PoseDeviation
{
Expand All @@ -39,6 +39,6 @@ double calcYawDeviation(
PoseDeviation calcPoseDeviation(
const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & target_pose);

} // namespace tier4_autoware_utils
} // namespace autoware_universe_utils

#endif // TIER4_AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_
#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,13 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__MATH__CONSTANTS_HPP_
#define TIER4_AUTOWARE_UTILS__MATH__CONSTANTS_HPP_
#ifndef AUTOWARE__UNIVERSE_UTILS__MATH__CONSTANTS_HPP_
#define AUTOWARE__UNIVERSE_UTILS__MATH__CONSTANTS_HPP_

namespace tier4_autoware_utils
namespace autoware_universe_utils
{
constexpr double pi = 3.14159265358979323846; // To be replaced by std::numbers::pi in C++20
constexpr double gravity = 9.80665;
} // namespace tier4_autoware_utils
} // namespace autoware_universe_utils

#endif // TIER4_AUTOWARE_UTILS__MATH__CONSTANTS_HPP_
#endif // AUTOWARE__UNIVERSE_UTILS__MATH__CONSTANTS_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,14 +12,14 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__MATH__NORMALIZATION_HPP_
#define TIER4_AUTOWARE_UTILS__MATH__NORMALIZATION_HPP_
#ifndef AUTOWARE__UNIVERSE_UTILS__MATH__NORMALIZATION_HPP_
#define AUTOWARE__UNIVERSE_UTILS__MATH__NORMALIZATION_HPP_

#include "tier4_autoware_utils/math/constants.hpp"
#include "autoware/universe_utils/math/constants.hpp"

#include <cmath>

namespace tier4_autoware_utils
namespace autoware_universe_utils
{
inline double normalizeDegree(const double deg, const double min_deg = -180)
{
Expand All @@ -45,6 +45,6 @@ inline double normalizeRadian(const double rad, const double min_rad = -pi)
return value - std::copysign(2 * pi, value);
}

} // namespace tier4_autoware_utils
} // namespace autoware_universe_utils

#endif // TIER4_AUTOWARE_UTILS__MATH__NORMALIZATION_HPP_
#endif // AUTOWARE__UNIVERSE_UTILS__MATH__NORMALIZATION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,15 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__MATH__RANGE_HPP_
#define TIER4_AUTOWARE_UTILS__MATH__RANGE_HPP_
#ifndef AUTOWARE__UNIVERSE_UTILS__MATH__RANGE_HPP_
#define AUTOWARE__UNIVERSE_UTILS__MATH__RANGE_HPP_

#include <cmath>
#include <limits>
#include <stdexcept>
#include <vector>

namespace tier4_autoware_utils
namespace autoware_universe_utils
{
template <class T>
std::vector<T> arange(const T start, const T stop, const T step = 1)
Expand Down Expand Up @@ -73,6 +73,6 @@ std::vector<double> linspace(const T start, const T stop, const size_t num)
return out;
}

} // namespace tier4_autoware_utils
} // namespace autoware_universe_utils

#endif // TIER4_AUTOWARE_UTILS__MATH__RANGE_HPP_
#endif // AUTOWARE__UNIVERSE_UTILS__MATH__RANGE_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -12,19 +12,19 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TIER4_AUTOWARE_UTILS__MATH__SIN_TABLE_HPP_
#define TIER4_AUTOWARE_UTILS__MATH__SIN_TABLE_HPP_
#ifndef AUTOWARE__UNIVERSE_UTILS__MATH__SIN_TABLE_HPP_
#define AUTOWARE__UNIVERSE_UTILS__MATH__SIN_TABLE_HPP_

#include <cstddef>

namespace tier4_autoware_utils
namespace autoware_universe_utils
{

constexpr size_t sin_table_size = 32769;
constexpr size_t discrete_arcs_num_90 = 32768;
constexpr size_t discrete_arcs_num_360 = 131072;
extern const float g_sin_table[sin_table_size];

} // namespace tier4_autoware_utils
} // namespace autoware_universe_utils

#endif // TIER4_AUTOWARE_UTILS__MATH__SIN_TABLE_HPP_
#endif // AUTOWARE__UNIVERSE_UTILS__MATH__SIN_TABLE_HPP_
Loading

0 comments on commit 7a3e6ed

Please sign in to comment.