|
void | initialize (const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override |
| Override the DWB constructor to also advertise the services. More...
|
|
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 () |
|
virtual | ~LocalPlanner () |
|
|
bool | debugLocalPlanService (dwb_msgs::DebugLocalPlan::Request &req, dwb_msgs::DebugLocalPlan::Response &res) |
|
bool | generateTrajectoryService (dwb_msgs::GenerateTrajectory::Request &req, dwb_msgs::GenerateTrajectory::Response &res) |
|
bool | generateTwistsService (dwb_msgs::GenerateTwists::Request &req, dwb_msgs::GenerateTwists::Response &res) |
|
TrajectoryCritic::Ptr | getCritic (std::string name) |
|
bool | getCriticScoreService (dwb_msgs::GetCriticScore::Request &req, dwb_msgs::GetCriticScore::Response &res) |
|
bool | scoreTrajectoryService (dwb_msgs::ScoreTrajectory::Request &req, dwb_msgs::ScoreTrajectory::Response &res) |
|
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...
|
|
A version of DWBLocalPlanner with ROS services for the major components.
Advertises three services: GenerateTwists, GenerateTrajectory and DebugLocalPlan
Definition at line 54 of file debug_dwb_local_planner.h.