Plugin-based flexible local_planner. More...
#include <dwb_local_planner.h>
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 | |
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. | |
DWBLocalPlanner () | |
Constructor that brings up pluginlib loaders. | |
void | initialize (const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override |
nav_core2 initialization | |
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. | |
virtual dwb_msgs::TrajectoryScore | scoreTrajectory (const dwb_msgs::Trajectory2D &traj, double best_score=-1) |
Score a given command. Can be used for testing. | |
void | setGoalPose (const nav_2d_msgs::Pose2DStamped &goal_pose) override |
nav_core2 setGoalPose - Sets the global goal pose | |
void | setPlan (const nav_2d_msgs::Path2D &path) override |
nav_core2 setPlan - Sets the global plan | |
virtual | ~DWBLocalPlanner () |
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. | |
virtual void | loadCritics (const std::string name) |
Load the critic parameters from the namespace. | |
virtual void | prepare (const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) |
Helper method for preparing for the core scoring algorithm. | |
std::string | resolveCriticClassName (std::string base_name) |
try to resolve a possibly shortened critic name with the default namespaces and the suffix "Critic" | |
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. | |
geometry_msgs::Pose2D | transformPoseToLocal (const nav_2d_msgs::Pose2DStamped &pose) |
Helper method to transform a given pose to the local costmap frame. | |
Protected Attributes | |
nav_core2::Costmap::Ptr | costmap_ |
pluginlib::ClassLoader < TrajectoryCritic > | critic_loader_ |
std::vector < TrajectoryCritic::Ptr > | critics_ |
bool | debug_trajectory_details_ |
std::vector< std::string > | default_critic_namespaces_ |
nav_2d_msgs::Path2D | global_plan_ |
Saved Global Plan. | |
GoalChecker::Ptr | goal_checker_ |
pluginlib::ClassLoader < GoalChecker > | goal_checker_loader_ |
nav_2d_msgs::Pose2DStamped | goal_pose_ |
Saved Goal Pose. | |
ros::NodeHandle | planner_nh_ |
double | prune_distance_ |
bool | prune_plan_ |
DWBPublisher | pub_ |
bool | short_circuit_trajectory_evaluation_ |
TFListenerPtr | tf_ |
pluginlib::ClassLoader < TrajectoryGenerator > | traj_gen_loader_ |
TrajectoryGenerator::Ptr | traj_generator_ |
bool | update_costmap_before_planning_ |
Plugin-based flexible local_planner.
Definition at line 54 of file dwb_local_planner.h.
Constructor that brings up pluginlib loaders.
Definition at line 51 of file dwb_local_planner.cpp.
virtual dwb_local_planner::DWBLocalPlanner::~DWBLocalPlanner | ( | ) | [inline, virtual] |
Definition at line 62 of file dwb_local_planner.h.
nav_2d_msgs::Twist2DStamped dwb_local_planner::DWBLocalPlanner::computeVelocityCommands | ( | const nav_2d_msgs::Pose2DStamped & | pose, |
const nav_2d_msgs::Twist2D & | velocity | ||
) | [override, virtual] |
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.
pose | Current robot pose |
velocity | Current robot velocity |
Implements nav_core2::LocalPlanner.
Definition at line 178 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.
pose | Current robot pose |
velocity | Current robot velocity |
results | Output param, if not null, will be filled in with full evaluation results |
Definition at line 227 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 | ||
) | [protected, virtual] |
Iterate through all the twists and find the best one.
Definition at line 274 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 | ||
) | [override] |
nav_core2 initialization
name | Namespace for this planner |
tf | TFListener pointer |
costmap_ros | Costmap pointer |
Reimplemented in dwb_local_planner::DebugDWBLocalPlanner.
Definition at line 58 of file dwb_local_planner.cpp.
bool dwb_local_planner::DWBLocalPlanner::isGoalReached | ( | const nav_2d_msgs::Pose2DStamped & | pose, |
const nav_2d_msgs::Twist2D & | velocity | ||
) | [override, virtual] |
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.
pose | Current pose |
velocity | Current velocity |
Implements nav_core2::LocalPlanner.
Definition at line 141 of file dwb_local_planner.cpp.
void dwb_local_planner::DWBLocalPlanner::loadCritics | ( | const std::string | name | ) | [protected, virtual] |
Load the critic parameters from the namespace.
name | The namespace of this planner. |
Definition at line 112 of file dwb_local_planner.cpp.
void dwb_local_planner::DWBLocalPlanner::prepare | ( | const nav_2d_msgs::Pose2DStamped & | pose, |
const nav_2d_msgs::Twist2D & | velocity | ||
) | [protected, virtual] |
Helper method for preparing for the core scoring algorithm.
Runs the prepare method on all the critics with freshly transformed data
Definition at line 200 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"
base_name | The name of the critic as read in from the parameter server |
Definition at line 91 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.
traj | Trajectory to check |
best_score | If positive, the threshold for early termination |
Definition at line 350 of file dwb_local_planner.cpp.
void dwb_local_planner::DWBLocalPlanner::setGoalPose | ( | const nav_2d_msgs::Pose2DStamped & | goal_pose | ) | [override, virtual] |
nav_core2 setGoalPose - Sets the global goal pose
goal_pose | The Goal Pose |
Implements nav_core2::LocalPlanner.
Definition at line 160 of file dwb_local_planner.cpp.
void dwb_local_planner::DWBLocalPlanner::setPlan | ( | const nav_2d_msgs::Path2D & | path | ) | [override, virtual] |
nav_core2 setPlan - Sets the global plan
path | The global plan |
Implements nav_core2::LocalPlanner.
Definition at line 172 of file dwb_local_planner.cpp.
nav_2d_msgs::Path2D dwb_local_planner::DWBLocalPlanner::transformGlobalPlan | ( | const nav_2d_msgs::Pose2DStamped & | pose | ) | [protected, virtual] |
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 389 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 475 of file dwb_local_planner.cpp.
nav_core2::Costmap::Ptr dwb_local_planner::DWBLocalPlanner::costmap_ [protected] |
Definition at line 205 of file dwb_local_planner.h.
pluginlib::ClassLoader<TrajectoryCritic> dwb_local_planner::DWBLocalPlanner::critic_loader_ [protected] |
Definition at line 186 of file dwb_local_planner.h.
std::vector<TrajectoryCritic::Ptr> dwb_local_planner::DWBLocalPlanner::critics_ [protected] |
Definition at line 187 of file dwb_local_planner.h.
bool dwb_local_planner::DWBLocalPlanner::debug_trajectory_details_ [protected] |
Definition at line 178 of file dwb_local_planner.h.
std::vector<std::string> dwb_local_planner::DWBLocalPlanner::default_critic_namespaces_ [protected] |
Definition at line 203 of file dwb_local_planner.h.
nav_2d_msgs::Path2D dwb_local_planner::DWBLocalPlanner::global_plan_ [protected] |
Saved Global Plan.
Definition at line 174 of file dwb_local_planner.h.
GoalChecker::Ptr dwb_local_planner::DWBLocalPlanner::goal_checker_ [protected] |
Definition at line 185 of file dwb_local_planner.h.
pluginlib::ClassLoader<GoalChecker> dwb_local_planner::DWBLocalPlanner::goal_checker_loader_ [protected] |
Definition at line 184 of file dwb_local_planner.h.
nav_2d_msgs::Pose2DStamped dwb_local_planner::DWBLocalPlanner::goal_pose_ [protected] |
Saved Goal Pose.
Definition at line 175 of file dwb_local_planner.h.
Definition at line 210 of file dwb_local_planner.h.
double dwb_local_planner::DWBLocalPlanner::prune_distance_ [protected] |
Definition at line 177 of file dwb_local_planner.h.
bool dwb_local_planner::DWBLocalPlanner::prune_plan_ [protected] |
Definition at line 176 of file dwb_local_planner.h.
DWBPublisher dwb_local_planner::DWBLocalPlanner::pub_ [protected] |
Definition at line 208 of file dwb_local_planner.h.
Definition at line 179 of file dwb_local_planner.h.
TFListenerPtr dwb_local_planner::DWBLocalPlanner::tf_ [protected] |
Definition at line 207 of file dwb_local_planner.h.
pluginlib::ClassLoader<TrajectoryGenerator> dwb_local_planner::DWBLocalPlanner::traj_gen_loader_ [protected] |
Definition at line 182 of file dwb_local_planner.h.
TrajectoryGenerator::Ptr dwb_local_planner::DWBLocalPlanner::traj_generator_ [protected] |
Definition at line 183 of file dwb_local_planner.h.
bool dwb_local_planner::DWBLocalPlanner::update_costmap_before_planning_ [protected] |
Definition at line 206 of file dwb_local_planner.h.