Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dwb_local_planner::DWBLocalPlanner Class Reference

Plugin-based flexible local_planner. More...

#include <dwb_local_planner.h>

Inheritance diagram for dwb_local_planner::DWBLocalPlanner:
Inheritance graph
[legend]

Public Member Functions

nav_2d_msgs::Twist2DStamped computeVelocityCommands (const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) override
 nav_core2 computeVelocityCommands - calculates the best command given the current pose and velocity More...
 
virtual nav_2d_msgs::Twist2DStamped computeVelocityCommands (const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity, std::shared_ptr< dwb_msgs::LocalPlanEvaluation > &results)
 Compute the best command given the current pose and velocity, with possible debug information. More...
 
 DWBLocalPlanner ()
 Constructor that brings up pluginlib loaders. More...
 
void initialize (const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
 nav_core2 initialization More...
 
bool isGoalReached (const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) override
 nav_core2 isGoalReached - Check whether the robot has reached its goal, given the current pose & velocity. More...
 
virtual dwb_msgs::TrajectoryScore scoreTrajectory (const dwb_msgs::Trajectory2D &traj, double best_score=-1)
 Score a given command. Can be used for testing. More...
 
void setGoalPose (const nav_2d_msgs::Pose2DStamped &goal_pose) override
 nav_core2 setGoalPose - Sets the global goal pose More...
 
void setPlan (const nav_2d_msgs::Path2D &path) override
 nav_core2 setPlan - Sets the global plan More...
 
virtual ~DWBLocalPlanner ()
 
- Public Member Functions inherited from nav_core2::LocalPlanner
virtual ~LocalPlanner ()
 

Protected Member Functions

virtual dwb_msgs::TrajectoryScore coreScoringAlgorithm (const geometry_msgs::Pose2D &pose, const nav_2d_msgs::Twist2D velocity, std::shared_ptr< dwb_msgs::LocalPlanEvaluation > &results)
 Iterate through all the twists and find the best one. More...
 
virtual void loadCritics (const std::string name)
 Load the critic parameters from the namespace. More...
 
virtual void prepare (const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity)
 Helper method for preparing for the core scoring algorithm. More...
 
std::string resolveCriticClassName (std::string base_name)
 try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic" More...
 
virtual nav_2d_msgs::Path2D transformGlobalPlan (const nav_2d_msgs::Pose2DStamped &pose)
 Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses. More...
 
geometry_msgs::Pose2D transformPoseToLocal (const nav_2d_msgs::Pose2DStamped &pose)
 Helper method to transform a given pose to the local costmap frame. More...
 

Protected Attributes

nav_core2::Costmap::Ptr costmap_
 
pluginlib::ClassLoader< TrajectoryCriticcritic_loader_
 
std::vector< TrajectoryCritic::Ptrcritics_
 
bool debug_trajectory_details_
 
std::vector< std::string > default_critic_namespaces_
 
nav_2d_msgs::Path2D global_plan_
 Saved Global Plan. More...
 
GoalChecker::Ptr goal_checker_
 
pluginlib::ClassLoader< GoalCheckergoal_checker_loader_
 
nav_2d_msgs::Pose2DStamped goal_pose_
 Saved Goal Pose. More...
 
ros::NodeHandle planner_nh_
 
double prune_distance_
 
bool prune_plan_
 
DWBPublisher pub_
 
bool short_circuit_trajectory_evaluation_
 
TFListenerPtr tf_
 
pluginlib::ClassLoader< TrajectoryGeneratortraj_gen_loader_
 
TrajectoryGenerator::Ptr traj_generator_
 
bool update_costmap_before_planning_
 

Detailed Description

Plugin-based flexible local_planner.

Definition at line 55 of file dwb_local_planner.h.

Constructor & Destructor Documentation

dwb_local_planner::DWBLocalPlanner::DWBLocalPlanner ( )

Constructor that brings up pluginlib loaders.

Definition at line 53 of file dwb_local_planner.cpp.

virtual dwb_local_planner::DWBLocalPlanner::~DWBLocalPlanner ( )
inlinevirtual

Definition at line 63 of file dwb_local_planner.h.

Member Function Documentation

nav_2d_msgs::Twist2DStamped dwb_local_planner::DWBLocalPlanner::computeVelocityCommands ( const nav_2d_msgs::Pose2DStamped &  pose,
const nav_2d_msgs::Twist2D &  velocity 
)
overridevirtual

nav_core2 computeVelocityCommands - calculates the best command given the current pose and velocity

It is presumed that the global plan is already set.

This is mostly a wrapper for the protected computeVelocityCommands function which has additional debugging info.

Parameters
poseCurrent robot pose
velocityCurrent robot velocity
Returns
The best command for the robot to drive

Implements nav_core2::LocalPlanner.

Definition at line 180 of file dwb_local_planner.cpp.

nav_2d_msgs::Twist2DStamped dwb_local_planner::DWBLocalPlanner::computeVelocityCommands ( const nav_2d_msgs::Pose2DStamped &  pose,
const nav_2d_msgs::Twist2D &  velocity,
std::shared_ptr< dwb_msgs::LocalPlanEvaluation > &  results 
)
virtual

Compute the best command given the current pose and velocity, with possible debug information.

Same as above computeVelocityCommands, but with debug results. If the results pointer is not null, additional information about the twists evaluated will be in results after the call.

Parameters
poseCurrent robot pose
velocityCurrent robot velocity
resultsOutput param, if not null, will be filled in with full evaluation results
Returns
Best command

Definition at line 229 of file dwb_local_planner.cpp.

dwb_msgs::TrajectoryScore dwb_local_planner::DWBLocalPlanner::coreScoringAlgorithm ( const geometry_msgs::Pose2D &  pose,
const nav_2d_msgs::Twist2D  velocity,
std::shared_ptr< dwb_msgs::LocalPlanEvaluation > &  results 
)
protectedvirtual

Iterate through all the twists and find the best one.

Definition at line 276 of file dwb_local_planner.cpp.

void dwb_local_planner::DWBLocalPlanner::initialize ( const ros::NodeHandle parent,
const std::string &  name,
TFListenerPtr  tf,
nav_core2::Costmap::Ptr  costmap 
)
overridevirtual

nav_core2 initialization

Parameters
nameNamespace for this planner
tfTFListener pointer
costmap_rosCostmap pointer

Implements nav_core2::LocalPlanner.

Definition at line 60 of file dwb_local_planner.cpp.

bool dwb_local_planner::DWBLocalPlanner::isGoalReached ( const nav_2d_msgs::Pose2DStamped &  pose,
const nav_2d_msgs::Twist2D &  velocity 
)
overridevirtual

nav_core2 isGoalReached - Check whether the robot has reached its goal, given the current pose & velocity.

The pose that it checks against is the last pose in the current global plan. The calculation is delegated to the goal_checker plugin.

Parameters
poseCurrent pose
velocityCurrent velocity
Returns
True if the robot should be considered as having reached the goal.

Implements nav_core2::LocalPlanner.

Definition at line 143 of file dwb_local_planner.cpp.

void dwb_local_planner::DWBLocalPlanner::loadCritics ( const std::string  name)
protectedvirtual

Load the critic parameters from the namespace.

Parameters
nameThe namespace of this planner.

Definition at line 114 of file dwb_local_planner.cpp.

void dwb_local_planner::DWBLocalPlanner::prepare ( const nav_2d_msgs::Pose2DStamped &  pose,
const nav_2d_msgs::Twist2D &  velocity 
)
protectedvirtual

Helper method for preparing for the core scoring algorithm.

Runs the prepare method on all the critics with freshly transformed data

Definition at line 202 of file dwb_local_planner.cpp.

std::string dwb_local_planner::DWBLocalPlanner::resolveCriticClassName ( std::string  base_name)
protected

try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic"

Parameters
base_nameThe name of the critic as read in from the parameter server
Returns
Our attempted resolution of the name, with namespace prepended and/or the suffix Critic appended

Definition at line 93 of file dwb_local_planner.cpp.

dwb_msgs::TrajectoryScore dwb_local_planner::DWBLocalPlanner::scoreTrajectory ( const dwb_msgs::Trajectory2D &  traj,
double  best_score = -1 
)
virtual

Score a given command. Can be used for testing.

Given a trajectory, calculate the score where lower scores are better. If the given (positive) score exceeds the best_score, calculation may be cut short, as the score can only go up from there.

Parameters
trajTrajectory to check
best_scoreIf positive, the threshold for early termination
Returns
The full scoring of the input trajectory

Definition at line 352 of file dwb_local_planner.cpp.

void dwb_local_planner::DWBLocalPlanner::setGoalPose ( const nav_2d_msgs::Pose2DStamped &  goal_pose)
overridevirtual

nav_core2 setGoalPose - Sets the global goal pose

Parameters
goal_poseThe Goal Pose

Implements nav_core2::LocalPlanner.

Definition at line 162 of file dwb_local_planner.cpp.

void dwb_local_planner::DWBLocalPlanner::setPlan ( const nav_2d_msgs::Path2D &  path)
overridevirtual

nav_core2 setPlan - Sets the global plan

Parameters
pathThe global plan

Implements nav_core2::LocalPlanner.

Definition at line 174 of file dwb_local_planner.cpp.

nav_2d_msgs::Path2D dwb_local_planner::DWBLocalPlanner::transformGlobalPlan ( const nav_2d_msgs::Pose2DStamped &  pose)
protectedvirtual

Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses.

Three key operations 1) Transforms global plan into frame of the given pose 2) Only returns poses that are near the robot, i.e. whether they are likely on the local costmap 3) If prune_plan_ is true, it will remove all points that we've already passed from both the transformed plan and the saved global_plan_. Technically, it iterates to a pose on the path that is within prune_distance_ of the robot and erases all poses before that.

Definition at line 391 of file dwb_local_planner.cpp.

geometry_msgs::Pose2D dwb_local_planner::DWBLocalPlanner::transformPoseToLocal ( const nav_2d_msgs::Pose2DStamped &  pose)
protected

Helper method to transform a given pose to the local costmap frame.

Definition at line 477 of file dwb_local_planner.cpp.

Member Data Documentation

nav_core2::Costmap::Ptr dwb_local_planner::DWBLocalPlanner::costmap_
protected

Definition at line 206 of file dwb_local_planner.h.

pluginlib::ClassLoader<TrajectoryCritic> dwb_local_planner::DWBLocalPlanner::critic_loader_
protected

Definition at line 187 of file dwb_local_planner.h.

std::vector<TrajectoryCritic::Ptr> dwb_local_planner::DWBLocalPlanner::critics_
protected

Definition at line 188 of file dwb_local_planner.h.

bool dwb_local_planner::DWBLocalPlanner::debug_trajectory_details_
protected

Definition at line 179 of file dwb_local_planner.h.

std::vector<std::string> dwb_local_planner::DWBLocalPlanner::default_critic_namespaces_
protected

Definition at line 204 of file dwb_local_planner.h.

nav_2d_msgs::Path2D dwb_local_planner::DWBLocalPlanner::global_plan_
protected

Saved Global Plan.

Definition at line 175 of file dwb_local_planner.h.

GoalChecker::Ptr dwb_local_planner::DWBLocalPlanner::goal_checker_
protected

Definition at line 186 of file dwb_local_planner.h.

pluginlib::ClassLoader<GoalChecker> dwb_local_planner::DWBLocalPlanner::goal_checker_loader_
protected

Definition at line 185 of file dwb_local_planner.h.

nav_2d_msgs::Pose2DStamped dwb_local_planner::DWBLocalPlanner::goal_pose_
protected

Saved Goal Pose.

Definition at line 176 of file dwb_local_planner.h.

ros::NodeHandle dwb_local_planner::DWBLocalPlanner::planner_nh_
protected

Definition at line 211 of file dwb_local_planner.h.

double dwb_local_planner::DWBLocalPlanner::prune_distance_
protected

Definition at line 178 of file dwb_local_planner.h.

bool dwb_local_planner::DWBLocalPlanner::prune_plan_
protected

Definition at line 177 of file dwb_local_planner.h.

DWBPublisher dwb_local_planner::DWBLocalPlanner::pub_
protected

Definition at line 209 of file dwb_local_planner.h.

bool dwb_local_planner::DWBLocalPlanner::short_circuit_trajectory_evaluation_
protected

Definition at line 180 of file dwb_local_planner.h.

TFListenerPtr dwb_local_planner::DWBLocalPlanner::tf_
protected

Definition at line 208 of file dwb_local_planner.h.

pluginlib::ClassLoader<TrajectoryGenerator> dwb_local_planner::DWBLocalPlanner::traj_gen_loader_
protected

Definition at line 183 of file dwb_local_planner.h.

TrajectoryGenerator::Ptr dwb_local_planner::DWBLocalPlanner::traj_generator_
protected

Definition at line 184 of file dwb_local_planner.h.

bool dwb_local_planner::DWBLocalPlanner::update_costmap_before_planning_
protected

Definition at line 207 of file dwb_local_planner.h.


The documentation for this class was generated from the following files:


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Sun Jan 10 2021 04:08:34