35 #ifndef DWB_LOCAL_PLANNER_PUBLISHER_H    36 #define DWB_LOCAL_PLANNER_PUBLISHER_H    41 #include <dwb_msgs/LocalPlanEvaluation.h>    84                           const nav_2d_msgs::Twist2D& velocity, 
const geometry_msgs::Pose2D& goal_pose);
   106 #endif  // DWB_LOCAL_PLANNER_PUBLISHER_H 
void publishCostGrid(const nav_core2::Costmap::Ptr costmap, const std::vector< TrajectoryCritic::Ptr > critics)
void publishTrajectories(const dwb_msgs::LocalPlanEvaluation &results)
void publishGlobalPlan(const nav_2d_msgs::Path2D plan)
void publishTransformedPlan(const nav_2d_msgs::Path2D plan)
bool publish_transformed_
ros::Publisher cost_grid_pc_pub_
ros::Publisher velocity_pub_
void publishGenericPlan(const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag)
bool publish_trajectories_
Consolidation of all the publishing logic for the DWB Local Planner. 
void publishInputParams(const nav_grid::NavGridInfo &info, const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &velocity, const geometry_msgs::Pose2D &goal_pose)
ros::Publisher local_pub_
ros::Duration marker_lifetime_
ros::Publisher transformed_pub_
bool publish_global_plan_
ros::Publisher global_pub_
ros::Publisher marker_pub_
void publishEvaluation(std::shared_ptr< dwb_msgs::LocalPlanEvaluation > results)
If the pointer is not null, publish the evaluation and trajectories as needed. 
bool publish_input_params_
void publishLocalPlan(const std_msgs::Header &header, const dwb_msgs::Trajectory2D &traj)
std::shared_ptr< Costmap > Ptr
bool shouldRecordEvaluation()
Does the publisher require that the LocalPlanEvaluation be saved. 
void initialize(ros::NodeHandle &nh)
Load the parameters and advertise topics as needed. 
bool publish_cost_grid_pc_