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_;
80 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<nav_msgs::msg::Path>>
planPub_;
82 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>>
89 void publishGoalMarker(
const geometry_msgs::msg::Pose & pose,
double r,
double g,
double b);
98 std::shared_ptr<tf2_ros::Buffer>
tf_;
103 const geometry_msgs::msg::PoseStamped & start,
const geometry_msgs::msg::PoseStamped & goal,
104 std::vector<geometry_msgs::msg::PoseStamped> & plan);