Local planner that explores alternative homotopy classes, create a plan for each alternative and finally return the robot controls for the current best path (repeated in each sampling interval) More...
#include <homotopy_class_planner.h>
Public Types | |
using | EquivalenceClassContainer = std::vector< std::pair< EquivalenceClassPtr, bool > > |
Public Member Functions | |
bool | addEquivalenceClassIfNew (const EquivalenceClassPtr &eq_class, bool lock=false) |
Internal helper function that adds a new equivalence class to the list of known classes only if it is unique. More... | |
int | bestTebIdx () const |
find the index of the currently best TEB in the container More... | |
template<typename BidirIter , typename Fun > | |
EquivalenceClassPtr | calculateEquivalenceClass (BidirIter path_start, BidirIter path_end, Fun fun_cplx_point, const ObstContainer *obstacles=NULL, boost::optional< TimeDiffSequence::iterator > timediff_start=boost::none, boost::optional< TimeDiffSequence::iterator > timediff_end=boost::none) |
Calculate the equivalence class of a path. More... | |
void | clearGraph () |
Clear any existing graph of the homotopy class search. More... | |
virtual void | clearPlanner () |
Reset the planner. More... | |
virtual void | computeCurrentCost (std::vector< double > &cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false) |
bool | computeStartOrientation (const TebOptimalPlannerPtr plan, const double len_orientation_vector, double &orientation) |
Given a plan, computes its start orientation using a vector of length >= len_orientation_vector starting from the initial pose. More... | |
const TebConfig * | config () const |
Access config (read-only) More... | |
void | deletePlansDetouringBackwards (const double orient_threshold, const double len_orientation_vector) |
Checks if the orientation of the computed trajectories differs from that of the best plan of more than the specified threshold and eventually deletes them. Also deletes detours with a duration much bigger than the duration of the best_teb (duration / best duration > max_ratio_detours_duration_best_duration). More... | |
const EquivalenceClassContainer & | getEquivalenceClassRef () const |
Return the current set of equivalence erelations (read-only) More... | |
const TebOptPlannerContainer & | getTrajectoryContainer () const |
Read-only access to the internal trajectory container. More... | |
HomotopyClassPlanner () | |
Default constructor. More... | |
HomotopyClassPlanner (const TebConfig &cfg, ObstContainer *obstacles=NULL, RobotFootprintModelPtr robot_model=boost::make_shared< PointRobotFootprint >(), TebVisualizationPtr visualization=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL) | |
Construct and initialize the HomotopyClassPlanner. More... | |
void | initialize (const TebConfig &cfg, ObstContainer *obstacles=NULL, RobotFootprintModelPtr robot_model=boost::make_shared< PointRobotFootprint >(), TebVisualizationPtr visualization=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL) |
Initialize the HomotopyClassPlanner. More... | |
bool | isInitialized () const |
Returns true if the planner is initialized. More... | |
const ObstContainer * | obstacles () const |
Access current obstacle container (read-only) More... | |
virtual void | setPreferredTurningDir (RotType dir) |
Prefer a desired initial turning direction (by penalizing the opposing one) More... | |
virtual | ~HomotopyClassPlanner () |
Destruct the HomotopyClassPlanner. More... | |
Plan a trajectory | |
virtual bool | plan (const std::vector< geometry_msgs::PoseStamped > &initial_plan, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false) |
Plan a trajectory based on an initial reference plan. More... | |
virtual bool | plan (const tf::Pose &start, const tf::Pose &goal, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false) |
Plan a trajectory between a given start and goal pose (tf::Pose version). More... | |
virtual bool | plan (const PoseSE2 &start, const PoseSE2 &goal, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false) |
Plan a trajectory between a given start and goal pose. More... | |
virtual bool | getVelocityCommand (double &vx, double &vy, double &omega, int look_ahead_poses) const |
Get the velocity command from a previously optimized plan to control the robot at the current sampling interval. More... | |
TebOptimalPlannerPtr | bestTeb () const |
Access current best trajectory candidate (that relates to the "best" homotopy class). More... | |
virtual bool | isTrajectoryFeasible (base_local_planner::CostmapModel *costmap_model, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1) |
Check whether the planned trajectory is feasible or not. More... | |
TebOptimalPlannerPtr | findBestTeb () |
In case of empty best teb, scores again the available plans to find the best one. The best_teb_ variable is updated consequently. More... | |
TebOptPlannerContainer::iterator | removeTeb (TebOptimalPlannerPtr &teb) |
Removes the specified teb and the corresponding homotopy class from the list of available ones. More... | |
Visualization | |
void | setVisualization (TebVisualizationPtr visualization) |
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and pose sequence) More... | |
virtual void | visualize () |
Publish the local plan, pose sequence and additional information via ros topics (e.g. subscribe with rviz). More... | |
Important steps that are called during planning | |
void | exploreEquivalenceClassesAndInitTebs (const PoseSE2 &start, const PoseSE2 &goal, double dist_to_obst, const geometry_msgs::Twist *start_vel) |
Explore paths in new equivalence classes (e.g. homotopy classes) and initialize TEBs from them. More... | |
template<typename BidirIter , typename Fun > | |
TebOptimalPlannerPtr | addAndInitNewTeb (BidirIter path_start, BidirIter path_end, Fun fun_position, double start_orientation, double goal_orientation, const geometry_msgs::Twist *start_velocity) |
Add a new Teb to the internal trajectory container, if this teb constitutes a new equivalence class. Initialize it using a generic 2D reference path. More... | |
TebOptimalPlannerPtr | addAndInitNewTeb (const PoseSE2 &start, const PoseSE2 &goal, const geometry_msgs::Twist *start_velocity) |
Add a new Teb to the internal trajectory container, if this teb constitutes a new equivalence class. Initialize it with a simple straight line between a given start and goal. More... | |
TebOptimalPlannerPtr | addAndInitNewTeb (const std::vector< geometry_msgs::PoseStamped > &initial_plan, const geometry_msgs::Twist *start_velocity) |
Add a new Teb to the internal trajectory container , if this teb constitutes a new equivalence class. Initialize it using a PoseStamped container. More... | |
void | updateAllTEBs (const PoseSE2 *start, const PoseSE2 *goal, const geometry_msgs::Twist *start_velocity) |
Update TEBs with new pose, goal and current velocity. More... | |
void | optimizeAllTEBs (int iter_innerloop, int iter_outerloop) |
Optimize all available trajectories by invoking the optimizer on each one. More... | |
TebOptimalPlannerPtr | getInitialPlanTEB () |
Returns a shared pointer to the TEB related to the initial plan. More... | |
TebOptimalPlannerPtr | selectBestTeb () |
In case of multiple, internally stored, alternative trajectories, select the best one according to their cost values. More... | |
Public Member Functions inherited from teb_local_planner::PlannerInterface | |
virtual void | computeCurrentCost (std::vector< double > &cost, double obst_cost_scale=1.0, bool alternative_time_cost=false) |
PlannerInterface () | |
Default constructor. More... | |
virtual | ~PlannerInterface () |
Virtual destructor. More... | |
Static Public Member Functions | |
static bool | isHSignatureSimilar (const std::complex< long double > &h1, const std::complex< long double > &h2, double threshold) |
Check if two h-signatures are similar (w.r.t. a certain threshold) More... | |
Protected Member Functions | |
Explore new paths and keep only a single one for each homotopy class | |
bool | hasEquivalenceClass (const EquivalenceClassPtr &eq_class) const |
Check if a h-signature exists already. More... | |
void | renewAndAnalyzeOldTebs (bool delete_detours) |
Renew all found h-signatures for the new planning step based on existing TEBs. Optionally detours can be discarded. More... | |
void | updateReferenceTrajectoryViaPoints (bool all_trajectories) |
Associate trajectories with via-points. More... | |
Protected Attributes | |
TebOptimalPlannerPtr | best_teb_ |
Store the current best teb. More... | |
const TebConfig * | cfg_ |
Config class that stores and manages all related parameters. More... | |
EquivalenceClassContainer | equivalence_classes_ |
Store all known quivalence classes (e.g. h-signatures) to allow checking for duplicates after finding and adding new ones. More... | |
boost::shared_ptr< GraphSearchInterface > | graph_search_ |
const std::vector< geometry_msgs::PoseStamped > * | initial_plan_ |
Store the initial plan if available for a better trajectory initialization. More... | |
EquivalenceClassPtr | initial_plan_eq_class_ |
Store the equivalence class of the initial plan. More... | |
TebOptimalPlannerPtr | initial_plan_teb_ |
Store pointer to the TEB related to the initial plan (use method getInitialPlanTEB() since it checks if initial_plan_teb_ is still included in tebs_.) More... | |
bool | initialized_ |
Keeps track about the correct initialization of this class. More... | |
TebOptimalPlannerPtr | last_best_teb_ |
Points to the plan used in the previous control cycle. More... | |
ros::Time | last_eq_class_switching_time_ |
Store the time at which the equivalence class changed recently. More... | |
ObstContainer * | obstacles_ |
Store obstacles that are relevant for planning. More... | |
RobotFootprintModelPtr | robot_model_ |
Robot model shared instance. More... | |
TebOptPlannerContainer | tebs_ |
Container that stores multiple local teb planners (for alternative equivalence classes) and their corresponding costs. More... | |
const ViaPointContainer * | via_points_ |
Store the current list of via-points. More... | |
TebVisualizationPtr | visualization_ |
Instance of the visualization class (local/global plan, obstacles, ...) More... | |
Local planner that explores alternative homotopy classes, create a plan for each alternative and finally return the robot controls for the current best path (repeated in each sampling interval)
Equivalence classes (e.g. homotopy) are explored using the help of a search-graph.
A couple of possible candidates are sampled / generated and filtered afterwards such that only a single candidate per homotopy class remain. Filtering is applied using the H-Signature, a homotopy (resp. homology) invariant:
Followed by the homotopy class search, each candidate is used as an initialization for the underlying trajectory optimization (in this case utilizing the TebOptimalPlanner class with the TimedElasticBand).
Depending on the config parameters, the optimization is performed in parallel.
After the optimization is completed, the best optimized candidate is selected w.r.t. to trajectory cost, since the cost already contains important features like clearance from obstacles and transition time.
Everyhting is performed by calling one of the overloaded plan() methods.
Afterwards the velocity command to control the robot is obtained from the "best" candidate via getVelocityCommand().
All steps are repeated in the subsequent sampling interval with the exception, that already planned (optimized) trajectories are preferred against new path initilizations in order to improve the hot-starting capability.
Definition at line 107 of file homotopy_class_planner.h.
using teb_local_planner::HomotopyClassPlanner::EquivalenceClassContainer = std::vector< std::pair<EquivalenceClassPtr, bool> > |
Definition at line 111 of file homotopy_class_planner.h.
teb_local_planner::HomotopyClassPlanner::HomotopyClassPlanner | ( | ) |
Default constructor.
Definition at line 46 of file homotopy_class_planner.cpp.
teb_local_planner::HomotopyClassPlanner::HomotopyClassPlanner | ( | const TebConfig & | cfg, |
ObstContainer * | obstacles = NULL , |
||
RobotFootprintModelPtr | robot_model = boost::make_shared<PointRobotFootprint>() , |
||
TebVisualizationPtr | visualization = TebVisualizationPtr() , |
||
const ViaPointContainer * | via_points = NULL |
||
) |
Construct and initialize the HomotopyClassPlanner.
cfg | Const reference to the TebConfig class for internal parameters |
obstacles | Container storing all relevant obstacles (see Obstacle) |
robot_model | Shared pointer to the robot shape model used for optimization (optional) |
visualization | Shared pointer to the TebVisualization class (optional) |
via_points | Container storing via-points (optional) |
Definition at line 50 of file homotopy_class_planner.cpp.
|
virtual |
Destruct the HomotopyClassPlanner.
Definition at line 56 of file homotopy_class_planner.cpp.
TebOptimalPlannerPtr teb_local_planner::HomotopyClassPlanner::addAndInitNewTeb | ( | BidirIter | path_start, |
BidirIter | path_end, | ||
Fun | fun_position, | ||
double | start_orientation, | ||
double | goal_orientation, | ||
const geometry_msgs::Twist * | start_velocity | ||
) |
Add a new Teb to the internal trajectory container, if this teb constitutes a new equivalence class. Initialize it using a generic 2D reference path.
Refer to TimedElasticBand::initTEBtoGoal() for more details about the template parameters.
path_start | start iterator of a generic 2d path |
path_end | end iterator of a generic 2d path |
fun_position | unary function that returns the Eigen::Vector2d object |
start_orientation | Orientation of the first pose of the trajectory (optional, otherwise use goal heading) |
goal_orientation | Orientation of the last pose of the trajectory (optional, otherwise use goal heading) |
start_velocity | start velocity (optional) |
BidirIter | Bidirectional iterator type |
Fun | unyary function that transforms the dereferenced iterator into an Eigen::Vector2d |
Definition at line 66 of file homotopy_class_planner.hpp.
TebOptimalPlannerPtr teb_local_planner::HomotopyClassPlanner::addAndInitNewTeb | ( | const PoseSE2 & | start, |
const PoseSE2 & | goal, | ||
const geometry_msgs::Twist * | start_velocity | ||
) |
Add a new Teb to the internal trajectory container, if this teb constitutes a new equivalence class. Initialize it with a simple straight line between a given start and goal.
start | start pose |
goal | goal pose |
start_velocity | start velocity (optional) |
Definition at line 353 of file homotopy_class_planner.cpp.
TebOptimalPlannerPtr teb_local_planner::HomotopyClassPlanner::addAndInitNewTeb | ( | const std::vector< geometry_msgs::PoseStamped > & | initial_plan, |
const geometry_msgs::Twist * | start_velocity | ||
) |
Add a new Teb to the internal trajectory container , if this teb constitutes a new equivalence class. Initialize it using a PoseStamped container.
initial_plan | container of poses (start and goal orientation should be valid!) |
start_velocity | start velocity (optional) |
Definition at line 378 of file homotopy_class_planner.cpp.
bool teb_local_planner::HomotopyClassPlanner::addEquivalenceClassIfNew | ( | const EquivalenceClassPtr & | eq_class, |
bool | lock = false |
||
) |
Internal helper function that adds a new equivalence class to the list of known classes only if it is unique.
eq_class | equivalence class that should be tested |
lock | if true , exclude the H-signature from deletion. |
true
if the h-signature was added and no duplicate was found, false
otherwise Definition at line 190 of file homotopy_class_planner.cpp.
|
inline |
Access current best trajectory candidate (that relates to the "best" homotopy class).
If no trajectory is available, the pointer will be empty. If only a single trajectory is available, return it. Otherwise return the best one, but call selectBestTeb() before to perform the actual selection (part of the plan() methods).
Definition at line 209 of file homotopy_class_planner.h.
int teb_local_planner::HomotopyClassPlanner::bestTebIdx | ( | ) | const |
find the index of the currently best TEB in the container
Definition at line 605 of file homotopy_class_planner.cpp.
EquivalenceClassPtr teb_local_planner::HomotopyClassPlanner::calculateEquivalenceClass | ( | BidirIter | path_start, |
BidirIter | path_end, | ||
Fun | fun_cplx_point, | ||
const ObstContainer * | obstacles = NULL , |
||
boost::optional< TimeDiffSequence::iterator > | timediff_start = boost::none , |
||
boost::optional< TimeDiffSequence::iterator > | timediff_end = boost::none |
||
) |
Calculate the equivalence class of a path.
Currently, only the H-signature (refer to HSignature) is implemented.
path_start | Iterator to the first element in the path |
path_end | Iterator to the last element in the path |
obstacles | obstacle container |
fun_cplx_point | function accepting the dereference iterator type and that returns the position as complex number. |
BidirIter | Bidirectional iterator type |
Fun | function of the form std::complex< long double > (const T& point_type) |
Definition at line 47 of file homotopy_class_planner.hpp.
|
inline |
Clear any existing graph of the homotopy class search.
Definition at line 459 of file homotopy_class_planner.h.
|
inlinevirtual |
Reset the planner.
Clear all previously found H-signatures, paths, tebs and the hcgraph.
Implements teb_local_planner::PlannerInterface.
Definition at line 359 of file homotopy_class_planner.h.
|
virtual |
Compute and return the cost of the current optimization graph (supports multiple trajectories)
[out] | cost | current cost value for each trajectory [for a planner with just a single trajectory: size=1, vector will not be cleared] |
obst_cost_scale | Specify extra scaling for obstacle costs | |
viapoint_cost_scale | Specify extra scaling for via points. | |
alternative_time_cost | Replace the cost for the time optimal objective by the actual (weighted) transition time |
Definition at line 685 of file homotopy_class_planner.cpp.
bool teb_local_planner::HomotopyClassPlanner::computeStartOrientation | ( | const TebOptimalPlannerPtr | plan, |
const double | len_orientation_vector, | ||
double & | orientation | ||
) |
Given a plan, computes its start orientation using a vector of length >= len_orientation_vector starting from the initial pose.
plan | Teb to be analyzed |
len_orientation_vector | min length of the vector used to compute the start orientation |
orientation | computed start orientation |
Definition at line 746 of file homotopy_class_planner.cpp.
|
inline |
Access config (read-only)
Definition at line 443 of file homotopy_class_planner.h.
void teb_local_planner::HomotopyClassPlanner::deletePlansDetouringBackwards | ( | const double | orient_threshold, |
const double | len_orientation_vector | ||
) |
Checks if the orientation of the computed trajectories differs from that of the best plan of more than the specified threshold and eventually deletes them. Also deletes detours with a duration much bigger than the duration of the best_teb (duration / best duration > max_ratio_detours_duration_best_duration).
orient_threshold | Threshold paramter for allowed orientation changes in radians |
len_orientation_vector | length of the vector used to compute the start orientation |
Definition at line 693 of file homotopy_class_planner.cpp.
void teb_local_planner::HomotopyClassPlanner::exploreEquivalenceClassesAndInitTebs | ( | const PoseSE2 & | start, |
const PoseSE2 & | goal, | ||
double | dist_to_obst, | ||
const geometry_msgs::Twist * | start_vel | ||
) |
Explore paths in new equivalence classes (e.g. homotopy classes) and initialize TEBs from them.
This "all-in-one" method creates a graph with position keypoints from which feasible paths (with clearance from obstacles) are extracted.
All obtained paths are filted to only keep a single path for each equivalence class.
Each time a new equivalence class is explored (by means of no previous trajectory/TEB remain in that equivalence class), a new trajectory/TEB will be initialized.
Everything is prepared now for the optimization step: see optimizeAllTEBs().
start | Current start pose (e.g. pose of the robot) |
goal | Goal pose (e.g. robot's goal) |
dist_to_obst | Allowed distance to obstacles: if not satisfying, the path will be rejected (note, this is not the distance used for optimization). |
Definition at line 332 of file homotopy_class_planner.cpp.
TebOptimalPlannerPtr teb_local_planner::HomotopyClassPlanner::findBestTeb | ( | ) |
In case of empty best teb, scores again the available plans to find the best one. The best_teb_ variable is updated consequently.
Definition at line 645 of file homotopy_class_planner.cpp.
|
inline |
Return the current set of equivalence erelations (read-only)
Definition at line 481 of file homotopy_class_planner.h.
TebOptimalPlannerPtr teb_local_planner::HomotopyClassPlanner::getInitialPlanTEB | ( | ) |
Returns a shared pointer to the TEB related to the initial plan.
Definition at line 456 of file homotopy_class_planner.cpp.
|
inline |
Read-only access to the internal trajectory container.
Definition at line 393 of file homotopy_class_planner.h.
|
virtual |
Get the velocity command from a previously optimized plan to control the robot at the current sampling interval.
[out] | vx | translational velocity [m/s] |
[out] | vy | strafing velocity which can be nonzero for holonomic robots [m/s] |
[out] | omega | rotational velocity [rad/s] |
[in] | look_ahead_poses | index of the final pose used to compute the velocity command. |
true
if command is valid, false
otherwise Implements teb_local_planner::PlannerInterface.
Definition at line 128 of file homotopy_class_planner.cpp.
|
protected |
Check if a h-signature exists already.
eq_class | equivalence class that should be tested |
true
if the h-signature is found, false
otherwise Definition at line 179 of file homotopy_class_planner.cpp.
void teb_local_planner::HomotopyClassPlanner::initialize | ( | const TebConfig & | cfg, |
ObstContainer * | obstacles = NULL , |
||
RobotFootprintModelPtr | robot_model = boost::make_shared<PointRobotFootprint>() , |
||
TebVisualizationPtr | visualization = TebVisualizationPtr() , |
||
const ViaPointContainer * | via_points = NULL |
||
) |
Initialize the HomotopyClassPlanner.
cfg | Const reference to the TebConfig class for internal parameters |
obstacles | Container storing all relevant obstacles (see Obstacle) |
robot_model | Shared pointer to the robot shape model used for optimization (optional) |
visualization | Shared pointer to the TebVisualization class (optional) |
via_points | Container storing via-points (optional) |
Definition at line 60 of file homotopy_class_planner.cpp.
|
inlinestatic |
Check if two h-signatures are similar (w.r.t. a certain threshold)
h1 | first h-signature |
h2 | second h-signature |
true
if both h-signatures are similar, false otherwise. Definition at line 411 of file homotopy_class_planner.h.
|
inline |
Returns true if the planner is initialized.
Definition at line 454 of file homotopy_class_planner.h.
|
virtual |
Check whether the planned trajectory is feasible or not.
This method currently checks only that the trajectory, or a part of the trajectory is collision free. Obstacles are here represented as costmap instead of the internal ObstacleContainer.
costmap_model | Pointer to the costmap model |
footprint_spec | The specification of the footprint of the robot in world coordinates |
inscribed_radius | The radius of the inscribed circle of the robot |
circumscribed_radius | The radius of the circumscribed circle of the robot |
look_ahead_idx | Number of poses along the trajectory that should be verified, if -1, the complete trajectory will be checked. |
true
, if the robot footprint along the first part of the trajectory intersects with any obstacle in the costmap, false
otherwise. Implements teb_local_planner::PlannerInterface.
Definition at line 622 of file homotopy_class_planner.cpp.
|
inline |
Access current obstacle container (read-only)
Definition at line 449 of file homotopy_class_planner.h.
void teb_local_planner::HomotopyClassPlanner::optimizeAllTEBs | ( | int | iter_innerloop, |
int | iter_outerloop | ||
) |
Optimize all available trajectories by invoking the optimizer on each one.
Depending on the configuration parameters, the optimization is performed either single or multi threaded.
iter_innerloop | Number of inner iterations (see TebOptimalPlanner::optimizeTEB()) |
iter_outerloop | Number of outer iterations (see TebOptimalPlanner::optimizeTEB()) |
Definition at line 427 of file homotopy_class_planner.cpp.
|
virtual |
Plan a trajectory based on an initial reference plan.
Provide this method to create and optimize a trajectory that is initialized according to an initial reference plan (given as a container of poses).
initial_plan | vector of geometry_msgs::PoseStamped (must be valid until clearPlanner() is called!) |
start_vel | Current start velocity (e.g. the velocity of the robot, only linear.x, linear.y (holonomic) and angular.z are used) |
free_goal_vel | if true , a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) |
true
if planning was successful, false
otherwise Implements teb_local_planner::PlannerInterface.
Definition at line 86 of file homotopy_class_planner.cpp.
|
virtual |
Plan a trajectory between a given start and goal pose (tf::Pose version).
Provide this method to create and optimize a trajectory that is initialized between a given start and goal pose.
start | tf::Pose containing the start pose of the trajectory |
goal | tf::Pose containing the goal pose of the trajectory |
start_vel | Current start velocity (e.g. the velocity of the robot, only linear.x, linear.y (holonomic) and angular.z are used) |
free_goal_vel | if true , a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) |
true
if planning was successful, false
otherwise Implements teb_local_planner::PlannerInterface.
Definition at line 100 of file homotopy_class_planner.cpp.
|
virtual |
Plan a trajectory between a given start and goal pose.
Provide this method to create and optimize a trajectory that is initialized between a given start and goal pose.
start | PoseSE2 containing the start pose of the trajectory |
goal | PoseSE2 containing the goal pose of the trajectory |
start_vel | Initial velocity at the start pose (twist message containing the translational and angular velocity). |
free_goal_vel | if true , a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) |
true
if planning was successful, false
otherwise Implements teb_local_planner::PlannerInterface.
Definition at line 108 of file homotopy_class_planner.cpp.
TebOptPlannerContainer::iterator teb_local_planner::HomotopyClassPlanner::removeTeb | ( | TebOptimalPlannerPtr & | teb | ) |
Removes the specified teb and the corresponding homotopy class from the list of available ones.
pointer | to the teb Band to be removed |
Definition at line 654 of file homotopy_class_planner.cpp.
|
protected |
Renew all found h-signatures for the new planning step based on existing TEBs. Optionally detours can be discarded.
Calling this method in each new planning interval is really important. First all old h-signatures are deleted, since they could be invalid for this planning step (obstacle position may changed). Afterwards the h-signatures are calculated for each existing TEB/trajectory and is inserted to the list of known h-signatures. Doing this is important to prefer already optimized trajectories in contrast to initialize newly explored coarse paths.
delete_detours | if this param is true , all existing TEBs are cleared from detour-candidates calling deletePlansGoingBackwards(). |
Definition at line 210 of file homotopy_class_planner.cpp.
TebOptimalPlannerPtr teb_local_planner::HomotopyClassPlanner::selectBestTeb | ( | ) |
In case of multiple, internally stored, alternative trajectories, select the best one according to their cost values.
The trajectory cost includes features such as transition time and clearance from obstacles.
The best trajectory can be accessed later by bestTeb() within the current sampling interval in order to avoid unessary recalculations.
Definition at line 500 of file homotopy_class_planner.cpp.
|
virtual |
Prefer a desired initial turning direction (by penalizing the opposing one)
A desired (initial) turning direction might be specified in case the planned trajectory oscillates between two solutions (in the same equivalence class!) with similar cost. Check the parameters in order to adjust the weight of the penalty. Initial means that the penalty is applied only to the first few poses of the trajectory.
dir | This parameter might be RotType::left (prefer left), RotType::right (prefer right) or RotType::none (prefer none) |
Reimplemented from teb_local_planner::PlannerInterface.
Definition at line 676 of file homotopy_class_planner.cpp.
void teb_local_planner::HomotopyClassPlanner::setVisualization | ( | TebVisualizationPtr | visualization | ) |
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and pose sequence)
visualization | shared pointer to a TebVisualization instance |
Definition at line 79 of file homotopy_class_planner.cpp.
void teb_local_planner::HomotopyClassPlanner::updateAllTEBs | ( | const PoseSE2 * | start, |
const PoseSE2 * | goal, | ||
const geometry_msgs::Twist * | start_velocity | ||
) |
Update TEBs with new pose, goal and current velocity.
start | New start pose (optional) |
goal | New goal pose (optional) |
start_velocity | start velocity (optional) |
Definition at line 404 of file homotopy_class_planner.cpp.
|
protected |
Associate trajectories with via-points.
If all_trajectories
is true, all trajectory candidates are connected with the set of via_points, otherwise only the trajectory sharing the homotopy class of the initial/global plan (and all via-points from alternative trajectories are removed)
all_trajectories | see method description |
Definition at line 299 of file homotopy_class_planner.cpp.
|
virtual |
Publish the local plan, pose sequence and additional information via ros topics (e.g. subscribe with rviz).
Make sure to register a TebVisualization instance before using setVisualization() or an overlaoded constructor.
Reimplemented from teb_local_planner::PlannerInterface.
Definition at line 145 of file homotopy_class_planner.cpp.
|
protected |
Store the current best teb.
Definition at line 528 of file homotopy_class_planner.h.
|
protected |
Config class that stores and manages all related parameters.
Definition at line 522 of file homotopy_class_planner.h.
|
protected |
Store all known quivalence classes (e.g. h-signatures) to allow checking for duplicates after finding and adding new ones.
Definition at line 537 of file homotopy_class_planner.h.
|
protected |
Definition at line 540 of file homotopy_class_planner.h.
|
protected |
Store the initial plan if available for a better trajectory initialization.
Definition at line 531 of file homotopy_class_planner.h.
|
protected |
Store the equivalence class of the initial plan.
Definition at line 532 of file homotopy_class_planner.h.
|
protected |
Store pointer to the TEB related to the initial plan (use method getInitialPlanTEB() since it checks if initial_plan_teb_ is still included in tebs_.)
Definition at line 533 of file homotopy_class_planner.h.
|
protected |
Keeps track about the correct initialization of this class.
Definition at line 544 of file homotopy_class_planner.h.
|
protected |
Points to the plan used in the previous control cycle.
Definition at line 546 of file homotopy_class_planner.h.
|
protected |
Store the time at which the equivalence class changed recently.
Definition at line 542 of file homotopy_class_planner.h.
|
protected |
Store obstacles that are relevant for planning.
Definition at line 523 of file homotopy_class_planner.h.
|
protected |
Robot model shared instance.
Definition at line 529 of file homotopy_class_planner.h.
|
protected |
Container that stores multiple local teb planners (for alternative equivalence classes) and their corresponding costs.
Definition at line 535 of file homotopy_class_planner.h.
|
protected |
Store the current list of via-points.
Definition at line 524 of file homotopy_class_planner.h.
|
protected |
Instance of the visualization class (local/global plan, obstacles, ...)
Definition at line 527 of file homotopy_class_planner.h.