Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

feat(freespace_planning_algorithms): use distance to nearest obstacle to improve path planning #8089

Merged
Show file tree
Hide file tree
Changes from 83 commits
Commits
Show all changes
90 commits
Select commit Hold shift + click to select a range
4d28815
refactor freespace planning algorithms
mkquda Jul 1, 2024
5ed5426
fix error
mkquda Jul 2, 2024
efdb10d
use vector instead of map for a-star node graph
mkquda Jul 2, 2024
95a323b
remove unnecessary parameters
mkquda Jul 2, 2024
597bcff
Merge branch 'awf-latest' into RT1-6959-refactor-astar-planning-algor…
mkquda Jul 2, 2024
9cbfb42
precompute average turning radius
mkquda Jul 2, 2024
502c5ea
add threshold for minimum distance between direction changes
mkquda Jul 3, 2024
d67861b
apply curvature weight and change in curvature weight
mkquda Jul 3, 2024
3e94c40
store total cost instead of heuristic cost
mkquda Jul 3, 2024
9d46b07
fix reverse weight application
mkquda Jul 3, 2024
be2368c
fix parameter description in README
mkquda Jul 4, 2024
2b3173e
implement edt map to store distance to nearest obstacle for each grid…
mkquda Jul 4, 2024
be3589f
use obstacle edt in collision check
mkquda Jul 4, 2024
a98c07b
add cost for distance to obstacle
mkquda Jul 4, 2024
a9a572a
Merge branch 'awf-latest' into RT1-6959-refactor-astar-planning-algor…
mkquda Jul 5, 2024
99fef5f
fix formats
mkquda Jul 5, 2024
216780c
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 5, 2024
3a23aab
add missing include
mkquda Jul 5, 2024
3440d06
refactor functions
mkquda Jul 5, 2024
34190f1
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 5, 2024
548b761
add missing include
mkquda Jul 5, 2024
578ccee
precompute number of margin cells to reduce out of range vertices che…
mkquda Jul 8, 2024
a960280
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 8, 2024
c60107d
add reset data function
mkquda Jul 8, 2024
fa42d14
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 8, 2024
8eed3bb
add member function set() to AstarNode struct
mkquda Jul 8, 2024
0f8ab5b
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 8, 2024
5e7e018
implement adaptive expansion distance
mkquda Jul 9, 2024
3331d62
remove unnecessary code
mkquda Jul 9, 2024
612f95d
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 9, 2024
8a1d045
Merge branch 'awf-latest' into RT1-6959-refactor-astar-planning-algor…
mkquda Jul 9, 2024
48d8b64
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 9, 2024
74394e9
interpolate nodes with large expansion distance
mkquda Jul 10, 2024
e0c1cb6
minor refactor
mkquda Jul 10, 2024
5ece1b8
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 10, 2024
06eeeb7
ensure expansion distance is larger than grid cell diagonal
mkquda Jul 11, 2024
5ab43b4
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 11, 2024
f1baaaa
compute collision free distance to goal map
mkquda Jul 11, 2024
ccf5729
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 11, 2024
d856ad6
use obstacle edt when computing collision free distance map
mkquda Jul 11, 2024
018c67f
minor refactor
mkquda Jul 11, 2024
b5c4ef2
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 11, 2024
6fa451e
fix expansion cost function
mkquda Jul 12, 2024
24126f7
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 12, 2024
fc2aea2
set distance map before setting start node
mkquda Jul 12, 2024
6eb2ec6
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 12, 2024
0a3c534
refactor detect collision function
mkquda Jul 16, 2024
3c38a52
Merge branch 'awf-latest' into RT1-6959-refactor-astar-planning-algor…
mkquda Jul 16, 2024
f93f576
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 16, 2024
d311167
add missing variable initialization
mkquda Jul 16, 2024
f600183
remove declared but undefined function
mkquda Jul 16, 2024
fad3515
remove unnecessary checks
mkquda Jul 16, 2024
f1f18c7
minor fix
mkquda Jul 17, 2024
e5fdc88
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 17, 2024
c6fdfe9
refactor computeEDTMap function
mkquda Jul 17, 2024
22f3a93
remove unnecessary code
mkquda Jul 17, 2024
895785d
set min and max expansion distance after setting costmap
mkquda Jul 17, 2024
d1e5ce4
refactor detectCollision function
mkquda Jul 18, 2024
14860bf
remove unused function
mkquda Jul 18, 2024
6ee0009
change default parameter values
mkquda Jul 18, 2024
6743aff
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 18, 2024
c312d2d
fix computeEDTMap function
mkquda Jul 19, 2024
530a2bf
Merge branch 'awf-latest' into RT1-6959-refactor-astar-planning-algor…
mkquda Jul 19, 2024
6f37063
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 19, 2024
8488294
rename parameter
mkquda Jul 22, 2024
4d23311
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 22, 2024
f10f858
use linear function for obstacle distance cost
mkquda Jul 22, 2024
46c60c4
Merge branch 'awf-latest' into RT1-6959-refactor-astar-planning-algor…
mkquda Jul 22, 2024
56f8763
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 22, 2024
f326714
fix rrtstar obstacle check
mkquda Jul 23, 2024
3de6a13
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 23, 2024
a576783
Merge branch 'awf-latest' into RT1-6959-refactor-astar-planning-algor…
mkquda Jul 23, 2024
2b849aa
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 23, 2024
1dde2b3
remove redundant return statements
mkquda Jul 26, 2024
701a3ec
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 26, 2024
8b4ebdb
Merge branch 'awf-latest' into RT1-6959-refactor-astar-planning-algor…
mkquda Jul 26, 2024
14c3a99
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 26, 2024
0ec7c2b
check goal pose validity before setting collision free distance map
mkquda Jul 29, 2024
061746a
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 29, 2024
8dc2425
declare variables as const where necessary
mkquda Jul 29, 2024
e8cc212
Merge branch 'RT1-6959-refactor-astar-planning-algorithm' into RT1-69…
mkquda Jul 29, 2024
ba4b328
Merge branch 'awf-latest' into RT1-6961-use-edt-map-to-improve-collis…
mkquda Jul 29, 2024
4c4f9d2
Merge branch 'awf-latest' into RT1-6961-use-edt-map-to-improve-collis…
mkquda Aug 5, 2024
1185bf6
compare front and back lengths when setting min and max dimension
mkquda Aug 5, 2024
386595a
add docstring and citation for computeEDTMap function
mkquda Aug 5, 2024
6f218f7
Merge branch 'main' into RT1-6961-use-edt-map-to-improve-collision-ch…
maxime-clem Aug 7, 2024
6fdce3c
Merge branch 'awf-latest' into RT1-6961-use-edt-map-to-improve-collis…
mkquda Aug 8, 2024
ffcf80e
Merge branch 'awf-latest' into RT1-6961-use-edt-map-to-improve-collis…
mkquda Aug 13, 2024
38b03a9
suppress spell check
mkquda Aug 13, 2024
20306db
Merge branch 'main' into RT1-6961-use-edt-map-to-improve-collision-ch…
mkquda Aug 13, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions planning/autoware_freespace_planner/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -76,9 +76,11 @@ None
| --------------------------- | ------ | ------------------------------------------------------- |
| `only_behind_solutions` | bool | whether restricting the solutions to be behind the goal |
| `use_back` | bool | whether using backward trajectory |
| `adapt_expansion_distance` | bool | if true, adapt expansion distance based on environment |
| `expansion_distance` | double | length of expansion for node transitions |
| `distance_heuristic_weight` | double | heuristic weight for estimating node's cost |
| `smoothness_weight` | double | cost factor for change in curvature |
| `obstacle_distance_weight` | double | cost factor for distance to obstacle |

#### RRT\* search parameters

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -32,9 +32,11 @@
astar:
only_behind_solutions: false
use_back: true
adapt_expansion_distance: true
expansion_distance: 0.5
distance_heuristic_weight: 1.0
distance_heuristic_weight: 1.5
smoothness_weight: 0.5
obstacle_distance_weight: 1.5

# -- RRT* search Configurations --
rrtstar:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -573,6 +573,7 @@ void FreespacePlannerNode::initializePlanningAlgorithm()
extended_vehicle_shape.length += margin;
extended_vehicle_shape.width += margin;
extended_vehicle_shape.base2back += margin / 2;
extended_vehicle_shape.setMinMaxDimension();

const auto planner_common_param = getPlannerCommonParam();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <tf2/utils.h>

#include <algorithm>
#include <limits>
#include <vector>

namespace autoware::freespace_planning_algorithms
Expand Down Expand Up @@ -63,6 +64,8 @@
double base_length;
double max_steering;
double base2back; // base_link to rear [m]
double min_dimension;
double max_dimension;

VehicleShape() = default;

Expand All @@ -74,6 +77,7 @@
max_steering(max_steering),
base2back(base2back)
{
setMinMaxDimension();
}

explicit VehicleShape(
Expand All @@ -84,6 +88,13 @@
max_steering(vehicle_info.max_steer_angle_rad),
base2back(vehicle_info.rear_overhang_m + margin / 2.0)
{
setMinMaxDimension();

Check warning on line 91 in planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_freespace_planning_algorithms/include/autoware/freespace_planning_algorithms/abstract_algorithm.hpp#L91

Added line #L91 was not covered by tests
}

void setMinMaxDimension()
{
min_dimension = std::min(0.5 * width, base2back);
max_dimension = std::hypot(length - base2back, 0.5 * width);
mkquda marked this conversation as resolved.
Show resolved Hide resolved
}
};

Expand Down Expand Up @@ -156,6 +167,8 @@
std::vector<IndexXY> & vertex_indexes_2d) const;
bool detectBoundaryExit(const IndexXYT & base_index) const;
bool detectCollision(const IndexXYT & base_index) const;
bool detectCollision(const geometry_msgs::msg::Pose & base_pose) const;
void computeEDTMap();
mkquda marked this conversation as resolved.
Show resolved Hide resolved

template <typename IndexType>
inline bool isOutOfRange(const IndexType & index) const
Expand Down Expand Up @@ -194,6 +207,12 @@
return is_obstacle_table_[indexToId(index)];
}

template <typename IndexType>
inline double getObstacleEDT(const IndexType & index) const
{
return edt_map_[indexToId(index)];
}

// compute single dimensional grid cell index from 2 dimensional index
template <typename IndexType>
inline int indexToId(const IndexType & index) const
Expand All @@ -216,6 +235,9 @@
// is_obstacle's table
std::vector<bool> is_obstacle_table_;

// Euclidean distance transform map (distance to nearest obstacle cell)
std::vector<double> edt_map_;

// pose in costmap frame
geometry_msgs::msg::Pose start_pose_;
geometry_msgs::msg::Pose goal_pose_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,13 @@ struct AstarParam
// base configs
bool only_behind_solutions; // solutions should be behind the goal
bool use_back; // backward search
bool adapt_expansion_distance;
double expansion_distance;

// search configs
double distance_heuristic_weight; // obstacle threshold on grid [0,255]
double smoothness_weight;
double obstacle_distance_weight;
};

struct AstarNode
Expand All @@ -56,9 +58,11 @@ struct AstarNode
double x; // x
double y; // y
double theta; // theta
double gc = 0; // actual motion cost
double fc = 0; // total node cost
double dir_distance = 0; // distance traveled from last direction change
double gc = 0.0; // actual motion cost
double fc = 0.0; // total node cost
double dir_distance = 0.0; // distance traveled from last direction change
double dist_to_goal = 0.0; // euclidean distance to goal pose
double dist_to_obs = 0.0; // euclidean distance to nearest obstacle
int steering_index; // steering index
bool is_back; // true if the current direction of the vehicle is back
AstarNode * parent = nullptr; // parent node
Expand All @@ -82,46 +86,9 @@ struct NodeComparison
bool operator()(const AstarNode * lhs, const AstarNode * rhs) const { return lhs->fc > rhs->fc; }
};

struct NodeUpdate
{
double shift_x;
double shift_y;
double shift_theta;
double distance;
int steering_index;
bool is_back;

NodeUpdate rotated(const double theta) const
{
NodeUpdate result = *this;
result.shift_x = std::cos(theta) * this->shift_x - std::sin(theta) * this->shift_y;
result.shift_y = std::sin(theta) * this->shift_x + std::cos(theta) * this->shift_y;
return result;
}

NodeUpdate flipped() const
{
NodeUpdate result = *this;
result.shift_y = -result.shift_y;
result.shift_theta = -result.shift_theta;
return result;
}

NodeUpdate reversed() const
{
NodeUpdate result = *this;
result.shift_x = -result.shift_x;
result.shift_theta = -result.shift_theta;
result.is_back = !result.is_back;
return result;
}
};

class AstarSearch : public AbstractPlanningAlgorithm
{
public:
using TransitionTable = std::vector<std::vector<NodeUpdate>>;

AstarSearch(
const PlannerCommonParam & planner_common_param, const VehicleShape & collision_vehicle_shape,
const AstarParam & astar_param);
Expand All @@ -134,12 +101,15 @@ class AstarSearch : public AbstractPlanningAlgorithm
AstarParam{
node.declare_parameter<bool>("astar.only_behind_solutions"),
node.declare_parameter<bool>("astar.use_back"),
node.declare_parameter<bool>("astar.adapt_expansion_distance"),
node.declare_parameter<double>("astar.expansion_distance"),
node.declare_parameter<double>("astar.distance_heuristic_weight"),
node.declare_parameter<double>("astar.smoothness_weight")})
node.declare_parameter<double>("astar.smoothness_weight"),
node.declare_parameter<double>("astar.obstacle_distance_weight")})
{
}

void setMap(const nav_msgs::msg::OccupancyGrid & costmap) override;
bool makePlan(const Pose & start_pose, const Pose & goal_pose) override;

const PlannerWaypoints & getWaypoints() const { return waypoints_; }
Expand All @@ -150,27 +120,26 @@ class AstarSearch : public AbstractPlanningAlgorithm
}

private:
void setTransitionTable();
void setCollisionFreeDistanceMap();
bool search();
void expandNodes(AstarNode & current_node);
void expandNodes(AstarNode & current_node, const bool is_back = false);
void resetData();
void setPath(const AstarNode & goal);
bool setStartNode();
bool setGoalNode();
double estimateCost(const Pose & pose, const IndexXYT & index) const;
bool isGoal(const AstarNode & node) const;
Pose node2pose(const AstarNode & node) const;

double getExpansionDistance(const AstarNode & current_node) const;
double getSteeringCost(const int steering_index) const;
double getSteeringChangeCost(const int steering_index, const int prev_steering_index) const;
double getDirectionChangeCost(const double dir_distance) const;
double getObsDistanceCost(const double obs_distance) const;

// Algorithm specific param
AstarParam astar_param_;

// hybrid astar variables
TransitionTable transition_table_;
std::vector<AstarNode> graph_;
std::vector<double> col_free_distance_map_;

Expand All @@ -185,6 +154,16 @@ class AstarSearch : public AbstractPlanningAlgorithm
double steering_resolution_;
double heading_resolution_;
double avg_turning_radius_;
double min_expansion_dist_;
double max_expansion_dist_;

// expansion distance factors
static constexpr double base_length_max_expansion_factor_ = 0.5;
static constexpr double dist_to_goal_expansion_factor_ = 0.15;
static constexpr double dist_to_obs_expansion_factor_ = 0.3;

// cost free obstacle distance
static constexpr double cost_free_obs_dist = 5.0;
mkquda marked this conversation as resolved.
Show resolved Hide resolved
};
} // namespace autoware::freespace_planning_algorithms

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,39 +31,26 @@ static constexpr double eps = 0.001;

inline double getTurningRadius(const double base_length, const double steering_angle)
{
return base_length / tan(steering_angle);
}

inline geometry_msgs::msg::Pose getPoseShift(
const double yaw, const double base_length, const double steering_angle, const double distance)
{
geometry_msgs::msg::Pose pose;
if (abs(steering_angle) < eps) {
pose.position.x = distance * cos(yaw);
pose.position.y = distance * sin(yaw);
return pose;
}
const double R = getTurningRadius(base_length, steering_angle);
const double beta = distance / R;
pose.position.x = R * sin(yaw + beta) - R * sin(yaw);
pose.position.y = R * cos(yaw) - R * cos(yaw + beta);
pose.orientation = autoware::universe_utils::createQuaternionFromYaw(beta);
return pose;
return base_length / std::tan(steering_angle);
}

inline geometry_msgs::msg::Pose getPose(
const geometry_msgs::msg::Pose & current_pose, const double base_length,
const double steering_angle, const double distance)
{
const double current_yaw = tf2::getYaw(current_pose.orientation);
const auto shift = getPoseShift(current_yaw, base_length, steering_angle, distance);
auto pose = current_pose;
pose.position.x += shift.position.x;
pose.position.y += shift.position.y;
if (abs(steering_angle) > eps) {
pose.orientation = autoware::universe_utils::createQuaternionFromYaw(
current_yaw + tf2::getYaw(shift.orientation));
const double yaw = tf2::getYaw(current_pose.orientation);
if (std::abs(steering_angle) < eps) {
pose.position.x += distance * std::cos(yaw);
pose.position.y += distance * std::sin(yaw);
return pose;
}

const double R = getTurningRadius(base_length, steering_angle);
const double beta = distance / R;
pose.position.x += (R * std::sin(yaw + beta) - R * std::sin(yaw));
pose.position.y += (R * std::cos(yaw) - R * std::cos(yaw + beta));
pose.orientation = autoware::universe_utils::createQuaternionFromYaw(yaw + beta);
return pose;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -114,13 +114,19 @@
.def_readwrite(
"only_behind_solutions", &freespace_planning_algorithms::AstarParam::only_behind_solutions)
.def_readwrite("use_back", &freespace_planning_algorithms::AstarParam::use_back)
.def_readwrite(

Check warning on line 117 in planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp#L117

Added line #L117 was not covered by tests
"adapt_expansion_distance",
&freespace_planning_algorithms::AstarParam::adapt_expansion_distance)
.def_readwrite(
"expansion_distance", &freespace_planning_algorithms::AstarParam::expansion_distance)
.def_readwrite(
"distance_heuristic_weight",
&freespace_planning_algorithms::AstarParam::distance_heuristic_weight)
.def_readwrite(
"smoothness_weight", &freespace_planning_algorithms::AstarParam::smoothness_weight);
"smoothness_weight", &freespace_planning_algorithms::AstarParam::smoothness_weight)
.def_readwrite(

Check warning on line 127 in planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp

View check run for this annotation

Codecov / codecov/patch

planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp#L127

Added line #L127 was not covered by tests
"obstacle_distance_weight",
&freespace_planning_algorithms::AstarParam::obstacle_distance_weight);

Check warning on line 129 in planning/autoware_freespace_planning_algorithms/scripts/bind/astar_search_pybind.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Large Method

PYBIND11_MODULE increases from 71 to 77 lines of code, threshold = 70. Large functions with many lines of code are generally harder to understand and lower the code health. Avoid adding more lines to this function.
auto pyPlannerCommonParam =
py::class_<freespace_planning_algorithms::PlannerCommonParam>(
p, "PlannerCommonParam", py::dynamic_attr())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,9 +46,11 @@
astar_param = fp.AstarParam()
astar_param.only_behind_solutions = False
astar_param.use_back = True
astar_param.adapt_expansion_distance = True
astar_param.expansion_distance = 0.4
astar_param.distance_heuristic_weight = 1.0
astar_param.smoothness_weight = 1.0
astar_param.obstacle_distance_weight = 1.0

astar = fp.AstarSearch(planner_param, vehicle_shape, astar_param)

Expand Down
Loading
Loading