48    const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
 
   49    std::shared_ptr<tf2_ros::Buffer> tf,
 
   50    std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros);
 
   74    const geometry_msgs::msg::PoseStamped & start, 
const geometry_msgs::msg::PoseStamped & goal);
 
   78  rclcpp_lifecycle::LifecycleNode::SharedPtr 
nh_;
 
   81  rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>::SharedPtr 
planPub_;
 
   83  rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>::SharedPtr 
markersPub_;
 
   92  void publishGoalMarker(
const geometry_msgs::msg::Pose & pose, 
double r, 
double g, 
double b);
 
   97    const geometry_msgs::msg::PoseStamped & start, 
const geometry_msgs::msg::PoseStamped & goal,
 
   98    std::vector<geometry_msgs::msg::PoseStamped> & plan);
 
  108  std::shared_ptr<tf2_ros::Buffer> 
tf_;