Skip to content

Commit

Permalink
po
Browse files Browse the repository at this point in the history
  • Loading branch information
takayuki5168 committed Oct 15, 2022
1 parent 2fe8167 commit 5d2bc60
Show file tree
Hide file tree
Showing 22 changed files with 616 additions and 1,125 deletions.
6 changes: 4 additions & 2 deletions planning/collision_free_path_planner/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,9 @@ find_package(Eigen3 REQUIRED)
find_package(OpenCV REQUIRED)

ament_auto_add_library(collision_free_path_planner SHARED
# node and core algorithms
# node
src/node.cpp
# core algorithms
src/replan_checker.cpp
src/costmap_generator.cpp
src/eb_path_optimizer.cpp
Expand All @@ -20,7 +21,8 @@ ament_auto_add_library(collision_free_path_planner SHARED
src/vehicle_model/vehicle_model_interface.cpp
src/vehicle_model/vehicle_model_bicycle_kinematics.cpp
# utils
src/utils/utils.cpp
src/utils/trajectory_utils.cpp
src/utils/geometry_utils.cpp
src/utils/cv_utils.cpp
)

Expand Down
21 changes: 10 additions & 11 deletions planning/collision_free_path_planner/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,14 @@ start
:createPlannerData;
group generateOptimizedTrajectory
group getMaps
:getDrivableArea;
:getRoadClearanceMap;
:drawObstacleOnImage;
:getObstacleClearanceMap;
end group
group getMaps
:getDrivableArea;
:getRoadClearanceMap;
:drawObstacleOnImage;
:getObstacleClearanceMap;
end group
group generateOptimizedTrajectory
group optimizeTrajectory
:checkReplan;
if (replanning required?) then (yes)
Expand All @@ -61,16 +61,15 @@ group generateOptimizedTrajectory
endif
end group
:updateVelocity;
:applyPathVelocity;
:insertZeroVelocityOutsideDrivableArea;
:publishDebugMarkerInOptimization;
end group
:extendedOptimizedTrajectory;
:alignVelocity;
:extendTrajectory;
:convertToTrajectory;
:setZeroVelocityAfterStopPoint;
:publishDebugDataInMain;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,6 +128,7 @@ struct DebugData
{
msg_stream = StreamWithPrint{};
msg_stream.enable_calculation_time_info = enable_calculation_time_info;
stop_pose_by_drivable_area = boost::none;
}

// string stream for calculation time
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.
// Copyright 2022 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.
// Copyright 2022 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.
// Copyright 2022 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand All @@ -16,7 +16,7 @@
*
* MIT License
*
* Copyright (c) 2020 Li Jiangnan
* Copyright (c) 2022 Li Jiangnan
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.
// Copyright 2022 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -222,20 +222,19 @@ class CollisionFreePathPlanner : public rclcpp::Node
// main functions
bool isDataReady();
PlannerData createPlannerData(const Path & path);
std::vector<TrajectoryPoint> generateOptimizedTrajectory(const PlannerData & planner_data);
std::vector<TrajectoryPoint> generateOptimizedTrajectory(
const PlannerData & planner_data, const CVMaps & cv_maps);
std::vector<TrajectoryPoint> extendTrajectory(
const std::vector<PathPoint> & path_points,
const std::vector<TrajectoryPoint> & optimized_points);
std::vector<TrajectoryPoint> generatePostProcessedTrajectory(
const PlannerData & planner_data, const std::vector<TrajectoryPoint> & merged_optimized_points);
void publishDebugDataInMain(const Path & path) const;

// functions for optimization
// functions in generateOptimizedTrajectory
std::vector<TrajectoryPoint> optimizeTrajectory(
const PlannerData & planner_data, const CVMaps & cv_maps);
std::vector<TrajectoryPoint> getPrevOptimizedTrajectory(
const std::vector<PathPoint> & path_points) const;
void updateVelocity(
void applyPathVelocity(
std::vector<TrajectoryPoint> & traj_points, const std::vector<PathPoint> & path_points) const;
void insertZeroVelocityOutsideDrivableArea(
const PlannerData & planner_data, std::vector<TrajectoryPoint> & traj_points,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#include "collision_free_path_planner/common_structs.hpp"
#include "collision_free_path_planner/mpt_optimizer.hpp"
#include "collision_free_path_planner/type_alias.hpp"
#include "collision_free_path_planner/utils/utils.hpp"

#include <rclcpp/rclcpp.hpp>

Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2020 Tier IV, Inc.
// Copyright 2022 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,108 @@
// Copyright 2022 Tier IV, Inc.
//
// 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.

#ifndef COLLISION_FREE_PATH_PLANNER__UTILS__GEOMETRY_UTILS_HPP_
#define COLLISION_FREE_PATH_PLANNER__UTILS__GEOMETRY_UTILS_HPP_

#include "collision_free_path_planner/common_structs.hpp"
#include "collision_free_path_planner/type_alias.hpp"
#include "eigen3/Eigen/Core"
#include "interpolation/linear_interpolation.hpp"
#include "interpolation/spline_interpolation.hpp"
#include "interpolation/spline_interpolation_points_2d.hpp"
#include "motion_utils/trajectory/trajectory.hpp"

#include "autoware_auto_planning_msgs/msg/path_point.hpp"
#include "autoware_auto_planning_msgs/msg/trajectory.hpp"

#include "boost/optional/optional_fwd.hpp"

#include <algorithm>
#include <limits>
#include <memory>
#include <string>
#include <vector>

struct collision_free_path_planner::ReferencePoint;

namespace tier4_autoware_utils
{
template <>
geometry_msgs::msg::Point getPoint(const collision_free_path_planner::ReferencePoint & p);

template <>
geometry_msgs::msg::Pose getPose(const collision_free_path_planner::ReferencePoint & p);
} // namespace tier4_autoware_utils

namespace collision_free_path_planner
{
namespace geometry_utils
{
template <typename T>
geometry_msgs::msg::Point transformToRelativeCoordinate2D(
const T & point, const geometry_msgs::msg::Pose & origin)
{
// NOTE: implement transformation without defining yaw variable
// but directly sin/cos of yaw for fast calculation
const auto & q = origin.orientation;
const double cos_yaw = 1 - 2 * q.z * q.z;
const double sin_yaw = 2 * q.w * q.z;

geometry_msgs::msg::Point relative_p;
const double tmp_x = point.x - origin.position.x;
const double tmp_y = point.y - origin.position.y;
relative_p.x = tmp_x * cos_yaw + tmp_y * sin_yaw;
relative_p.y = -tmp_x * sin_yaw + tmp_y * cos_yaw;
relative_p.z = point.z;

return relative_p;
}

geometry_msgs::msg::Point transformToAbsoluteCoordinate2D(
const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & origin);

geometry_msgs::msg::Quaternion getQuaternionFromPoints(
const geometry_msgs::msg::Point & a, const geometry_msgs::msg::Point & a_root);

geometry_msgs::msg::Quaternion getQuaternionFromPoints(
const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2,
const geometry_msgs::msg::Point & p3, const geometry_msgs::msg::Point & p4);

template <typename T>
geometry_msgs::msg::Point transformMapToImage(
const T & map_point, const nav_msgs::msg::MapMetaData & occupancy_grid_info)
{
geometry_msgs::msg::Point relative_p =
transformToRelativeCoordinate2D(map_point, occupancy_grid_info.origin);
double resolution = occupancy_grid_info.resolution;
double map_y_height = occupancy_grid_info.height;
double map_x_width = occupancy_grid_info.width;
double map_x_in_image_resolution = relative_p.x / resolution;
double map_y_in_image_resolution = relative_p.y / resolution;
geometry_msgs::msg::Point image_point;
image_point.x = map_y_height - map_y_in_image_resolution;
image_point.y = map_x_width - map_x_in_image_resolution;
return image_point;
}

boost::optional<geometry_msgs::msg::Point> transformMapToOptionalImage(
const geometry_msgs::msg::Point & map_point,
const nav_msgs::msg::MapMetaData & occupancy_grid_info);

bool transformMapToImage(
const geometry_msgs::msg::Point & map_point,
const nav_msgs::msg::MapMetaData & occupancy_grid_info, geometry_msgs::msg::Point & image_point);
} // namespace geometry_utils
} // namespace collision_free_path_planner
#endif // COLLISION_FREE_PATH_PLANNER__UTILS__GEOMETRY_UTILS_HPP_
Loading

0 comments on commit 5d2bc60

Please sign in to comment.