49 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent, std::string name,
50 const std::shared_ptr<tf2_ros::Buffer> tf,
51 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros)
override;
61 void setPlan(
const nav_msgs::msg::Path & path)
override;
76 const geometry_msgs::msg::PoseStamped & pose,
const geometry_msgs::msg::Twist & velocity,
77 nav2_core::GoalChecker * goal_checker)
override;
82 virtual void setSpeedLimit(
const double & speed_limit,
const bool & percentage)
override;
86 nav2_util::LifecycleNode::SharedPtr
nh_;
92 std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher<visualization_msgs::msg::MarkerArray>>
95 std::vector<geometry_msgs::msg::PoseStamped>
plan_;
97 std::shared_ptr<tf2_ros::Buffer>
tf_;