Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dwb_core::DWBLocalPlanner Class Reference

Plugin-based flexible controller. More...

#include <nav2_dwb_controller/dwb_core/include/dwb_core/dwb_local_planner.hpp>

Inheritance diagram for dwb_core::DWBLocalPlanner:
Inheritance graph
[legend]
Collaboration diagram for dwb_core::DWBLocalPlanner:
Collaboration graph
[legend]

Public Member Functions

 DWBLocalPlanner ()
 Constructor that brings up pluginlib loaders.
 
void configure (const nav2::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros) override
 
void activate () override
 Activate lifecycle node.
 
void deactivate () override
 Deactivate lifecycle node.
 
void cleanup () override
 Cleanup lifecycle node.
 
void setPlan (const nav_msgs::msg::Path &path) override
 nav2_core setPlan - Sets the global plan More...
 
geometry_msgs::msg::TwistStamped computeVelocityCommands (const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::Twist &velocity, nav2_core::GoalChecker *) override
 nav2_core computeVelocityCommands - calculates the best command given the current pose and velocity More...
 
virtual dwb_msgs::msg::TrajectoryScore scoreTrajectory (const dwb_msgs::msg::Trajectory2D &traj, double best_score=-1)
 Score a given command. Can be used for testing. More...
 
virtual nav_2d_msgs::msg::Twist2DStamped computeVelocityCommands (const geometry_msgs::msg::PoseStamped &pose, const nav_2d_msgs::msg::Twist2D &velocity, std::shared_ptr< dwb_msgs::msg::LocalPlanEvaluation > &results)
 Compute the best command given the current pose and velocity, with possible debug information. More...
 
void setSpeedLimit (const double &speed_limit, const bool &percentage) override
 Limits the maximum linear speed of the robot. More...
 
- Public Member Functions inherited from nav2_core::Controller
virtual ~Controller ()
 Virtual destructor.
 
virtual bool cancel ()
 Cancel the current control action. More...
 
virtual void reset ()
 Reset the state of the controller if necessary after task is exited.
 

Protected Member Functions

void prepareGlobalPlan (const geometry_msgs::msg::PoseStamped &pose, nav_msgs::msg::Path &transformed_plan, geometry_msgs::msg::PoseStamped &goal_pose, bool publish_plan=true)
 Helper method for two common operations for the operating on the global_plan. More...
 
virtual dwb_msgs::msg::TrajectoryScore coreScoringAlgorithm (const geometry_msgs::msg::Pose &pose, const nav_2d_msgs::msg::Twist2D velocity, std::shared_ptr< dwb_msgs::msg::LocalPlanEvaluation > &results)
 Iterate through all the twists and find the best one.
 
virtual nav_msgs::msg::Path transformGlobalPlan (const geometry_msgs::msg::PoseStamped &pose)
 Transforms global plan into same frame as pose, clips far away poses and possibly prunes passed poses. 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 void loadCritics ()
 Load the critic parameters from the namespace. More...
 

Protected Attributes

nav_msgs::msg::Path global_plan_
 Saved Global Plan.
 
bool prune_plan_
 
double prune_distance_
 
bool debug_trajectory_details_
 
double transform_tolerance_ {0}
 
bool shorten_transformed_plan_
 
double forward_prune_distance_
 
nav2::LifecycleNode::WeakPtr node_
 
rclcpp::Clock::SharedPtr clock_
 
rclcpp::Logger logger_ {rclcpp::get_logger("DWBLocalPlanner")}
 
std::shared_ptr< tf2_ros::Buffer > tf_
 
std::shared_ptr< nav2_costmap_2d::Costmap2DROScostmap_ros_
 
std::unique_ptr< DWBPublisherpub_
 
std::vector< std::string > default_critic_namespaces_
 
pluginlib::ClassLoader< TrajectoryGeneratortraj_gen_loader_
 
TrajectoryGenerator::Ptr traj_generator_
 
pluginlib::ClassLoader< TrajectoryCriticcritic_loader_
 
std::vector< TrajectoryCritic::Ptr > critics_
 
std::string dwb_plugin_name_
 
bool short_circuit_trajectory_evaluation_
 

Additional Inherited Members

- Public Types inherited from nav2_core::Controller
using Ptr = std::shared_ptr< nav2_core::Controller >
 

Detailed Description

Plugin-based flexible controller.

Definition at line 61 of file dwb_local_planner.hpp.

Member Function Documentation

◆ computeVelocityCommands() [1/2]

geometry_msgs::msg::TwistStamped dwb_core::DWBLocalPlanner::computeVelocityCommands ( const geometry_msgs::msg::PoseStamped &  pose,
const geometry_msgs::msg::Twist &  velocity,
nav2_core::GoalChecker  
)
overridevirtual

nav2_core 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
goal_checkerPtr to the goal checker for this task in case useful in computing commands
Returns
The best command for the robot to drive

Implements nav2_core::Controller.

Definition at line 249 of file dwb_local_planner.cpp.

◆ computeVelocityCommands() [2/2]

nav_2d_msgs::msg::Twist2DStamped dwb_core::DWBLocalPlanner::computeVelocityCommands ( const geometry_msgs::msg::PoseStamped &  pose,
const nav_2d_msgs::msg::Twist2D &  velocity,
std::shared_ptr< dwb_msgs::msg::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 300 of file dwb_local_planner.cpp.

References coreScoringAlgorithm(), and prepareGlobalPlan().

Here is the call graph for this function:

◆ configure()

void dwb_core::DWBLocalPlanner::configure ( const nav2::LifecycleNode::WeakPtr &  ,
std::string  name,
std::shared_ptr< tf2_ros::Buffer >  ,
std::shared_ptr< nav2_costmap_2d::Costmap2DROS  
)
overridevirtual
Parameters
parentpointer to user's node
costmap_rosA pointer to the costmap

Implements nav2_core::Controller.

Definition at line 67 of file dwb_local_planner.cpp.

References loadCritics().

Here is the call graph for this function:

◆ loadCritics()

void dwb_core::DWBLocalPlanner::loadCritics ( )
protectedvirtual

Load the critic parameters from the namespace.

Parameters
nameThe namespace of this planner.

Definition at line 189 of file dwb_local_planner.cpp.

References resolveCriticClassName().

Referenced by configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ prepareGlobalPlan()

void dwb_core::DWBLocalPlanner::prepareGlobalPlan ( const geometry_msgs::msg::PoseStamped &  pose,
nav_msgs::msg::Path &  transformed_plan,
geometry_msgs::msg::PoseStamped &  goal_pose,
bool  publish_plan = true 
)
protected

Helper method for two common operations for the operating on the global_plan.

Transforms the global plan (stored in global_plan_) relative to the pose and saves it in transformed_plan and possibly publishes it. Then it takes the last pose and transforms it to match the local costmap's frame

Definition at line 283 of file dwb_local_planner.cpp.

References global_plan_, and transformGlobalPlan().

Referenced by computeVelocityCommands().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ resolveCriticClassName()

std::string dwb_core::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 171 of file dwb_local_planner.cpp.

Referenced by loadCritics().

Here is the caller graph for this function:

◆ scoreTrajectory()

dwb_msgs::msg::TrajectoryScore dwb_core::DWBLocalPlanner::scoreTrajectory ( const dwb_msgs::msg::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 431 of file dwb_local_planner.cpp.

Referenced by coreScoringAlgorithm().

Here is the caller graph for this function:

◆ setPlan()

void dwb_core::DWBLocalPlanner::setPlan ( const nav_msgs::msg::Path &  path)
overridevirtual

nav2_core setPlan - Sets the global plan

Parameters
pathThe global plan

Implements nav2_core::Controller.

Definition at line 236 of file dwb_local_planner.cpp.

References global_plan_.

◆ setSpeedLimit()

void dwb_core::DWBLocalPlanner::setSpeedLimit ( const double &  speed_limit,
const bool &  percentage 
)
inlineoverridevirtual

Limits the maximum linear speed of the robot.

Parameters
speed_limitexpressed in absolute value (in m/s) or in percentage from maximum robot speed.
percentageSetting speed limit in percentage if true or in absolute values in false case.

Implements nav2_core::Controller.

Definition at line 154 of file dwb_local_planner.hpp.

◆ transformGlobalPlan()

nav_msgs::msg::Path dwb_core::DWBLocalPlanner::transformGlobalPlan ( const geometry_msgs::msg::PoseStamped &  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.

Additionally, shorten_transformed_plan_ determines whether we will pass the full plan all the way to the nav goal on to the critics or just a subset of the plan near the robot. True means pass just a subset. This gives DWB less discretion to decide how it gets to the nav goal. Instead it is encouraged to try to get on to the path generated by the global planner.

Definition at line 462 of file dwb_local_planner.cpp.

References nav2_costmap_2d::Costmap2D::getResolution(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), nav2_costmap_2d::Costmap2D::getSizeInCellsY(), and global_plan_.

Referenced by prepareGlobalPlan().

Here is the call graph for this function:
Here is the caller graph for this function:

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