Skip to content

Commit

Permalink
Merge pull request #1878 from mitsudome-r/beta-0.41-replace-autoware-…
Browse files Browse the repository at this point in the history
…universe-utils

feat: replace autoware_universe_utils with autoware_utils
  • Loading branch information
rej55 authored Feb 27, 2025
2 parents 998ad18 + df5688b commit 64eaa47
Show file tree
Hide file tree
Showing 898 changed files with 8,305 additions and 8,531 deletions.
2 changes: 1 addition & 1 deletion build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ repositories:
core/autoware_utils:
type: git
url: https://github.com/autowarefoundation/autoware_utils.git
version: 1.0.0
version: 1.1.0
core/autoware_lanelet2_extension:
type: git
url: https://github.com/autowarefoundation/autoware_lanelet2_extension.git
Expand Down
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,7 +16,7 @@
#define AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_HPP_

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

#include <Eigen/Core>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class SplineInterpolationPoints2d
{
std::vector<geometry_msgs::msg::Point> points_inner;
for (const auto & p : points) {
points_inner.push_back(autoware::universe_utils::getPoint(p));
points_inner.push_back(autoware_utils::get_point(p));
}
calcSplineCoefficientsInner(points_inner);
}
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_interpolation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_universe_utils</depend>
<depend>autoware_utils</depend>
<depend>eigen</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,8 +89,7 @@ geometry_msgs::msg::Pose SplineInterpolationPoints2d::getSplineInterpolatedPose(
{
geometry_msgs::msg::Pose pose;
pose.position = getSplineInterpolatedPoint(idx, s);
pose.orientation =
autoware::universe_utils::createQuaternionFromYaw(getSplineInterpolatedYaw(idx, s));
pose.orientation = autoware_utils::create_quaternion_from_yaw(getSplineInterpolatedYaw(idx, s));
return pose;
}

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

#include "autoware/interpolation/spline_interpolation.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 @@ -14,7 +14,7 @@

#include "autoware/interpolation/spline_interpolation.hpp"
#include "autoware/interpolation/spline_interpolation_points_2d.hpp"
#include "autoware/universe_utils/geometry/geometry.hpp"
#include "autoware_utils/geometry/geometry.hpp"

#include <gtest/gtest.h>

Expand All @@ -27,15 +27,15 @@ using autoware::interpolation::SplineInterpolationPoints2d;

TEST(spline_interpolation, splineYawFromPoints)
{
using autoware::universe_utils::createPoint;
using autoware_utils::create_point;

{ // straight
std::vector<geometry_msgs::msg::Point> points;
points.push_back(createPoint(0.0, 0.0, 0.0));
points.push_back(createPoint(1.0, 1.5, 0.0));
points.push_back(createPoint(2.0, 3.0, 0.0));
points.push_back(createPoint(3.0, 4.5, 0.0));
points.push_back(createPoint(4.0, 6.0, 0.0));
points.push_back(create_point(0.0, 0.0, 0.0));
points.push_back(create_point(1.0, 1.5, 0.0));
points.push_back(create_point(2.0, 3.0, 0.0));
points.push_back(create_point(3.0, 4.5, 0.0));
points.push_back(create_point(4.0, 6.0, 0.0));

const std::vector<double> ans{0.9827937, 0.9827937, 0.9827937, 0.9827937, 0.9827937};

Expand All @@ -47,11 +47,11 @@ TEST(spline_interpolation, splineYawFromPoints)

{ // curve
std::vector<geometry_msgs::msg::Point> points;
points.push_back(createPoint(-2.0, -10.0, 0.0));
points.push_back(createPoint(2.0, 1.5, 0.0));
points.push_back(createPoint(3.0, 3.0, 0.0));
points.push_back(createPoint(5.0, 10.0, 0.0));
points.push_back(createPoint(10.0, 12.5, 0.0));
points.push_back(create_point(-2.0, -10.0, 0.0));
points.push_back(create_point(2.0, 1.5, 0.0));
points.push_back(create_point(3.0, 3.0, 0.0));
points.push_back(create_point(5.0, 10.0, 0.0));
points.push_back(create_point(10.0, 12.5, 0.0));

const std::vector<double> ans{1.368174, 0.961318, 1.086098, 0.938357, 0.278594};
const auto yaws = autoware::interpolation::splineYawFromPoints(points);
Expand All @@ -62,15 +62,15 @@ TEST(spline_interpolation, splineYawFromPoints)

{ // size of base_keys is 1 (infeasible to interpolate)
std::vector<geometry_msgs::msg::Point> points;
points.push_back(createPoint(1.0, 0.0, 0.0));
points.push_back(create_point(1.0, 0.0, 0.0));

EXPECT_THROW(autoware::interpolation::splineYawFromPoints(points), std::logic_error);
}

{ // straight: size of base_keys is 2 (edge case in the implementation)
std::vector<geometry_msgs::msg::Point> points;
points.push_back(createPoint(1.0, 0.0, 0.0));
points.push_back(createPoint(2.0, 1.5, 0.0));
points.push_back(create_point(1.0, 0.0, 0.0));
points.push_back(create_point(2.0, 1.5, 0.0));

const std::vector<double> ans{0.9827937, 0.9827937};

Expand All @@ -82,9 +82,9 @@ TEST(spline_interpolation, splineYawFromPoints)

{ // straight: size of base_keys is 3 (edge case in the implementation)
std::vector<geometry_msgs::msg::Point> points;
points.push_back(createPoint(1.0, 0.0, 0.0));
points.push_back(createPoint(2.0, 1.5, 0.0));
points.push_back(createPoint(3.0, 3.0, 0.0));
points.push_back(create_point(1.0, 0.0, 0.0));
points.push_back(create_point(2.0, 1.5, 0.0));
points.push_back(create_point(3.0, 3.0, 0.0));

const std::vector<double> ans{0.9827937, 0.9827937, 0.9827937};

Expand All @@ -97,15 +97,15 @@ TEST(spline_interpolation, splineYawFromPoints)

TEST(spline_interpolation, SplineInterpolationPoints2d)
{
using autoware::universe_utils::createPoint;
using autoware_utils::create_point;

// curve
std::vector<geometry_msgs::msg::Point> points;
points.push_back(createPoint(-2.0, -10.0, 0.0));
points.push_back(createPoint(2.0, 1.5, 0.0));
points.push_back(createPoint(3.0, 3.0, 0.0));
points.push_back(createPoint(5.0, 10.0, 0.0));
points.push_back(createPoint(10.0, 12.5, 0.0));
points.push_back(create_point(-2.0, -10.0, 0.0));
points.push_back(create_point(2.0, 1.5, 0.0));
points.push_back(create_point(3.0, 3.0, 0.0));
points.push_back(create_point(5.0, 10.0, 0.0));
points.push_back(create_point(10.0, 12.5, 0.0));

SplineInterpolationPoints2d s(points);

Expand Down Expand Up @@ -194,19 +194,19 @@ TEST(spline_interpolation, SplineInterpolationPoints2d)

// size of base_keys is 1 (infeasible to interpolate)
std::vector<geometry_msgs::msg::Point> single_points;
single_points.push_back(createPoint(1.0, 0.0, 0.0));
single_points.push_back(create_point(1.0, 0.0, 0.0));
EXPECT_THROW(SplineInterpolationPoints2d{single_points}, std::logic_error);
}

TEST(spline_interpolation, SplineInterpolationPoints2dPolymorphism)
{
using autoware::universe_utils::createPoint;
using autoware_planning_msgs::msg::TrajectoryPoint;
using autoware_utils::create_point;

std::vector<geometry_msgs::msg::Point> points;
points.push_back(createPoint(-2.0, -10.0, 0.0));
points.push_back(createPoint(2.0, 1.5, 0.0));
points.push_back(createPoint(3.0, 3.0, 0.0));
points.push_back(create_point(-2.0, -10.0, 0.0));
points.push_back(create_point(2.0, 1.5, 0.0));
points.push_back(create_point(3.0, 3.0, 0.0));

std::vector<TrajectoryPoint> trajectory_points;
for (const auto & p : points) {
Expand Down
4 changes: 2 additions & 2 deletions common/autoware_motion_utils/docs/vehicle/vehicle.md
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ bool isVehicleStopped(const double stop_duration)
Necessary includes:
```c++
#include <autoware/universe_utils/vehicle/vehicle_state_checker.hpp>
#include <autoware_utils/vehicle/vehicle_state_checker.hpp>
```

1.Create a checker instance.
Expand Down Expand Up @@ -116,7 +116,7 @@ bool isVehicleStoppedAtStopPoint(const double stop_duration)
Necessary includes:

```c++
#include <autoware/universe_utils/vehicle/vehicle_state_checker.hpp>
#include <autoware_utils/vehicle/vehicle_state_checker.hpp>
```

1.Create a checker instance.
Expand Down
Loading

0 comments on commit 64eaa47

Please sign in to comment.