50 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
51 std::shared_ptr<tf2_ros::Buffer> tf,
52 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros);
77 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal,
78 std::function<
bool()> cancel_checker)
override;
82 rclcpp_lifecycle::LifecycleNode::SharedPtr
nh_;
85 rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr
planPub_;
87 rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr
markersPub_;
96 void publishGoalMarker(
const geometry_msgs::msg::Pose & pose,
double r,
double g,
double b);
101 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal,
102 std::vector<geometry_msgs::msg::PoseStamped> & plan);
112 std::shared_ptr<tf2_ros::Buffer>
tf_;