Skip to content

Commit aa5ed51

Browse files
author
github-actions
committed
feat(deviation_estimator): replace autoware_universe_utils with specific autoware_utils sub-packages
Migrates all autoware_universe_utils usages in the deviation_estimator package to the specific autoware_utils sub-packages, as part of the autoware_universe_utils deprecation tracked in autowarefoundation/autoware_universe#12376. Changes: - package.xml: - <depend>autoware_universe_utils</depend> removed - Added <depend>autoware_utils_geometry</depend> - Added <depend>autoware_utils_math</depend> - Added <depend>autoware_utils_tf</depend> - Header includes swapped (in internal wrapper, source, and test files): - autoware/universe_utils/geometry/geometry.hpp -> autoware_utils_geometry/geometry.hpp - autoware/universe_utils/math/constants.hpp -> autoware_utils_math/constants.hpp - autoware/universe_utils/math/normalization.hpp -> autoware_utils_math/normalization.hpp - autoware/universe_utils/ros/transform_listener.hpp -> autoware_utils_tf/transform_listener.hpp - Geometry symbols (autoware_utils_geometry::): - getPose -> get_pose - getPoint -> get_point - getRPY -> get_rpy - createPoint -> create_point - calcAzimuthAngle -> calc_azimuth_angle - calcDistance2d -> calc_distance2d - calcElevationAngle -> calc_elevation_angle - createQuaternionFromRPY -> create_quaternion_from_rpy - Math symbols (autoware_utils_math::): - normalizeRadian -> normalize_radian - pi (name unchanged) - TF symbols (autoware_utils_tf::): - TransformListener (name unchanged) The internal wrapper header (include/deviation_estimator/autoware_universe_utils.hpp) keeps its filename since it is referenced by utils.hpp as the package's public-facing helper. Only its internal includes and symbol references are migrated. The tf2_ros::TransformListener in deviation_estimator.hpp is intentionally left unchanged as it is a tf2 API, not an autoware API. Signed-off-by: github-actions <github-actions@github.com>
1 parent 700c544 commit aa5ed51

9 files changed

Lines changed: 42 additions & 40 deletions

File tree

localization/deviation_estimation_tools/deviation_estimator/include/deviation_estimator/autoware_universe_utils.hpp

Lines changed: 24 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@
1515
#ifndef DEVIATION_ESTIMATOR__AUTOWARE_UNIVERSE_UTILS_HPP_
1616
#define DEVIATION_ESTIMATOR__AUTOWARE_UNIVERSE_UTILS_HPP_
1717

18-
#include "autoware/universe_utils/geometry/geometry.hpp"
19-
#include "autoware/universe_utils/math/constants.hpp"
20-
#include "autoware/universe_utils/math/normalization.hpp"
18+
#include <autoware_utils_geometry/geometry.hpp>
19+
#include <autoware_utils_math/constants.hpp>
20+
#include <autoware_utils_math/normalization.hpp>
2121

2222
#include <tf2/utils.h>
2323

@@ -38,11 +38,11 @@ template <class Pose1, class Pose2>
3838
bool isDrivingForward(const Pose1 & src_pose, const Pose2 & dst_pose)
3939
{
4040
// check the first point direction
41-
const double src_yaw = tf2::getYaw(autoware::universe_utils::getPose(src_pose).orientation);
42-
const double pose_direction_yaw = autoware::universe_utils::calcAzimuthAngle(
43-
autoware::universe_utils::getPoint(src_pose), autoware::universe_utils::getPoint(dst_pose));
44-
return std::fabs(autoware::universe_utils::normalizeRadian(src_yaw - pose_direction_yaw)) <
45-
autoware::universe_utils::pi / 2.0;
41+
const double src_yaw = tf2::getYaw(autoware_utils_geometry::get_pose(src_pose).orientation);
42+
const double pose_direction_yaw = autoware_utils_geometry::calc_azimuth_angle(
43+
autoware_utils_geometry::get_point(src_pose), autoware_utils_geometry::get_point(dst_pose));
44+
return std::fabs(autoware_utils_math::normalize_radian(src_yaw - pose_direction_yaw)) <
45+
autoware_utils_math::pi / 2.0;
4646
}
4747

4848
/**
@@ -56,8 +56,8 @@ template <class Point1, class Point2>
5656
geometry_msgs::msg::Point calcInterpolatedPoint(
5757
const Point1 & src, const Point2 & dst, const double ratio)
5858
{
59-
const auto src_point = autoware::universe_utils::getPoint(src);
60-
const auto dst_point = autoware::universe_utils::getPoint(dst);
59+
const auto src_point = autoware_utils_geometry::get_point(src);
60+
const auto dst_point = autoware_utils_geometry::get_point(dst);
6161

6262
tf2::Vector3 src_vec;
6363
src_vec.setX(src_point.x);
@@ -101,35 +101,35 @@ geometry_msgs::msg::Pose calcInterpolatedPose(
101101

102102
geometry_msgs::msg::Pose output_pose;
103103
output_pose.position = calcInterpolatedPoint(
104-
autoware::universe_utils::getPoint(src_pose), autoware::universe_utils::getPoint(dst_pose),
104+
autoware_utils_geometry::get_point(src_pose), autoware_utils_geometry::get_point(dst_pose),
105105
clamped_ratio);
106106

107107
if (set_orientation_from_position_direction) {
108-
const double input_poses_dist = autoware::universe_utils::calcDistance2d(
109-
autoware::universe_utils::getPoint(src_pose), autoware::universe_utils::getPoint(dst_pose));
108+
const double input_poses_dist = autoware_utils_geometry::calc_distance2d(
109+
autoware_utils_geometry::get_point(src_pose), autoware_utils_geometry::get_point(dst_pose));
110110
const bool is_driving_forward = isDrivingForward(src_pose, dst_pose);
111111

112112
// Get orientation from interpolated point and src_pose
113113
if ((is_driving_forward && clamped_ratio > 1.0 - (1e-6)) || input_poses_dist < 1e-3) {
114-
output_pose.orientation = autoware::universe_utils::getPose(dst_pose).orientation;
114+
output_pose.orientation = autoware_utils_geometry::get_pose(dst_pose).orientation;
115115
} else if (!is_driving_forward && clamped_ratio < 1e-6) {
116-
output_pose.orientation = autoware::universe_utils::getPose(src_pose).orientation;
116+
output_pose.orientation = autoware_utils_geometry::get_pose(src_pose).orientation;
117117
} else {
118118
const auto & base_pose = is_driving_forward ? dst_pose : src_pose;
119-
const double pitch = autoware::universe_utils::calcElevationAngle(
120-
autoware::universe_utils::getPoint(output_pose),
121-
autoware::universe_utils::getPoint(base_pose));
122-
const double yaw = autoware::universe_utils::calcAzimuthAngle(
123-
autoware::universe_utils::getPoint(output_pose),
124-
autoware::universe_utils::getPoint(base_pose));
125-
output_pose.orientation = autoware::universe_utils::createQuaternionFromRPY(0.0, pitch, yaw);
119+
const double pitch = autoware_utils_geometry::calc_elevation_angle(
120+
autoware_utils_geometry::get_point(output_pose),
121+
autoware_utils_geometry::get_point(base_pose));
122+
const double yaw = autoware_utils_geometry::calc_azimuth_angle(
123+
autoware_utils_geometry::get_point(output_pose),
124+
autoware_utils_geometry::get_point(base_pose));
125+
output_pose.orientation = autoware_utils_geometry::create_quaternion_from_rpy(0.0, pitch, yaw);
126126
}
127127
} else {
128128
// Get orientation by spherical linear interpolation
129129
tf2::Transform src_tf;
130130
tf2::Transform dst_tf;
131-
tf2::fromMsg(autoware::universe_utils::getPose(src_pose), src_tf);
132-
tf2::fromMsg(autoware::universe_utils::getPose(dst_pose), dst_tf);
131+
tf2::fromMsg(autoware_utils_geometry::get_pose(src_pose), src_tf);
132+
tf2::fromMsg(autoware_utils_geometry::get_pose(dst_pose), dst_tf);
133133
const auto & quaternion = tf2::slerp(src_tf.getRotation(), dst_tf.getRotation(), clamped_ratio);
134134
output_pose.orientation = tf2::toMsg(quaternion);
135135
}

localization/deviation_estimation_tools/deviation_estimator/include/deviation_estimator/deviation_estimator.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
#ifndef DEVIATION_ESTIMATOR__DEVIATION_ESTIMATOR_HPP_
1616
#define DEVIATION_ESTIMATOR__DEVIATION_ESTIMATOR_HPP_
1717

18-
#include "autoware/universe_utils/ros/transform_listener.hpp"
18+
#include <autoware_utils_tf/transform_listener.hpp>
1919
#include "deviation_estimator/gyro_bias_module.hpp"
2020
#include "deviation_estimator/logger.hpp"
2121
#include "deviation_estimator/utils.hpp"
@@ -103,7 +103,7 @@ class DeviationEstimator : public rclcpp::Node
103103
std::unique_ptr<VelocityCoefModule> vel_coef_module_;
104104
std::unique_ptr<ValidationModule> validation_module_;
105105

106-
std::shared_ptr<autoware::universe_utils::TransformListener> transform_listener_;
106+
std::shared_ptr<autoware_utils_tf::TransformListener> transform_listener_;
107107

108108
void callback_pose_with_covariance(geometry_msgs::msg::PoseWithCovarianceStamped::SharedPtr msg);
109109

localization/deviation_estimation_tools/deviation_estimator/package.xml

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,9 @@
1313
<build_depend>autoware_cmake</build_depend>
1414

1515
<depend>autoware_internal_debug_msgs</depend>
16-
<depend>autoware_universe_utils</depend>
16+
<depend>autoware_utils_geometry</depend>
17+
<depend>autoware_utils_math</depend>
18+
<depend>autoware_utils_tf</depend>
1719
<depend>autoware_vehicle_msgs</depend>
1820
<depend>geometry_msgs</depend>
1921
<depend>nav_msgs</depend>

localization/deviation_estimation_tools/deviation_estimator/src/deviation_estimator.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
#include "deviation_estimator/deviation_estimator.hpp"
1616

17-
#include "autoware/universe_utils/geometry/geometry.hpp"
17+
#include <autoware_utils_geometry/geometry.hpp>
1818
#include "deviation_estimator/logger.hpp"
1919
#include "deviation_estimator/utils.hpp"
2020
#include "rclcpp/logging.hpp"
@@ -178,7 +178,7 @@ DeviationEstimator::DeviationEstimator(
178178
declare_parameter<double>("thres_coef_vx"), declare_parameter<double>("thres_stddev_vx"),
179179
declare_parameter<double>("thres_bias_gyro"), declare_parameter<double>("thres_stddev_gyro"),
180180
5);
181-
transform_listener_ = std::make_shared<autoware::universe_utils::TransformListener>(this);
181+
transform_listener_ = std::make_shared<autoware_utils_tf::TransformListener>(this);
182182

183183
RCLCPP_INFO(this->get_logger(), "[Deviation Estimator] launch success");
184184
}

localization/deviation_estimation_tools/deviation_estimator/src/gyro_bias_module.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
#include "deviation_estimator/gyro_bias_module.hpp"
1616

17-
#include "autoware/universe_utils/geometry/geometry.hpp"
17+
#include <autoware_utils_geometry/geometry.hpp>
1818
#include "deviation_estimator/utils.hpp"
1919

2020
#include <vector>

localization/deviation_estimation_tools/deviation_estimator/src/utils.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
#include "deviation_estimator/utils.hpp"
1616

17-
#include "autoware/universe_utils/geometry/geometry.hpp"
17+
#include <autoware_utils_geometry/geometry.hpp>
1818
#include "rclcpp/rclcpp.hpp"
1919

2020
#include <tf2/LinearMath/Quaternion.h>
@@ -93,7 +93,7 @@ geometry_msgs::msg::Point integrate_position(
9393
{
9494
double t_prev = rclcpp::Time(vx_list.front().stamp).seconds();
9595
double yaw = yaw_init;
96-
geometry_msgs::msg::Point d_pos = autoware::universe_utils::createPoint(0.0, 0.0, 0.0);
96+
geometry_msgs::msg::Point d_pos = autoware_utils_geometry::create_point(0.0, 0.0, 0.0);
9797
for (std::size_t i = 0; i < vx_list.size() - 1; ++i) {
9898
const double t_cur = rclcpp::Time(vx_list[i + 1].stamp).seconds();
9999
const geometry_msgs::msg::Vector3 gyro_interpolated =
@@ -118,9 +118,9 @@ geometry_msgs::msg::Vector3 calculate_error_rpy(
118118
const geometry_msgs::msg::Vector3 & gyro_bias)
119119
{
120120
const geometry_msgs::msg::Vector3 rpy_0 =
121-
autoware::universe_utils::getRPY(pose_list.front().pose.orientation);
121+
autoware_utils_geometry::get_rpy(pose_list.front().pose.orientation);
122122
const geometry_msgs::msg::Vector3 rpy_1 =
123-
autoware::universe_utils::getRPY(pose_list.back().pose.orientation);
123+
autoware_utils_geometry::get_rpy(pose_list.back().pose.orientation);
124124
const geometry_msgs::msg::Vector3 d_rpy = integrate_orientation(gyro_list, gyro_bias);
125125

126126
geometry_msgs::msg::Vector3 error_rpy = createVector3(

localization/deviation_estimation_tools/deviation_estimator/src/velocity_coef_module.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
#include "deviation_estimator/velocity_coef_module.hpp"
1616

17-
#include "autoware/universe_utils/geometry/geometry.hpp"
17+
#include <autoware_utils_geometry/geometry.hpp>
1818
#include "deviation_estimator/utils.hpp"
1919

2020
/**

localization/deviation_estimation_tools/deviation_estimator/test/test_gyro_bias.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware/universe_utils/geometry/geometry.hpp"
15+
#include <autoware_utils_geometry/geometry.hpp>
1616
#include "deviation_estimator/gyro_bias_module.hpp"
1717

1818
#include <gtest/gtest.h>
@@ -54,7 +54,7 @@ TEST(DeviationEstimatorGyroBias, SmokeTestDefault)
5454
for (int i = 0; i <= ndt_rate * dt; ++i) {
5555
geometry_msgs::msg::PoseStamped pose;
5656
pose.header.stamp = t_start + rclcpp::Duration::from_seconds(1.0 * i / ndt_rate);
57-
pose.pose.orientation = autoware::universe_utils::createQuaternionFromRPY(0.0, 0.0, 0.0);
57+
pose.pose.orientation = autoware_utils_geometry::create_quaternion_from_rpy(0.0, 0.0, 0.0);
5858
pose_list.push_back(pose);
5959
}
6060

localization/deviation_estimation_tools/deviation_estimator/test/test_gyro_stddev.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "autoware/universe_utils/geometry/geometry.hpp"
15+
#include <autoware_utils_geometry/geometry.hpp>
1616
#include "deviation_estimator/deviation_estimator.hpp"
1717

1818
#include <gtest/gtest.h>
@@ -53,7 +53,7 @@ TEST(DeviationEstimatorGyroStddev, SmokeTestDefault)
5353
for (int i = 0; i <= ndt_rate * t_window; ++i) {
5454
geometry_msgs::msg::PoseStamped pose;
5555
pose.header.stamp = t_start + rclcpp::Duration::from_seconds(1.0 * i / ndt_rate);
56-
pose.pose.orientation = autoware::universe_utils::createQuaternionFromRPY(0.0, 0.0, 0.0);
56+
pose.pose.orientation = autoware_utils_geometry::create_quaternion_from_rpy(0.0, 0.0, 0.0);
5757
pose_list.push_back(pose);
5858
}
5959

@@ -104,7 +104,7 @@ TEST(DeviationEstimatorGyroStddev, SmokeTestWithBias)
104104
for (int i = 0; i <= ndt_rate * t_window; ++i) {
105105
geometry_msgs::msg::PoseStamped pose;
106106
pose.header.stamp = t_start + rclcpp::Duration::from_seconds(1.0 * i / ndt_rate);
107-
pose.pose.orientation = autoware::universe_utils::createQuaternionFromRPY(0.0, 0.0, 0.0);
107+
pose.pose.orientation = autoware_utils_geometry::create_quaternion_from_rpy(0.0, 0.0, 0.0);
108108
pose_list.push_back(pose);
109109
}
110110

0 commit comments

Comments
 (0)