Skip to content

feat(autoware_vehicle_info_utils): replace autoware_universe_utils with autoware_utils #10167

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
#ifndef AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_

#include <autoware_utils/geometry/boost_geometry.hpp>

#include <boost/geometry/core/cs.hpp>
#include <boost/geometry/geometries/geometries.hpp>
#include <boost/geometry/geometries/register/point.hpp>
Expand All @@ -28,7 +30,7 @@
namespace autoware::universe_utils
{
// 2D
struct Point2d;
using Point2d = autoware_utils::Point2d;
using Segment2d = boost::geometry::model::segment<Point2d>;
using Box2d = boost::geometry::model::box<Point2d>;
using LineString2d = boost::geometry::model::linestring<Point2d>;
Expand All @@ -40,7 +42,7 @@ using MultiLineString2d = boost::geometry::model::multi_linestring<LineString2d>
using MultiPolygon2d = boost::geometry::model::multi_polygon<Polygon2d>;

// 3D
struct Point3d;
using Point3d = autoware_utils::Point3d;
using Segment3d = boost::geometry::model::segment<Point3d>;
using Box3d = boost::geometry::model::box<Point3d>;
using LineString3d = boost::geometry::model::linestring<Point3d>;
Expand All @@ -50,32 +52,6 @@ using MultiPoint3d = boost::geometry::model::multi_point<Point3d>;
using MultiLineString3d = boost::geometry::model::multi_linestring<LineString3d>;
using MultiPolygon3d = boost::geometry::model::multi_polygon<Polygon3d>;

struct Point2d : public Eigen::Vector2d
{
Point2d() = default;
Point2d(const double x, const double y) : Eigen::Vector2d(x, y) {}

[[nodiscard]] Point3d to_3d(const double z = 0.0) const;
};

struct Point3d : public Eigen::Vector3d
{
Point3d() = default;
Point3d(const double x, const double y, const double z) : Eigen::Vector3d(x, y, z) {}

[[nodiscard]] Point2d to_2d() const;
};

inline Point3d Point2d::to_3d(const double z) const
{
return Point3d{x(), y(), z};
}

inline Point2d Point3d::to_2d() const
{
return Point2d{x(), y()};
}

inline geometry_msgs::msg::Point toMsg(const Point3d & point)
{
geometry_msgs::msg::Point msg;
Expand All @@ -95,10 +71,4 @@ inline Point3d fromMsg(const geometry_msgs::msg::Point & msg)
}
} // namespace autoware::universe_utils

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 // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
1 change: 1 addition & 0 deletions common/autoware_universe_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
<depend>autoware_internal_planning_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_utils</depend>
<depend>autoware_vehicle_msgs</depend>
<depend>builtin_interfaces</depend>
<depend>diagnostic_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_HPP_
#define AUTOWARE_VEHICLE_INFO_UTILS__VEHICLE_INFO_HPP_

#include "autoware/universe_utils/geometry/boost_geometry.hpp"
#include <autoware_utils/geometry/boost_geometry.hpp>

namespace autoware::vehicle_info_utils
{
Expand Down Expand Up @@ -58,15 +58,15 @@ struct VehicleInfo
* polygon
* @param margin the longitudinal and lateral inflation margin
*/
autoware::universe_utils::LinearRing2d createFootprint(const double margin = 0.0) const;
autoware_utils::LinearRing2d createFootprint(const double margin = 0.0) const;

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

double calcMaxCurvature() const;
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_vehicle_info_utils/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_universe_utils</depend>
<depend>autoware_utils</depend>
<depend>rclcpp</depend>

<test_depend>ament_cmake_ros</test_depend>
Expand Down
8 changes: 4 additions & 4 deletions common/autoware_vehicle_info_utils/src/vehicle_info.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,16 +20,16 @@

namespace autoware::vehicle_info_utils
{
autoware::universe_utils::LinearRing2d VehicleInfo::createFootprint(const double margin) const
autoware_utils::LinearRing2d VehicleInfo::createFootprint(const double margin) const
{
return createFootprint(margin, margin);
}

autoware::universe_utils::LinearRing2d VehicleInfo::createFootprint(
autoware_utils::LinearRing2d VehicleInfo::createFootprint(
const double lat_margin, const double lon_margin) const
{
using autoware::universe_utils::LinearRing2d;
using autoware::universe_utils::Point2d;
using autoware_utils::LinearRing2d;
using autoware_utils::Point2d;

const double x_front = front_overhang_m + wheel_base_m + lon_margin;
const double x_center = wheel_base_m / 2.0;
Expand Down
1 change: 1 addition & 0 deletions control/autoware_collision_detector/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@

<depend>autoware_adapi_v1_msgs</depend>
<depend>autoware_perception_msgs</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_utils</depend>
<depend>autoware_vehicle_info_utils</depend>
<depend>diagnostic_msgs</depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -557,8 +557,8 @@
const auto p1 = vehicle_footprint.at(i);
const auto p2 = vehicle_footprint.at(i + 1);

marker.points.push_back(toMsg(p1.to_3d(base_link_z)));
marker.points.push_back(toMsg(p2.to_3d(base_link_z)));
marker.points.push_back(autoware::universe_utils::toMsg(p1.to_3d(base_link_z)));
marker.points.push_back(autoware::universe_utils::toMsg(p2.to_3d(base_link_z)));

Check warning on line 561 in control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp

View check run for this annotation

Codecov / codecov/patch

control/autoware_lane_departure_checker/src/lane_departure_checker_node/lane_departure_checker_node.cpp#L561

Added line #L561 was not covered by tests
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -143,8 +143,8 @@ std::vector<LinearRing2d> createVehicleFootprints(
// Create vehicle footprint on each TrajectoryPoint
std::vector<LinearRing2d> vehicle_footprints;
for (const auto & p : trajectory) {
vehicle_footprints.push_back(
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(p.pose)));
vehicle_footprints.push_back(autoware::universe_utils::transformVector(
local_vehicle_footprint, autoware::universe_utils::pose2transform(p.pose)));
}

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

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

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>

#include <autoware_planning_msgs/msg/trajectory.hpp>
Expand Down
4 changes: 2 additions & 2 deletions control/autoware_obstacle_collision_checker/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,8 +76,8 @@ visualization_msgs::msg::MarkerArray create_marker_array(
const auto & p1 = vehicle_footprint.at(i);
const auto & p2 = vehicle_footprint.at(i + 1);

marker.points.push_back(toMsg(p1.to_3d(base_link_z)));
marker.points.push_back(toMsg(p2.to_3d(base_link_z)));
marker.points.push_back(autoware::universe_utils::toMsg(p1.to_3d(base_link_z)));
marker.points.push_back(autoware::universe_utils::toMsg(p2.to_3d(base_link_z)));
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include "autoware/universe_utils/math/accumulator.hpp"

#include <autoware/route_handler/route_handler.hpp>
#include <autoware/universe_utils/geometry/boost_geometry.hpp>
#include <autoware/universe_utils/ros/polling_subscriber.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -176,8 +176,8 @@ void ControlEvaluatorNode::AddBoundaryDistanceMetricMsg(
lanelet::ConstLanelet current_lane;
lanelet::utils::query::getClosestLanelet(current_lanelets, ego_pose, &current_lane);
const auto local_vehicle_footprint = vehicle_info_.createFootprint();
const auto current_vehicle_footprint =
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
const auto current_vehicle_footprint = autoware::universe_utils::transformVector(
local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));

if (behavior_path.left_bound.size() >= 1) {
LineString2d left_boundary;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#ifndef AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_
#define AUTOWARE__PERCEPTION_ONLINE_EVALUATOR__UTILS__MARKER_UTILS_HPP_

#include <autoware/universe_utils/geometry/boost_geometry.hpp>
#include <autoware_vehicle_info_utils/vehicle_info.hpp>

#include "autoware_perception_msgs/msg/predicted_objects.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,9 +14,9 @@

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

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

#include <autoware/universe_utils/geometry/boost_geometry.hpp>
#include <autoware/universe_utils/geometry/boost_polygon_utils.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware/universe_utils/ros/marker_helper.hpp>
#include <autoware/universe_utils/ros/uuid_helper.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -259,8 +259,8 @@ bool DefaultPlanner::is_goal_valid(
}

const auto local_vehicle_footprint = vehicle_info_.createFootprint();
autoware::universe_utils::LinearRing2d goal_footprint =
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(goal));
autoware::universe_utils::LinearRing2d goal_footprint = autoware::universe_utils::transformVector(
local_vehicle_footprint, autoware::universe_utils::pose2transform(goal));
pub_goal_footprint_marker_->publish(visualize_debug_footprint(goal_footprint));
const auto polygon_footprint = convert_linear_ring_to_polygon(goal_footprint);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

#include <autoware/mission_planner_universe/mission_planner_plugin.hpp>
#include <autoware/route_handler/route_handler.hpp>
#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware_vehicle_info_utils/vehicle_info_utils.hpp>
#include <rclcpp/rclcpp.hpp>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@

#include "autoware_vehicle_info_utils/vehicle_info_utils.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>

#include "autoware_internal_debug_msgs/msg/float32_stamped.hpp"
#include "autoware_internal_debug_msgs/msg/float64_stamped.hpp"
#include "autoware_perception_msgs/msg/predicted_object.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -223,8 +223,8 @@ GoalCandidates GoalSearcher::search(
for (double dy = 0; dy <= max_lateral_offset; dy += lateral_offset_interval) {
search_pose = calcOffsetPose(original_search_pose, 0, sign * dy, 0);

const auto transformed_vehicle_footprint =
transformVector(vehicle_footprint_, autoware::universe_utils::pose2transform(search_pose));
const auto transformed_vehicle_footprint = autoware::universe_utils::transformVector(
vehicle_footprint_, autoware::universe_utils::pose2transform(search_pose));

if (
parameters_.bus_stop_area.use_bus_stop_area &&
Expand Down Expand Up @@ -324,8 +324,8 @@ void GoalSearcher::countObjectsToAvoid(
// count number of objects to avoid
for (const auto & object : objects.objects) {
for (const auto & p : current_center_line_path.points) {
const auto transformed_vehicle_footprint =
transformVector(vehicle_footprint_, autoware::universe_utils::pose2transform(p.point.pose));
const auto transformed_vehicle_footprint = autoware::universe_utils::transformVector(
vehicle_footprint_, autoware::universe_utils::pose2transform(p.point.pose));
const auto obj_polygon = autoware::universe_utils::toPolygon2d(object);
const double distance = boost::geometry::distance(obj_polygon, transformed_vehicle_footprint);
if (distance > parameters_.object_recognition_collision_check_hard_margins.back()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -118,8 +118,8 @@ bool checkCollisionBetweenFootprintAndObjects(
const autoware::universe_utils::LinearRing2d & local_vehicle_footprint, const Pose & ego_pose,
const PredictedObjects & dynamic_objects, const double margin)
{
const auto vehicle_footprint =
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
const auto vehicle_footprint = autoware::universe_utils::transformVector(
local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));

for (const auto & object : dynamic_objects.objects) {
const auto obj_polygon = autoware::universe_utils::toPolygon2d(object);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -457,8 +457,8 @@ bool StartPlannerModule::isPreventingRearVehicleFromPassingThrough(const Pose &
geometry_msgs::msg::Pose & ego_overhang_point_as_pose,
const bool ego_is_merging_from_the_left) -> std::optional<std::pair<double, double>> {
const auto local_vehicle_footprint = vehicle_info_.createFootprint();
const auto vehicle_footprint =
transformVector(local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
const auto vehicle_footprint = autoware::universe_utils::transformVector(
local_vehicle_footprint, autoware::universe_utils::pose2transform(ego_pose));
double smallest_lateral_gap_between_ego_and_border = std::numeric_limits<double>::max();
double corresponding_lateral_gap_with_other_lane_bound = std::numeric_limits<double>::max();

Expand Down
Loading