Class DWBLocalPlanner

Inheritance Relationships

Base Type

  • public nav2_core::Controller

Class Documentation

class DWBLocalPlanner : public nav2_core::Controller

Plugin-based flexible controller.

Public Functions

DWBLocalPlanner()

Constructor that brings up pluginlib loaders.

void configure(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr<tf2_ros::Buffer> tf, std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override
inline virtual ~DWBLocalPlanner()
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

Parameters:

path – The global plan

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

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:
  • pose – Current robot pose

  • velocity – Current robot velocity

  • goal_checker – Ptr to the goal checker for this task in case useful in computing commands

Returns:

The best command for the robot to drive

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.

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:
  • traj – Trajectory to check

  • best_score – If positive, the threshold for early termination

Returns:

The full scoring of the input trajectory

virtual nav_2d_msgs::msg::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::msg::Pose2DStamped &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.

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:
  • pose – Current robot pose

  • velocity – Current robot velocity

  • results – Output param, if not NULL, will be filled in with full evaluation results

Returns:

Best command

inline void setSpeedLimit(const double &speed_limit, const bool &percentage) override

Limits the maximum linear speed of the robot.

Parameters:
  • speed_limit – expressed in absolute value (in m/s) or in percentage from maximum robot speed.

  • percentage – Setting speed limit in percentage if true or in absolute values in false case.

Protected Functions

void prepareGlobalPlan(const nav_2d_msgs::msg::Pose2DStamped &pose, nav_2d_msgs::msg::Path2D &transformed_plan, nav_2d_msgs::msg::Pose2DStamped &goal_pose, bool publish_plan = true)

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

virtual dwb_msgs::msg::TrajectoryScore coreScoringAlgorithm(const geometry_msgs::msg::Pose2D &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_2d_msgs::msg::Path2D transformGlobalPlan(const nav_2d_msgs::msg::Pose2DStamped &pose)

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.

std::string resolveCriticClassName(std::string base_name)

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

Parameters:

base_name – The 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

virtual void loadCritics()

Load the critic parameters from the namespace.

Parameters:

name – The namespace of this planner.

Protected Attributes

nav_2d_msgs::msg::Path2D global_plan_

Saved Global Plan.

bool prune_plan_
double prune_distance_
bool debug_trajectory_details_
rclcpp::Duration transform_tolerance_ = {0, 0}
bool shorten_transformed_plan_
double forward_prune_distance_
rclcpp_lifecycle::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::Costmap2DROS> costmap_ros_
std::unique_ptr<DWBPublisher> pub_
std::vector<std::string> default_critic_namespaces_
pluginlib::ClassLoader<TrajectoryGenerator> traj_gen_loader_
TrajectoryGenerator::Ptr traj_generator_
pluginlib::ClassLoader<TrajectoryCritic> critic_loader_
std::vector<TrajectoryCritic::Ptr> critics_
std::string dwb_plugin_name_
bool short_circuit_trajectory_evaluation_