Public Member Functions | Protected Member Functions | Protected Attributes
dwb_local_planner::DebugDWBLocalPlanner Class Reference

A version of DWBLocalPlanner with ROS services for the major components. More...

#include <debug_dwb_local_planner.h>

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

List of all members.

Public Member Functions

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.

Protected Member Functions

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)

Protected Attributes

ros::ServiceServer critic_service_
ros::ServiceServer debug_service_
ros::ServiceServer generate_traj_service_
ros::ServiceServer score_service_
ros::ServiceServer twist_gen_service_

Detailed Description

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.


Member Function Documentation

bool dwb_local_planner::DebugDWBLocalPlanner::debugLocalPlanService ( dwb_msgs::DebugLocalPlan::Request &  req,
dwb_msgs::DebugLocalPlan::Response &  res 
) [protected]

Definition at line 124 of file debug_dwb_local_planner.cpp.

bool dwb_local_planner::DebugDWBLocalPlanner::generateTrajectoryService ( dwb_msgs::GenerateTrajectory::Request &  req,
dwb_msgs::GenerateTrajectory::Response &  res 
) [protected]

Definition at line 68 of file debug_dwb_local_planner.cpp.

bool dwb_local_planner::DebugDWBLocalPlanner::generateTwistsService ( dwb_msgs::GenerateTwists::Request &  req,
dwb_msgs::GenerateTwists::Response &  res 
) [protected]

Definition at line 61 of file debug_dwb_local_planner.cpp.

TrajectoryCritic::Ptr dwb_local_planner::DebugDWBLocalPlanner::getCritic ( std::string  name) [protected]

Definition at line 88 of file debug_dwb_local_planner.cpp.

bool dwb_local_planner::DebugDWBLocalPlanner::getCriticScoreService ( dwb_msgs::GetCriticScore::Request &  req,
dwb_msgs::GetCriticScore::Response &  res 
) [protected]

Definition at line 98 of file debug_dwb_local_planner.cpp.

void dwb_local_planner::DebugDWBLocalPlanner::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.

Reimplemented from dwb_local_planner::DWBLocalPlanner.

Definition at line 44 of file debug_dwb_local_planner.cpp.

bool dwb_local_planner::DebugDWBLocalPlanner::scoreTrajectoryService ( dwb_msgs::ScoreTrajectory::Request &  req,
dwb_msgs::ScoreTrajectory::Response &  res 
) [protected]

Definition at line 75 of file debug_dwb_local_planner.cpp.


Member Data Documentation

Definition at line 76 of file debug_dwb_local_planner.h.

Definition at line 76 of file debug_dwb_local_planner.h.

Definition at line 76 of file debug_dwb_local_planner.h.

Definition at line 76 of file debug_dwb_local_planner.h.

Definition at line 76 of file debug_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 Wed Jun 26 2019 20:09:38