35 #ifndef DWB_CORE__PUBLISHER_HPP_
36 #define DWB_CORE__PUBLISHER_HPP_
42 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
43 #include "dwb_core/trajectory_critic.hpp"
44 #include "dwb_msgs/msg/local_plan_evaluation.hpp"
45 #include "nav_msgs/msg/path.hpp"
46 #include "rclcpp/rclcpp.hpp"
47 #include "sensor_msgs/msg/point_cloud2.hpp"
48 #include "visualization_msgs/msg/marker_array.hpp"
49 #include "nav2_util/lifecycle_node.hpp"
50 #include "builtin_interfaces/msg/duration.hpp"
52 using rclcpp_lifecycle::LifecyclePublisher;
73 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
74 const std::string & plugin_name);
76 nav2_util::CallbackReturn on_configure();
77 nav2_util::CallbackReturn on_activate();
78 nav2_util::CallbackReturn on_deactivate();
79 nav2_util::CallbackReturn on_cleanup();
90 void publishEvaluation(std::shared_ptr<dwb_msgs::msg::LocalPlanEvaluation> results);
91 void publishLocalPlan(
92 const std_msgs::msg::Header & header,
93 const dwb_msgs::msg::Trajectory2D & traj);
95 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros,
96 const std::vector<TrajectoryCritic::Ptr> critics);
97 void publishGlobalPlan(
const nav_2d_msgs::msg::Path2D plan);
98 void publishTransformedPlan(
const nav_2d_msgs::msg::Path2D plan);
99 void publishLocalPlan(
const nav_2d_msgs::msg::Path2D plan);
102 void publishTrajectories(
const dwb_msgs::msg::LocalPlanEvaluation & results);
105 void publishGenericPlan(
106 const nav_2d_msgs::msg::Path2D plan,
107 rclcpp::Publisher<nav_msgs::msg::Path> & pub,
bool flag);
110 bool publish_evaluation_;
111 bool publish_global_plan_;
112 bool publish_transformed_;
113 bool publish_local_plan_;
114 bool publish_trajectories_;
115 bool publish_cost_grid_pc_;
116 bool publish_input_params_;
119 builtin_interfaces::msg::Duration marker_lifetime_;
122 std::shared_ptr<LifecyclePublisher<dwb_msgs::msg::LocalPlanEvaluation>> eval_pub_;
123 std::shared_ptr<LifecyclePublisher<nav_msgs::msg::Path>> global_pub_;
124 std::shared_ptr<LifecyclePublisher<nav_msgs::msg::Path>> transformed_pub_;
125 std::shared_ptr<LifecyclePublisher<nav_msgs::msg::Path>> local_pub_;
126 std::shared_ptr<LifecyclePublisher<visualization_msgs::msg::MarkerArray>> marker_pub_;
127 std::shared_ptr<LifecyclePublisher<sensor_msgs::msg::PointCloud2>> cost_grid_pc_pub_;
129 rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
130 rclcpp::Clock::SharedPtr clock_;
131 std::string plugin_name_;
Consolidation of all the publishing logic for the DWB Local Planner.
bool shouldRecordEvaluation()
Does the publisher require that the LocalPlanEvaluation be saved.
void publishEvaluation(std::shared_ptr< dwb_msgs::msg::LocalPlanEvaluation > results)
If the pointer is not null, publish the evaluation and trajectories as needed.