Skip to content

Commit

Permalink
feat(autoware_utils): replace autoware_universe_utils with autoware_u…
Browse files Browse the repository at this point in the history
…tils (autowarefoundation#10191)

Signed-off-by: liuXinGangChina <[email protected]>
Signed-off-by: Ryohsuke Mitsudome <[email protected]>
  • Loading branch information
liuXinGangChina authored Feb 26, 2025
1 parent a0816b7 commit ece3809
Show file tree
Hide file tree
Showing 849 changed files with 7,327 additions and 7,571 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE__GOAL_DISTANCE_CALCULATOR__GOAL_DISTANCE_CALCULATOR_HPP_
#define AUTOWARE__GOAL_DISTANCE_CALCULATOR__GOAL_DISTANCE_CALCULATOR_HPP_

#include <autoware/universe_utils/geometry/pose_deviation.hpp>
#include <autoware_utils/geometry/pose_deviation.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_planning_msgs/msg/lanelet_route.hpp>
Expand All @@ -25,7 +25,7 @@

namespace autoware::goal_distance_calculator
{
using autoware::universe_utils::PoseDeviation;
using autoware_utils::PoseDeviation;

struct Param
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@

#include "autoware/goal_distance_calculator/goal_distance_calculator.hpp"

#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
#include <autoware/universe_utils/ros/self_pose_listener.hpp>
#include <autoware_utils/ros/debug_publisher.hpp>
#include <autoware_utils/ros/polling_subscriber.hpp>
#include <autoware_utils/ros/self_pose_listener.hpp>
#include <rclcpp/rclcpp.hpp>

#include <autoware_internal_debug_msgs/msg/float64_stamped.hpp>
Expand All @@ -45,12 +45,12 @@ class GoalDistanceCalculatorNode : public rclcpp::Node

private:
// Subscriber
autoware::universe_utils::SelfPoseListener self_pose_listener_;
autoware::universe_utils::InterProcessPollingSubscriber<autoware_planning_msgs::msg::LaneletRoute>
autoware_utils::SelfPoseListener self_pose_listener_;
autoware_utils::InterProcessPollingSubscriber<autoware_planning_msgs::msg::LaneletRoute>
sub_route_{this, "/planning/mission_planning/route"};

// Publisher
autoware::universe_utils::DebugPublisher debug_publisher_;
autoware_utils::DebugPublisher debug_publisher_;

// Timer
rclcpp::TimerBase::SharedPtr timer_;
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_goal_distance_calculator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@

<depend>autoware_internal_debug_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_utils</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ Output GoalDistanceCalculator::update(const Input & input)
Output output{};

output.goal_deviation =
autoware::universe_utils::calcPoseDeviation(input.route->goal_pose, input.current_pose->pose);
autoware_utils::calc_pose_deviation(input.route->goal_pose, input.current_pose->pose);

return output;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "autoware/goal_distance_calculator/goal_distance_calculator_node.hpp"

#include <autoware/universe_utils/math/unit_conversion.hpp>
#include <autoware_utils/math/unit_conversion.hpp>
#include <rclcpp/rclcpp.hpp>
#include <rclcpp/timer.hpp>

Expand Down Expand Up @@ -42,7 +42,7 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions
goal_distance_calculator_->setParam(param_);

// Wait for first self pose
self_pose_listener_.waitForFirstPose();
self_pose_listener_.wait_for_first_pose();

// Timer
const auto period_ns = rclcpp::Rate(node_param_.update_rate).period();
Expand All @@ -54,7 +54,7 @@ GoalDistanceCalculatorNode::GoalDistanceCalculatorNode(const rclcpp::NodeOptions
bool GoalDistanceCalculatorNode::tryGetCurrentPose(
geometry_msgs::msg::PoseStamped::ConstSharedPtr current_pose)
{
auto current_pose_tmp = self_pose_listener_.getCurrentPose();
auto current_pose_tmp = self_pose_listener_.get_current_pose();
if (!current_pose_tmp) return false;
current_pose = current_pose_tmp;
return true;
Expand All @@ -63,7 +63,7 @@ bool GoalDistanceCalculatorNode::tryGetCurrentPose(
bool GoalDistanceCalculatorNode::tryGetRoute(
autoware_planning_msgs::msg::LaneletRoute::ConstSharedPtr route)
{
auto route_tmp = sub_route_.takeData();
auto route_tmp = sub_route_.take_data();
if (!route_tmp) return false;
route = route_tmp;
return true;
Expand Down Expand Up @@ -97,7 +97,7 @@ void GoalDistanceCalculatorNode::onTimer()
Output output = goal_distance_calculator_->update(input);

{
using autoware::universe_utils::rad2deg;
using autoware_utils::rad2deg;
const auto & deviation = output.goal_deviation;

debug_publisher_.publish<autoware_internal_debug_msgs::msg::Float64Stamped>(
Expand Down
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,7 +10,7 @@
<buildtool_depend>autoware_cmake</buildtool_depend>
<buildtool_depend>eigen3_cmake_module</buildtool_depend>

<depend>autoware_universe_utils</depend>
<depend>autoware_utils</depend>
<depend>grid_map_core</depend>
<depend>grid_map_cv</depend>
<depend>libopencv-dev</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,7 +17,7 @@
#include "grid_map_cv/GridMapCvConverter.hpp"
#include "grid_map_cv/GridMapCvProcessing.hpp"

#include <autoware/universe_utils/system/stop_watch.hpp>
#include <autoware_utils/system/stop_watch.hpp>
#include <grid_map_core/iterators/PolygonIterator.hpp>
#include <grid_map_cv/grid_map_cv.hpp>
#include <opencv2/core.hpp>
Expand Down Expand Up @@ -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";
autoware::universe_utils::StopWatch<std::chrono::milliseconds> stopwatch;
autoware_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,7 +14,7 @@

#include "autoware/grid_map_utils/polygon_iterator.hpp"

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

// gtest
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@
#define AUTOWARE__OBJECT_RECOGNITION_UTILS__MATCHING_HPP_

#include "autoware/object_recognition_utils/geometry.hpp"
#include "autoware/universe_utils/geometry/boost_geometry.hpp"
#include "autoware/universe_utils/geometry/boost_polygon_utils.hpp"
#include "autoware_utils/geometry/boost_geometry.hpp"
#include "autoware_utils/geometry/boost_polygon_utils.hpp"

#include <boost/geometry.hpp>

Expand All @@ -28,7 +28,7 @@

namespace autoware::object_recognition_utils
{
using autoware::universe_utils::Polygon2d;
using autoware_utils::Polygon2d;
// minimum area to avoid division by zero
static const double MIN_AREA = 1e-6;

Expand All @@ -37,7 +37,7 @@ inline double getConvexShapeArea(const Polygon2d & source_polygon, const Polygon
boost::geometry::model::multi_polygon<Polygon2d> union_polygons;
boost::geometry::union_(source_polygon, target_polygon, union_polygons);

autoware::universe_utils::Polygon2d hull;
autoware_utils::Polygon2d hull;
boost::geometry::convex_hull(union_polygons, hull);
return boost::geometry::area(hull);
}
Expand Down Expand Up @@ -67,9 +67,9 @@ inline double getUnionArea(const Polygon2d & source_polygon, const Polygon2d & t
template <class T1, class T2>
double get2dIoU(const T1 source_object, const T2 target_object, const double min_union_area = 0.01)
{
const auto source_polygon = autoware::universe_utils::toPolygon2d(source_object);
const auto source_polygon = autoware_utils::to_polygon2d(source_object);
if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0;
const auto target_polygon = autoware::universe_utils::toPolygon2d(target_object);
const auto target_polygon = autoware_utils::to_polygon2d(target_object);
if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0;

const double intersection_area = getIntersectionArea(source_polygon, target_polygon);
Expand All @@ -84,9 +84,9 @@ double get2dIoU(const T1 source_object, const T2 target_object, const double min
template <class T1, class T2>
double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object)
{
const auto source_polygon = autoware::universe_utils::toPolygon2d(source_object);
const auto source_polygon = autoware_utils::to_polygon2d(source_object);
if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0;
const auto target_polygon = autoware::universe_utils::toPolygon2d(target_object);
const auto target_polygon = autoware_utils::to_polygon2d(target_object);
if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0;

const double intersection_area = getIntersectionArea(source_polygon, target_polygon);
Expand All @@ -100,10 +100,10 @@ double get2dGeneralizedIoU(const T1 & source_object, const T2 & target_object)
template <class T1, class T2>
double get2dPrecision(const T1 source_object, const T2 target_object)
{
const auto source_polygon = autoware::universe_utils::toPolygon2d(source_object);
const auto source_polygon = autoware_utils::to_polygon2d(source_object);
const double source_area = boost::geometry::area(source_polygon);
if (source_area < MIN_AREA) return 0.0;
const auto target_polygon = autoware::universe_utils::toPolygon2d(target_object);
const auto target_polygon = autoware_utils::to_polygon2d(target_object);
if (boost::geometry::area(target_polygon) < MIN_AREA) return 0.0;

const double intersection_area = getIntersectionArea(source_polygon, target_polygon);
Expand All @@ -115,9 +115,9 @@ double get2dPrecision(const T1 source_object, const T2 target_object)
template <class T1, class T2>
double get2dRecall(const T1 source_object, const T2 target_object)
{
const auto source_polygon = autoware::universe_utils::toPolygon2d(source_object);
const auto source_polygon = autoware_utils::to_polygon2d(source_object);
if (boost::geometry::area(source_polygon) < MIN_AREA) return 0.0;
const auto target_polygon = autoware::universe_utils::toPolygon2d(target_object);
const auto target_polygon = autoware_utils::to_polygon2d(target_object);
const double target_area = boost::geometry::area(target_polygon);
if (target_area < MIN_AREA) return 0.0;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE__OBJECT_RECOGNITION_UTILS__PREDICTED_PATH_UTILS_HPP_
#define AUTOWARE__OBJECT_RECOGNITION_UTILS__PREDICTED_PATH_UTILS_HPP_

#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware_utils/geometry/geometry.hpp"

#include <autoware_perception_msgs/msg/predicted_path.hpp>
#include <geometry_msgs/msg/pose.hpp>
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_object_recognition_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@

<depend>autoware_interpolation</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_utils</depend>
<depend>geometry_msgs</depend>
<depend>libboost-dev</depend>
<depend>pcl_conversions</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ boost::optional<geometry_msgs::msg::Pose> calcInterpolatedPose(
if (relative_time - epsilon < time_step * path_idx) {
const double offset = relative_time - time_step * (path_idx - 1);
const double ratio = std::clamp(offset / time_step, 0.0, 1.0);
return autoware::universe_utils::calcInterpolatedPose(prev_pt, pt, ratio, false);
return autoware_utils::calc_interpolated_pose(prev_pt, pt, ratio, false);
}
}

Expand Down Expand Up @@ -91,7 +91,7 @@ autoware_perception_msgs::msg::PredictedPath resamplePredictedPath(

// Set Position
for (size_t i = 0; i < resampled_size; ++i) {
const auto p = autoware::universe_utils::createPoint(
const auto p = autoware_utils::create_point(
interpolated_x.at(i), interpolated_y.at(i), interpolated_z.at(i));
resampled_path.path.at(i).position = p;
resampled_path.path.at(i).orientation = interpolated_quat.at(i);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
// limitations under the License.

#include "autoware/object_recognition_utils/conversion.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware_utils/geometry/geometry.hpp"

#include <gtest/gtest.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,14 @@
// limitations under the License.

#include "autoware/object_recognition_utils/matching.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware_utils/geometry/geometry.hpp"

#include <autoware_perception_msgs/msg/detected_object.hpp>

#include <gtest/gtest.h>

using autoware::universe_utils::Point2d;
using autoware::universe_utils::Point3d;
using autoware_utils::Point2d;
using autoware_utils::Point3d;

constexpr double epsilon = 1e-06;

Expand All @@ -30,7 +30,7 @@ geometry_msgs::msg::Pose createPose(const double x, const double y, const double
{
geometry_msgs::msg::Pose p;
p.position = geometry_msgs::build<geometry_msgs::msg::Point>().x(x).y(y).z(0.0);
p.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw);
p.orientation = autoware_utils::create_quaternion_from_yaw(yaw);
return p;
}
} // namespace
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,33 +13,33 @@
// limitations under the License.

#include "autoware/object_recognition_utils/predicted_path_utils.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware/universe_utils/math/unit_conversion.hpp"
#include "autoware_utils/geometry/geometry.hpp"
#include "autoware_utils/math/unit_conversion.hpp"

#include <boost/optional/optional_io.hpp>

#include <gtest/gtest.h>

#include <vector>

using autoware::universe_utils::Point2d;
using autoware::universe_utils::Point3d;
using autoware_utils::Point2d;
using autoware_utils::Point3d;

constexpr double epsilon = 1e-06;

namespace
{
using autoware::universe_utils::createPoint;
using autoware::universe_utils::createQuaternionFromRPY;
using autoware::universe_utils::transformPoint;
using autoware_perception_msgs::msg::PredictedPath;
using autoware_utils::create_point;
using autoware_utils::create_quaternion_from_rpy;
using autoware_utils::transform_point;

geometry_msgs::msg::Pose createPose(
double x, double y, double z, double roll, double pitch, double yaw)
{
geometry_msgs::msg::Pose p;
p.position = createPoint(x, y, z);
p.orientation = createQuaternionFromRPY(roll, pitch, yaw);
p.position = create_point(x, y, z);
p.orientation = create_quaternion_from_rpy(roll, pitch, yaw);
return p;
}

Expand Down Expand Up @@ -67,15 +67,15 @@ PredictedPath createTestPredictedPath(
TEST(predicted_path_utils, testCalcInterpolatedPose)
{
using autoware::object_recognition_utils::calcInterpolatedPose;
using autoware::universe_utils::createQuaternionFromRPY;
using autoware::universe_utils::createQuaternionFromYaw;
using autoware::universe_utils::deg2rad;
using autoware_utils::create_quaternion_from_rpy;
using autoware_utils::create_quaternion_from_yaw;
using autoware_utils::deg2rad;

const auto path = createTestPredictedPath(100, 0.1, 1.0);

// Normal Case (same point as the original point)
{
const auto ans_quat = createQuaternionFromRPY(deg2rad(0.0), deg2rad(0.0), deg2rad(0.0));
const auto ans_quat = create_quaternion_from_rpy(deg2rad(0.0), deg2rad(0.0), deg2rad(0.0));
for (double t = 0.0; t < 9.0 + 1e-6; t += 1.0) {
const auto p = calcInterpolatedPose(path, t);

Expand All @@ -92,7 +92,7 @@ TEST(predicted_path_utils, testCalcInterpolatedPose)

// Normal Case (random case)
{
const auto ans_quat = createQuaternionFromRPY(deg2rad(0.0), deg2rad(0.0), deg2rad(0.0));
const auto ans_quat = create_quaternion_from_rpy(deg2rad(0.0), deg2rad(0.0), deg2rad(0.0));
for (double t = 0.0; t < 9.0; t += 0.3) {
const auto p = calcInterpolatedPose(path, t);

Expand Down Expand Up @@ -133,9 +133,9 @@ TEST(predicted_path_utils, testCalcInterpolatedPose)
TEST(predicted_path_utils, resamplePredictedPath_by_vector)
{
using autoware::object_recognition_utils::resamplePredictedPath;
using autoware::universe_utils::createQuaternionFromRPY;
using autoware::universe_utils::createQuaternionFromYaw;
using autoware::universe_utils::deg2rad;
using autoware_utils::create_quaternion_from_rpy;
using autoware_utils::create_quaternion_from_yaw;
using autoware_utils::deg2rad;

const auto path = createTestPredictedPath(10, 1.0, 1.0);

Expand Down Expand Up @@ -210,9 +210,9 @@ TEST(predicted_path_utils, resamplePredictedPath_by_vector)
TEST(predicted_path_utils, resamplePredictedPath_by_sampling_time)
{
using autoware::object_recognition_utils::resamplePredictedPath;
using autoware::universe_utils::createQuaternionFromRPY;
using autoware::universe_utils::createQuaternionFromYaw;
using autoware::universe_utils::deg2rad;
using autoware_utils::create_quaternion_from_rpy;
using autoware_utils::create_quaternion_from_yaw;
using autoware_utils::deg2rad;

const auto path = createTestPredictedPath(10, 1.0, 1.0);

Expand Down
Loading

0 comments on commit ece3809

Please sign in to comment.