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

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

#include <publisher.h>

List of all members.

Public Member Functions

void initialize (ros::NodeHandle &nh)
 Load the parameters and advertise topics as needed.
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.
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.

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 59 of file publisher.h.


Member Function Documentation

Load the parameters and advertise topics as needed.

Parameters:
nhNodeHandle to load parameters from

Definition at line 46 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 161 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 87 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 227 of file publisher.cpp.

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

Definition at line 212 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 234 of file publisher.cpp.

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

Definition at line 152 of file publisher.cpp.

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

Definition at line 222 of file publisher.cpp.

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

Definition at line 97 of file publisher.cpp.

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

Definition at line 217 of file publisher.cpp.

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 72 of file publisher.h.


Member Data Documentation

Definition at line 100 of file publisher.h.

Definition at line 100 of file publisher.h.

Definition at line 100 of file publisher.h.

Definition at line 100 of file publisher.h.

Definition at line 100 of file publisher.h.

Definition at line 100 of file publisher.h.

Definition at line 97 of file publisher.h.

Definition at line 100 of file publisher.h.

Definition at line 100 of file publisher.h.

Definition at line 94 of file publisher.h.

Definition at line 93 of file publisher.h.

Definition at line 93 of file publisher.h.

Definition at line 94 of file publisher.h.

Definition at line 93 of file publisher.h.

Definition at line 93 of file publisher.h.

Definition at line 93 of file publisher.h.

Definition at line 100 of file publisher.h.

Definition at line 100 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 Wed Jun 26 2019 20:09:38