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) |
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.
void dwb_local_planner::DWBPublisher::initialize | ( | ros::NodeHandle & | nh | ) |
Load the parameters and advertise topics as needed.
nh | NodeHandle 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.
|
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.
|
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.
|
inline |
Does the publisher require that the LocalPlanEvaluation be saved.
Definition at line 73 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.
|
protected |
Definition at line 98 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.
|
protected |
Definition at line 95 of file publisher.h.
|
protected |
Definition at line 94 of file publisher.h.
|
protected |
Definition at line 94 of file publisher.h.
|
protected |
Definition at line 95 of file publisher.h.
|
protected |
Definition at line 94 of file publisher.h.
|
protected |
Definition at line 94 of file publisher.h.
|
protected |
Definition at line 94 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.
|
protected |
Definition at line 101 of file publisher.h.