Skip to content
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

chore: sync awf-latest #1853

Merged
merged 2 commits into from
Feb 20, 2025
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 @@ -13,6 +13,7 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>

<depend>autoware_test_utils</depend>
<depend>autoware_universe_utils</depend>
<depend>message_filters</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
2 changes: 1 addition & 1 deletion planning/autoware_route_handler/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
<depend>autoware_map_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_test_utils</depend>
<depend>autoware_universe_utils</depend>
<depend>autoware_utils</depend>
<depend>geometry_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
Expand Down
20 changes: 9 additions & 11 deletions planning/autoware_route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,12 +14,12 @@

#include "autoware/route_handler/route_handler.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <autoware_lanelet2_extension/io/autoware_osm_parser.hpp>
#include <autoware_lanelet2_extension/utility/message_conversion.hpp>
#include <autoware_lanelet2_extension/utility/query.hpp>
#include <autoware_lanelet2_extension/utility/route_checker.hpp>
#include <autoware_lanelet2_extension/utility/utilities.hpp>
#include <autoware_utils/geometry/geometry.hpp>
#include <autoware_utils/math/normalization.hpp>
#include <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -50,12 +50,12 @@ namespace autoware::route_handler
{
namespace
{
using autoware::universe_utils::createPoint;
using autoware::universe_utils::createQuaternionFromYaw;
using autoware_internal_planning_msgs::msg::PathPointWithLaneId;
using autoware_internal_planning_msgs::msg::PathWithLaneId;
using autoware_planning_msgs::msg::LaneletPrimitive;
using autoware_planning_msgs::msg::Path;
using autoware_utils::create_point;
using autoware_utils::create_quaternion_from_yaw;
using geometry_msgs::msg::Pose;
using lanelet::utils::to2D;

Expand Down Expand Up @@ -114,9 +114,7 @@ PathWithLaneId removeOverlappingPoints(const PathWithLaneId & input_path)
}

constexpr double min_dist = 0.001;
if (
autoware::universe_utils::calcDistance3d(filtered_path.points.back().point, pt.point) <
min_dist) {
if (autoware_utils::calc_distance3d(filtered_path.points.back().point, pt.point) < min_dist) {
filtered_path.points.back().lane_ids.push_back(pt.lane_ids.front());
filtered_path.points.back().point.longitudinal_velocity_mps = std::min(
pt.point.longitudinal_velocity_mps,
Expand Down Expand Up @@ -1642,14 +1640,14 @@ PathWithLaneId RouteHandler::getCenterLinePath(
double angle{0.0};
const auto & pts = reference_path.points;
if (i + 1 < reference_path.points.size()) {
angle = autoware::universe_utils::calcAzimuthAngle(
angle = autoware_utils::calc_azimuth_angle(
pts.at(i).point.pose.position, pts.at(i + 1).point.pose.position);
} else if (i != 0) {
angle = autoware::universe_utils::calcAzimuthAngle(
angle = autoware_utils::calc_azimuth_angle(
pts.at(i - 1).point.pose.position, pts.at(i).point.pose.position);
}
reference_path.points.at(i).point.pose.orientation =
autoware::universe_utils::createQuaternionFromYaw(angle);
autoware_utils::create_quaternion_from_yaw(angle);
}

return reference_path;
Expand Down Expand Up @@ -2104,8 +2102,8 @@ Pose RouteHandler::get_pose_from_2d_arc_length(
const auto interpolated_pt = pt.basicPoint() * (1 - ratio) + next_pt.basicPoint() * ratio;
const auto yaw = std::atan2(next_pt.y() - pt.y(), next_pt.x() - pt.x());
Pose pose;
pose.position = createPoint(interpolated_pt.x(), interpolated_pt.y(), interpolated_pt.z());
pose.orientation = createQuaternionFromYaw(yaw);
pose.position = create_point(interpolated_pt.x(), interpolated_pt.y(), interpolated_pt.z());
pose.orientation = create_quaternion_from_yaw(yaw);
return pose;
}
accumulated_distance2d += distance2d;
Expand Down
19 changes: 9 additions & 10 deletions planning/autoware_route_handler/test/test_route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

#include "test_route_handler.hpp"

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

#include <rclcpp/rclcpp.hpp>

Expand Down Expand Up @@ -54,10 +54,10 @@ TEST_F(TestRouteHandler, getLaneletSequenceWhenOverlappingRoute)

geometry_msgs::msg::Pose start_pose;
geometry_msgs::msg::Pose goal_pose;
start_pose.position = autoware::universe_utils::createPoint(3728.870361, 73739.281250, 0);
start_pose.orientation = autoware::universe_utils::createQuaternion(0, 0, -0.513117, 0.858319);
goal_pose.position = autoware::universe_utils::createPoint(3729.961182, 73727.328125, 0);
goal_pose.orientation = autoware::universe_utils::createQuaternion(0, 0, 0.234831, 0.972036);
start_pose.position = autoware_utils::create_point(3728.870361, 73739.281250, 0);
start_pose.orientation = autoware_utils::create_quaternion(0, 0, -0.513117, 0.858319);
goal_pose.position = autoware_utils::create_point(3729.961182, 73727.328125, 0);
goal_pose.orientation = autoware_utils::create_quaternion(0, 0, 0.234831, 0.972036);

lanelet::ConstLanelets path_lanelets;
ASSERT_TRUE(
Expand Down Expand Up @@ -88,17 +88,16 @@ TEST_F(TestRouteHandler, getClosestRouteLaneletFromLaneletWhenOverlappingRoute)
geometry_msgs::msg::Pose search_pose;

lanelet::ConstLanelet reference_lanelet;
reference_pose.position = autoware::universe_utils::createPoint(3730.88, 73735.3, 0);
reference_pose.orientation =
autoware::universe_utils::createQuaternion(0, 0, -0.504626, 0.863338);
reference_pose.position = autoware_utils::create_point(3730.88, 73735.3, 0);
reference_pose.orientation = autoware_utils::create_quaternion(0, 0, -0.504626, 0.863338);
const auto found_reference_lanelet =
route_handler_->getClosestLaneletWithinRoute(reference_pose, &reference_lanelet);
ASSERT_TRUE(found_reference_lanelet);
ASSERT_EQ(reference_lanelet.id(), 168);

lanelet::ConstLanelet closest_lanelet;
search_pose.position = autoware::universe_utils::createPoint(3736.89, 73730.8, 0);
search_pose.orientation = autoware::universe_utils::createQuaternion(0, 0, 0.223244, 0.974763);
search_pose.position = autoware_utils::create_point(3736.89, 73730.8, 0);
search_pose.orientation = autoware_utils::create_quaternion(0, 0, 0.223244, 0.974763);
bool found_lanelet = route_handler_->getClosestLaneletWithinRoute(search_pose, &closest_lanelet);
ASSERT_TRUE(found_lanelet);
ASSERT_EQ(closest_lanelet.id(), 345);
Expand Down
Loading