Skip to content

Commit 6d0788b

Browse files
authored
feat(autoware_vehicle_info_utils): replace autoware_universe_utils with autoware_utils (#10167)
Signed-off-by: mitsudome-r <ryohsuke.mitsudome@tier4.jp>
1 parent 3fd5f8c commit 6d0788b

File tree

20 files changed

+42
-64
lines changed

20 files changed

+42
-64
lines changed

common/autoware_universe_utils/include/autoware/universe_utils/geometry/boost_geometry.hpp

+4-34
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,8 @@
1515
#ifndef AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
1616
#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
1717

18+
#include <autoware_utils/geometry/boost_geometry.hpp>
19+
1820
#include <boost/geometry/core/cs.hpp>
1921
#include <boost/geometry/geometries/geometries.hpp>
2022
#include <boost/geometry/geometries/register/point.hpp>
@@ -28,7 +30,7 @@
2830
namespace autoware::universe_utils
2931
{
3032
// 2D
31-
struct Point2d;
33+
using Point2d = autoware_utils::Point2d;
3234
using Segment2d = boost::geometry::model::segment<Point2d>;
3335
using Box2d = boost::geometry::model::box<Point2d>;
3436
using LineString2d = boost::geometry::model::linestring<Point2d>;
@@ -40,7 +42,7 @@ using MultiLineString2d = boost::geometry::model::multi_linestring<LineString2d>
4042
using MultiPolygon2d = boost::geometry::model::multi_polygon<Polygon2d>;
4143

4244
// 3D
43-
struct Point3d;
45+
using Point3d = autoware_utils::Point3d;
4446
using Segment3d = boost::geometry::model::segment<Point3d>;
4547
using Box3d = boost::geometry::model::box<Point3d>;
4648
using LineString3d = boost::geometry::model::linestring<Point3d>;
@@ -50,32 +52,6 @@ using MultiPoint3d = boost::geometry::model::multi_point<Point3d>;
5052
using MultiLineString3d = boost::geometry::model::multi_linestring<LineString3d>;
5153
using MultiPolygon3d = boost::geometry::model::multi_polygon<Polygon3d>;
5254

53-
struct Point2d : public Eigen::Vector2d
54-
{
55-
Point2d() = default;
56-
Point2d(const double x, const double y) : Eigen::Vector2d(x, y) {}
57-
58-
[[nodiscard]] Point3d to_3d(const double z = 0.0) const;
59-
};
60-
61-
struct Point3d : public Eigen::Vector3d
62-
{
63-
Point3d() = default;
64-
Point3d(const double x, const double y, const double z) : Eigen::Vector3d(x, y, z) {}
65-
66-
[[nodiscard]] Point2d to_2d() const;
67-
};
68-
69-
inline Point3d Point2d::to_3d(const double z) const
70-
{
71-
return Point3d{x(), y(), z};
72-
}
73-
74-
inline Point2d Point3d::to_2d() const
75-
{
76-
return Point2d{x(), y()};
77-
}
78-
7955
inline geometry_msgs::msg::Point toMsg(const Point3d & point)
8056
{
8157
geometry_msgs::msg::Point msg;
@@ -95,10 +71,4 @@ inline Point3d fromMsg(const geometry_msgs::msg::Point & msg)
9571
}
9672
} // namespace autoware::universe_utils
9773

98-
BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLINT
99-
autoware::universe_utils::Point2d, double, cs::cartesian, x(), y()) // NOLINT
100-
BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT
101-
autoware::universe_utils::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT
102-
BOOST_GEOMETRY_REGISTER_RING(autoware::universe_utils::LinearRing2d) // NOLINT
103-
10474
#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_

common/autoware_universe_utils/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
<depend>autoware_internal_planning_msgs</depend>
1818
<depend>autoware_perception_msgs</depend>
1919
<depend>autoware_planning_msgs</depend>
20+
<depend>autoware_utils</depend>
2021
<depend>autoware_vehicle_msgs</depend>
2122
<depend>builtin_interfaces</depend>
2223
<depend>diagnostic_msgs</depend>

common/autoware_vehicle_info_utils/include/autoware_vehicle_info_utils/vehicle_info.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
#ifndef AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_HPP_
1616
#define AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_HPP_
1717

18-
#include "autoware/universe_utils/geometry/boost_geometry.hpp"
18+
#include <autoware_utils/geometry/boost_geometry.hpp>
1919

2020
namespace autoware::vehicle_info_utils
2121
{
@@ -58,15 +58,15 @@ struct VehicleInfo
5858
* polygon
5959
* @param margin the longitudinal and lateral inflation margin
6060
*/
61-
autoware::universe_utils::LinearRing2d createFootprint(const double margin = 0.0) const;
61+
autoware_utils::LinearRing2d createFootprint(const double margin = 0.0) const;
6262

6363
/**
6464
* @brief calculate the vehicle footprint in clockwise manner starting from the front-left edge,
6565
* through front-right edge, center-right point, to front-left edge again to form a enclosed
6666
* polygon
6767
* @param margin the longitudinal and lateral inflation margin
6868
*/
69-
autoware::universe_utils::LinearRing2d createFootprint(
69+
autoware_utils::LinearRing2d createFootprint(
7070
const double lat_margin, const double lon_margin) const;
7171

7272
double calcMaxCurvature() const;

common/autoware_vehicle_info_utils/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@
1717
<buildtool_depend>ament_cmake_auto</buildtool_depend>
1818
<buildtool_depend>autoware_cmake</buildtool_depend>
1919

20-
<depend>autoware_universe_utils</depend>
20+
<depend>autoware_utils</depend>
2121
<depend>rclcpp</depend>
2222

2323
<test_depend>ament_cmake_ros</test_depend>

common/autoware_vehicle_info_utils/src/vehicle_info.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -20,16 +20,16 @@
2020

2121
namespace autoware::vehicle_info_utils
2222
{
23-
autoware::universe_utils::LinearRing2d VehicleInfo::createFootprint(const double margin) const
23+
autoware_utils::LinearRing2d VehicleInfo::createFootprint(const double margin) const
2424
{
2525
return createFootprint(margin, margin);
2626
}
2727

28-
autoware::universe_utils::LinearRing2d VehicleInfo::createFootprint(
28+
autoware_utils::LinearRing2d VehicleInfo::createFootprint(
2929
const double lat_margin, const double lon_margin) const
3030
{
31-
using autoware::universe_utils::LinearRing2d;
32-
using autoware::universe_utils::Point2d;
31+
using autoware_utils::LinearRing2d;
32+
using autoware_utils::Point2d;
3333

3434
const double x_front = front_overhang_m + wheel_base_m + lon_margin;
3535
const double x_center = wheel_base_m / 2.0;

control/autoware_collision_detector/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020

2121
<depend>autoware_adapi_v1_msgs</depend>
2222
<depend>autoware_perception_msgs</depend>
23+
<depend>autoware_universe_utils</depend>
2324
<depend>autoware_utils</depend>
2425
<depend>autoware_vehicle_info_utils</depend>
2526
<depend>diagnostic_msgs</depend>

control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -557,8 +557,8 @@ visualization_msgs::msg::MarkerArray LaneDepartureCheckerNode::createMarkerArray
557557
const auto p1 = vehicle_footprint.at(i);
558558
const auto p2 = vehicle_footprint.at(i + 1);
559559

560-
marker.points.push_back(toMsg(p1.to_3d(base_link_z)));
561-
marker.points.push_back(toMsg(p2.to_3d(base_link_z)));
560+
marker.points.push_back(autoware::universe_utils::toMsg(p1.to_3d(base_link_z)));
561+
marker.points.push_back(autoware::universe_utils::toMsg(p2.to_3d(base_link_z)));
562562
}
563563
}
564564

control/autoware_lane_departure_checker/src/lane_departure_checker_node/utils.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -143,8 +143,8 @@ std::vector<LinearRing2d> createVehicleFootprints(
143143
// Create vehicle footprint on each TrajectoryPoint
144144
std::vector<LinearRing2d> vehicle_footprints;
145145
for (const auto & p : trajectory) {
146-
vehicle_footprints.push_back(
147-
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(p.pose)));
146+
vehicle_footprints.push_back(autoware::universe_utils::transformVector(
147+
local_vehicle_footprint, autoware::universe_utils::pose2transform(p.pose)));
148148
}
149149

150150
return vehicle_footprints;
@@ -160,7 +160,7 @@ std::vector<LinearRing2d> createVehicleFootprints(
160160
// Create vehicle footprint on each Path point
161161
std::vector<LinearRing2d> vehicle_footprints;
162162
for (const auto & p : path.points) {
163-
vehicle_footprints.push_back(transformVector(
163+
vehicle_footprints.push_back(autoware::universe_utils::transformVector(
164164
local_vehicle_footprint, autoware::universe_utils::pose2transform(p.point.pose)));
165165
}
166166

control/autoware_obstacle_collision_checker/include/autoware/obstacle_collision_checker/obstacle_collision_checker.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef AUTOWARE__OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_
1616
#define AUTOWARE__OBSTACLE_COLLISION_CHECKER__OBSTACLE_COLLISION_CHECKER_HPP_
1717

18+
#include <autoware/universe_utils/geometry/geometry.hpp>
1819
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
1920

2021
#include <autoware_planning_msgs/msg/trajectory.hpp>

control/autoware_obstacle_collision_checker/src/debug.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -76,8 +76,8 @@ visualization_msgs::msg::MarkerArray create_marker_array(
7676
const auto & p1 = vehicle_footprint.at(i);
7777
const auto & p2 = vehicle_footprint.at(i + 1);
7878

79-
marker.points.push_back(toMsg(p1.to_3d(base_link_z)));
80-
marker.points.push_back(toMsg(p2.to_3d(base_link_z)));
79+
marker.points.push_back(autoware::universe_utils::toMsg(p1.to_3d(base_link_z)));
80+
marker.points.push_back(autoware::universe_utils::toMsg(p2.to_3d(base_link_z)));
8181
}
8282
}
8383

evaluator/autoware_control_evaluator/include/autoware/control_evaluator/control_evaluator_node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include "autoware/universe_utils/math/accumulator.hpp"
2121

2222
#include <autoware/route_handler/route_handler.hpp>
23+
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
2324
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
2425
#include <autoware/universe_utils/system/stop_watch.hpp>
2526
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>

evaluator/autoware_control_evaluator/src/control_evaluator_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -176,8 +176,8 @@ void ControlEvaluatorNode::AddBoundaryDistanceMetricMsg(
176176
lanelet::ConstLanelet current_lane;
177177
lanelet::utils::query::getClosestLanelet(current_lanelets, ego_pose, &current_lane);
178178
const auto local_vehicle_footprint = vehicle_info_.createFootprint();
179-
const auto current_vehicle_footprint =
180-
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
179+
const auto current_vehicle_footprint = autoware::universe_utils::transformVector(
180+
local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
181181

182182
if (behavior_path.left_bound.size() >= 1) {
183183
LineString2d left_boundary;

evaluator/autoware_perception_online_evaluator/include/autoware/perception_online_evaluator/utils/marker_utils.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_
1616
#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_
1717

18+
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
1819
#include <autoware_vehicle_info_utils/vehicle_info.hpp>
1920

2021
#include "autoware_perception_msgs/msg/predicted_objects.hpp"

evaluator/autoware_perception_online_evaluator/src/utils/marker_utils.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,9 @@
1414

1515
#include "autoware/perception_online_evaluator/utils/marker_utils.hpp"
1616

17-
#include "autoware/universe_utils/geometry/boost_polygon_utils.hpp"
18-
#include "autoware/universe_utils/geometry/geometry.hpp"
19-
17+
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
18+
#include <autoware/universe_utils/geometry/boost_polygon_utils.hpp>
19+
#include <autoware/universe_utils/geometry/geometry.hpp>
2020
#include <autoware/universe_utils/ros/marker_helper.hpp>
2121
#include <autoware/universe_utils/ros/uuid_helper.hpp>
2222

planning/autoware_mission_planner_universe/src/lanelet2_plugins/default_planner.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -259,8 +259,8 @@ bool DefaultPlanner::is_goal_valid(
259259
}
260260

261261
const auto local_vehicle_footprint = vehicle_info_.createFootprint();
262-
autoware::universe_utils::LinearRing2d goal_footprint =
263-
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(goal));
262+
autoware::universe_utils::LinearRing2d goal_footprint = autoware::universe_utils::transformVector(
263+
local_vehicle_footprint, autoware::universe_utils::pose2transform(goal));
264264
pub_goal_footprint_marker_->publish(visualize_debug_footprint(goal_footprint));
265265
const auto polygon_footprint = convert_linear_ring_to_polygon(goal_footprint);
266266

planning/autoware_mission_planner_universe/src/lanelet2_plugins/default_planner.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include <autoware/mission_planner_universe/mission_planner_plugin.hpp>
1919
#include <autoware/route_handler/route_handler.hpp>
20+
#include <autoware/universe_utils/geometry/geometry.hpp>
2021
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
2122
#include <rclcpp/rclcpp.hpp>
2223

planning/autoware_obstacle_cruise_planner/include/autoware/obstacle_cruise_planner/type_alias.hpp

+2
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,8 @@
1717

1818
#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"
1919

20+
#include <autoware/universe_utils/geometry/geometry.hpp>
21+
2022
#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp"
2123
#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
2224
#include "autoware_perception_msgs/msg/predicted_object.hpp"

planning/behavior_path_planner/autoware_behavior_path_goal_planner_module/src/goal_searcher.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -223,8 +223,8 @@ GoalCandidates GoalSearcher::search(
223223
for (double dy = 0; dy <= max_lateral_offset; dy += lateral_offset_interval) {
224224
search_pose = calcOffsetPose(original_search_pose, 0, sign * dy, 0);
225225

226-
const auto transformed_vehicle_footprint =
227-
transformVector(vehicle_footprint_, autoware::universe_utils::pose2transform(search_pose));
226+
const auto transformed_vehicle_footprint = autoware::universe_utils::transformVector(
227+
vehicle_footprint_, autoware::universe_utils::pose2transform(search_pose));
228228

229229
if (
230230
parameters_.bus_stop_area.use_bus_stop_area &&
@@ -324,8 +324,8 @@ void GoalSearcher::countObjectsToAvoid(
324324
// count number of objects to avoid
325325
for (const auto & object : objects.objects) {
326326
for (const auto & p : current_center_line_path.points) {
327-
const auto transformed_vehicle_footprint =
328-
transformVector(vehicle_footprint_, autoware::universe_utils::pose2transform(p.point.pose));
327+
const auto transformed_vehicle_footprint = autoware::universe_utils::transformVector(
328+
vehicle_footprint_, autoware::universe_utils::pose2transform(p.point.pose));
329329
const auto obj_polygon = autoware::universe_utils::toPolygon2d(object);
330330
const double distance = boost::geometry::distance(obj_polygon, transformed_vehicle_footprint);
331331
if (distance > parameters_.object_recognition_collision_check_hard_margins.back()) {

planning/behavior_path_planner/autoware_behavior_path_planner_common/src/utils/utils.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -118,8 +118,8 @@ bool checkCollisionBetweenFootprintAndObjects(
118118
const autoware::universe_utils::LinearRing2d & local_vehicle_footprint, const Pose & ego_pose,
119119
const PredictedObjects & dynamic_objects, const double margin)
120120
{
121-
const auto vehicle_footprint =
122-
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
121+
const auto vehicle_footprint = autoware::universe_utils::transformVector(
122+
local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
123123

124124
for (const auto & object : dynamic_objects.objects) {
125125
const auto obj_polygon = autoware::universe_utils::toPolygon2d(object);

planning/behavior_path_planner/autoware_behavior_path_start_planner_module/src/start_planner_module.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -457,8 +457,8 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough(const Pose &
457457
geometry_msgs::msg::Pose & ego_overhang_point_as_pose,
458458
const bool ego_is_merging_from_the_left) -> std::optional<std::pair<double, double>> {
459459
const auto local_vehicle_footprint = vehicle_info_.createFootprint();
460-
const auto vehicle_footprint =
461-
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
460+
const auto vehicle_footprint = autoware::universe_utils::transformVector(
461+
local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
462462
double smallest_lateral_gap_between_ego_and_border = std::numeric_limits<double>::max();
463463
double corresponding_lateral_gap_with_other_lane_bound = std::numeric_limits<double>::max();
464464

0 commit comments

Comments
 (0)