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

fix(tier4_autoware_utils): fix build error #296

Merged
merged 4 commits into from
Mar 1, 2023
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 @@ -47,7 +47,7 @@ std::vector<geometry_msgs::msg::Point> removeOverlapPoints(const T & points, con
const auto p_next = tier4_autoware_utils::getPoint(dst.at(i + 1));
const Eigen::Vector3d v{p_next.x - p.x, p_next.y - p.y, 0.0};
if (v.norm() < eps) {
dst.erase(dst.begin() + i + 1);
dst.erase(dst.begin() + static_cast<int32_t>(i) + 1);
yn-mrse marked this conversation as resolved.
Show resolved Hide resolved
} else {
++i;
}
Expand Down
36 changes: 21 additions & 15 deletions common/tier4_autoware_utils/test/src/trajectory/test_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ TEST(trajectory, searchZeroVelocityIndex)
using tier4_autoware_utils::searchZeroVelocityIndex;

// Empty
EXPECT_THROW(searchZeroVelocityIndex(Trajectory{}.points), std::invalid_argument);
EXPECT_FALSE(searchZeroVelocityIndex(Trajectory{}.points));

// No zero velocity point
{
Expand Down Expand Up @@ -229,8 +229,7 @@ TEST(trajectory, findNearestIndex_Pose_NoThreshold)
const auto traj = generateTestTrajectory<Trajectory>(10, 1.0);

// Empty
EXPECT_THROW(
findNearestIndex(Trajectory{}.points, geometry_msgs::msg::Pose{}, {}), std::invalid_argument);
EXPECT_FALSE(findNearestIndex(Trajectory{}.points, geometry_msgs::msg::Pose{}, {}));

// Start point
EXPECT_EQ(*findNearestIndex(traj.points, createPose(0.0, 0.0, 0.0, 0.0, 0.0, 0.0)), 0U);
Expand Down Expand Up @@ -343,26 +342,30 @@ TEST(trajectory, calcLongitudinalOffsetToSegment_StraightTrajectory)
using tier4_autoware_utils::calcLongitudinalOffsetToSegment;

const auto traj = generateTestTrajectory<Trajectory>(10, 1.0);
const bool throw_exception = true;

// Empty
EXPECT_THROW(
calcLongitudinalOffsetToSegment(Trajectory{}.points, {}, geometry_msgs::msg::Point{}),
calcLongitudinalOffsetToSegment(
Trajectory{}.points, {}, geometry_msgs::msg::Point{}, throw_exception),
std::invalid_argument);

// Out of range
EXPECT_THROW(
calcLongitudinalOffsetToSegment(traj.points, -1, geometry_msgs::msg::Point{}),
calcLongitudinalOffsetToSegment(traj.points, -1, geometry_msgs::msg::Point{}, throw_exception),
std::out_of_range);
EXPECT_THROW(
calcLongitudinalOffsetToSegment(
traj.points, traj.points.size() - 1, geometry_msgs::msg::Point{}),
traj.points, traj.points.size() - 1, geometry_msgs::msg::Point{}, throw_exception),
std::out_of_range);

// Same close points in trajectory
{
const auto invalid_traj = generateTestTrajectory<Trajectory>(10, 0.0);
const auto p = createPoint(3.0, 0.0, 0.0);
EXPECT_THROW(calcLongitudinalOffsetToSegment(invalid_traj.points, 3, p), std::runtime_error);
EXPECT_THROW(
calcLongitudinalOffsetToSegment(invalid_traj.points, 3, p, throw_exception),
std::runtime_error);
}

// Same point
Expand Down Expand Up @@ -401,23 +404,26 @@ TEST(trajectory, calcLateralOffset)
using tier4_autoware_utils::calcLateralOffset;

const auto traj = generateTestTrajectory<Trajectory>(10, 1.0);
const bool throw_exception = true;

// Empty
EXPECT_THROW(
calcLateralOffset(Trajectory{}.points, geometry_msgs::msg::Point{}), std::invalid_argument);
calcLateralOffset(Trajectory{}.points, geometry_msgs::msg::Point{}, throw_exception),
std::invalid_argument);

// Trajectory size is 1
{
const auto one_point_traj = generateTestTrajectory<Trajectory>(1, 1.0);
EXPECT_THROW(
calcLateralOffset(one_point_traj.points, geometry_msgs::msg::Point{}), std::out_of_range);
calcLateralOffset(one_point_traj.points, geometry_msgs::msg::Point{}, throw_exception),
std::runtime_error);
}

// Same close points in trajectory
{
const auto invalid_traj = generateTestTrajectory<Trajectory>(10, 0.0);
const auto p = createPoint(3.0, 0.0, 0.0);
EXPECT_THROW(calcLateralOffset(invalid_traj.points, p), std::runtime_error);
EXPECT_THROW(calcLateralOffset(invalid_traj.points, p, throw_exception), std::runtime_error);
}

// Point on trajectory
Expand Down Expand Up @@ -452,7 +458,7 @@ TEST(trajectory, calcSignedArcLengthFromIndexToIndex)
const auto traj = generateTestTrajectory<Trajectory>(10, 1.0);

// Empty
EXPECT_THROW(calcSignedArcLength(Trajectory{}.points, {}, {}), std::invalid_argument);
EXPECT_DOUBLE_EQ(calcSignedArcLength(Trajectory{}.points, {}, {}), 0.0);

// Out of range
EXPECT_THROW(calcSignedArcLength(traj.points, -1, 1), std::out_of_range);
Expand All @@ -475,7 +481,7 @@ TEST(trajectory, calcSignedArcLengthFromPointToIndex)
const auto traj = generateTestTrajectory<Trajectory>(10, 1.0);

// Empty
EXPECT_THROW(calcSignedArcLength(Trajectory{}.points, {}, {}), std::invalid_argument);
EXPECT_DOUBLE_EQ(calcSignedArcLength(Trajectory{}.points, {}, {}), 0.0);

// Same point
EXPECT_NEAR(calcSignedArcLength(traj.points, createPoint(3.0, 0.0, 0.0), 3), 0, epsilon);
Expand Down Expand Up @@ -504,7 +510,7 @@ TEST(trajectory, calcSignedArcLengthFromIndexToPoint)
const auto traj = generateTestTrajectory<Trajectory>(10, 1.0);

// Empty
EXPECT_THROW(calcSignedArcLength(Trajectory{}.points, {}, {}), std::invalid_argument);
EXPECT_DOUBLE_EQ(calcSignedArcLength(Trajectory{}.points, {}, {}), 0.0);

// Same point
EXPECT_NEAR(calcSignedArcLength(traj.points, 3, createPoint(3.0, 0.0, 0.0)), 0, epsilon);
Expand Down Expand Up @@ -533,7 +539,7 @@ TEST(trajectory, calcSignedArcLengthFromPointToPoint)
const auto traj = generateTestTrajectory<Trajectory>(10, 1.0);

// Empty
EXPECT_THROW(calcSignedArcLength(Trajectory{}.points, {}, {}), std::invalid_argument);
EXPECT_DOUBLE_EQ(calcSignedArcLength(Trajectory{}.points, {}, {}), 0.0);

// Same point
{
Expand Down Expand Up @@ -596,7 +602,7 @@ TEST(trajectory, calcArcLength)
const auto traj = generateTestTrajectory<Trajectory>(10, 1.0);

// Empty
EXPECT_THROW(calcArcLength(Trajectory{}.points), std::invalid_argument);
EXPECT_DOUBLE_EQ(calcArcLength(Trajectory{}.points), 0.0);

// Whole Length
EXPECT_NEAR(calcArcLength(traj.points), 9.0, epsilon);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,8 +60,8 @@ TEST(TestLongitudinalControllerUtils, calcStopDistance) {
point.pose.position.y = 0.0;
point.longitudinal_velocity_mps = 0.0;
traj.points.push_back(point);
EXPECT_THROW(
longitudinal_utils::calcStopDistance(current_pose, traj, max_dist, max_yaw), std::out_of_range);
EXPECT_DOUBLE_EQ(
longitudinal_utils::calcStopDistance(current_pose, traj, max_dist, max_yaw), 0.0);
traj.points.clear();
// non stopping trajectory: stop distance = trajectory length
point.pose.position.x = 0.0;
Expand Down