Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
dwb_local_planner::DWBPublisher Class Reference

Consolidation of all the publishing logic for the DWB Local Planner. More...

#include <publisher.h>

Public Member Functions

void initialize (ros::NodeHandle &nh)
 Load the parameters and advertise topics as needed. More...
 
void publishCostGrid (const nav_core2::Costmap::Ptr costmap, const std::vector< TrajectoryCritic::Ptr > critics)
 
void publishEvaluation (std::shared_ptr< dwb_msgs::LocalPlanEvaluation > results)
 If the pointer is not null, publish the evaluation and trajectories as needed. More...
 
void publishGlobalPlan (const nav_2d_msgs::Path2D plan)
 
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)
 
void publishLocalPlan (const std_msgs::Header &header, const dwb_msgs::Trajectory2D &traj)
 
void publishLocalPlan (const nav_2d_msgs::Path2D plan)
 
void publishTransformedPlan (const nav_2d_msgs::Path2D plan)
 
bool shouldRecordEvaluation ()
 Does the publisher require that the LocalPlanEvaluation be saved. More...
 

Protected Member Functions

void publishGenericPlan (const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag)
 
void publishTrajectories (const dwb_msgs::LocalPlanEvaluation &results)
 

Protected Attributes

ros::Publisher cost_grid_pc_pub_
 
ros::Publisher eval_pub_
 
ros::Publisher global_pub_
 
ros::Publisher goal_pub_
 
ros::Publisher info_pub_
 
ros::Publisher local_pub_
 
ros::Duration marker_lifetime_
 
ros::Publisher marker_pub_
 
ros::Publisher pose_pub_
 
bool publish_cost_grid_pc_
 
bool publish_evaluation_
 
bool publish_global_plan_
 
bool publish_input_params_
 
bool publish_local_plan_
 
bool publish_trajectories_
 
bool publish_transformed_
 
ros::Publisher transformed_pub_
 
ros::Publisher velocity_pub_
 

Detailed Description

Consolidation of all the publishing logic for the DWB Local Planner.

Right now, it can publish 1) The Global Plan (as passed in using setPath) 2) The Local Plan (after it is calculated) 3) The Transformed Global Plan (since it may be different than the global) 4) The Full LocalPlanEvaluation 5) Markers representing the different trajectories evaluated 6) The CostGrid (in the form of a complex PointCloud2)

Definition at line 60 of file publisher.h.

Member Function Documentation

void dwb_local_planner::DWBPublisher::initialize ( ros::NodeHandle nh)

Load the parameters and advertise topics as needed.

Parameters
nhNodeHandle to load parameters from

Definition at line 47 of file publisher.cpp.

void dwb_local_planner::DWBPublisher::publishCostGrid ( const nav_core2::Costmap::Ptr  costmap,
const std::vector< TrajectoryCritic::Ptr critics 
)

Definition at line 162 of file publisher.cpp.

void dwb_local_planner::DWBPublisher::publishEvaluation ( std::shared_ptr< dwb_msgs::LocalPlanEvaluation >  results)

If the pointer is not null, publish the evaluation and trajectories as needed.

Definition at line 88 of file publisher.cpp.

void dwb_local_planner::DWBPublisher::publishGenericPlan ( const nav_2d_msgs::Path2D  plan,
const ros::Publisher  pub,
bool  flag 
)
protected

Definition at line 228 of file publisher.cpp.

void dwb_local_planner::DWBPublisher::publishGlobalPlan ( const nav_2d_msgs::Path2D  plan)

Definition at line 213 of file publisher.cpp.

void dwb_local_planner::DWBPublisher::publishInputParams ( const nav_grid::NavGridInfo info,
const geometry_msgs::Pose2D &  start_pose,
const nav_2d_msgs::Twist2D &  velocity,
const geometry_msgs::Pose2D &  goal_pose 
)

Definition at line 235 of file publisher.cpp.

void dwb_local_planner::DWBPublisher::publishLocalPlan ( const std_msgs::Header header,
const dwb_msgs::Trajectory2D &  traj 
)

Definition at line 153 of file publisher.cpp.

void dwb_local_planner::DWBPublisher::publishLocalPlan ( const nav_2d_msgs::Path2D  plan)

Definition at line 223 of file publisher.cpp.

void dwb_local_planner::DWBPublisher::publishTrajectories ( const dwb_msgs::LocalPlanEvaluation &  results)
protected

Definition at line 98 of file publisher.cpp.

void dwb_local_planner::DWBPublisher::publishTransformedPlan ( const nav_2d_msgs::Path2D  plan)

Definition at line 218 of file publisher.cpp.

bool dwb_local_planner::DWBPublisher::shouldRecordEvaluation ( )
inline

Does the publisher require that the LocalPlanEvaluation be saved.

Returns
True if the Evaluation is needed to publish either directly or as trajectories

Definition at line 73 of file publisher.h.

Member Data Documentation

ros::Publisher dwb_local_planner::DWBPublisher::cost_grid_pc_pub_
protected

Definition at line 101 of file publisher.h.

ros::Publisher dwb_local_planner::DWBPublisher::eval_pub_
protected

Definition at line 101 of file publisher.h.

ros::Publisher dwb_local_planner::DWBPublisher::global_pub_
protected

Definition at line 101 of file publisher.h.

ros::Publisher dwb_local_planner::DWBPublisher::goal_pub_
protected

Definition at line 101 of file publisher.h.

ros::Publisher dwb_local_planner::DWBPublisher::info_pub_
protected

Definition at line 101 of file publisher.h.

ros::Publisher dwb_local_planner::DWBPublisher::local_pub_
protected

Definition at line 101 of file publisher.h.

ros::Duration dwb_local_planner::DWBPublisher::marker_lifetime_
protected

Definition at line 98 of file publisher.h.

ros::Publisher dwb_local_planner::DWBPublisher::marker_pub_
protected

Definition at line 101 of file publisher.h.

ros::Publisher dwb_local_planner::DWBPublisher::pose_pub_
protected

Definition at line 101 of file publisher.h.

bool dwb_local_planner::DWBPublisher::publish_cost_grid_pc_
protected

Definition at line 95 of file publisher.h.

bool dwb_local_planner::DWBPublisher::publish_evaluation_
protected

Definition at line 94 of file publisher.h.

bool dwb_local_planner::DWBPublisher::publish_global_plan_
protected

Definition at line 94 of file publisher.h.

bool dwb_local_planner::DWBPublisher::publish_input_params_
protected

Definition at line 95 of file publisher.h.

bool dwb_local_planner::DWBPublisher::publish_local_plan_
protected

Definition at line 94 of file publisher.h.

bool dwb_local_planner::DWBPublisher::publish_trajectories_
protected

Definition at line 94 of file publisher.h.

bool dwb_local_planner::DWBPublisher::publish_transformed_
protected

Definition at line 94 of file publisher.h.

ros::Publisher dwb_local_planner::DWBPublisher::transformed_pub_
protected

Definition at line 101 of file publisher.h.

ros::Publisher dwb_local_planner::DWBPublisher::velocity_pub_
protected

Definition at line 101 of file publisher.h.


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


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Sun Jan 10 2021 04:08:34