From ca627a71376537bc4cba110e4b64ff1eed9834fe Mon Sep 17 00:00:00 2001 From: jim-works Date: Fri, 5 Nov 2021 14:35:36 -0500 Subject: [PATCH 1/8] added path_planner package, cubic spline implementation, and offset spline header --- .gitignore | 1 + src/planning/path_planner/CMakeLists.txt | 56 +++++ .../design/path_planner-design.md | 8 + .../include/path_planner/cubic_spline.hpp | 54 +++++ .../include/path_planner/offset_spline.hpp | 65 ++++++ .../include/path_planner/path_planner.hpp | 37 ++++ src/planning/path_planner/package.xml | 31 +++ .../path_planner/src/cubic_spline.cpp | 59 ++++++ .../path_planner/src/offset_spline.cpp | 21 ++ .../path_planner/src/path_planner.cpp | 21 ++ .../path_planner/test/test_path_planner.cpp | 191 ++++++++++++++++++ 11 files changed, 544 insertions(+) create mode 100644 src/planning/path_planner/CMakeLists.txt create mode 100644 src/planning/path_planner/design/path_planner-design.md create mode 100644 src/planning/path_planner/include/path_planner/cubic_spline.hpp create mode 100644 src/planning/path_planner/include/path_planner/offset_spline.hpp create mode 100644 src/planning/path_planner/include/path_planner/path_planner.hpp create mode 100644 src/planning/path_planner/package.xml create mode 100644 src/planning/path_planner/src/cubic_spline.cpp create mode 100644 src/planning/path_planner/src/offset_spline.cpp create mode 100644 src/planning/path_planner/src/path_planner.cpp create mode 100644 src/planning/path_planner/test/test_path_planner.cpp diff --git a/.gitignore b/.gitignore index c1fe9c963..51ab62a9e 100644 --- a/.gitignore +++ b/.gitignore @@ -2,3 +2,4 @@ __pycache__ build install log +.vscode diff --git a/src/planning/path_planner/CMakeLists.txt b/src/planning/path_planner/CMakeLists.txt new file mode 100644 index 000000000..c634935ce --- /dev/null +++ b/src/planning/path_planner/CMakeLists.txt @@ -0,0 +1,56 @@ +# Copyright 2020 The Autoware Foundation +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +#    http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +cmake_minimum_required(VERSION 3.5) + +project(path_planner) + +# dependencies +find_package(ament_cmake_auto REQUIRED) +ament_auto_find_build_dependencies() + +set(LANE_PLANNER_LIB_SRC + src/path_planner.cpp + src/cubic_spline.cpp + src/offset_spline.cpp +) + +set(LANE_PLANNER_LIB_HEADERS + include/path_planner/path_planner.hpp + include/path_planner/cubic_spline.hpp + include/path_planner/offset_spline.hpp +) + +# generate library +ament_auto_add_library(${PROJECT_NAME} SHARED + ${LANE_PLANNER_LIB_SRC} + ${LANE_PLANNER_LIB_HEADERS} +) +autoware_set_compile_options(${PROJECT_NAME}) + +# Testing +#if(BUILD_TESTING) +# find_package(ament_lint_auto REQUIRED) +# ament_lint_auto_find_test_dependencies() + + # Unit tests +# set(TEST_SOURCES test/test_lane_planner.cpp) +# set(TEST_LANE_PLANNER_EXE test_lane_planner) +# ament_add_gtest(${TEST_LANE_PLANNER_EXE} ${TEST_SOURCES}) +# autoware_set_compile_options(${TEST_LANE_PLANNER_EXE}) +# target_link_libraries(${TEST_LANE_PLANNER_EXE} ${PROJECT_NAME}) +# add_dependencies(${TEST_LANE_PLANNER_EXE} ${PROJECT_NAME}) +#endif() + +# ament package generation and installing +ament_auto_package() diff --git a/src/planning/path_planner/design/path_planner-design.md b/src/planning/path_planner/design/path_planner-design.md new file mode 100644 index 000000000..ff13c4d75 --- /dev/null +++ b/src/planning/path_planner/design/path_planner-design.md @@ -0,0 +1,8 @@ +Path planner {#path-planner} +=========== + +This is the design document for the `path_planner` package. + +# Purpose / Use cases +Path Planner is used to determine trajectory +It will use centerline of lanes obtained from HADMap, convert it to cubic spline, and convert it into a set of potential trajectories. It selects the trajectory that minimizes a cost function. \ No newline at end of file diff --git a/src/planning/path_planner/include/path_planner/cubic_spline.hpp b/src/planning/path_planner/include/path_planner/cubic_spline.hpp new file mode 100644 index 000000000..6aafdc86f --- /dev/null +++ b/src/planning/path_planner/include/path_planner/cubic_spline.hpp @@ -0,0 +1,54 @@ +// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/// \copyright Copyright 2020 The Autoware Foundation +/// \file +/// \brief This file defines the lane_planner class. + +#ifndef PATH_PLANNER__CUBIC_SPLINE_HPP_ +#define PATH_PLANNER__CUBIC_SPLINE_HPP_ + +#include + +namespace navigator +{ +namespace path_planner +{ + //represents a cubic spline: + // x(s) = a_x*s^3 + b_x*s^2 + c_x*s + d_x + // y(s) = a_y*s^3 + b_y*s^2 + c_y*s + d_y + //we can sample a point at a given length along the curve s by evaluating (x(s),y(s)) + + class cubic_spline + { + private: + double ax,bx,cx,dx,ay,by,cy,dy; //coefficients for x(s) and y(s) + + public: + + cubic_spline(double start_arclength, double end_arclength, double ax, double bx, double cx, double dx, double ay, double by, double cy, double dy) + : ax(ax), bx(bx), cx(cx), dx(dx), ay(ay), by(by), cy(cy), dy(dy) { + } + ~cubic_spline() {} + std::pair sample(double arclength); + std::pair sample_first_derivative(double arclength); + std::pair sample_second_derivative(double arclength); + double sample_curvature(double arclength); + double sample_heading(double arclength); + + }; +} +} + +#endif // PATH_PLANNER__CUBIC_SPLINE_HPP_ diff --git a/src/planning/path_planner/include/path_planner/offset_spline.hpp b/src/planning/path_planner/include/path_planner/offset_spline.hpp new file mode 100644 index 000000000..297073692 --- /dev/null +++ b/src/planning/path_planner/include/path_planner/offset_spline.hpp @@ -0,0 +1,65 @@ +// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/// \copyright Copyright 2020 The Autoware Foundation +/// \file +/// \brief This file defines the lane_planner class. + +#ifndef PATH_PLANNER__OFFSET_SPLINE_HPP_ +#define PATH_PLANNER__OFFSET_SPLINE_HPP_ + +#include +#include +#include + +namespace navigator +{ +namespace path_planner +{ + //represents a curve with a lateral offset from a cubic spline: + // p(s) = a(s-start_arclength)^3 + b(s-start_arclength)^2 + c(s-start_arclength) + offset_start + //this curve is in a different coordinate system than the cartesian plane, so we have to convert + // before using the coordinates in other places. + + class offset_spline + { + private: + double start_arclength, end_arclength; + double a,b,c,offset_start,offset_end; //coefficients + double da,db,dc; //coefficients for first derivative wrt s + double d2a,d2b; //coefficients for second derivative wrt s + + void populate_derivatives(); + public: + + offset_spline(double start_arclength, double end_arclength, double offset_start, double offset_end, double a, double b, double c) + : start_arclength(start_arclength), end_arclength(end_arclength), offset_start(offset_start), offset_end(offset_end), a(a), b(b), c(c) { + populate_derivatives(); + } + ~offset_spline() {} + std::tuple sample(double arclength); + std::tuple sample_offset(double arclength, double lateral_offset); + std::tuple sample_first_derivative(double arclength); + std::tuple sample_second_derivative(double arclength); + double sample_curvature(double arclength); + double sample_heading(double arclength); + double sample_heading_offset(double arclength, double lateral_offset); + + }; +} +} + + + +#endif // PATH_PLANNER__OFFSET_SPLINE_HPP_ diff --git a/src/planning/path_planner/include/path_planner/path_planner.hpp b/src/planning/path_planner/include/path_planner/path_planner.hpp new file mode 100644 index 000000000..9c79b38df --- /dev/null +++ b/src/planning/path_planner/include/path_planner/path_planner.hpp @@ -0,0 +1,37 @@ +// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/// \copyright Copyright 2020 The Autoware Foundation +/// \file +/// \brief This file defines the lane_planner class. + +#ifndef PATH_PLANNER__PATH_PLANNER_HPP_ +#define PATH_PLANNER__PATH_PLANNER_HPP_ + +#include + +#include +#include + +namespace navigator +{ +namespace path_planner +{ + +} +} + + + +#endif // PATH_PLANNER__PATH_PLANNER_HPP_ diff --git a/src/planning/path_planner/package.xml b/src/planning/path_planner/package.xml new file mode 100644 index 000000000..75654646a --- /dev/null +++ b/src/planning/path_planner/package.xml @@ -0,0 +1,31 @@ + + + + path_planner + 0.0.1 + path_planner + jim-m + Apache 2.0 + + ament_cmake_auto + autoware_auto_cmake + + autoware_auto_common + autoware_auto_geometry + autoware_auto_msgs + autoware_auto_tf2 + had_map_utils + lanelet2_traffic_rules + motion_common + tf2 + tf2_ros + trajectory_smoother + + ament_cmake_gtest + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/src/planning/path_planner/src/cubic_spline.cpp b/src/planning/path_planner/src/cubic_spline.cpp new file mode 100644 index 000000000..cbcece260 --- /dev/null +++ b/src/planning/path_planner/src/cubic_spline.cpp @@ -0,0 +1,59 @@ +// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "path_planner/cubic_spline.hpp" + +#include + +namespace navigator { +namespace path_planner { + +std::pair cubic_spline::sample(double arclength) { + double s2 = arclength*arclength; + double s3 = arclength*s2; + double xs = ax*s3 + bx*s2 + cx*arclength + dx; + double ys = ay*s3 + by*s2 + cy*arclength + dy; + return std::make_pair(xs,ys); +} + +std::pair cubic_spline::sample_first_derivative(double arclength) { + double s2 = arclength*arclength; + double xs = 3*ax*s2 + 2*bx*arclength + cx; + double ys = 3*ay*s2 + 2*by*arclength + cy; + return std::make_pair(xs,ys); +} + +std::pair cubic_spline::sample_second_derivative(double arclength) { + double xs = 6*ax*arclength + bx; + double ys = 6*ay*arclength + by; + return std::make_pair(xs,ys); +} + +double cubic_spline::sample_heading(double arclength) { + //equation from Hu paper + auto derivative = sample_first_derivative(arclength); + return atan2(derivative.second, derivative.first); +} + +double cubic_spline::sample_curvature(double arclength) { + //equation from Hu paper + auto first_derivative = sample_first_derivative(arclength); + auto second_derivative = sample_second_derivative(arclength); + double denom = first_derivative.first + first_derivative.second; + return (first_derivative.first*second_derivative.second - second_derivative.first*first_derivative.second) + / sqrt(denom*denom*denom); +} + +} +} \ No newline at end of file diff --git a/src/planning/path_planner/src/offset_spline.cpp b/src/planning/path_planner/src/offset_spline.cpp new file mode 100644 index 000000000..3ef3875cf --- /dev/null +++ b/src/planning/path_planner/src/offset_spline.cpp @@ -0,0 +1,21 @@ +// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "path_planner/offset_spline.hpp" + +namespace navigator { +namespace path_planner { + +} +} \ No newline at end of file diff --git a/src/planning/path_planner/src/path_planner.cpp b/src/planning/path_planner/src/path_planner.cpp new file mode 100644 index 000000000..af4aa34f9 --- /dev/null +++ b/src/planning/path_planner/src/path_planner.cpp @@ -0,0 +1,21 @@ +// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "path_planner/path_planner.hpp" + +namespace navigator { + namespace path_planner { + + } +} \ No newline at end of file diff --git a/src/planning/path_planner/test/test_path_planner.cpp b/src/planning/path_planner/test/test_path_planner.cpp new file mode 100644 index 000000000..5058906f2 --- /dev/null +++ b/src/planning/path_planner/test/test_path_planner.cpp @@ -0,0 +1,191 @@ +/*// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +#include "gtest/gtest.h" + +using autoware_auto_msgs::msg::MapPrimitive; +using autoware_auto_msgs::msg::HADMapRoute; +using autoware_auto_msgs::msg::HADMapSegment; +using autoware_auto_msgs::msg::TrajectoryPoint; + +using motion::motion_common::VehicleConfig; +using motion::planning::trajectory_smoother::TrajectorySmootherConfig; + +using autoware::common::types::bool8_t; +using autoware::common::types::float32_t; +using autoware::common::types::float64_t; + +// returns a map with a lane has given number of points(n_points) +// length of the lane will be n_points meters in y direction +lanelet::LaneletMapPtr getALaneletMapWithLaneId( + const lanelet::Id & id, const float64_t velocity, + const size_t n_points) +{ + lanelet::Points3d right_points, left_points, center_points; + constexpr float64_t resolution = 1.0; + for (size_t i = 0; i < n_points; i++) { + const auto y = resolution * static_cast(i); + left_points.push_back(lanelet::Point3d(lanelet::utils::getId(), -1, y, 0)); + right_points.push_back(lanelet::Point3d(lanelet::utils::getId(), 1, y, 0)); + center_points.push_back(lanelet::Point3d(lanelet::utils::getId(), 0, y, 0)); + } + lanelet::LineString3d ls1(lanelet::utils::getId(), left_points); + lanelet::LineString3d ls2(lanelet::utils::getId(), right_points); + lanelet::LineString3d ls3(lanelet::utils::getId(), center_points); + + lanelet::Lanelet ll(id, ls1, ls2); + ll.setCenterline(ls3); + ll.setAttribute(lanelet::AttributeName::SpeedLimit, velocity); + + return lanelet::utils::createMap({ll}); +} + +HADMapRoute getARoute(const int64_t lane_id, const float32_t length) +{ + HADMapRoute had_map_route; + had_map_route.start_point.position.x = 0; + had_map_route.start_point.position.y = 0; + had_map_route.goal_point.position.x = 0; + had_map_route.goal_point.position.y = length; + + MapPrimitive primitive; + primitive.id = lane_id; + HADMapSegment segment; + segment.preferred_primitive_id = primitive.id; + had_map_route.segments.push_back(segment); + had_map_route.segments.front().primitives.push_back(primitive); + + return had_map_route; +} + +class LanePlannerTest : public ::testing::Test +{ +public: + LanePlannerTest() + { + const VehicleConfig vehicle_param{ + 1.0F, // cg_to_front_m: + 1.0F, // cg_to_rear_m: + 0.1F, // front_corner_stiffness: + 0.1F, // rear_corner_stiffness: + 1500.0F, // mass_kg: + 12.0F, // yaw_inertia_kgm2: + 2.0F, // width_m: + 0.5F, // front_overhang_m: + 0.5F // rear_overhang_m: + }; + const TrajectorySmootherConfig config{ + 1.0F, // standard_deviation + 5 // kernel_size + }; + const autoware::lane_planner::LanePlannerConfig planner_config{ + 2.0F // trajectory_resolution + }; + m_planner_ptr = std::make_shared( + vehicle_param, config, + planner_config); + } + std::shared_ptr m_planner_ptr; +}; + +TEST(TestFunction, Distance2d) +{ + TrajectoryPoint pt1, pt2; + pt1.x = 3.0F; + pt1.y = 0.0F; + + pt2.x = 0.0F; + pt2.y = 4.0F; + + // same point returns distance 0 + ASSERT_FLOAT_EQ(autoware::lane_planner::distance2d(pt1, pt1), 0.0F); + + ASSERT_FLOAT_EQ(autoware::lane_planner::distance2d(pt1, pt2), 5.0F); +} + +TEST(TestFunction, Curvature) +{ + TrajectoryPoint pt1, pt2, pt3; + pt1.x = 1.0F; + pt1.y = 0.0F; + + pt2.x = 0.0F; + pt2.y = 1.0F; + + pt3.x = -1.0F; + pt3.y = 0.0F; + + // circle with radius = 1 + ASSERT_FLOAT_EQ(autoware::lane_planner::calculate_curvature(pt1, pt2, pt3), 1.0F); + + // opposite direction gives -1 + ASSERT_FLOAT_EQ(autoware::lane_planner::calculate_curvature(pt3, pt2, pt1), -1.0F); + + pt1 = autoware::common::geometry::times_2d(pt1, 2.0F); + pt2 = autoware::common::geometry::times_2d(pt2, 2.0F); + pt3 = autoware::common::geometry::times_2d(pt3, 2.0F); + + // doubling the radius results in half the curvature + ASSERT_FLOAT_EQ(autoware::lane_planner::calculate_curvature(pt1, pt2, pt3), 0.5F); +} + +TEST_F(LanePlannerTest, PlanSimpleTrajectory) +{ + // create map + const auto lane_id = lanelet::utils::getId(); + constexpr float64_t velocity_mps = 1.0; + constexpr size_t n_points = 5; + const auto lanelet_map_ptr = getALaneletMapWithLaneId(lane_id, velocity_mps, n_points); + + // create route message + const auto had_map_route = getARoute(lane_id, 5.0F); + + const auto trajectory = m_planner_ptr->plan_trajectory(had_map_route, lanelet_map_ptr); + + // return trajectory should not be empty + ASSERT_FALSE(trajectory.points.empty()); + + TrajectoryPoint trajectory_start_point; + trajectory_start_point.x = static_cast(had_map_route.start_point.position.x); + trajectory_start_point.y = static_cast(had_map_route.start_point.position.y); + trajectory_start_point.heading = had_map_route.start_point.heading; + + // start point of trajectory should be same as start point + const auto distance = autoware::lane_planner::distance2d( + trajectory_start_point, + trajectory.points.front()); + ASSERT_DOUBLE_EQ(distance, 0.0); +} + +TEST_F(LanePlannerTest, PlanInvalidRoute) +{ + // create map + const auto lane_id = lanelet::utils::getId(); + constexpr float64_t velocity_mps = 1.0; + constexpr size_t n_points = 5; + const auto lanelet_map_ptr = getALaneletMapWithLaneId(lane_id, velocity_mps, n_points); + + // create route message with invalid id + const auto route = getARoute(lanelet::InvalId, 5.0F); + + const auto trajectory = m_planner_ptr->plan_trajectory(route, lanelet_map_ptr); + + // return trajectory should be empty if there is no valid lane + ASSERT_TRUE(trajectory.points.empty()); +} +*/ \ No newline at end of file From ee349265fb6334df57bc7d798e1f769e5219f3fa Mon Sep 17 00:00:00 2001 From: Jim Date: Wed, 10 Nov 2021 17:16:23 -0600 Subject: [PATCH 2/8] - added library for splines - added wrapper for position splines - added lane center line->spline generation --- src/planning/path_planner/CMakeLists.txt | 32 +- .../path_planner/parameterized_spline.hpp | 50 ++ .../include/path_planner/path_planner.hpp | 33 +- .../include/path_planner/spline.hpp | 747 ++++++++++++++++++ .../path_planner/src/parameterized_spline.cpp | 41 + .../path_planner/src/path_planner.cpp | 126 ++- 6 files changed, 1004 insertions(+), 25 deletions(-) create mode 100644 src/planning/path_planner/include/path_planner/parameterized_spline.hpp create mode 100644 src/planning/path_planner/include/path_planner/spline.hpp create mode 100644 src/planning/path_planner/src/parameterized_spline.cpp diff --git a/src/planning/path_planner/CMakeLists.txt b/src/planning/path_planner/CMakeLists.txt index c634935ce..f3dda05dd 100644 --- a/src/planning/path_planner/CMakeLists.txt +++ b/src/planning/path_planner/CMakeLists.txt @@ -23,12 +23,15 @@ set(LANE_PLANNER_LIB_SRC src/path_planner.cpp src/cubic_spline.cpp src/offset_spline.cpp + src/parameterized_spline.cpp ) set(LANE_PLANNER_LIB_HEADERS include/path_planner/path_planner.hpp include/path_planner/cubic_spline.hpp include/path_planner/offset_spline.hpp + include/path_planner/spline.hpp + include/path_planner/parameterized_spline.hpp ) # generate library @@ -38,19 +41,22 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) autoware_set_compile_options(${PROJECT_NAME}) -# Testing -#if(BUILD_TESTING) -# find_package(ament_lint_auto REQUIRED) -# ament_lint_auto_find_test_dependencies() - - # Unit tests -# set(TEST_SOURCES test/test_lane_planner.cpp) -# set(TEST_LANE_PLANNER_EXE test_lane_planner) -# ament_add_gtest(${TEST_LANE_PLANNER_EXE} ${TEST_SOURCES}) -# autoware_set_compile_options(${TEST_LANE_PLANNER_EXE}) -# target_link_libraries(${TEST_LANE_PLANNER_EXE} ${PROJECT_NAME}) -# add_dependencies(${TEST_LANE_PLANNER_EXE} ${PROJECT_NAME}) -#endif() + Testing +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() + # Unit tests + set(TEST_SOURCES + test/test_lane_planner.cpp + ) + set(TEST_LANE_PLANNER_EXE + test_lane_planner + ) + ament_add_gtest(${TEST_LANE_PLANNER_EXE} ${TEST_SOURCES}) + autoware_set_compile_options(${TEST_LANE_PLANNER_EXE}) + target_link_libraries(${TEST_LANE_PLANNER_EXE} ${PROJECT_NAME}) + add_dependencies(${TEST_LANE_PLANNER_EXE} ${PROJECT_NAME}) +endif() # ament package generation and installing ament_auto_package() diff --git a/src/planning/path_planner/include/path_planner/parameterized_spline.hpp b/src/planning/path_planner/include/path_planner/parameterized_spline.hpp new file mode 100644 index 000000000..cc2130b7a --- /dev/null +++ b/src/planning/path_planner/include/path_planner/parameterized_spline.hpp @@ -0,0 +1,50 @@ +// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/// \copyright Copyright 2020 The Autoware Foundation +/// \file +/// \brief This file defines the lane_planner class. + +#ifndef PATH_PLANNER__PARAMETERIZED_SPLINE_HPP_ +#define PATH_PLANNER__PARAMETERIZED_SPLINE_HPP_ + +#include +#include + +namespace navigator +{ + namespace path_planner + { + // represents a cubic spline: + // x(s) = a_x*s^3 + b_x*s^2 + c_x*s + d_x + // y(s) = a_y*s^3 + b_y*s^2 + c_y*s + d_y + // we can sample a point at a given length along the curve s by evaluating (x(s),y(s)) + // the arc length is based on the chord between points, so it's an approximation. + // using points close in distance helps + + class ParameterizedSpline + { + private: + tk::spline sx, sy; + + public: + ParameterizedSpline(tk::spline sx, tk::spline sy) + : sx(sx), sy(sy) {} + ParameterizedSpline(const std::vector &x, const std::vector &y); + std::pair sample(double s); + } + } +} + +#endif diff --git a/src/planning/path_planner/include/path_planner/path_planner.hpp b/src/planning/path_planner/include/path_planner/path_planner.hpp index 9c79b38df..b1e28efca 100644 --- a/src/planning/path_planner/include/path_planner/path_planner.hpp +++ b/src/planning/path_planner/include/path_planner/path_planner.hpp @@ -19,19 +19,34 @@ #ifndef PATH_PLANNER__PATH_PLANNER_HPP_ #define PATH_PLANNER__PATH_PLANNER_HPP_ -#include - +#include +#include +#include +#include +#include +#include + +#include +#include #include +#include #include namespace navigator { -namespace path_planner -{ - + namespace path_planner + { + class PathPlanner + { + public: + TrajectoryPoints generate_position_trajectory(const HADMapRoute &route, const LaneletMapConstPtr &map); + + private: + //probably need to find a way to bound start and end window + ParameterizedSpline get_center_line_spline(const std::vector &line_points); + std::vector get_center_line_points(const HADMapRoute &route, const LaneletMapConstPtr &map, double resolution) + } + } } -} - - -#endif // PATH_PLANNER__PATH_PLANNER_HPP_ +#endif // PATH_PLANNER__PATH_PLANNER_HPP_ diff --git a/src/planning/path_planner/include/path_planner/spline.hpp b/src/planning/path_planner/include/path_planner/spline.hpp new file mode 100644 index 000000000..7afa01cb4 --- /dev/null +++ b/src/planning/path_planner/include/path_planner/spline.hpp @@ -0,0 +1,747 @@ +/* + * spline.h + * + * simple cubic spline interpolation library without external + * dependencies https://kluge.in-chemnitz.de/opensource/spline/ + * + * --------------------------------------------------------------------- + * Copyright (C) 2011, 2014, 2016, 2021 Tino Kluge (ttk448 at gmail.com) + * + * This program is free software; you can redistribute it and/or + * modify it under the terms of the GNU General Public License + * as published by the Free Software Foundation; either version 2 + * of the License, or (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * --------------------------------------------------------------------- + * + */ + +#ifndef TK_SPLINE_H +#define TK_SPLINE_H + +#include +#include +#include +#include +#include +#ifdef HAVE_SSTREAM +#include +#include +#endif // HAVE_SSTREAM + +// not ideal but disable unused-function warnings +// (we get them because we have implementations in the header file, +// and this is because we want to be able to quickly separate them +// into a cpp file if necessary) +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-function" + +// unnamed namespace only because the implementation is in this +// header file and we don't want to export symbols to the obj files +namespace +{ + + namespace tk + { + + // spline interpolation + class spline + { + public: + // spline types + enum spline_type + { + linear = 10, // linear interpolation + cspline = 30, // cubic splines (classical C^2) + cspline_hermite = 31 // cubic hermite splines (local, only C^1) + }; + + // boundary condition type for the spline end-points + enum bd_type + { + first_deriv = 1, + second_deriv = 2 + }; + + protected: + std::vector m_x, m_y; // x,y coordinates of points + // interpolation parameters + // f(x) = a_i + b_i*(x-x_i) + c_i*(x-x_i)^2 + d_i*(x-x_i)^3 + // where a_i = y_i, or else it won't go through grid points + std::vector m_b, m_c, m_d; // spline coefficients + double m_c0; // for left extrapolation + spline_type m_type; + bd_type m_left, m_right; + double m_left_value, m_right_value; + bool m_made_monotonic; + void set_coeffs_from_b(); // calculate c_i, d_i from b_i + size_t find_closest(double x) const; // closest idx so that m_x[idx]<=x + + public: + // default constructor: set boundary condition to be zero curvature + // at both ends, i.e. natural splines + spline() : m_type(cspline), + m_left(second_deriv), m_right(second_deriv), + m_left_value(0.0), m_right_value(0.0), m_made_monotonic(false) + { + ; + } + spline(const std::vector &X, const std::vector &Y, + spline_type type = cspline, + bool make_monotonic = false, + bd_type left = second_deriv, double left_value = 0.0, + bd_type right = second_deriv, double right_value = 0.0) : m_type(type), + m_left(left), m_right(right), + m_left_value(left_value), m_right_value(right_value), + m_made_monotonic(false) // false correct here: make_monotonic() sets it + { + this->set_points(X, Y, m_type); + if (make_monotonic) + { + this->make_monotonic(); + } + } + + // modify boundary conditions: if called it must be before set_points() + void set_boundary(bd_type left, double left_value, + bd_type right, double right_value); + + // set all data points (cubic_spline=false means linear interpolation) + void set_points(const std::vector &x, + const std::vector &y, + spline_type type = cspline); + + // adjust coefficients so that the spline becomes piecewise monotonic + // where possible + // this is done by adjusting slopes at grid points by a non-negative + // factor and this will break C^2 + // this can also break boundary conditions if adjustments need to + // be made at the boundary points + // returns false if no adjustments have been made, true otherwise + bool make_monotonic(); + + // evaluates the spline at point x + double operator()(double x) const; + double deriv(int order, double x) const; + + // returns the input data points + std::vector get_x() const { return m_x; } + std::vector get_y() const { return m_y; } + double get_x_min() const + { + assert(!m_x.empty()); + return m_x.front(); + } + double get_x_max() const + { + assert(!m_x.empty()); + return m_x.back(); + } + +#ifdef HAVE_SSTREAM + // spline info string, i.e. spline type, boundary conditions etc. + std::string info() const; +#endif // HAVE_SSTREAM + }; + + namespace internal + { + + // band matrix solver + class band_matrix + { + private: + std::vector> m_upper; // upper band + std::vector> m_lower; // lower band + public: + band_matrix(){}; // constructor + band_matrix(int dim, int n_u, int n_l); // constructor + ~band_matrix(){}; // destructor + void resize(int dim, int n_u, int n_l); // init with dim,n_u,n_l + int dim() const; // matrix dimension + int num_upper() const + { + return (int)m_upper.size() - 1; + } + int num_lower() const + { + return (int)m_lower.size() - 1; + } + // access operator + double &operator()(int i, int j); // write + double operator()(int i, int j) const; // read + // we can store an additional diagonal (in m_lower) + double &saved_diag(int i); + double saved_diag(int i) const; + void lu_decompose(); + std::vector r_solve(const std::vector &b) const; + std::vector l_solve(const std::vector &b) const; + std::vector lu_solve(const std::vector &b, + bool is_lu_decomposed = false); + }; + + } // namespace internal + + // --------------------------------------------------------------------- + // implementation part, which could be separated into a cpp file + // --------------------------------------------------------------------- + + // spline implementation + // ----------------------- + + void spline::set_boundary(spline::bd_type left, double left_value, + spline::bd_type right, double right_value) + { + assert(m_x.size() == 0); // set_points() must not have happened yet + m_left = left; + m_right = right; + m_left_value = left_value; + m_right_value = right_value; + } + + void spline::set_coeffs_from_b() + { + assert(m_x.size() == m_y.size()); + assert(m_x.size() == m_b.size()); + assert(m_x.size() > 2); + size_t n = m_b.size(); + if (m_c.size() != n) + m_c.resize(n); + if (m_d.size() != n) + m_d.resize(n); + + for (size_t i = 0; i < n - 1; i++) + { + const double h = m_x[i + 1] - m_x[i]; + // from continuity and differentiability condition + m_c[i] = (3.0 * (m_y[i + 1] - m_y[i]) / h - (2.0 * m_b[i] + m_b[i + 1])) / h; + // from differentiability condition + m_d[i] = ((m_b[i + 1] - m_b[i]) / (3.0 * h) - 2.0 / 3.0 * m_c[i]) / h; + } + + // for left extrapolation coefficients + m_c0 = (m_left == first_deriv) ? 0.0 : m_c[0]; + } + + void spline::set_points(const std::vector &x, + const std::vector &y, + spline_type type) + { + assert(x.size() == y.size()); + assert(x.size() > 2); + m_type = type; + m_made_monotonic = false; + m_x = x; + m_y = y; + int n = (int)x.size(); + // check strict monotonicity of input vector x + for (int i = 0; i < n - 1; i++) + { + assert(m_x[i] < m_x[i + 1]); + } + + if (type == linear) + { + // linear interpolation + m_d.resize(n); + m_c.resize(n); + m_b.resize(n); + for (int i = 0; i < n - 1; i++) + { + m_d[i] = 0.0; + m_c[i] = 0.0; + m_b[i] = (m_y[i + 1] - m_y[i]) / (m_x[i + 1] - m_x[i]); + } + // ignore boundary conditions, set slope equal to the last segment + m_b[n - 1] = m_b[n - 2]; + m_c[n - 1] = 0.0; + m_d[n - 1] = 0.0; + } + else if (type == cspline) + { + // classical cubic splines which are C^2 (twice cont differentiable) + // this requires solving an equation system + + // setting up the matrix and right hand side of the equation system + // for the parameters b[] + internal::band_matrix A(n, 1, 1); + std::vector rhs(n); + for (int i = 1; i < n - 1; i++) + { + A(i, i - 1) = 1.0 / 3.0 * (x[i] - x[i - 1]); + A(i, i) = 2.0 / 3.0 * (x[i + 1] - x[i - 1]); + A(i, i + 1) = 1.0 / 3.0 * (x[i + 1] - x[i]); + rhs[i] = (y[i + 1] - y[i]) / (x[i + 1] - x[i]) - (y[i] - y[i - 1]) / (x[i] - x[i - 1]); + } + // boundary conditions + if (m_left == spline::second_deriv) + { + // 2*c[0] = f'' + A(0, 0) = 2.0; + A(0, 1) = 0.0; + rhs[0] = m_left_value; + } + else if (m_left == spline::first_deriv) + { + // b[0] = f', needs to be re-expressed in terms of c: + // (2c[0]+c[1])(x[1]-x[0]) = 3 ((y[1]-y[0])/(x[1]-x[0]) - f') + A(0, 0) = 2.0 * (x[1] - x[0]); + A(0, 1) = 1.0 * (x[1] - x[0]); + rhs[0] = 3.0 * ((y[1] - y[0]) / (x[1] - x[0]) - m_left_value); + } + else + { + assert(false); + } + if (m_right == spline::second_deriv) + { + // 2*c[n-1] = f'' + A(n - 1, n - 1) = 2.0; + A(n - 1, n - 2) = 0.0; + rhs[n - 1] = m_right_value; + } + else if (m_right == spline::first_deriv) + { + // b[n-1] = f', needs to be re-expressed in terms of c: + // (c[n-2]+2c[n-1])(x[n-1]-x[n-2]) + // = 3 (f' - (y[n-1]-y[n-2])/(x[n-1]-x[n-2])) + A(n - 1, n - 1) = 2.0 * (x[n - 1] - x[n - 2]); + A(n - 1, n - 2) = 1.0 * (x[n - 1] - x[n - 2]); + rhs[n - 1] = 3.0 * (m_right_value - (y[n - 1] - y[n - 2]) / (x[n - 1] - x[n - 2])); + } + else + { + assert(false); + } + + // solve the equation system to obtain the parameters c[] + m_c = A.lu_solve(rhs); + + // calculate parameters b[] and d[] based on c[] + m_d.resize(n); + m_b.resize(n); + for (int i = 0; i < n - 1; i++) + { + m_d[i] = 1.0 / 3.0 * (m_c[i + 1] - m_c[i]) / (x[i + 1] - x[i]); + m_b[i] = (y[i + 1] - y[i]) / (x[i + 1] - x[i]) - 1.0 / 3.0 * (2.0 * m_c[i] + m_c[i + 1]) * (x[i + 1] - x[i]); + } + // for the right extrapolation coefficients (zero cubic term) + // f_{n-1}(x) = y_{n-1} + b*(x-x_{n-1}) + c*(x-x_{n-1})^2 + double h = x[n - 1] - x[n - 2]; + // m_c[n-1] is determined by the boundary condition + m_d[n - 1] = 0.0; + m_b[n - 1] = 3.0 * m_d[n - 2] * h * h + 2.0 * m_c[n - 2] * h + m_b[n - 2]; // = f'_{n-2}(x_{n-1}) + if (m_right == first_deriv) + m_c[n - 1] = 0.0; // force linear extrapolation + } + else if (type == cspline_hermite) + { + // hermite cubic splines which are C^1 (cont. differentiable) + // and derivatives are specified on each grid point + // (here we use 3-point finite differences) + m_b.resize(n); + m_c.resize(n); + m_d.resize(n); + // set b to match 1st order derivative finite difference + for (int i = 1; i < n - 1; i++) + { + const double h = m_x[i + 1] - m_x[i]; + const double hl = m_x[i] - m_x[i - 1]; + m_b[i] = -h / (hl * (hl + h)) * m_y[i - 1] + (h - hl) / (hl * h) * m_y[i] + hl / (h * (hl + h)) * m_y[i + 1]; + } + // boundary conditions determine b[0] and b[n-1] + if (m_left == first_deriv) + { + m_b[0] = m_left_value; + } + else if (m_left == second_deriv) + { + const double h = m_x[1] - m_x[0]; + m_b[0] = 0.5 * (-m_b[1] - 0.5 * m_left_value * h + 3.0 * (m_y[1] - m_y[0]) / h); + } + else + { + assert(false); + } + if (m_right == first_deriv) + { + m_b[n - 1] = m_right_value; + m_c[n - 1] = 0.0; + } + else if (m_right == second_deriv) + { + const double h = m_x[n - 1] - m_x[n - 2]; + m_b[n - 1] = 0.5 * (-m_b[n - 2] + 0.5 * m_right_value * h + 3.0 * (m_y[n - 1] - m_y[n - 2]) / h); + m_c[n - 1] = 0.5 * m_right_value; + } + else + { + assert(false); + } + m_d[n - 1] = 0.0; + + // parameters c and d are determined by continuity and differentiability + set_coeffs_from_b(); + } + else + { + assert(false); + } + + // for left extrapolation coefficients + m_c0 = (m_left == first_deriv) ? 0.0 : m_c[0]; + } + + bool spline::make_monotonic() + { + assert(m_x.size() == m_y.size()); + assert(m_x.size() == m_b.size()); + assert(m_x.size() > 2); + bool modified = false; + const int n = (int)m_x.size(); + // make sure: input data monotonic increasing --> b_i>=0 + // input data monotonic decreasing --> b_i<=0 + for (int i = 0; i < n; i++) + { + int im1 = std::max(i - 1, 0); + int ip1 = std::min(i + 1, n - 1); + if (((m_y[im1] <= m_y[i]) && (m_y[i] <= m_y[ip1]) && m_b[i] < 0.0) || + ((m_y[im1] >= m_y[i]) && (m_y[i] >= m_y[ip1]) && m_b[i] > 0.0)) + { + modified = true; + m_b[i] = 0.0; + } + } + // if input data is monotonic (b[i], b[i+1], avg have all the same sign) + // ensure a sufficient criteria for monotonicity is satisfied: + // sqrt(b[i]^2+b[i+1]^2) <= 3 |avg|, with avg=(y[i+1]-y[i])/h, + for (int i = 0; i < n - 1; i++) + { + double h = m_x[i + 1] - m_x[i]; + double avg = (m_y[i + 1] - m_y[i]) / h; + if (avg == 0.0 && (m_b[i] != 0.0 || m_b[i + 1] != 0.0)) + { + modified = true; + m_b[i] = 0.0; + m_b[i + 1] = 0.0; + } + else if ((m_b[i] >= 0.0 && m_b[i + 1] >= 0.0 && avg > 0.0) || + (m_b[i] <= 0.0 && m_b[i + 1] <= 0.0 && avg < 0.0)) + { + // input data is monotonic + double r = sqrt(m_b[i] * m_b[i] + m_b[i + 1] * m_b[i + 1]) / std::fabs(avg); + if (r > 3.0) + { + // sufficient criteria for monotonicity: r<=3 + // adjust b[i] and b[i+1] + modified = true; + m_b[i] *= (3.0 / r); + m_b[i + 1] *= (3.0 / r); + } + } + } + + if (modified == true) + { + set_coeffs_from_b(); + m_made_monotonic = true; + } + + return modified; + } + + // return the closest idx so that m_x[idx] <= x (return 0 if x::const_iterator it; + it = std::upper_bound(m_x.begin(), m_x.end(), x); // *it > x + size_t idx = std::max(int(it - m_x.begin()) - 1, 0); // m_x[idx] <= x + return idx; + } + + double spline::operator()(double x) const + { + // polynomial evaluation using Horner's scheme + // TODO: consider more numerically accurate algorithms, e.g.: + // - Clenshaw + // - Even-Odd method by A.C.R. Newbery + // - Compensated Horner Scheme + size_t n = m_x.size(); + size_t idx = find_closest(x); + + double h = x - m_x[idx]; + double interpol; + if (x < m_x[0]) + { + // extrapolation to the left + interpol = (m_c0 * h + m_b[0]) * h + m_y[0]; + } + else if (x > m_x[n - 1]) + { + // extrapolation to the right + interpol = (m_c[n - 1] * h + m_b[n - 1]) * h + m_y[n - 1]; + } + else + { + // interpolation + interpol = ((m_d[idx] * h + m_c[idx]) * h + m_b[idx]) * h + m_y[idx]; + } + return interpol; + } + + double spline::deriv(int order, double x) const + { + assert(order > 0); + size_t n = m_x.size(); + size_t idx = find_closest(x); + + double h = x - m_x[idx]; + double interpol; + if (x < m_x[0]) + { + // extrapolation to the left + switch (order) + { + case 1: + interpol = 2.0 * m_c0 * h + m_b[0]; + break; + case 2: + interpol = 2.0 * m_c0; + break; + default: + interpol = 0.0; + break; + } + } + else if (x > m_x[n - 1]) + { + // extrapolation to the right + switch (order) + { + case 1: + interpol = 2.0 * m_c[n - 1] * h + m_b[n - 1]; + break; + case 2: + interpol = 2.0 * m_c[n - 1]; + break; + default: + interpol = 0.0; + break; + } + } + else + { + // interpolation + switch (order) + { + case 1: + interpol = (3.0 * m_d[idx] * h + 2.0 * m_c[idx]) * h + m_b[idx]; + break; + case 2: + interpol = 6.0 * m_d[idx] * h + 2.0 * m_c[idx]; + break; + case 3: + interpol = 6.0 * m_d[idx]; + break; + default: + interpol = 0.0; + break; + } + } + return interpol; + } + +#ifdef HAVE_SSTREAM + std::string spline::info() const + { + std::stringstream ss; + ss << "type " << m_type << ", left boundary deriv " << m_left << " = "; + ss << m_left_value << ", right boundary deriv " << m_right << " = "; + ss << m_right_value << std::endl; + if (m_made_monotonic) + { + ss << "(spline has been adjusted for piece-wise monotonicity)"; + } + return ss.str(); + } +#endif // HAVE_SSTREAM + + namespace internal + { + + // band_matrix implementation + // ------------------------- + + band_matrix::band_matrix(int dim, int n_u, int n_l) + { + resize(dim, n_u, n_l); + } + void band_matrix::resize(int dim, int n_u, int n_l) + { + assert(dim > 0); + assert(n_u >= 0); + assert(n_l >= 0); + m_upper.resize(n_u + 1); + m_lower.resize(n_l + 1); + for (size_t i = 0; i < m_upper.size(); i++) + { + m_upper[i].resize(dim); + } + for (size_t i = 0; i < m_lower.size(); i++) + { + m_lower[i].resize(dim); + } + } + int band_matrix::dim() const + { + if (m_upper.size() > 0) + { + return m_upper[0].size(); + } + else + { + return 0; + } + } + + // defines the new operator (), so that we can access the elements + // by A(i,j), index going from i=0,...,dim()-1 + double &band_matrix::operator()(int i, int j) + { + int k = j - i; // what band is the entry + assert((i >= 0) && (i < dim()) && (j >= 0) && (j < dim())); + assert((-num_lower() <= k) && (k <= num_upper())); + // k=0 -> diagonal, k<0 lower left part, k>0 upper right part + if (k >= 0) + return m_upper[k][i]; + else + return m_lower[-k][i]; + } + double band_matrix::operator()(int i, int j) const + { + int k = j - i; // what band is the entry + assert((i >= 0) && (i < dim()) && (j >= 0) && (j < dim())); + assert((-num_lower() <= k) && (k <= num_upper())); + // k=0 -> diagonal, k<0 lower left part, k>0 upper right part + if (k >= 0) + return m_upper[k][i]; + else + return m_lower[-k][i]; + } + // second diag (used in LU decomposition), saved in m_lower + double band_matrix::saved_diag(int i) const + { + assert((i >= 0) && (i < dim())); + return m_lower[0][i]; + } + double &band_matrix::saved_diag(int i) + { + assert((i >= 0) && (i < dim())); + return m_lower[0][i]; + } + + // LR-Decomposition of a band matrix + void band_matrix::lu_decompose() + { + int i_max, j_max; + int j_min; + double x; + + // preconditioning + // normalize column i so that a_ii=1 + for (int i = 0; i < this->dim(); i++) + { + assert(this->operator()(i, i) != 0.0); + this->saved_diag(i) = 1.0 / this->operator()(i, i); + j_min = std::max(0, i - this->num_lower()); + j_max = std::min(this->dim() - 1, i + this->num_upper()); + for (int j = j_min; j <= j_max; j++) + { + this->operator()(i, j) *= this->saved_diag(i); + } + this->operator()(i, i) = 1.0; // prevents rounding errors + } + + // Gauss LR-Decomposition + for (int k = 0; k < this->dim(); k++) + { + i_max = std::min(this->dim() - 1, k + this->num_lower()); // num_lower not a mistake! + for (int i = k + 1; i <= i_max; i++) + { + assert(this->operator()(k, k) != 0.0); + x = -this->operator()(i, k) / this->operator()(k, k); + this->operator()(i, k) = -x; // assembly part of L + j_max = std::min(this->dim() - 1, k + this->num_upper()); + for (int j = k + 1; j <= j_max; j++) + { + // assembly part of R + this->operator()(i, j) = this->operator()(i, j) + x * this->operator()(k, j); + } + } + } + } + // solves Ly=b + std::vector band_matrix::l_solve(const std::vector &b) const + { + assert(this->dim() == (int)b.size()); + std::vector x(this->dim()); + int j_start; + double sum; + for (int i = 0; i < this->dim(); i++) + { + sum = 0; + j_start = std::max(0, i - this->num_lower()); + for (int j = j_start; j < i; j++) + sum += this->operator()(i, j) * x[j]; + x[i] = (b[i] * this->saved_diag(i)) - sum; + } + return x; + } + // solves Rx=y + std::vector band_matrix::r_solve(const std::vector &b) const + { + assert(this->dim() == (int)b.size()); + std::vector x(this->dim()); + int j_stop; + double sum; + for (int i = this->dim() - 1; i >= 0; i--) + { + sum = 0; + j_stop = std::min(this->dim() - 1, i + this->num_upper()); + for (int j = i + 1; j <= j_stop; j++) + sum += this->operator()(i, j) * x[j]; + x[i] = (b[i] - sum) / this->operator()(i, i); + } + return x; + } + + std::vector band_matrix::lu_solve(const std::vector &b, + bool is_lu_decomposed) + { + assert(this->dim() == (int)b.size()); + std::vector x, y; + if (is_lu_decomposed == false) + { + this->lu_decompose(); + } + y = this->l_solve(b); + x = this->r_solve(y); + return x; + } + + } // namespace internal + + } // namespace tk + +} // namespace + +#pragma GCC diagnostic pop + +#endif /* TK_SPLINE_H */ diff --git a/src/planning/path_planner/src/parameterized_spline.cpp b/src/planning/path_planner/src/parameterized_spline.cpp new file mode 100644 index 000000000..5b5f6dad2 --- /dev/null +++ b/src/planning/path_planner/src/parameterized_spline.cpp @@ -0,0 +1,41 @@ +// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "path_planner/parameterized_spline.hpp" + +#include + +namespace navigator +{ + namespace path_planner + { + std::pair ParameterizedSpline::sample(double s) + { + return std::pair(sx(s), sy(s)); + } + ParameterizedSpline::ParameterizedSpline(const std::vector &points) + { + std::vector T(0, points.size()); + + // time proportional to distance, i.e. traverse the curve at constant speed + // approximate arclength parameter by using straight line distance between points + T[0] = 0; + for (size_t i = 1; i < T.size(); i++) + T[i] = T[i - 1] + sqrt((points[i].x() - points[i - 1].x()) * (points[i].x() - points[i - 1].x()) + (points[i].y() - points[i - 1].y()) * (points[i].y() - points[i - 1].y())); + // setup splines for x and y coordinate + sx = tk::spline(T, X); + sy = tk::spline(T, Y); + } + } +} \ No newline at end of file diff --git a/src/planning/path_planner/src/path_planner.cpp b/src/planning/path_planner/src/path_planner.cpp index af4aa34f9..8cdd305b0 100644 --- a/src/planning/path_planner/src/path_planner.cpp +++ b/src/planning/path_planner/src/path_planner.cpp @@ -14,8 +14,128 @@ #include "path_planner/path_planner.hpp" -namespace navigator { - namespace path_planner { +namespace navigator +{ + namespace path_planner + { + size_t get_closest_lanelet(const lanelet::ConstLanelets &lanelets, const TrajectoryPoint &point) + { + float64_t closest_distance = std::numeric_limits::max(); + size_t closest_index = 0; + for (size_t i = 0; i < lanelets.size(); i++) + { + const auto &llt = lanelets.at(i); + const auto &point2d = lanelet::Point2d(lanelet::InvalId, point.x, point.y).basicPoint2d(); + // TODO(mitsudome-r): change this implementation to remove dependency to boost + const float64_t distance = lanelet::geometry::distanceToCenterline2d(llt, point2d); + if (distance < closest_distance) + { + closest_distance = distance; + closest_index = i; + } + } + return closest_index; + } + float distance2d(const TrajectoryPoint &p1, const TrajectoryPoint &p2) + { + const auto diff = autoware::common::geometry::minus_2d(p1, p2); + return autoware::common::geometry::norm_2d(diff); + } + lanelet::Point3d convertToLaneletPoint( + const autoware_auto_msgs::msg::TrajectoryPoint &pt) + { + return lanelet::Point3d(lanelet::InvalId, pt.x, pt.y, 0.0); + } + ParameterizedSpline get_center_line_spline(const std::vector &line_points) + { + std::vector x_points(line_points.size()); + std::vector y_points(line_points.size()); + for (const auto &p : line_points) + { + x_points.push_back(p.x()); + y_points.push_back(p.y()); + } + return ParameterizedSpline(x_points, y_points); + } + std::vector get_center_line_points(const HADMapRoute &route, const LaneletMapConstPtr &map, double resolution) + { + //a lot of this taken from the autoware implementation of lane_planner + //add the lanes from the route + lanelet::ConstLanelets lanelets; + for (const auto &segment : route.segments) + { + const auto &primitive = segment.primitives.front(); + try + { + const auto lane = map->laneletLayer.get(primitive.id); + lanelets.push_back(lane); + } + catch (const lanelet::NoSuchPrimitiveError &ex) + { + // stop adding lanelets if lane cannot be found. e.g. goal is outside of queried submap + break; + } + } + // return empty trajectory if there are no lanes + if (lanelets.empty()) + { + return TrajectoryPoints(); + } - } + TrajectoryPoint trajectory_start_point; + trajectory_start_point.x = static_cast(had_map_route.start_point.position.x); + trajectory_start_point.y = static_cast(had_map_route.start_point.position.y); + trajectory_start_point.heading = had_map_route.start_point.heading; + + TrajectoryPoint trajectory_goal_point; + trajectory_goal_point.x = static_cast(had_map_route.goal_point.position.x); + trajectory_goal_point.y = static_cast(had_map_route.goal_point.position.y); + trajectory_goal_point.heading = had_map_route.goal_point.heading; + + const auto start_index = get_closest_lanelet(lanelets, trajectory_start_point); + std::vector line_points; + // set position and velocity + for (size_t i = start_index; i < lanelets.size(); i++) + { + const auto &lanelet = lanelets.at(i); + const auto ¢erline = autoware::common::had_map_utils::generateFineCenterline( + lanelet, + m_planner_config.trajectory_resolution); + + float64_t start_length = 0; + if (i == start_index) + { + const auto start_point = convertToLaneletPoint(trajectory_start_point); + start_length = + lanelet::geometry::toArcCoordinates(to2D(centerline), to2D(start_point)).length; + } + + float64_t end_length = std::numeric_limits::max(); + if (i == lanelets.size() - 1) + { + const auto goal_point = convertToLaneletPoint(trajectory_goal_point); + end_length = lanelet::geometry::toArcCoordinates(to2D(centerline), to2D(goal_point)).length; + } + + float64_t accumulated_length = 0; + // skip first point to avoid inserting overlaps + for (size_t j = 1; j < centerline.size(); j++) + { + const auto llt_prev_pt = centerline[j - 1]; + const auto llt_pt = centerline[j]; + accumulated_length += lanelet::geometry::distance2d(to2D(llt_prev_pt), to2D(llt_pt)); + if (accumulated_length < start_length) + { + continue; + } + if (accumulated_length > end_length) + { + break; + } + line_points.push_back(llt_pt); + } + } + line_points.push_back(trajectory_goal_point); + } + } } \ No newline at end of file From ffeab79b42c4284d2598fe9836cfb82d872454ca Mon Sep 17 00:00:00 2001 From: Jim Date: Wed, 10 Nov 2021 17:18:44 -0600 Subject: [PATCH 3/8] fix typo --- src/planning/path_planner/src/path_planner.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/planning/path_planner/src/path_planner.cpp b/src/planning/path_planner/src/path_planner.cpp index 8cdd305b0..a672526f2 100644 --- a/src/planning/path_planner/src/path_planner.cpp +++ b/src/planning/path_planner/src/path_planner.cpp @@ -100,8 +100,9 @@ namespace navigator const auto &lanelet = lanelets.at(i); const auto ¢erline = autoware::common::had_map_utils::generateFineCenterline( lanelet, - m_planner_config.trajectory_resolution); + resolution); + //arc length along lane for start point float64_t start_length = 0; if (i == start_index) { @@ -109,7 +110,7 @@ namespace navigator start_length = lanelet::geometry::toArcCoordinates(to2D(centerline), to2D(start_point)).length; } - + //arc length along lane for end point float64_t end_length = std::numeric_limits::max(); if (i == lanelets.size() - 1) { @@ -121,6 +122,7 @@ namespace navigator // skip first point to avoid inserting overlaps for (size_t j = 1; j < centerline.size(); j++) { + //may be able to make searching for the first length more effecient const auto llt_prev_pt = centerline[j - 1]; const auto llt_pt = centerline[j]; accumulated_length += lanelet::geometry::distance2d(to2D(llt_prev_pt), to2D(llt_pt)); From d112d089ea6a027a1c1f786ae4a873727b2c50f8 Mon Sep 17 00:00:00 2001 From: Jim Date: Wed, 10 Nov 2021 19:12:03 -0600 Subject: [PATCH 4/8] added points for lane boundaries --- .../path_planner/include/lane_points.hpp | 45 +++++++++++++++++++ .../include/path_planner/path_planner.hpp | 1 + .../path_planner/src/path_planner.cpp | 39 ++++++++++++++-- 3 files changed, 82 insertions(+), 3 deletions(-) create mode 100644 src/planning/path_planner/include/lane_points.hpp diff --git a/src/planning/path_planner/include/lane_points.hpp b/src/planning/path_planner/include/lane_points.hpp new file mode 100644 index 000000000..535456164 --- /dev/null +++ b/src/planning/path_planner/include/lane_points.hpp @@ -0,0 +1,45 @@ +// Copyright 2020 The Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +//    http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +/// \copyright Copyright 2020 The Autoware Foundation +/// \file +/// \brief This file defines the lane_planner class. + +#ifndef PATH_PLANNER__LANE_POINTS_HPP_ +#define PATH_PLANNER__LANE_POINTS_HPP_ + +#include +#include + +namespace navigator +{ + namespace path_planner + { + //represents a sampling of points for the left boundary, center line, and right boundary of a lane + + class LanePoints + { + public: + const lanelet::LineString3d left; + const lanelet::LineString3d center; + const lanelet::LineString3d right; + LanePoints(lanelet::LineString3d left, lanelet::LineString3d center, lanelet::LineString3d right) + : left(left), cneter(center), right(right) + { + } + }; + } +} + +#endif diff --git a/src/planning/path_planner/include/path_planner/path_planner.hpp b/src/planning/path_planner/include/path_planner/path_planner.hpp index b1e28efca..31b3a42be 100644 --- a/src/planning/path_planner/include/path_planner/path_planner.hpp +++ b/src/planning/path_planner/include/path_planner/path_planner.hpp @@ -20,6 +20,7 @@ #define PATH_PLANNER__PATH_PLANNER_HPP_ #include +#include #include #include #include diff --git a/src/planning/path_planner/src/path_planner.cpp b/src/planning/path_planner/src/path_planner.cpp index a672526f2..677409078 100644 --- a/src/planning/path_planner/src/path_planner.cpp +++ b/src/planning/path_planner/src/path_planner.cpp @@ -18,6 +18,38 @@ namespace navigator { namespace path_planner { + LanePoints sample_center_line_and_boundaries( + const lanelet::ConstLanelet &lanelet_obj, const float64_t resolution) + { + // Get length of longer border + const float64_t left_length = + static_cast(lanelet::geometry::length(lanelet_obj.leftBound())); + const float64_t right_length = + static_cast(lanelet::geometry::length(lanelet_obj.rightBound())); + const float64_t longer_distance = (left_length > right_length) ? left_length : right_length; + const int32_t num_segments = + std::max(static_cast(ceil(longer_distance / resolution)), 1); + + // Resample points + const auto left_points = resamplePoints(lanelet_obj.leftBound(), num_segments); + const auto right_points = resamplePoints(lanelet_obj.rightBound(), num_segments); + + // Create centerline + lanelet::LineString3d centerline(lanelet::utils::getId()); + lanelet::LineString3d leftBoundary(lanelet::utils::getId()); + lanelet::LineString3d rightBoundary(lanelet::utils::getId()); + for (size_t i = 0; i < static_cast(num_segments + 1); i++) + { + const auto center_basic_point = (right_points.at(i) + left_points.at(i)) / 2.0; + const lanelet::Point3d center_point( + lanelet::utils::getId(), center_basic_point.x(), center_basic_point.y(), + center_basic_point.z()); + centerline.push_back(center_point); + leftBoundary.push_back(left_points.at(i)); + rightBoundary.push_back(right_points.at(i)); + } + return LanePoints(liftBoundary, centerline, rightBoundary); + } size_t get_closest_lanelet(const lanelet::ConstLanelets &lanelets, const TrajectoryPoint &point) { float64_t closest_distance = std::numeric_limits::max(); @@ -98,9 +130,10 @@ namespace navigator for (size_t i = start_index; i < lanelets.size(); i++) { const auto &lanelet = lanelets.at(i); - const auto ¢erline = autoware::common::had_map_utils::generateFineCenterline( - lanelet, - resolution); + const auto ¢erline = sample_center_line_and_boundaries( + lanelet, + resolution) + .center; //arc length along lane for start point float64_t start_length = 0; From 5e3d6baabb1c06d8d3af229c7bd5fa4c49f02eb4 Mon Sep 17 00:00:00 2001 From: jim-works Date: Thu, 11 Nov 2021 19:54:07 -0600 Subject: [PATCH 5/8] fix compiler errors and some other stuff i forgot --- src/planning/path_planner/CMakeLists.txt | 23 ++- .../include/path_planner/cubic_spline.hpp | 54 ------ .../{ => path_planner}/lane_points.hpp | 2 +- .../include/path_planner/map_utils.hpp | 27 +++ .../include/path_planner/offset_spline.hpp | 65 ------- .../path_planner/parameterized_spline.hpp | 6 +- .../include/path_planner/path_planner.hpp | 13 +- .../include/path_planner/spline.hpp | 4 + .../path_planner/src/cubic_spline.cpp | 59 ------- src/planning/path_planner/src/map_utils.cpp | 159 ++++++++++++++++++ .../path_planner/src/offset_spline.cpp | 21 --- .../path_planner/src/parameterized_spline.cpp | 13 +- .../path_planner/src/path_planner.cpp | 93 +++++----- 13 files changed, 263 insertions(+), 276 deletions(-) delete mode 100644 src/planning/path_planner/include/path_planner/cubic_spline.hpp rename src/planning/path_planner/include/{ => path_planner}/lane_points.hpp (95%) create mode 100644 src/planning/path_planner/include/path_planner/map_utils.hpp delete mode 100644 src/planning/path_planner/include/path_planner/offset_spline.hpp delete mode 100644 src/planning/path_planner/src/cubic_spline.cpp create mode 100644 src/planning/path_planner/src/map_utils.cpp delete mode 100644 src/planning/path_planner/src/offset_spline.cpp diff --git a/src/planning/path_planner/CMakeLists.txt b/src/planning/path_planner/CMakeLists.txt index f3dda05dd..d1a8ab011 100644 --- a/src/planning/path_planner/CMakeLists.txt +++ b/src/planning/path_planner/CMakeLists.txt @@ -21,17 +21,16 @@ ament_auto_find_build_dependencies() set(LANE_PLANNER_LIB_SRC src/path_planner.cpp - src/cubic_spline.cpp - src/offset_spline.cpp src/parameterized_spline.cpp + src/map_utils.cpp ) set(LANE_PLANNER_LIB_HEADERS include/path_planner/path_planner.hpp - include/path_planner/cubic_spline.hpp - include/path_planner/offset_spline.hpp include/path_planner/spline.hpp include/path_planner/parameterized_spline.hpp + include/path_planner/lane_points.hpp + include/path_planner/map_utils.hpp ) # generate library @@ -41,21 +40,21 @@ ament_auto_add_library(${PROJECT_NAME} SHARED ) autoware_set_compile_options(${PROJECT_NAME}) - Testing +# Testing if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() # Unit tests set(TEST_SOURCES - test/test_lane_planner.cpp + test/test_path_planner.cpp ) - set(TEST_LANE_PLANNER_EXE - test_lane_planner + set(TEST_PATH_PLANNER_EXE + test_path_planner ) - ament_add_gtest(${TEST_LANE_PLANNER_EXE} ${TEST_SOURCES}) - autoware_set_compile_options(${TEST_LANE_PLANNER_EXE}) - target_link_libraries(${TEST_LANE_PLANNER_EXE} ${PROJECT_NAME}) - add_dependencies(${TEST_LANE_PLANNER_EXE} ${PROJECT_NAME}) + ament_add_gtest(${TEST_PATH_PLANNER_EXE} ${TEST_SOURCES}) + autoware_set_compile_options(${TEST_PATH_PLANNER_EXE}) + target_link_libraries(${TEST_PATH_PLANNER_EXE} ${PROJECT_NAME}) + add_dependencies(${TEST_PATH_PLANNER_EXE} ${PROJECT_NAME}) endif() # ament package generation and installing diff --git a/src/planning/path_planner/include/path_planner/cubic_spline.hpp b/src/planning/path_planner/include/path_planner/cubic_spline.hpp deleted file mode 100644 index 6aafdc86f..000000000 --- a/src/planning/path_planner/include/path_planner/cubic_spline.hpp +++ /dev/null @@ -1,54 +0,0 @@ -// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/// \copyright Copyright 2020 The Autoware Foundation -/// \file -/// \brief This file defines the lane_planner class. - -#ifndef PATH_PLANNER__CUBIC_SPLINE_HPP_ -#define PATH_PLANNER__CUBIC_SPLINE_HPP_ - -#include - -namespace navigator -{ -namespace path_planner -{ - //represents a cubic spline: - // x(s) = a_x*s^3 + b_x*s^2 + c_x*s + d_x - // y(s) = a_y*s^3 + b_y*s^2 + c_y*s + d_y - //we can sample a point at a given length along the curve s by evaluating (x(s),y(s)) - - class cubic_spline - { - private: - double ax,bx,cx,dx,ay,by,cy,dy; //coefficients for x(s) and y(s) - - public: - - cubic_spline(double start_arclength, double end_arclength, double ax, double bx, double cx, double dx, double ay, double by, double cy, double dy) - : ax(ax), bx(bx), cx(cx), dx(dx), ay(ay), by(by), cy(cy), dy(dy) { - } - ~cubic_spline() {} - std::pair sample(double arclength); - std::pair sample_first_derivative(double arclength); - std::pair sample_second_derivative(double arclength); - double sample_curvature(double arclength); - double sample_heading(double arclength); - - }; -} -} - -#endif // PATH_PLANNER__CUBIC_SPLINE_HPP_ diff --git a/src/planning/path_planner/include/lane_points.hpp b/src/planning/path_planner/include/path_planner/lane_points.hpp similarity index 95% rename from src/planning/path_planner/include/lane_points.hpp rename to src/planning/path_planner/include/path_planner/lane_points.hpp index 535456164..e6298cc21 100644 --- a/src/planning/path_planner/include/lane_points.hpp +++ b/src/planning/path_planner/include/path_planner/lane_points.hpp @@ -35,7 +35,7 @@ namespace navigator const lanelet::LineString3d center; const lanelet::LineString3d right; LanePoints(lanelet::LineString3d left, lanelet::LineString3d center, lanelet::LineString3d right) - : left(left), cneter(center), right(right) + : left(left), center(center), right(right) { } }; diff --git a/src/planning/path_planner/include/path_planner/map_utils.hpp b/src/planning/path_planner/include/path_planner/map_utils.hpp new file mode 100644 index 000000000..37edf4a83 --- /dev/null +++ b/src/planning/path_planner/include/path_planner/map_utils.hpp @@ -0,0 +1,27 @@ +#include "autoware_auto_msgs/msg/trajectory.hpp" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace autoware::common::types; +using TrajectoryPoint = autoware_auto_msgs::msg::TrajectoryPoint; +using autoware_auto_msgs::msg::HADMapRoute; +using autoware_auto_msgs::msg::Trajectory; + +namespace navigator +{ + namespace path_planner + { + namespace map_utils { + LanePoints sample_center_line_and_boundaries( + const lanelet::ConstLanelet &lanelet_obj, const float64_t resolution); + } + } +} \ No newline at end of file diff --git a/src/planning/path_planner/include/path_planner/offset_spline.hpp b/src/planning/path_planner/include/path_planner/offset_spline.hpp deleted file mode 100644 index 297073692..000000000 --- a/src/planning/path_planner/include/path_planner/offset_spline.hpp +++ /dev/null @@ -1,65 +0,0 @@ -// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/// \copyright Copyright 2020 The Autoware Foundation -/// \file -/// \brief This file defines the lane_planner class. - -#ifndef PATH_PLANNER__OFFSET_SPLINE_HPP_ -#define PATH_PLANNER__OFFSET_SPLINE_HPP_ - -#include -#include -#include - -namespace navigator -{ -namespace path_planner -{ - //represents a curve with a lateral offset from a cubic spline: - // p(s) = a(s-start_arclength)^3 + b(s-start_arclength)^2 + c(s-start_arclength) + offset_start - //this curve is in a different coordinate system than the cartesian plane, so we have to convert - // before using the coordinates in other places. - - class offset_spline - { - private: - double start_arclength, end_arclength; - double a,b,c,offset_start,offset_end; //coefficients - double da,db,dc; //coefficients for first derivative wrt s - double d2a,d2b; //coefficients for second derivative wrt s - - void populate_derivatives(); - public: - - offset_spline(double start_arclength, double end_arclength, double offset_start, double offset_end, double a, double b, double c) - : start_arclength(start_arclength), end_arclength(end_arclength), offset_start(offset_start), offset_end(offset_end), a(a), b(b), c(c) { - populate_derivatives(); - } - ~offset_spline() {} - std::tuple sample(double arclength); - std::tuple sample_offset(double arclength, double lateral_offset); - std::tuple sample_first_derivative(double arclength); - std::tuple sample_second_derivative(double arclength); - double sample_curvature(double arclength); - double sample_heading(double arclength); - double sample_heading_offset(double arclength, double lateral_offset); - - }; -} -} - - - -#endif // PATH_PLANNER__OFFSET_SPLINE_HPP_ diff --git a/src/planning/path_planner/include/path_planner/parameterized_spline.hpp b/src/planning/path_planner/include/path_planner/parameterized_spline.hpp index cc2130b7a..57901974c 100644 --- a/src/planning/path_planner/include/path_planner/parameterized_spline.hpp +++ b/src/planning/path_planner/include/path_planner/parameterized_spline.hpp @@ -20,7 +20,9 @@ #define PATH_PLANNER__PARAMETERIZED_SPLINE_HPP_ #include -#include +#include + +#pragma GCC diagnostic ignored "-Wsubobject-linkage" //disable this warning since the spline library uses an anonymous namespace namespace navigator { @@ -43,7 +45,7 @@ namespace navigator : sx(sx), sy(sy) {} ParameterizedSpline(const std::vector &x, const std::vector &y); std::pair sample(double s); - } + }; } } diff --git a/src/planning/path_planner/include/path_planner/path_planner.hpp b/src/planning/path_planner/include/path_planner/path_planner.hpp index 31b3a42be..505690c90 100644 --- a/src/planning/path_planner/include/path_planner/path_planner.hpp +++ b/src/planning/path_planner/include/path_planner/path_planner.hpp @@ -21,11 +21,9 @@ #include #include -#include #include #include #include -#include #include #include @@ -33,6 +31,11 @@ #include #include +using TrajectoryPoint = autoware_auto_msgs::msg::TrajectoryPoint; +using autoware_auto_msgs::msg::HADMapRoute; +using autoware_auto_msgs::msg::Trajectory; + + namespace navigator { namespace path_planner @@ -40,13 +43,13 @@ namespace navigator class PathPlanner { public: - TrajectoryPoints generate_position_trajectory(const HADMapRoute &route, const LaneletMapConstPtr &map); + std::vector generate_position_trajectory(const HADMapRoute &route, const lanelet::LaneletMapConstPtr &map); private: //probably need to find a way to bound start and end window ParameterizedSpline get_center_line_spline(const std::vector &line_points); - std::vector get_center_line_points(const HADMapRoute &route, const LaneletMapConstPtr &map, double resolution) - } + std::vector get_center_line_points(const HADMapRoute &route, const lanelet::LaneletMapConstPtr &map, double resolution); + }; } } diff --git a/src/planning/path_planner/include/path_planner/spline.hpp b/src/planning/path_planner/include/path_planner/spline.hpp index 7afa01cb4..653195359 100644 --- a/src/planning/path_planner/include/path_planner/spline.hpp +++ b/src/planning/path_planner/include/path_planner/spline.hpp @@ -42,6 +42,10 @@ // into a cpp file if necessary) #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wunused-function" +#pragma GCC diagnostic ignored "-Wsign-conversion" +#pragma GCC diagnostic ignored "-Wconversion" +#pragma GCC diagnostic ignored "-Wold-style-cast" + // unnamed namespace only because the implementation is in this // header file and we don't want to export symbols to the obj files diff --git a/src/planning/path_planner/src/cubic_spline.cpp b/src/planning/path_planner/src/cubic_spline.cpp deleted file mode 100644 index cbcece260..000000000 --- a/src/planning/path_planner/src/cubic_spline.cpp +++ /dev/null @@ -1,59 +0,0 @@ -// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "path_planner/cubic_spline.hpp" - -#include - -namespace navigator { -namespace path_planner { - -std::pair cubic_spline::sample(double arclength) { - double s2 = arclength*arclength; - double s3 = arclength*s2; - double xs = ax*s3 + bx*s2 + cx*arclength + dx; - double ys = ay*s3 + by*s2 + cy*arclength + dy; - return std::make_pair(xs,ys); -} - -std::pair cubic_spline::sample_first_derivative(double arclength) { - double s2 = arclength*arclength; - double xs = 3*ax*s2 + 2*bx*arclength + cx; - double ys = 3*ay*s2 + 2*by*arclength + cy; - return std::make_pair(xs,ys); -} - -std::pair cubic_spline::sample_second_derivative(double arclength) { - double xs = 6*ax*arclength + bx; - double ys = 6*ay*arclength + by; - return std::make_pair(xs,ys); -} - -double cubic_spline::sample_heading(double arclength) { - //equation from Hu paper - auto derivative = sample_first_derivative(arclength); - return atan2(derivative.second, derivative.first); -} - -double cubic_spline::sample_curvature(double arclength) { - //equation from Hu paper - auto first_derivative = sample_first_derivative(arclength); - auto second_derivative = sample_second_derivative(arclength); - double denom = first_derivative.first + first_derivative.second; - return (first_derivative.first*second_derivative.second - second_derivative.first*first_derivative.second) - / sqrt(denom*denom*denom); -} - -} -} \ No newline at end of file diff --git a/src/planning/path_planner/src/map_utils.cpp b/src/planning/path_planner/src/map_utils.cpp new file mode 100644 index 000000000..8fd017ad7 --- /dev/null +++ b/src/planning/path_planner/src/map_utils.cpp @@ -0,0 +1,159 @@ +#include "autoware_auto_msgs/msg/trajectory.hpp" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace autoware::common::types; +using TrajectoryPoint = autoware_auto_msgs::msg::TrajectoryPoint; +using autoware_auto_msgs::msg::HADMapRoute; +using autoware_auto_msgs::msg::Trajectory; + +namespace navigator +{ + namespace path_planner + { + namespace map_utils + { + //all these functions are copied from autoware's had_map_utils. I needed them available here for the get_center_line_points function + // and exposing them in the header for had_map_utils broke the build for another package + std::vector calculateSegmentDistances(const lanelet::ConstLineString3d &line_string) + { + std::vector segment_distances; + segment_distances.reserve(line_string.size() - 1); + + for (size_t i = 1; i < line_string.size(); ++i) + { + const auto distance = lanelet::geometry::distance(line_string[i], line_string[i - 1]); + segment_distances.push_back(distance); + } + + return segment_distances; + } + + std::vector calculateAccumulatedLengths(const lanelet::ConstLineString3d &line_string) + { + const auto segment_distances = calculateSegmentDistances(line_string); + + std::vector accumulated_lengths{0}; + accumulated_lengths.reserve(segment_distances.size() + 1); + std::partial_sum( + std::begin(segment_distances), std::end(segment_distances), + std::back_inserter(accumulated_lengths)); + + return accumulated_lengths; + } + + std::pair findNearestIndexPair( + const std::vector &accumulated_lengths, const float64_t target_length) + { + // List size + const auto N = accumulated_lengths.size(); + + // Front + if (target_length < accumulated_lengths.at(1)) + { + return std::make_pair(0, 1); + } + + // Back + if (target_length > accumulated_lengths.at(N - 2)) + { + return std::make_pair(N - 2, N - 1); + } + + // Middle + for (size_t i = 1; i < N; ++i) + { + if ( + accumulated_lengths.at(i - 1) <= target_length && + target_length <= accumulated_lengths.at(i)) + { + return std::make_pair(i - 1, i); + } + } + + // Throw an exception because this never happens + throw std::runtime_error( + "findNearestIndexPair(): No nearest point found."); + } + + std::vector resamplePoints( + const lanelet::ConstLineString3d &line_string, const int32_t num_segments) + { + // Calculate length + const auto line_length = lanelet::geometry::length(line_string); + + // Calculate accumulated lengths + const auto accumulated_lengths = calculateAccumulatedLengths(line_string); + + // Create each segment + std::vector resampled_points; + for (auto i = 0; i <= num_segments; ++i) + { + // Find two nearest points + const float64_t target_length = (static_cast(i) / num_segments) * + static_cast(line_length); + const auto index_pair = findNearestIndexPair(accumulated_lengths, target_length); + + // Apply linear interpolation + const lanelet::BasicPoint3d back_point = line_string[index_pair.first]; + const lanelet::BasicPoint3d front_point = line_string[index_pair.second]; + const auto direction_vector = (front_point - back_point); + + const auto back_length = accumulated_lengths.at(index_pair.first); + const auto front_length = accumulated_lengths.at(index_pair.second); + const auto segment_length = front_length - back_length; + const auto target_point = + back_point + (direction_vector * (target_length - back_length) / segment_length); + + // Add to list + resampled_points.push_back(target_point); + } + + return resampled_points; + } + LanePoints sample_center_line_and_boundaries( + const lanelet::ConstLanelet &lanelet_obj, const float64_t resolution) + { + // Get length of longer border + const float64_t left_length = + static_cast(lanelet::geometry::length(lanelet_obj.leftBound())); + const float64_t right_length = + static_cast(lanelet::geometry::length(lanelet_obj.rightBound())); + const float64_t longer_distance = (left_length > right_length) ? left_length : right_length; + const int32_t num_segments = + std::max(static_cast(ceil(longer_distance / resolution)), 1); + + // Resample points + const auto left_points = resamplePoints(lanelet_obj.leftBound(), num_segments); + const auto right_points = resamplePoints(lanelet_obj.rightBound(), num_segments); + + // Create centerline + lanelet::LineString3d centerline(lanelet::utils::getId()); + lanelet::LineString3d leftBoundary(lanelet::utils::getId()); + lanelet::LineString3d rightBoundary(lanelet::utils::getId()); + for (size_t i = 0; i < static_cast(num_segments + 1); i++) + { + const auto center_basic_point = (right_points.at(i) + left_points.at(i)) / 2.0; + //converting to point3d + const lanelet::Point3d center_point( + lanelet::utils::getId(), center_basic_point.x(), center_basic_point.y(), + center_basic_point.z()); + const lanelet::Point3d left_point(lanelet::utils::getId(), left_points.at(i).x(), left_points.at(i).y(), left_points.at(i).z()); + const lanelet::Point3d right_point(lanelet::utils::getId(), right_points.at(i).x(), right_points.at(i).y(), right_points.at(i).z()); + centerline.push_back(center_point); + leftBoundary.push_back(left_point); + rightBoundary.push_back(right_point); + } + return LanePoints(leftBoundary, centerline, rightBoundary); + } + } + } +} \ No newline at end of file diff --git a/src/planning/path_planner/src/offset_spline.cpp b/src/planning/path_planner/src/offset_spline.cpp deleted file mode 100644 index 3ef3875cf..000000000 --- a/src/planning/path_planner/src/offset_spline.cpp +++ /dev/null @@ -1,21 +0,0 @@ -// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include "path_planner/offset_spline.hpp" - -namespace navigator { -namespace path_planner { - -} -} \ No newline at end of file diff --git a/src/planning/path_planner/src/parameterized_spline.cpp b/src/planning/path_planner/src/parameterized_spline.cpp index 5b5f6dad2..1156632a1 100644 --- a/src/planning/path_planner/src/parameterized_spline.cpp +++ b/src/planning/path_planner/src/parameterized_spline.cpp @@ -22,20 +22,21 @@ namespace navigator { std::pair ParameterizedSpline::sample(double s) { - return std::pair(sx(s), sy(s)); + return std::pair(sx(s), sy(s)); } - ParameterizedSpline::ParameterizedSpline(const std::vector &points) + ParameterizedSpline::ParameterizedSpline(const std::vector &x, const std::vector &y) { - std::vector T(0, points.size()); + assert(x.size() == y.size()); + std::vector T(x.size(), 0); // time proportional to distance, i.e. traverse the curve at constant speed // approximate arclength parameter by using straight line distance between points T[0] = 0; for (size_t i = 1; i < T.size(); i++) - T[i] = T[i - 1] + sqrt((points[i].x() - points[i - 1].x()) * (points[i].x() - points[i - 1].x()) + (points[i].y() - points[i - 1].y()) * (points[i].y() - points[i - 1].y())); + T[i] = T[i - 1] + sqrt((x[i] - x[i - 1]) * (x[i] - x[i - 1]) + (y[i] - y[i - 1]) * (y[i] - y[i - 1])); // setup splines for x and y coordinate - sx = tk::spline(T, X); - sy = tk::spline(T, Y); + sx = tk::spline(T, x); + sy = tk::spline(T, y); } } } \ No newline at end of file diff --git a/src/planning/path_planner/src/path_planner.cpp b/src/planning/path_planner/src/path_planner.cpp index 677409078..84bcdf340 100644 --- a/src/planning/path_planner/src/path_planner.cpp +++ b/src/planning/path_planner/src/path_planner.cpp @@ -13,44 +13,30 @@ // limitations under the License. #include "path_planner/path_planner.hpp" +#include "path_planner/map_utils.hpp" + +#include "autoware_auto_msgs/msg/trajectory.hpp" +#include +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace autoware::common::types; +using TrajectoryPoint = autoware_auto_msgs::msg::TrajectoryPoint; +using autoware_auto_msgs::msg::HADMapRoute; +using autoware_auto_msgs::msg::Trajectory; namespace navigator { namespace path_planner { - LanePoints sample_center_line_and_boundaries( - const lanelet::ConstLanelet &lanelet_obj, const float64_t resolution) - { - // Get length of longer border - const float64_t left_length = - static_cast(lanelet::geometry::length(lanelet_obj.leftBound())); - const float64_t right_length = - static_cast(lanelet::geometry::length(lanelet_obj.rightBound())); - const float64_t longer_distance = (left_length > right_length) ? left_length : right_length; - const int32_t num_segments = - std::max(static_cast(ceil(longer_distance / resolution)), 1); - - // Resample points - const auto left_points = resamplePoints(lanelet_obj.leftBound(), num_segments); - const auto right_points = resamplePoints(lanelet_obj.rightBound(), num_segments); - - // Create centerline - lanelet::LineString3d centerline(lanelet::utils::getId()); - lanelet::LineString3d leftBoundary(lanelet::utils::getId()); - lanelet::LineString3d rightBoundary(lanelet::utils::getId()); - for (size_t i = 0; i < static_cast(num_segments + 1); i++) - { - const auto center_basic_point = (right_points.at(i) + left_points.at(i)) / 2.0; - const lanelet::Point3d center_point( - lanelet::utils::getId(), center_basic_point.x(), center_basic_point.y(), - center_basic_point.z()); - centerline.push_back(center_point); - leftBoundary.push_back(left_points.at(i)); - rightBoundary.push_back(right_points.at(i)); - } - return LanePoints(liftBoundary, centerline, rightBoundary); - } - size_t get_closest_lanelet(const lanelet::ConstLanelets &lanelets, const TrajectoryPoint &point) + + size_t get_closest_lanelet(const lanelet::ConstLanelets &lanelets, const autoware_auto_msgs::msg::TrajectoryPoint &point) { float64_t closest_distance = std::numeric_limits::max(); size_t closest_index = 0; @@ -68,11 +54,6 @@ namespace navigator } return closest_index; } - float distance2d(const TrajectoryPoint &p1, const TrajectoryPoint &p2) - { - const auto diff = autoware::common::geometry::minus_2d(p1, p2); - return autoware::common::geometry::norm_2d(diff); - } lanelet::Point3d convertToLaneletPoint( const autoware_auto_msgs::msg::TrajectoryPoint &pt) { @@ -89,8 +70,17 @@ namespace navigator } return ParameterizedSpline(x_points, y_points); } - std::vector get_center_line_points(const HADMapRoute &route, const LaneletMapConstPtr &map, double resolution) + autoware_auto_msgs::msg::TrajectoryPoint convertToTrajectoryPoint(const lanelet::ConstPoint3d & pt) + { + autoware_auto_msgs::msg::TrajectoryPoint trajectory_point; + trajectory_point.x = static_cast(pt.x()); + trajectory_point.y = static_cast(pt.y()); + trajectory_point.longitudinal_velocity_mps = 0; + return trajectory_point; + } + std::vector get_center_line_points(const HADMapRoute &route, const lanelet::LaneletMapConstPtr &map, double resolution) { + using lanelet::utils::to2D; //a lot of this taken from the autoware implementation of lane_planner //add the lanes from the route lanelet::ConstLanelets lanelets; @@ -111,26 +101,26 @@ namespace navigator // return empty trajectory if there are no lanes if (lanelets.empty()) { - return TrajectoryPoints(); + return std::vector(); } - TrajectoryPoint trajectory_start_point; - trajectory_start_point.x = static_cast(had_map_route.start_point.position.x); - trajectory_start_point.y = static_cast(had_map_route.start_point.position.y); - trajectory_start_point.heading = had_map_route.start_point.heading; + autoware_auto_msgs::msg::TrajectoryPoint trajectory_start_point; + trajectory_start_point.x = static_cast(route.start_point.position.x); + trajectory_start_point.y = static_cast(route.start_point.position.y); + trajectory_start_point.heading = route.start_point.heading; - TrajectoryPoint trajectory_goal_point; - trajectory_goal_point.x = static_cast(had_map_route.goal_point.position.x); - trajectory_goal_point.y = static_cast(had_map_route.goal_point.position.y); - trajectory_goal_point.heading = had_map_route.goal_point.heading; + autoware_auto_msgs::msg::TrajectoryPoint trajectory_goal_point; + trajectory_goal_point.x = static_cast(route.goal_point.position.x); + trajectory_goal_point.y = static_cast(route.goal_point.position.y); + trajectory_goal_point.heading = route.goal_point.heading; const auto start_index = get_closest_lanelet(lanelets, trajectory_start_point); - std::vector line_points; + std::vector line_points; // set position and velocity for (size_t i = start_index; i < lanelets.size(); i++) { const auto &lanelet = lanelets.at(i); - const auto ¢erline = sample_center_line_and_boundaries( + const auto ¢erline = map_utils::sample_center_line_and_boundaries( lanelet, resolution) .center; @@ -167,10 +157,11 @@ namespace navigator { break; } - line_points.push_back(llt_pt); + line_points.push_back(convertToTrajectoryPoint(llt_pt)); } } line_points.push_back(trajectory_goal_point); + return line_points; } } } \ No newline at end of file From 53dc8f2b7a9e3d708639107ea5e40d4c9ec61f97 Mon Sep 17 00:00:00 2001 From: jim-works Date: Wed, 17 Nov 2021 20:38:31 -0600 Subject: [PATCH 6/8] updated formatting + tests --- src/planning/path_planner/CMakeLists.txt | 61 ++++---- .../include/path_planner/lane_points.hpp | 25 +-- .../include/path_planner/map_utils.hpp | 17 +- .../path_planner/parameterized_spline.hpp | 25 +-- .../include/path_planner/path_planner.hpp | 30 ++-- src/planning/path_planner/package.xml | 8 +- src/planning/path_planner/src/map_utils.cpp | 9 ++ .../path_planner/src/parameterized_spline.cpp | 8 + .../path_planner/src/path_planner.cpp | 27 ++-- .../test/test_parameterized_spline.cpp | 56 +++++++ .../path_planner/test/test_path_planner.cpp | 145 ++++-------------- 11 files changed, 194 insertions(+), 217 deletions(-) create mode 100644 src/planning/path_planner/test/test_parameterized_spline.cpp diff --git a/src/planning/path_planner/CMakeLists.txt b/src/planning/path_planner/CMakeLists.txt index d1a8ab011..539336240 100644 --- a/src/planning/path_planner/CMakeLists.txt +++ b/src/planning/path_planner/CMakeLists.txt @@ -1,31 +1,34 @@ -# Copyright 2020 The Autoware Foundation # -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -#    http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. + # Package: path_planner + # Filename: CMakeLists.txt + # Author: Jim Moore + # Email: jim3moore@gmail.com + # Copyright: 2021, Nova UTD + # License: MIT License + # cmake_minimum_required(VERSION 3.5) project(path_planner) +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 14) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + # dependencies find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() -set(LANE_PLANNER_LIB_SRC +set(PATH_PLANNER_LIB_SRC src/path_planner.cpp src/parameterized_spline.cpp src/map_utils.cpp ) -set(LANE_PLANNER_LIB_HEADERS +set(PATH_PLANNER_LIB_HEADERS include/path_planner/path_planner.hpp include/path_planner/spline.hpp include/path_planner/parameterized_spline.hpp @@ -35,26 +38,26 @@ set(LANE_PLANNER_LIB_HEADERS # generate library ament_auto_add_library(${PROJECT_NAME} SHARED - ${LANE_PLANNER_LIB_SRC} - ${LANE_PLANNER_LIB_HEADERS} + ${PATH_PLANNER_LIB_SRC} + ${PATH_PLANNER_LIB_HEADERS} ) autoware_set_compile_options(${PROJECT_NAME}) -# Testing if(BUILD_TESTING) - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() - # Unit tests - set(TEST_SOURCES + find_package(ament_lint_auto REQUIRED) # General test dependency + ament_lint_auto_find_test_dependencies() # Find any test dependencies declared in package.xml + + ament_add_gtest(tests test/test_path_planner.cpp - ) - set(TEST_PATH_PLANNER_EXE - test_path_planner - ) - ament_add_gtest(${TEST_PATH_PLANNER_EXE} ${TEST_SOURCES}) - autoware_set_compile_options(${TEST_PATH_PLANNER_EXE}) - target_link_libraries(${TEST_PATH_PLANNER_EXE} ${PROJECT_NAME}) - add_dependencies(${TEST_PATH_PLANNER_EXE} ${PROJECT_NAME}) + test/test_parameterized_spline.cpp) + + ament_target_dependencies(tests + autoware_auto_common autoware_auto_geometry + autoware_auto_msgs + had_map_utils) + + target_link_libraries(tests ${PROJECT_NAME} gtest_main) + add_dependencies(tests ${PROJECT_NAME}) endif() # ament package generation and installing diff --git a/src/planning/path_planner/include/path_planner/lane_points.hpp b/src/planning/path_planner/include/path_planner/lane_points.hpp index e6298cc21..51a3880a8 100644 --- a/src/planning/path_planner/include/path_planner/lane_points.hpp +++ b/src/planning/path_planner/include/path_planner/lane_points.hpp @@ -1,20 +1,11 @@ -// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/// \copyright Copyright 2020 The Autoware Foundation -/// \file -/// \brief This file defines the lane_planner class. +/* + * Package: path_planner + * Filename: lane_points.hpp + * Author: Jim Moore + * Email: jim3moore@gmail.com + * Copyright: 2021, Nova UTD + * License: MIT License + */ #ifndef PATH_PLANNER__LANE_POINTS_HPP_ #define PATH_PLANNER__LANE_POINTS_HPP_ diff --git a/src/planning/path_planner/include/path_planner/map_utils.hpp b/src/planning/path_planner/include/path_planner/map_utils.hpp index 37edf4a83..4ae6df8cc 100644 --- a/src/planning/path_planner/include/path_planner/map_utils.hpp +++ b/src/planning/path_planner/include/path_planner/map_utils.hpp @@ -1,3 +1,16 @@ +/* + * Package: path_planner + * Filename: map_utils.hpp + * Author: Jim Moore + * Email: jim3moore@gmail.com + * Copyright: 2021, Nova UTD + * License: MIT License + */ + +#ifndef PATH_PLANNER_MAP_UTILS_HPP +#define PATH_PLANNER_MAP_UTILS_HPP + + #include "autoware_auto_msgs/msg/trajectory.hpp" #include #include @@ -24,4 +37,6 @@ namespace navigator const lanelet::ConstLanelet &lanelet_obj, const float64_t resolution); } } -} \ No newline at end of file +} + +#endif \ No newline at end of file diff --git a/src/planning/path_planner/include/path_planner/parameterized_spline.hpp b/src/planning/path_planner/include/path_planner/parameterized_spline.hpp index 57901974c..507a960fb 100644 --- a/src/planning/path_planner/include/path_planner/parameterized_spline.hpp +++ b/src/planning/path_planner/include/path_planner/parameterized_spline.hpp @@ -1,20 +1,11 @@ -// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/// \copyright Copyright 2020 The Autoware Foundation -/// \file -/// \brief This file defines the lane_planner class. +/* + * Package: path_planner + * Filename: parameterized_spline.hpp + * Author: Jim Moore + * Email: jim3moore@gmail.com + * Copyright: 2021, Nova UTD + * License: MIT License + */ #ifndef PATH_PLANNER__PARAMETERIZED_SPLINE_HPP_ #define PATH_PLANNER__PARAMETERIZED_SPLINE_HPP_ diff --git a/src/planning/path_planner/include/path_planner/path_planner.hpp b/src/planning/path_planner/include/path_planner/path_planner.hpp index 505690c90..b9fec10d3 100644 --- a/src/planning/path_planner/include/path_planner/path_planner.hpp +++ b/src/planning/path_planner/include/path_planner/path_planner.hpp @@ -1,20 +1,11 @@ -// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -/// \copyright Copyright 2020 The Autoware Foundation -/// \file -/// \brief This file defines the lane_planner class. +/* + * Package: path_planner + * Filename: path_planner.hpp + * Author: Jim Moore + * Email: jim3moore@gmail.com + * Copyright: 2021, Nova UTD + * License: MIT License + */ #ifndef PATH_PLANNER__PATH_PLANNER_HPP_ #define PATH_PLANNER__PATH_PLANNER_HPP_ @@ -44,11 +35,12 @@ namespace navigator { public: std::vector generate_position_trajectory(const HADMapRoute &route, const lanelet::LaneletMapConstPtr &map); + ParameterizedSpline get_center_line_spline(const std::vector &line_points); + std::vector get_center_line_points(const HADMapRoute &route, const lanelet::LaneletMapConstPtr &map, double resolution); private: //probably need to find a way to bound start and end window - ParameterizedSpline get_center_line_spline(const std::vector &line_points); - std::vector get_center_line_points(const HADMapRoute &route, const lanelet::LaneletMapConstPtr &map, double resolution); + }; } } diff --git a/src/planning/path_planner/package.xml b/src/planning/path_planner/package.xml index 75654646a..3f2e86fd2 100644 --- a/src/planning/path_planner/package.xml +++ b/src/planning/path_planner/package.xml @@ -4,8 +4,8 @@ path_planner 0.0.1 path_planner - jim-m - Apache 2.0 + Jim Moore + MIT ament_cmake_auto autoware_auto_cmake @@ -15,15 +15,13 @@ autoware_auto_msgs autoware_auto_tf2 had_map_utils - lanelet2_traffic_rules motion_common tf2 tf2_ros - trajectory_smoother ament_cmake_gtest ament_lint_auto - ament_lint_common + voltron_test_utils ament_cmake diff --git a/src/planning/path_planner/src/map_utils.cpp b/src/planning/path_planner/src/map_utils.cpp index 8fd017ad7..bfdbdfda7 100644 --- a/src/planning/path_planner/src/map_utils.cpp +++ b/src/planning/path_planner/src/map_utils.cpp @@ -1,3 +1,12 @@ +/* + * Package: path_planner + * Filename: map_utils.cpp + * Author: Jim Moore + * Email: jim3moore@gmail.com + * Copyright: 2021, Nova UTD + * License: MIT License + */ + #include "autoware_auto_msgs/msg/trajectory.hpp" #include #include diff --git a/src/planning/path_planner/src/parameterized_spline.cpp b/src/planning/path_planner/src/parameterized_spline.cpp index 1156632a1..d77e90570 100644 --- a/src/planning/path_planner/src/parameterized_spline.cpp +++ b/src/planning/path_planner/src/parameterized_spline.cpp @@ -12,6 +12,14 @@ // See the License for the specific language governing permissions and // limitations under the License. +/* + * Package: path_planner + * Filename: parameterized_spline.cpp + * Author: Jim Moore + * Email: jim3moore@gmail.com + * Copyright: 2021, Nova UTD + * License: MIT License + */ #include "path_planner/parameterized_spline.hpp" #include diff --git a/src/planning/path_planner/src/path_planner.cpp b/src/planning/path_planner/src/path_planner.cpp index 84bcdf340..5bfe02337 100644 --- a/src/planning/path_planner/src/path_planner.cpp +++ b/src/planning/path_planner/src/path_planner.cpp @@ -1,16 +1,11 @@ -// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. +/* + * Package: path_planner + * Filename: path_planner.cpp + * Author: Jim Moore + * Email: jim3moore@gmail.com + * Copyright: 2021, Nova UTD + * License: MIT License + */ #include "path_planner/path_planner.hpp" #include "path_planner/map_utils.hpp" @@ -59,14 +54,14 @@ namespace navigator { return lanelet::Point3d(lanelet::InvalId, pt.x, pt.y, 0.0); } - ParameterizedSpline get_center_line_spline(const std::vector &line_points) + ParameterizedSpline get_center_line_spline(const std::vector &line_points) { std::vector x_points(line_points.size()); std::vector y_points(line_points.size()); for (const auto &p : line_points) { - x_points.push_back(p.x()); - y_points.push_back(p.y()); + x_points.push_back(p.x); + y_points.push_back(p.y); } return ParameterizedSpline(x_points, y_points); } diff --git a/src/planning/path_planner/test/test_parameterized_spline.cpp b/src/planning/path_planner/test/test_parameterized_spline.cpp new file mode 100644 index 000000000..2f39ea6b6 --- /dev/null +++ b/src/planning/path_planner/test/test_parameterized_spline.cpp @@ -0,0 +1,56 @@ +/* + * Package: path_planner + * Filename: test_parameterized_spline.cpp + * Author: Jim Moore + * Email: jim3moore@gmail.com + * Copyright: 2021, Nova UTD + * License: MIT License + */ + +// Basic tests for the splines + +#include +#include + +#include + +using namespace navigator::path_planner; + +class TestSpline : public ::testing::Test { +public: + + TestSpline() : spline(std::vector(),std::vector()) { + xs.push_back(0); + ys.push_back(0); + + xs.push_back(0.1); + ys.push_back(0.2); + + xs.push_back(0.5); + ys.push_back(0.5); + + xs.push_back(0.2); + ys.push_back(0.7); + + spline = ParameterizedSpline(xs, ys); + }; + ParameterizedSpline spline; + std::vector xs; + std::vector ys; +}; + + +TEST_F(TestSpline, test_arc_length_parameterization) { + //estimate arc length by evaluating at small intervals + double arclength = 0; + double step_size = 0.1; + auto old_point = spline.sample(0); + for (double p = 0; p < 2; p += step_size) { + auto current_point = spline.sample(p); + arclength += sqrt((old_point.first - current_point.first) * (old_point.first - current_point.first) + (old_point.second - current_point.second) * (old_point.second - current_point.second)); + old_point = current_point; + } + //last point sampled should be approx equal to point sampled at estimated arc length + ASSERT_TRUE(abs(old_point.first-spline.sample(arclength).first < 0.1)); + ASSERT_TRUE(abs(old_point.second-spline.sample(arclength).second < 0.1)); +} \ No newline at end of file diff --git a/src/planning/path_planner/test/test_path_planner.cpp b/src/planning/path_planner/test/test_path_planner.cpp index 5058906f2..65677623a 100644 --- a/src/planning/path_planner/test/test_path_planner.cpp +++ b/src/planning/path_planner/test/test_path_planner.cpp @@ -1,18 +1,13 @@ -/*// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - -#include +/* + * Package: path_planner + * Filename: test_path_planner.cpp + * Author: Jim Moore + * Email: jim3moore@gmail.com + * Copyright: 2021, Nova UTD + * License: MIT License + */ + +#include #include #include @@ -23,9 +18,6 @@ using autoware_auto_msgs::msg::HADMapRoute; using autoware_auto_msgs::msg::HADMapSegment; using autoware_auto_msgs::msg::TrajectoryPoint; -using motion::motion_common::VehicleConfig; -using motion::planning::trajectory_smoother::TrajectorySmootherConfig; - using autoware::common::types::bool8_t; using autoware::common::types::float32_t; using autoware::common::types::float64_t; @@ -73,78 +65,21 @@ HADMapRoute getARoute(const int64_t lane_id, const float32_t length) return had_map_route; } -class LanePlannerTest : public ::testing::Test +double sqr_distance(TrajectoryPoint a, TrajectoryPoint b) { + return (a.x-b.x)*(a.x-b.x)+(a.y-b.y)*(a.y-b.y)+(a.z-b.z)*(a.z-b.z); +} + +class PathPlannerTest : public ::testing::Test { public: - LanePlannerTest() + PathPlannerTest() { - const VehicleConfig vehicle_param{ - 1.0F, // cg_to_front_m: - 1.0F, // cg_to_rear_m: - 0.1F, // front_corner_stiffness: - 0.1F, // rear_corner_stiffness: - 1500.0F, // mass_kg: - 12.0F, // yaw_inertia_kgm2: - 2.0F, // width_m: - 0.5F, // front_overhang_m: - 0.5F // rear_overhang_m: - }; - const TrajectorySmootherConfig config{ - 1.0F, // standard_deviation - 5 // kernel_size - }; - const autoware::lane_planner::LanePlannerConfig planner_config{ - 2.0F // trajectory_resolution - }; - m_planner_ptr = std::make_shared( - vehicle_param, config, - planner_config); + m_planner_ptr = std::make_shared(); } - std::shared_ptr m_planner_ptr; + std::shared_ptr m_planner_ptr; }; -TEST(TestFunction, Distance2d) -{ - TrajectoryPoint pt1, pt2; - pt1.x = 3.0F; - pt1.y = 0.0F; - - pt2.x = 0.0F; - pt2.y = 4.0F; - - // same point returns distance 0 - ASSERT_FLOAT_EQ(autoware::lane_planner::distance2d(pt1, pt1), 0.0F); - - ASSERT_FLOAT_EQ(autoware::lane_planner::distance2d(pt1, pt2), 5.0F); -} - -TEST(TestFunction, Curvature) -{ - TrajectoryPoint pt1, pt2, pt3; - pt1.x = 1.0F; - pt1.y = 0.0F; - - pt2.x = 0.0F; - pt2.y = 1.0F; - - pt3.x = -1.0F; - pt3.y = 0.0F; - - // circle with radius = 1 - ASSERT_FLOAT_EQ(autoware::lane_planner::calculate_curvature(pt1, pt2, pt3), 1.0F); - - // opposite direction gives -1 - ASSERT_FLOAT_EQ(autoware::lane_planner::calculate_curvature(pt3, pt2, pt1), -1.0F); - - pt1 = autoware::common::geometry::times_2d(pt1, 2.0F); - pt2 = autoware::common::geometry::times_2d(pt2, 2.0F); - pt3 = autoware::common::geometry::times_2d(pt3, 2.0F); - - // doubling the radius results in half the curvature - ASSERT_FLOAT_EQ(autoware::lane_planner::calculate_curvature(pt1, pt2, pt3), 0.5F); -} - -TEST_F(LanePlannerTest, PlanSimpleTrajectory) +TEST_F(PathPlannerTest, get_center_line_points) { // create map const auto lane_id = lanelet::utils::getId(); @@ -155,37 +90,21 @@ TEST_F(LanePlannerTest, PlanSimpleTrajectory) // create route message const auto had_map_route = getARoute(lane_id, 5.0F); - const auto trajectory = m_planner_ptr->plan_trajectory(had_map_route, lanelet_map_ptr); + const std::vector points = m_planner_ptr->get_center_line_points(had_map_route, lanelet_map_ptr, 5); - // return trajectory should not be empty - ASSERT_FALSE(trajectory.points.empty()); + // return points should not be empty + ASSERT_FALSE(points.empty()); + // there should be 5 points total + ASSERT_TRUE(points.size() == 5); - TrajectoryPoint trajectory_start_point; - trajectory_start_point.x = static_cast(had_map_route.start_point.position.x); - trajectory_start_point.y = static_cast(had_map_route.start_point.position.y); - trajectory_start_point.heading = had_map_route.start_point.heading; + TrajectoryPoint start_point; + start_point.x = static_cast(had_map_route.start_point.position.x); + start_point.y = static_cast(had_map_route.start_point.position.y); + start_point.heading = had_map_route.start_point.heading; - // start point of trajectory should be same as start point - const auto distance = autoware::lane_planner::distance2d( - trajectory_start_point, - trajectory.points.front()); + // start point of center line and route should be the same + auto distance = sqr_distance( + start_point, + points.front()); ASSERT_DOUBLE_EQ(distance, 0.0); } - -TEST_F(LanePlannerTest, PlanInvalidRoute) -{ - // create map - const auto lane_id = lanelet::utils::getId(); - constexpr float64_t velocity_mps = 1.0; - constexpr size_t n_points = 5; - const auto lanelet_map_ptr = getALaneletMapWithLaneId(lane_id, velocity_mps, n_points); - - // create route message with invalid id - const auto route = getARoute(lanelet::InvalId, 5.0F); - - const auto trajectory = m_planner_ptr->plan_trajectory(route, lanelet_map_ptr); - - // return trajectory should be empty if there is no valid lane - ASSERT_TRUE(trajectory.points.empty()); -} -*/ \ No newline at end of file From 2349ee5128e2d3d7d02adbcb2196abee81eac2af Mon Sep 17 00:00:00 2001 From: jim-works Date: Thu, 18 Nov 2021 16:51:45 -0600 Subject: [PATCH 7/8] fix tests and add more comments --- src/planning/path_planner/CMakeLists.txt | 35 +-- .../path_planner/parameterized_spline.hpp | 2 + .../include/path_planner/path_planner.hpp | 2 + .../path_planner/src/path_planner.cpp | 232 +++++++++--------- .../test/test_parameterized_spline.cpp | 54 ++-- .../path_planner/test/test_path_planner.cpp | 29 +-- 6 files changed, 182 insertions(+), 172 deletions(-) diff --git a/src/planning/path_planner/CMakeLists.txt b/src/planning/path_planner/CMakeLists.txt index 539336240..480424db9 100644 --- a/src/planning/path_planner/CMakeLists.txt +++ b/src/planning/path_planner/CMakeLists.txt @@ -1,11 +1,11 @@ # - # Package: path_planner - # Filename: CMakeLists.txt - # Author: Jim Moore - # Email: jim3moore@gmail.com - # Copyright: 2021, Nova UTD - # License: MIT License - # +# Package: path_planner +# Filename: CMakeLists.txt +# Author: Jim Moore +# Email: jim3moore@gmail.com +# Copyright: 2021, Nova UTD +# License: MIT License +# cmake_minimum_required(VERSION 3.5) project(path_planner) @@ -22,26 +22,18 @@ endif() find_package(ament_cmake_auto REQUIRED) ament_auto_find_build_dependencies() -set(PATH_PLANNER_LIB_SRC +# Build a library from our source files. This is just a convenience +# mechanism to prevent having to explicitly list all files for every +# executable. +ament_auto_add_library(path_planner_lib STATIC src/path_planner.cpp src/parameterized_spline.cpp src/map_utils.cpp -) - -set(PATH_PLANNER_LIB_HEADERS - include/path_planner/path_planner.hpp include/path_planner/spline.hpp - include/path_planner/parameterized_spline.hpp include/path_planner/lane_points.hpp - include/path_planner/map_utils.hpp ) +target_include_directories(path_planner_lib PUBLIC include) -# generate library -ament_auto_add_library(${PROJECT_NAME} SHARED - ${PATH_PLANNER_LIB_SRC} - ${PATH_PLANNER_LIB_HEADERS} -) -autoware_set_compile_options(${PROJECT_NAME}) if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) # General test dependency @@ -56,8 +48,7 @@ if(BUILD_TESTING) autoware_auto_msgs had_map_utils) - target_link_libraries(tests ${PROJECT_NAME} gtest_main) - add_dependencies(tests ${PROJECT_NAME}) + target_link_libraries(tests path_planner_lib gtest_main) endif() # ament package generation and installing diff --git a/src/planning/path_planner/include/path_planner/parameterized_spline.hpp b/src/planning/path_planner/include/path_planner/parameterized_spline.hpp index 507a960fb..7c4fd50ee 100644 --- a/src/planning/path_planner/include/path_planner/parameterized_spline.hpp +++ b/src/planning/path_planner/include/path_planner/parameterized_spline.hpp @@ -25,6 +25,7 @@ namespace navigator // we can sample a point at a given length along the curve s by evaluating (x(s),y(s)) // the arc length is based on the chord between points, so it's an approximation. // using points close in distance helps + // NOTE: points should be < 0.1 units away from each other for a good approximation class ParameterizedSpline { @@ -34,6 +35,7 @@ namespace navigator public: ParameterizedSpline(tk::spline sx, tk::spline sy) : sx(sx), sy(sy) {} + // NOTE: points should be < 0.1 units away from each other for a good approximation ParameterizedSpline(const std::vector &x, const std::vector &y); std::pair sample(double s); }; diff --git a/src/planning/path_planner/include/path_planner/path_planner.hpp b/src/planning/path_planner/include/path_planner/path_planner.hpp index b9fec10d3..153880b20 100644 --- a/src/planning/path_planner/include/path_planner/path_planner.hpp +++ b/src/planning/path_planner/include/path_planner/path_planner.hpp @@ -31,6 +31,8 @@ namespace navigator { namespace path_planner { + //generates potential paths using cubic splines and gives them costs according to several factors + //right now only generates the center line for a lane and the spline for that class PathPlanner { public: diff --git a/src/planning/path_planner/src/path_planner.cpp b/src/planning/path_planner/src/path_planner.cpp index 5bfe02337..4de8025e2 100644 --- a/src/planning/path_planner/src/path_planner.cpp +++ b/src/planning/path_planner/src/path_planner.cpp @@ -26,137 +26,137 @@ using TrajectoryPoint = autoware_auto_msgs::msg::TrajectoryPoint; using autoware_auto_msgs::msg::HADMapRoute; using autoware_auto_msgs::msg::Trajectory; -namespace navigator +using namespace navigator::path_planner; + + + +size_t get_closest_lanelet(const lanelet::ConstLanelets &lanelets, const autoware_auto_msgs::msg::TrajectoryPoint &point) { - namespace path_planner + float64_t closest_distance = std::numeric_limits::max(); + size_t closest_index = 0; + for (size_t i = 0; i < lanelets.size(); i++) { - - size_t get_closest_lanelet(const lanelet::ConstLanelets &lanelets, const autoware_auto_msgs::msg::TrajectoryPoint &point) + const auto &llt = lanelets.at(i); + const auto &point2d = lanelet::Point2d(lanelet::InvalId, point.x, point.y).basicPoint2d(); + // TODO(mitsudome-r): change this implementation to remove dependency to boost + const float64_t distance = lanelet::geometry::distanceToCenterline2d(llt, point2d); + if (distance < closest_distance) { - float64_t closest_distance = std::numeric_limits::max(); - size_t closest_index = 0; - for (size_t i = 0; i < lanelets.size(); i++) - { - const auto &llt = lanelets.at(i); - const auto &point2d = lanelet::Point2d(lanelet::InvalId, point.x, point.y).basicPoint2d(); - // TODO(mitsudome-r): change this implementation to remove dependency to boost - const float64_t distance = lanelet::geometry::distanceToCenterline2d(llt, point2d); - if (distance < closest_distance) - { - closest_distance = distance; - closest_index = i; - } - } - return closest_index; + closest_distance = distance; + closest_index = i; } - lanelet::Point3d convertToLaneletPoint( - const autoware_auto_msgs::msg::TrajectoryPoint &pt) + } + return closest_index; +} +lanelet::Point3d convertToLaneletPoint( + const autoware_auto_msgs::msg::TrajectoryPoint &pt) +{ + return lanelet::Point3d(lanelet::InvalId, pt.x, pt.y, 0.0); +} +ParameterizedSpline PathPlanner::get_center_line_spline(const std::vector &line_points) +{ + std::vector x_points(line_points.size()); + std::vector y_points(line_points.size()); + for (const auto &p : line_points) + { + x_points.push_back(p.x); + y_points.push_back(p.y); + } + return ParameterizedSpline(x_points, y_points); +} +autoware_auto_msgs::msg::TrajectoryPoint convertToTrajectoryPoint(const lanelet::ConstPoint3d &pt) +{ + autoware_auto_msgs::msg::TrajectoryPoint trajectory_point; + trajectory_point.x = static_cast(pt.x()); + trajectory_point.y = static_cast(pt.y()); + trajectory_point.longitudinal_velocity_mps = 0; + return trajectory_point; +} +//resolution should be < 0.1 to get good approximation +std::vector PathPlanner::get_center_line_points(const HADMapRoute &route, const lanelet::LaneletMapConstPtr &map, double resolution) +{ + using lanelet::utils::to2D; + //a lot of this taken from the autoware implementation of lane_planner + //add the lanes from the route + lanelet::ConstLanelets lanelets; + for (const auto &segment : route.segments) + { + const auto &primitive = segment.primitives.front(); + try { - return lanelet::Point3d(lanelet::InvalId, pt.x, pt.y, 0.0); + const auto lane = map->laneletLayer.get(primitive.id); + lanelets.push_back(lane); } - ParameterizedSpline get_center_line_spline(const std::vector &line_points) + catch (const lanelet::NoSuchPrimitiveError &ex) { - std::vector x_points(line_points.size()); - std::vector y_points(line_points.size()); - for (const auto &p : line_points) - { - x_points.push_back(p.x); - y_points.push_back(p.y); - } - return ParameterizedSpline(x_points, y_points); + // stop adding lanelets if lane cannot be found. e.g. goal is outside of queried submap + break; } - autoware_auto_msgs::msg::TrajectoryPoint convertToTrajectoryPoint(const lanelet::ConstPoint3d & pt) + } + // return empty trajectory if there are no lanes + if (lanelets.empty()) + { + return std::vector(); + } + + autoware_auto_msgs::msg::TrajectoryPoint trajectory_start_point; + trajectory_start_point.x = static_cast(route.start_point.position.x); + trajectory_start_point.y = static_cast(route.start_point.position.y); + trajectory_start_point.heading = route.start_point.heading; + + autoware_auto_msgs::msg::TrajectoryPoint trajectory_goal_point; + trajectory_goal_point.x = static_cast(route.goal_point.position.x); + trajectory_goal_point.y = static_cast(route.goal_point.position.y); + trajectory_goal_point.heading = route.goal_point.heading; + + const auto start_index = get_closest_lanelet(lanelets, trajectory_start_point); + std::vector line_points; + // set position and velocity + std::cout << "start index: " << start_index << std::endl; + for (size_t i = start_index; i < lanelets.size(); i++) + { + const auto &lanelet = lanelets.at(i); + const auto ¢erline = map_utils::sample_center_line_and_boundaries( + lanelet, + resolution) + .center; + //arc length along lane for start point + float64_t start_length = 0; + if (i == start_index) { - autoware_auto_msgs::msg::TrajectoryPoint trajectory_point; - trajectory_point.x = static_cast(pt.x()); - trajectory_point.y = static_cast(pt.y()); - trajectory_point.longitudinal_velocity_mps = 0; - return trajectory_point; + const auto start_point = convertToLaneletPoint(trajectory_start_point); + start_length = + lanelet::geometry::toArcCoordinates(to2D(centerline), to2D(start_point)).length; + } - std::vector get_center_line_points(const HADMapRoute &route, const lanelet::LaneletMapConstPtr &map, double resolution) + std::cout << "start length: " << start_length << std::endl; + //arc length along lane for end point + float64_t end_length = std::numeric_limits::max(); + if (i == lanelets.size() - 1) { - using lanelet::utils::to2D; - //a lot of this taken from the autoware implementation of lane_planner - //add the lanes from the route - lanelet::ConstLanelets lanelets; - for (const auto &segment : route.segments) - { - const auto &primitive = segment.primitives.front(); - try - { - const auto lane = map->laneletLayer.get(primitive.id); - lanelets.push_back(lane); - } - catch (const lanelet::NoSuchPrimitiveError &ex) - { - // stop adding lanelets if lane cannot be found. e.g. goal is outside of queried submap - break; - } - } - // return empty trajectory if there are no lanes - if (lanelets.empty()) + const auto goal_point = convertToLaneletPoint(trajectory_goal_point); + end_length = lanelet::geometry::toArcCoordinates(to2D(centerline), to2D(goal_point)).length; + } + std::cout << "end length: " << end_length << std::endl; + float64_t accumulated_length = 0; + // skip first point on later iterations to avoid inserting overlaps + for (size_t j = 1; j < centerline.size(); j++) + { + //may be able to make searching for the first length more effecient + const auto llt_prev_pt = centerline[j - 1]; + const auto llt_pt = centerline[j]; + accumulated_length += lanelet::geometry::distance2d(to2D(llt_prev_pt), to2D(llt_pt)); + if (accumulated_length < start_length) { - return std::vector(); + continue; } - - autoware_auto_msgs::msg::TrajectoryPoint trajectory_start_point; - trajectory_start_point.x = static_cast(route.start_point.position.x); - trajectory_start_point.y = static_cast(route.start_point.position.y); - trajectory_start_point.heading = route.start_point.heading; - - autoware_auto_msgs::msg::TrajectoryPoint trajectory_goal_point; - trajectory_goal_point.x = static_cast(route.goal_point.position.x); - trajectory_goal_point.y = static_cast(route.goal_point.position.y); - trajectory_goal_point.heading = route.goal_point.heading; - - const auto start_index = get_closest_lanelet(lanelets, trajectory_start_point); - std::vector line_points; - // set position and velocity - for (size_t i = start_index; i < lanelets.size(); i++) + if (accumulated_length > end_length) { - const auto &lanelet = lanelets.at(i); - const auto ¢erline = map_utils::sample_center_line_and_boundaries( - lanelet, - resolution) - .center; - - //arc length along lane for start point - float64_t start_length = 0; - if (i == start_index) - { - const auto start_point = convertToLaneletPoint(trajectory_start_point); - start_length = - lanelet::geometry::toArcCoordinates(to2D(centerline), to2D(start_point)).length; - } - //arc length along lane for end point - float64_t end_length = std::numeric_limits::max(); - if (i == lanelets.size() - 1) - { - const auto goal_point = convertToLaneletPoint(trajectory_goal_point); - end_length = lanelet::geometry::toArcCoordinates(to2D(centerline), to2D(goal_point)).length; - } - - float64_t accumulated_length = 0; - // skip first point to avoid inserting overlaps - for (size_t j = 1; j < centerline.size(); j++) - { - //may be able to make searching for the first length more effecient - const auto llt_prev_pt = centerline[j - 1]; - const auto llt_pt = centerline[j]; - accumulated_length += lanelet::geometry::distance2d(to2D(llt_prev_pt), to2D(llt_pt)); - if (accumulated_length < start_length) - { - continue; - } - if (accumulated_length > end_length) - { - break; - } - line_points.push_back(convertToTrajectoryPoint(llt_pt)); - } + break; } - line_points.push_back(trajectory_goal_point); - return line_points; + line_points.push_back(convertToTrajectoryPoint(llt_pt)); } } + line_points.push_back(trajectory_goal_point); + return line_points; } \ No newline at end of file diff --git a/src/planning/path_planner/test/test_parameterized_spline.cpp b/src/planning/path_planner/test/test_parameterized_spline.cpp index 2f39ea6b6..6c88e6717 100644 --- a/src/planning/path_planner/test/test_parameterized_spline.cpp +++ b/src/planning/path_planner/test/test_parameterized_spline.cpp @@ -18,39 +18,53 @@ using namespace navigator::path_planner; class TestSpline : public ::testing::Test { public: - - TestSpline() : spline(std::vector(),std::vector()) { + std::vector xs; + std::vector ys; + + TestSpline() { + //wiggly path that goes loops around and is not a function of x or y xs.push_back(0); ys.push_back(0); xs.push_back(0.1); + ys.push_back(0.1); + + xs.push_back(0.2); + ys.push_back(0.1); + + xs.push_back(0.3); ys.push_back(0.2); - xs.push_back(0.5); - ys.push_back(0.5); + xs.push_back(0.3); + ys.push_back(0.3); + + xs.push_back(0.2); + ys.push_back(0.3); xs.push_back(0.2); - ys.push_back(0.7); + ys.push_back(0.2); + + xs.push_back(0.1); + ys.push_back(0.3); + + xs.push_back(0); + ys.push_back(0.2); - spline = ParameterizedSpline(xs, ys); + spline = std::make_shared(xs, ys); }; - ParameterizedSpline spline; - std::vector xs; - std::vector ys; + std::shared_ptr spline; }; TEST_F(TestSpline, test_arc_length_parameterization) { - //estimate arc length by evaluating at small intervals - double arclength = 0; - double step_size = 0.1; - auto old_point = spline.sample(0); - for (double p = 0; p < 2; p += step_size) { - auto current_point = spline.sample(p); - arclength += sqrt((old_point.first - current_point.first) * (old_point.first - current_point.first) + (old_point.second - current_point.second) * (old_point.second - current_point.second)); - old_point = current_point; + const double tolerance = 0.04; + const double length_step = 0.1; + //validate arc length parameterization by seeing if the distance over small intervals is equal to the change in the parameter + auto old = spline->sample(0); + for (double s = length_step; s < 1; s += length_step) { + auto current = spline->sample(s); + double d = sqrt((old.first-current.first)*(old.first-current.first) + (old.second-current.second)*(old.second-current.second)); + old = current; + ASSERT_TRUE(abs(d-length_step) < tolerance); } - //last point sampled should be approx equal to point sampled at estimated arc length - ASSERT_TRUE(abs(old_point.first-spline.sample(arclength).first < 0.1)); - ASSERT_TRUE(abs(old_point.second-spline.sample(arclength).second < 0.1)); } \ No newline at end of file diff --git a/src/planning/path_planner/test/test_path_planner.cpp b/src/planning/path_planner/test/test_path_planner.cpp index 65677623a..b5ef4cbee 100644 --- a/src/planning/path_planner/test/test_path_planner.cpp +++ b/src/planning/path_planner/test/test_path_planner.cpp @@ -79,7 +79,7 @@ class PathPlannerTest : public ::testing::Test std::shared_ptr m_planner_ptr; }; -TEST_F(PathPlannerTest, get_center_line_points) +TEST_F(PathPlannerTest, get_center_line) { // create map const auto lane_id = lanelet::utils::getId(); @@ -90,21 +90,22 @@ TEST_F(PathPlannerTest, get_center_line_points) // create route message const auto had_map_route = getARoute(lane_id, 5.0F); - const std::vector points = m_planner_ptr->get_center_line_points(had_map_route, lanelet_map_ptr, 5); + const std::vector points = m_planner_ptr->get_center_line_points(had_map_route, lanelet_map_ptr, 1); // return points should not be empty ASSERT_FALSE(points.empty()); // there should be 5 points total - ASSERT_TRUE(points.size() == 5); - - TrajectoryPoint start_point; - start_point.x = static_cast(had_map_route.start_point.position.x); - start_point.y = static_cast(had_map_route.start_point.position.y); - start_point.heading = had_map_route.start_point.heading; - - // start point of center line and route should be the same - auto distance = sqr_distance( - start_point, - points.front()); - ASSERT_DOUBLE_EQ(distance, 0.0); + ASSERT_EQ(size_t(5),points.size()); + + //testing start point position + //we expect the center line to be: (0,1) -> (0,2) -> (0,3) -> (0,4) -> (0,5) + auto prev = points.front(); + ASSERT_DOUBLE_EQ(prev.x, 0); + ASSERT_DOUBLE_EQ(prev.y, 1); + //points should be spaced out by 1 vertically + for (size_t i = 1; i < points.size(); i++) { + ASSERT_DOUBLE_EQ(prev.y + 1, points[i].y); + ASSERT_DOUBLE_EQ(prev.x, points[i].x); + prev = points[i]; + } } From 4da4a92a0a4aabbe9732fe2553398b4d2f0303af Mon Sep 17 00:00:00 2001 From: jim-works Date: Thu, 2 Dec 2021 11:17:00 -0600 Subject: [PATCH 8/8] Update license with GPL and add test function comment --- LICENSE | 678 ++++++++++++++++++ .../path_planner/src/parameterized_spline.cpp | 14 - .../path_planner/test/test_path_planner.cpp | 2 + 3 files changed, 680 insertions(+), 14 deletions(-) diff --git a/LICENSE b/LICENSE index f97199288..4a06f940f 100644 --- a/LICENSE +++ b/LICENSE @@ -224,3 +224,681 @@ A copy of the original Autoware.Auto license is below. WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License. + + +GNU GENERAL PUBLIC LICENSE: Used for Tino Kluge's cubic spline library (https://kluge.in-chemnitz.de/opensource/spline/) + GNU GENERAL PUBLIC LICENSE + Version 3, 29 June 2007 + + Copyright (C) 2007 Free Software Foundation, Inc. + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + + Preamble + + The GNU General Public License is a free, copyleft license for +software and other kinds of works. + + The licenses for most software and other practical works are designed +to take away your freedom to share and change the works. By contrast, +the GNU General Public License is intended to guarantee your freedom to +share and change all versions of a program--to make sure it remains free +software for all its users. We, the Free Software Foundation, use the +GNU General Public License for most of our software; it applies also to +any other work released this way by its authors. You can apply it to +your programs, too. + + When we speak of free software, we are referring to freedom, not +price. Our General Public Licenses are designed to make sure that you +have the freedom to distribute copies of free software (and charge for +them if you wish), that you receive source code or can get it if you +want it, that you can change the software or use pieces of it in new +free programs, and that you know you can do these things. + + To protect your rights, we need to prevent others from denying you +these rights or asking you to surrender the rights. Therefore, you have +certain responsibilities if you distribute copies of the software, or if +you modify it: responsibilities to respect the freedom of others. + + For example, if you distribute copies of such a program, whether +gratis or for a fee, you must pass on to the recipients the same +freedoms that you received. You must make sure that they, too, receive +or can get the source code. And you must show them these terms so they +know their rights. + + Developers that use the GNU GPL protect your rights with two steps: +(1) assert copyright on the software, and (2) offer you this License +giving you legal permission to copy, distribute and/or modify it. + + For the developers' and authors' protection, the GPL clearly explains +that there is no warranty for this free software. For both users' and +authors' sake, the GPL requires that modified versions be marked as +changed, so that their problems will not be attributed erroneously to +authors of previous versions. + + Some devices are designed to deny users access to install or run +modified versions of the software inside them, although the manufacturer +can do so. This is fundamentally incompatible with the aim of +protecting users' freedom to change the software. The systematic +pattern of such abuse occurs in the area of products for individuals to +use, which is precisely where it is most unacceptable. Therefore, we +have designed this version of the GPL to prohibit the practice for those +products. If such problems arise substantially in other domains, we +stand ready to extend this provision to those domains in future versions +of the GPL, as needed to protect the freedom of users. + + Finally, every program is threatened constantly by software patents. +States should not allow patents to restrict development and use of +software on general-purpose computers, but in those that do, we wish to +avoid the special danger that patents applied to a free program could +make it effectively proprietary. To prevent this, the GPL assures that +patents cannot be used to render the program non-free. + + The precise terms and conditions for copying, distribution and +modification follow. + + TERMS AND CONDITIONS + + 0. Definitions. + + "This License" refers to version 3 of the GNU General Public License. + + "Copyright" also means copyright-like laws that apply to other kinds of +works, such as semiconductor masks. + + "The Program" refers to any copyrightable work licensed under this +License. Each licensee is addressed as "you". "Licensees" and +"recipients" may be individuals or organizations. + + To "modify" a work means to copy from or adapt all or part of the work +in a fashion requiring copyright permission, other than the making of an +exact copy. The resulting work is called a "modified version" of the +earlier work or a work "based on" the earlier work. + + A "covered work" means either the unmodified Program or a work based +on the Program. + + To "propagate" a work means to do anything with it that, without +permission, would make you directly or secondarily liable for +infringement under applicable copyright law, except executing it on a +computer or modifying a private copy. Propagation includes copying, +distribution (with or without modification), making available to the +public, and in some countries other activities as well. + + To "convey" a work means any kind of propagation that enables other +parties to make or receive copies. Mere interaction with a user through +a computer network, with no transfer of a copy, is not conveying. + + An interactive user interface displays "Appropriate Legal Notices" +to the extent that it includes a convenient and prominently visible +feature that (1) displays an appropriate copyright notice, and (2) +tells the user that there is no warranty for the work (except to the +extent that warranties are provided), that licensees may convey the +work under this License, and how to view a copy of this License. If +the interface presents a list of user commands or options, such as a +menu, a prominent item in the list meets this criterion. + + 1. Source Code. + + The "source code" for a work means the preferred form of the work +for making modifications to it. "Object code" means any non-source +form of a work. + + A "Standard Interface" means an interface that either is an official +standard defined by a recognized standards body, or, in the case of +interfaces specified for a particular programming language, one that +is widely used among developers working in that language. + + The "System Libraries" of an executable work include anything, other +than the work as a whole, that (a) is included in the normal form of +packaging a Major Component, but which is not part of that Major +Component, and (b) serves only to enable use of the work with that +Major Component, or to implement a Standard Interface for which an +implementation is available to the public in source code form. A +"Major Component", in this context, means a major essential component +(kernel, window system, and so on) of the specific operating system +(if any) on which the executable work runs, or a compiler used to +produce the work, or an object code interpreter used to run it. + + The "Corresponding Source" for a work in object code form means all +the source code needed to generate, install, and (for an executable +work) run the object code and to modify the work, including scripts to +control those activities. However, it does not include the work's +System Libraries, or general-purpose tools or generally available free +programs which are used unmodified in performing those activities but +which are not part of the work. For example, Corresponding Source +includes interface definition files associated with source files for +the work, and the source code for shared libraries and dynamically +linked subprograms that the work is specifically designed to require, +such as by intimate data communication or control flow between those +subprograms and other parts of the work. + + The Corresponding Source need not include anything that users +can regenerate automatically from other parts of the Corresponding +Source. + + The Corresponding Source for a work in source code form is that +same work. + + 2. Basic Permissions. + + All rights granted under this License are granted for the term of +copyright on the Program, and are irrevocable provided the stated +conditions are met. This License explicitly affirms your unlimited +permission to run the unmodified Program. The output from running a +covered work is covered by this License only if the output, given its +content, constitutes a covered work. This License acknowledges your +rights of fair use or other equivalent, as provided by copyright law. + + You may make, run and propagate covered works that you do not +convey, without conditions so long as your license otherwise remains +in force. You may convey covered works to others for the sole purpose +of having them make modifications exclusively for you, or provide you +with facilities for running those works, provided that you comply with +the terms of this License in conveying all material for which you do +not control copyright. Those thus making or running the covered works +for you must do so exclusively on your behalf, under your direction +and control, on terms that prohibit them from making any copies of +your copyrighted material outside their relationship with you. + + Conveying under any other circumstances is permitted solely under +the conditions stated below. Sublicensing is not allowed; section 10 +makes it unnecessary. + + 3. Protecting Users' Legal Rights From Anti-Circumvention Law. + + No covered work shall be deemed part of an effective technological +measure under any applicable law fulfilling obligations under article +11 of the WIPO copyright treaty adopted on 20 December 1996, or +similar laws prohibiting or restricting circumvention of such +measures. + + When you convey a covered work, you waive any legal power to forbid +circumvention of technological measures to the extent such circumvention +is effected by exercising rights under this License with respect to +the covered work, and you disclaim any intention to limit operation or +modification of the work as a means of enforcing, against the work's +users, your or third parties' legal rights to forbid circumvention of +technological measures. + + 4. Conveying Verbatim Copies. + + You may convey verbatim copies of the Program's source code as you +receive it, in any medium, provided that you conspicuously and +appropriately publish on each copy an appropriate copyright notice; +keep intact all notices stating that this License and any +non-permissive terms added in accord with section 7 apply to the code; +keep intact all notices of the absence of any warranty; and give all +recipients a copy of this License along with the Program. + + You may charge any price or no price for each copy that you convey, +and you may offer support or warranty protection for a fee. + + 5. Conveying Modified Source Versions. + + You may convey a work based on the Program, or the modifications to +produce it from the Program, in the form of source code under the +terms of section 4, provided that you also meet all of these conditions: + + a) The work must carry prominent notices stating that you modified + it, and giving a relevant date. + + b) The work must carry prominent notices stating that it is + released under this License and any conditions added under section + 7. This requirement modifies the requirement in section 4 to + "keep intact all notices". + + c) You must license the entire work, as a whole, under this + License to anyone who comes into possession of a copy. This + License will therefore apply, along with any applicable section 7 + additional terms, to the whole of the work, and all its parts, + regardless of how they are packaged. This License gives no + permission to license the work in any other way, but it does not + invalidate such permission if you have separately received it. + + d) If the work has interactive user interfaces, each must display + Appropriate Legal Notices; however, if the Program has interactive + interfaces that do not display Appropriate Legal Notices, your + work need not make them do so. + + A compilation of a covered work with other separate and independent +works, which are not by their nature extensions of the covered work, +and which are not combined with it such as to form a larger program, +in or on a volume of a storage or distribution medium, is called an +"aggregate" if the compilation and its resulting copyright are not +used to limit the access or legal rights of the compilation's users +beyond what the individual works permit. Inclusion of a covered work +in an aggregate does not cause this License to apply to the other +parts of the aggregate. + + 6. Conveying Non-Source Forms. + + You may convey a covered work in object code form under the terms +of sections 4 and 5, provided that you also convey the +machine-readable Corresponding Source under the terms of this License, +in one of these ways: + + a) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by the + Corresponding Source fixed on a durable physical medium + customarily used for software interchange. + + b) Convey the object code in, or embodied in, a physical product + (including a physical distribution medium), accompanied by a + written offer, valid for at least three years and valid for as + long as you offer spare parts or customer support for that product + model, to give anyone who possesses the object code either (1) a + copy of the Corresponding Source for all the software in the + product that is covered by this License, on a durable physical + medium customarily used for software interchange, for a price no + more than your reasonable cost of physically performing this + conveying of source, or (2) access to copy the + Corresponding Source from a network server at no charge. + + c) Convey individual copies of the object code with a copy of the + written offer to provide the Corresponding Source. This + alternative is allowed only occasionally and noncommercially, and + only if you received the object code with such an offer, in accord + with subsection 6b. + + d) Convey the object code by offering access from a designated + place (gratis or for a charge), and offer equivalent access to the + Corresponding Source in the same way through the same place at no + further charge. You need not require recipients to copy the + Corresponding Source along with the object code. If the place to + copy the object code is a network server, the Corresponding Source + may be on a different server (operated by you or a third party) + that supports equivalent copying facilities, provided you maintain + clear directions next to the object code saying where to find the + Corresponding Source. Regardless of what server hosts the + Corresponding Source, you remain obligated to ensure that it is + available for as long as needed to satisfy these requirements. + + e) Convey the object code using peer-to-peer transmission, provided + you inform other peers where the object code and Corresponding + Source of the work are being offered to the general public at no + charge under subsection 6d. + + A separable portion of the object code, whose source code is excluded +from the Corresponding Source as a System Library, need not be +included in conveying the object code work. + + A "User Product" is either (1) a "consumer product", which means any +tangible personal property which is normally used for personal, family, +or household purposes, or (2) anything designed or sold for incorporation +into a dwelling. In determining whether a product is a consumer product, +doubtful cases shall be resolved in favor of coverage. For a particular +product received by a particular user, "normally used" refers to a +typical or common use of that class of product, regardless of the status +of the particular user or of the way in which the particular user +actually uses, or expects or is expected to use, the product. A product +is a consumer product regardless of whether the product has substantial +commercial, industrial or non-consumer uses, unless such uses represent +the only significant mode of use of the product. + + "Installation Information" for a User Product means any methods, +procedures, authorization keys, or other information required to install +and execute modified versions of a covered work in that User Product from +a modified version of its Corresponding Source. The information must +suffice to ensure that the continued functioning of the modified object +code is in no case prevented or interfered with solely because +modification has been made. + + If you convey an object code work under this section in, or with, or +specifically for use in, a User Product, and the conveying occurs as +part of a transaction in which the right of possession and use of the +User Product is transferred to the recipient in perpetuity or for a +fixed term (regardless of how the transaction is characterized), the +Corresponding Source conveyed under this section must be accompanied +by the Installation Information. But this requirement does not apply +if neither you nor any third party retains the ability to install +modified object code on the User Product (for example, the work has +been installed in ROM). + + The requirement to provide Installation Information does not include a +requirement to continue to provide support service, warranty, or updates +for a work that has been modified or installed by the recipient, or for +the User Product in which it has been modified or installed. Access to a +network may be denied when the modification itself materially and +adversely affects the operation of the network or violates the rules and +protocols for communication across the network. + + Corresponding Source conveyed, and Installation Information provided, +in accord with this section must be in a format that is publicly +documented (and with an implementation available to the public in +source code form), and must require no special password or key for +unpacking, reading or copying. + + 7. Additional Terms. + + "Additional permissions" are terms that supplement the terms of this +License by making exceptions from one or more of its conditions. +Additional permissions that are applicable to the entire Program shall +be treated as though they were included in this License, to the extent +that they are valid under applicable law. If additional permissions +apply only to part of the Program, that part may be used separately +under those permissions, but the entire Program remains governed by +this License without regard to the additional permissions. + + When you convey a copy of a covered work, you may at your option +remove any additional permissions from that copy, or from any part of +it. (Additional permissions may be written to require their own +removal in certain cases when you modify the work.) You may place +additional permissions on material, added by you to a covered work, +for which you have or can give appropriate copyright permission. + + Notwithstanding any other provision of this License, for material you +add to a covered work, you may (if authorized by the copyright holders of +that material) supplement the terms of this License with terms: + + a) Disclaiming warranty or limiting liability differently from the + terms of sections 15 and 16 of this License; or + + b) Requiring preservation of specified reasonable legal notices or + author attributions in that material or in the Appropriate Legal + Notices displayed by works containing it; or + + c) Prohibiting misrepresentation of the origin of that material, or + requiring that modified versions of such material be marked in + reasonable ways as different from the original version; or + + d) Limiting the use for publicity purposes of names of licensors or + authors of the material; or + + e) Declining to grant rights under trademark law for use of some + trade names, trademarks, or service marks; or + + f) Requiring indemnification of licensors and authors of that + material by anyone who conveys the material (or modified versions of + it) with contractual assumptions of liability to the recipient, for + any liability that these contractual assumptions directly impose on + those licensors and authors. + + All other non-permissive additional terms are considered "further +restrictions" within the meaning of section 10. If the Program as you +received it, or any part of it, contains a notice stating that it is +governed by this License along with a term that is a further +restriction, you may remove that term. If a license document contains +a further restriction but permits relicensing or conveying under this +License, you may add to a covered work material governed by the terms +of that license document, provided that the further restriction does +not survive such relicensing or conveying. + + If you add terms to a covered work in accord with this section, you +must place, in the relevant source files, a statement of the +additional terms that apply to those files, or a notice indicating +where to find the applicable terms. + + Additional terms, permissive or non-permissive, may be stated in the +form of a separately written license, or stated as exceptions; +the above requirements apply either way. + + 8. Termination. + + You may not propagate or modify a covered work except as expressly +provided under this License. Any attempt otherwise to propagate or +modify it is void, and will automatically terminate your rights under +this License (including any patent licenses granted under the third +paragraph of section 11). + + However, if you cease all violation of this License, then your +license from a particular copyright holder is reinstated (a) +provisionally, unless and until the copyright holder explicitly and +finally terminates your license, and (b) permanently, if the copyright +holder fails to notify you of the violation by some reasonable means +prior to 60 days after the cessation. + + Moreover, your license from a particular copyright holder is +reinstated permanently if the copyright holder notifies you of the +violation by some reasonable means, this is the first time you have +received notice of violation of this License (for any work) from that +copyright holder, and you cure the violation prior to 30 days after +your receipt of the notice. + + Termination of your rights under this section does not terminate the +licenses of parties who have received copies or rights from you under +this License. If your rights have been terminated and not permanently +reinstated, you do not qualify to receive new licenses for the same +material under section 10. + + 9. Acceptance Not Required for Having Copies. + + You are not required to accept this License in order to receive or +run a copy of the Program. Ancillary propagation of a covered work +occurring solely as a consequence of using peer-to-peer transmission +to receive a copy likewise does not require acceptance. However, +nothing other than this License grants you permission to propagate or +modify any covered work. These actions infringe copyright if you do +not accept this License. Therefore, by modifying or propagating a +covered work, you indicate your acceptance of this License to do so. + + 10. Automatic Licensing of Downstream Recipients. + + Each time you convey a covered work, the recipient automatically +receives a license from the original licensors, to run, modify and +propagate that work, subject to this License. You are not responsible +for enforcing compliance by third parties with this License. + + An "entity transaction" is a transaction transferring control of an +organization, or substantially all assets of one, or subdividing an +organization, or merging organizations. If propagation of a covered +work results from an entity transaction, each party to that +transaction who receives a copy of the work also receives whatever +licenses to the work the party's predecessor in interest had or could +give under the previous paragraph, plus a right to possession of the +Corresponding Source of the work from the predecessor in interest, if +the predecessor has it or can get it with reasonable efforts. + + You may not impose any further restrictions on the exercise of the +rights granted or affirmed under this License. For example, you may +not impose a license fee, royalty, or other charge for exercise of +rights granted under this License, and you may not initiate litigation +(including a cross-claim or counterclaim in a lawsuit) alleging that +any patent claim is infringed by making, using, selling, offering for +sale, or importing the Program or any portion of it. + + 11. Patents. + + A "contributor" is a copyright holder who authorizes use under this +License of the Program or a work on which the Program is based. The +work thus licensed is called the contributor's "contributor version". + + A contributor's "essential patent claims" are all patent claims +owned or controlled by the contributor, whether already acquired or +hereafter acquired, that would be infringed by some manner, permitted +by this License, of making, using, or selling its contributor version, +but do not include claims that would be infringed only as a +consequence of further modification of the contributor version. For +purposes of this definition, "control" includes the right to grant +patent sublicenses in a manner consistent with the requirements of +this License. + + Each contributor grants you a non-exclusive, worldwide, royalty-free +patent license under the contributor's essential patent claims, to +make, use, sell, offer for sale, import and otherwise run, modify and +propagate the contents of its contributor version. + + In the following three paragraphs, a "patent license" is any express +agreement or commitment, however denominated, not to enforce a patent +(such as an express permission to practice a patent or covenant not to +sue for patent infringement). To "grant" such a patent license to a +party means to make such an agreement or commitment not to enforce a +patent against the party. + + If you convey a covered work, knowingly relying on a patent license, +and the Corresponding Source of the work is not available for anyone +to copy, free of charge and under the terms of this License, through a +publicly available network server or other readily accessible means, +then you must either (1) cause the Corresponding Source to be so +available, or (2) arrange to deprive yourself of the benefit of the +patent license for this particular work, or (3) arrange, in a manner +consistent with the requirements of this License, to extend the patent +license to downstream recipients. "Knowingly relying" means you have +actual knowledge that, but for the patent license, your conveying the +covered work in a country, or your recipient's use of the covered work +in a country, would infringe one or more identifiable patents in that +country that you have reason to believe are valid. + + If, pursuant to or in connection with a single transaction or +arrangement, you convey, or propagate by procuring conveyance of, a +covered work, and grant a patent license to some of the parties +receiving the covered work authorizing them to use, propagate, modify +or convey a specific copy of the covered work, then the patent license +you grant is automatically extended to all recipients of the covered +work and works based on it. + + A patent license is "discriminatory" if it does not include within +the scope of its coverage, prohibits the exercise of, or is +conditioned on the non-exercise of one or more of the rights that are +specifically granted under this License. You may not convey a covered +work if you are a party to an arrangement with a third party that is +in the business of distributing software, under which you make payment +to the third party based on the extent of your activity of conveying +the work, and under which the third party grants, to any of the +parties who would receive the covered work from you, a discriminatory +patent license (a) in connection with copies of the covered work +conveyed by you (or copies made from those copies), or (b) primarily +for and in connection with specific products or compilations that +contain the covered work, unless you entered into that arrangement, +or that patent license was granted, prior to 28 March 2007. + + Nothing in this License shall be construed as excluding or limiting +any implied license or other defenses to infringement that may +otherwise be available to you under applicable patent law. + + 12. No Surrender of Others' Freedom. + + If conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot convey a +covered work so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you may +not convey it at all. For example, if you agree to terms that obligate you +to collect a royalty for further conveying from those to whom you convey +the Program, the only way you could satisfy both those terms and this +License would be to refrain entirely from conveying the Program. + + 13. Use with the GNU Affero General Public License. + + Notwithstanding any other provision of this License, you have +permission to link or combine any covered work with a work licensed +under version 3 of the GNU Affero General Public License into a single +combined work, and to convey the resulting work. The terms of this +License will continue to apply to the part which is the covered work, +but the special requirements of the GNU Affero General Public License, +section 13, concerning interaction through a network will apply to the +combination as such. + + 14. Revised Versions of this License. + + The Free Software Foundation may publish revised and/or new versions of +the GNU General Public License from time to time. Such new versions will +be similar in spirit to the present version, but may differ in detail to +address new problems or concerns. + + Each version is given a distinguishing version number. If the +Program specifies that a certain numbered version of the GNU General +Public License "or any later version" applies to it, you have the +option of following the terms and conditions either of that numbered +version or of any later version published by the Free Software +Foundation. If the Program does not specify a version number of the +GNU General Public License, you may choose any version ever published +by the Free Software Foundation. + + If the Program specifies that a proxy can decide which future +versions of the GNU General Public License can be used, that proxy's +public statement of acceptance of a version permanently authorizes you +to choose that version for the Program. + + Later license versions may give you additional or different +permissions. However, no additional obligations are imposed on any +author or copyright holder as a result of your choosing to follow a +later version. + + 15. Disclaimer of Warranty. + + THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY +APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT +HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY +OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, +THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM +IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF +ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. Limitation of Liability. + + IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING +WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS +THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY +GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE +USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF +DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD +PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS), +EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF +SUCH DAMAGES. + + 17. Interpretation of Sections 15 and 16. + + If the disclaimer of warranty and limitation of liability provided +above cannot be given local legal effect according to their terms, +reviewing courts shall apply local law that most closely approximates +an absolute waiver of all civil liability in connection with the +Program, unless a warranty or assumption of liability accompanies a +copy of the Program in return for a fee. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Programs + + If you develop a new program, and you want it to be of the greatest +possible use to the public, the best way to achieve this is to make it +free software which everyone can redistribute and change under these terms. + + To do so, attach the following notices to the program. It is safest +to attach them to the start of each source file to most effectively +state the exclusion of warranty; and each file should have at least +the "copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + +Also add information on how to contact you by electronic and paper mail. + + If the program does terminal interaction, make it output a short +notice like this when it starts in an interactive mode: + + Copyright (C) + This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'. + This is free software, and you are welcome to redistribute it + under certain conditions; type `show c' for details. + +The hypothetical commands `show w' and `show c' should show the appropriate +parts of the General Public License. Of course, your program's commands +might be different; for a GUI interface, you would use an "about box". + + You should also get your employer (if you work as a programmer) or school, +if any, to sign a "copyright disclaimer" for the program, if necessary. +For more information on this, and how to apply and follow the GNU GPL, see +. + + The GNU General Public License does not permit incorporating your program +into proprietary programs. If your program is a subroutine library, you +may consider it more useful to permit linking proprietary applications with +the library. If this is what you want to do, use the GNU Lesser General +Public License instead of this License. But first, please read +. + diff --git a/src/planning/path_planner/src/parameterized_spline.cpp b/src/planning/path_planner/src/parameterized_spline.cpp index d77e90570..80221c53e 100644 --- a/src/planning/path_planner/src/parameterized_spline.cpp +++ b/src/planning/path_planner/src/parameterized_spline.cpp @@ -1,17 +1,3 @@ -// Copyright 2020 The Autoware Foundation -// -// Licensed under the Apache License, Version 2.0 (the "License"); -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// -//    http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. - /* * Package: path_planner * Filename: parameterized_spline.cpp diff --git a/src/planning/path_planner/test/test_path_planner.cpp b/src/planning/path_planner/test/test_path_planner.cpp index b5ef4cbee..693d77db2 100644 --- a/src/planning/path_planner/test/test_path_planner.cpp +++ b/src/planning/path_planner/test/test_path_planner.cpp @@ -47,6 +47,8 @@ lanelet::LaneletMapPtr getALaneletMapWithLaneId( return lanelet::utils::createMap({ll}); } +//returns a HAD map route with one segment that starts at (0,0) and goes to (0,length) +//this lets us test the path planner on a very simple route with easily predictable output HADMapRoute getARoute(const int64_t lane_id, const float32_t length) { HADMapRoute had_map_route;