Autoware.Auto
autoware::planning::freespace_planner Namespace Reference

Namespaces

 reeds_shepp
 

Classes

struct  AstarNode
 
struct  AstarParam
 
class  AstarSearch
 A* Hybrid algorithm implementation using ROS2 typical structures. More...
 
class  BasePlanningAlgorithm
 Planning algorithm base class. More...
 
class  FreespacePlannerNode
 Creates Hybrid A* planning algorithm node. More...
 
struct  IndexXY
 
struct  IndexXYT
 
struct  NodeComparison
 
struct  NodeParam
 
struct  NodeUpdate
 
struct  PlannerCommonParam
 Parameters defining common algorithm configuration. More...
 
struct  PlannerWaypoint
 
struct  PlannerWaypoints
 Trajectory points representation as an algorithms output. More...
 
class  ReedsShepp
 Class calculating shortest path on plane, considering arc and straight, forward and backward movements. The algorithm analyzes a sufficient subset of situations where robot can move clockwise, counterclockwise, straight in forward or backward direction. The clockwise and counterclockwise turns can be generalized by substituting the left/right nomenclature with an arc movement marked by the 'C' character. A straight movement can be marked as the 'S'. The situation "(...)CC(...)" means a change in the direction of the turn, regardless of whether the first turn is counterclockwise or clockwise. This class uses implementation of algorithm described by J. A. REEDS and L. A. SHEPP. For more detailed info please refer to "Optimal paths for a car that goes both forwards and backwards" paper. More...
 
struct  ReedsSheppNode
 Definition of car's position and orientation in ReedsShepp state space. More...
 
class  ReedsSheppPath
 Complete description of a ReedsShepp parametrized path. More...
 
struct  StateXYT
 Input position and orientation representation. More...
 
struct  VehicleShape
 Definition of essential vehicle dimensions. More...
 

Enumerations

enum  NodeStatus : uint8_t { NodeStatus::None, NodeStatus::Open, NodeStatus::Closed, NodeStatus::Obstacle }
 
enum  SearchStatus {
  SearchStatus::SUCCESS, SearchStatus::FAILURE_COLLISION_AT_START, SearchStatus::FAILURE_COLLISION_AT_GOAL, SearchStatus::FAILURE_TIMEOUT_EXCEEDED,
  SearchStatus::FAILURE_NO_PATH_FOUND
}
 Possible planning results. More...
 
enum  ReedsSheppPathSegmentType { NO_OPERATION, COUNTERCLOCKWISE, STRAIGHT, CLOCKWISE }
 The Reeds-Shepp path segment types. More...
 
enum  FreespacePlannerState { FreespacePlannerState::IDLE, FreespacePlannerState::PLANNING }
 

Functions

double normalizeRadian (const double rad, const double min_rad=-M_PI)
 
int discretizeAngle (const double theta, const size_t theta_size)
 
geometry_msgs::msg::Pose transformPose (const geometry_msgs::msg::Pose &pose, const geometry_msgs::msg::TransformStamped &transform)
 Transform pose using given transform. More...
 
IndexXYT pose2index (const geometry_msgs::msg::Pose &pose_local, const float &costmap_resolution, const size_t theta_size)
 Transform pose floating-point values to discrete costmap coordinates. More...
 
geometry_msgs::msg::Pose index2pose (const IndexXYT &index, const float &costmap_resolution, const size_t theta_size)
 Transform discrete costmap coordinates to floating-point pose values. More...
 
geometry_msgs::msg::Pose global2local (const nav_msgs::msg::OccupancyGrid &costmap, const geometry_msgs::msg::Pose &pose_global)
 Transform pose from its frame to costmaps local frame. More...
 
geometry_msgs::msg::Pose local2global (const nav_msgs::msg::OccupancyGrid &costmap, const geometry_msgs::msg::Pose &pose_local)
 Transform pose from costmaps to its original frame. More...
 
bool FREESPACE_PLANNER_PUBLIC isSuccess (const SearchStatus &status)
 Determines if passed status is a success status. More...
 
constexpr double deg2rad (const double deg)
 
double calcReedsSheppDistance (const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2, double radius)
 
double calcDistance2d (const geometry_msgs::msg::Point &p1, const geometry_msgs::msg::Point &p2)
 
double calcDistance2d (const geometry_msgs::msg::Pose &p1, const geometry_msgs::msg::Pose &p2)
 
geometry_msgs::msg::Quaternion makeQuaternionWithYaw (const double yaw)
 
geometry_msgs::msg::Pose calcRelativePose (const geometry_msgs::msg::Pose &base_pose, const geometry_msgs::msg::Pose &pose)
 
geometry_msgs::msg::Pose node2pose (const AstarNode &node)
 
AstarSearch::TransitionTable createTransitionTable (const double minimum_turning_radius, const double maximum_turning_radius, const size_t turning_radius_size, const size_t theta_size, const bool use_back)
 
PlannerWaypoints adjustWaypointsSize (const PlannerWaypoints &planner_waypoints)
 
autoware_auto_planning_msgs::msg::Trajectory createTrajectory (const geometry_msgs::msg::PoseStamped &current_pose, const PlannerWaypoints &planner_waypoints, const float &velocity)
 

Variables

const ReedsSheppPathSegmentType RP_PATH_TYPE [18][5]
 Reeds-Shepp path configurations. More...
 

Enumeration Type Documentation

◆ FreespacePlannerState

Enumerator
IDLE 
PLANNING 

◆ NodeStatus

Enumerator
None 
Open 
Closed 
Obstacle 

◆ ReedsSheppPathSegmentType

The Reeds-Shepp path segment types.

Enumerator
NO_OPERATION 
COUNTERCLOCKWISE 
STRAIGHT 
CLOCKWISE 

◆ SearchStatus

Possible planning results.

Enumerator
SUCCESS 

Planning successful.

FAILURE_COLLISION_AT_START 

Collision at start position detected.

FAILURE_COLLISION_AT_GOAL 

Collision at goal position detected.

FAILURE_TIMEOUT_EXCEEDED 

Planning timeout exceeded.

FAILURE_NO_PATH_FOUND 

Planner didn't manage to find path.

Function Documentation

◆ adjustWaypointsSize()

PlannerWaypoints autoware::planning::freespace_planner::adjustWaypointsSize ( const PlannerWaypoints planner_waypoints)

◆ calcDistance2d() [1/2]

double autoware::planning::freespace_planner::calcDistance2d ( const geometry_msgs::msg::Point p1,
const geometry_msgs::msg::Point p2 
)

◆ calcDistance2d() [2/2]

double autoware::planning::freespace_planner::calcDistance2d ( const geometry_msgs::msg::Pose &  p1,
const geometry_msgs::msg::Pose &  p2 
)

◆ calcReedsSheppDistance()

double autoware::planning::freespace_planner::calcReedsSheppDistance ( const geometry_msgs::msg::Pose &  p1,
const geometry_msgs::msg::Pose &  p2,
double  radius 
)

◆ calcRelativePose()

geometry_msgs::msg::Pose autoware::planning::freespace_planner::calcRelativePose ( const geometry_msgs::msg::Pose &  base_pose,
const geometry_msgs::msg::Pose &  pose 
)

◆ createTrajectory()

autoware_auto_planning_msgs::msg::Trajectory autoware::planning::freespace_planner::createTrajectory ( const geometry_msgs::msg::PoseStamped &  current_pose,
const PlannerWaypoints planner_waypoints,
const float &  velocity 
)

◆ createTransitionTable()

AstarSearch::TransitionTable autoware::planning::freespace_planner::createTransitionTable ( const double  minimum_turning_radius,
const double  maximum_turning_radius,
const size_t  turning_radius_size,
const size_t  theta_size,
const bool  use_back 
)

◆ deg2rad()

constexpr double autoware::planning::freespace_planner::deg2rad ( const double  deg)
constexpr

◆ discretizeAngle()

int autoware::planning::freespace_planner::discretizeAngle ( const double  theta,
const size_t  theta_size 
)

◆ global2local()

geometry_msgs::msg::Pose autoware::planning::freespace_planner::global2local ( const nav_msgs::msg::OccupancyGrid &  costmap,
const geometry_msgs::msg::Pose &  pose_global 
)

Transform pose from its frame to costmaps local frame.

◆ index2pose()

geometry_msgs::msg::Pose autoware::planning::freespace_planner::index2pose ( const IndexXYT index,
const float &  costmap_resolution,
const size_t  theta_size 
)

Transform discrete costmap coordinates to floating-point pose values.

◆ isSuccess()

bool FREESPACE_PLANNER_PUBLIC autoware::planning::freespace_planner::isSuccess ( const SearchStatus status)
inline

Determines if passed status is a success status.

◆ local2global()

geometry_msgs::msg::Pose autoware::planning::freespace_planner::local2global ( const nav_msgs::msg::OccupancyGrid &  costmap,
const geometry_msgs::msg::Pose &  pose_local 
)

Transform pose from costmaps to its original frame.

◆ makeQuaternionWithYaw()

geometry_msgs::msg::Quaternion autoware::planning::freespace_planner::makeQuaternionWithYaw ( const double  yaw)

◆ node2pose()

geometry_msgs::msg::Pose autoware::planning::freespace_planner::node2pose ( const AstarNode node)

◆ normalizeRadian()

double autoware::planning::freespace_planner::normalizeRadian ( const double  rad,
const double  min_rad = -M_PI 
)

◆ pose2index()

IndexXYT autoware::planning::freespace_planner::pose2index ( const geometry_msgs::msg::Pose &  pose_local,
const float &  costmap_resolution,
const size_t  theta_size 
)

Transform pose floating-point values to discrete costmap coordinates.

◆ transformPose()

geometry_msgs::msg::Pose autoware::planning::freespace_planner::transformPose ( const geometry_msgs::msg::Pose &  pose,
const geometry_msgs::msg::TransformStamped &  transform 
)

Transform pose using given transform.

Variable Documentation

◆ RP_PATH_TYPE

autoware::planning::freespace_planner::NO_OPERATION
@ NO_OPERATION
Definition: reeds_shepp_impl.hpp:99
autoware::planning::freespace_planner::STRAIGHT
@ STRAIGHT
Definition: reeds_shepp_impl.hpp:99
autoware::planning::freespace_planner::COUNTERCLOCKWISE
@ COUNTERCLOCKWISE
Definition: reeds_shepp_impl.hpp:99
autoware::planning::freespace_planner::CLOCKWISE
@ CLOCKWISE
Definition: reeds_shepp_impl.hpp:99