Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef DWB_LOCAL_PLANNER_PUBLISHER_H
00036 #define DWB_LOCAL_PLANNER_PUBLISHER_H
00037
00038 #include <ros/ros.h>
00039 #include <nav_core2/common.h>
00040 #include <dwb_local_planner/trajectory_critic.h>
00041 #include <dwb_msgs/LocalPlanEvaluation.h>
00042 #include <vector>
00043
00044 namespace dwb_local_planner
00045 {
00046
00059 class DWBPublisher
00060 {
00061 public:
00066 void initialize(ros::NodeHandle& nh);
00067
00072 bool shouldRecordEvaluation() { return publish_evaluation_ || publish_trajectories_; }
00073
00077 void publishEvaluation(std::shared_ptr<dwb_msgs::LocalPlanEvaluation> results);
00078 void publishLocalPlan(const std_msgs::Header& header, const dwb_msgs::Trajectory2D& traj);
00079 void publishCostGrid(const nav_core2::Costmap::Ptr costmap, const std::vector<TrajectoryCritic::Ptr> critics);
00080 void publishGlobalPlan(const nav_2d_msgs::Path2D plan);
00081 void publishTransformedPlan(const nav_2d_msgs::Path2D plan);
00082 void publishLocalPlan(const nav_2d_msgs::Path2D plan);
00083 void publishInputParams(const nav_grid::NavGridInfo& info, const geometry_msgs::Pose2D& start_pose,
00084 const nav_2d_msgs::Twist2D& velocity, const geometry_msgs::Pose2D& goal_pose);
00085
00086 protected:
00087 void publishTrajectories(const dwb_msgs::LocalPlanEvaluation& results);
00088
00089
00090 void publishGenericPlan(const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag);
00091
00092
00093 bool publish_evaluation_, publish_global_plan_, publish_transformed_, publish_local_plan_, publish_trajectories_;
00094 bool publish_cost_grid_pc_, publish_input_params_;
00095
00096
00097 ros::Duration marker_lifetime_;
00098
00099
00100 ros::Publisher eval_pub_, global_pub_, transformed_pub_, local_pub_, marker_pub_, cost_grid_pc_pub_,
00101 info_pub_, pose_pub_, goal_pub_, velocity_pub_;
00102 };
00103
00104 }
00105
00106 #endif // DWB_LOCAL_PLANNER_PUBLISHER_H