15 #ifndef OPENNAV_DOCKING__NAVIGATOR_HPP_
16 #define OPENNAV_DOCKING__NAVIGATOR_HPP_
23 #include "rclcpp/rclcpp.hpp"
24 #include "rclcpp_action/rclcpp_action.hpp"
25 #include "pluginlib/class_loader.hpp"
26 #include "pluginlib/class_list_macros.hpp"
28 #include "nav2_msgs/action/navigate_to_pose.hpp"
29 #include "nav2_ros_common/node_utils.hpp"
30 #include "opennav_docking/utils.hpp"
31 #include "opennav_docking/types.hpp"
33 namespace opennav_docking
42 using Nav2Pose = nav2_msgs::action::NavigateToPose;
43 using ActionClient = nav2::ActionClient<Nav2Pose>;
49 explicit Navigator(
const nav2::LifecycleNode::WeakPtr & parent);
76 const geometry_msgs::msg::PoseStamped & pose,
77 rclcpp::Duration remaining_staging_duration,
78 std::function<
bool()> isPreempted,
79 bool recursed =
false);
82 nav2::LifecycleNode::WeakPtr node_;
83 rclcpp::CallbackGroup::SharedPtr callback_group_;
84 rclcpp::executors::SingleThreadedExecutor executor_;
85 ActionClient::SharedPtr nav_to_pose_client_;
86 std::string navigator_bt_xml_;
An object the call navigation to obtain initial staging pose.
void activate()
An activation method.
Navigator(const nav2::LifecycleNode::WeakPtr &parent)
A constructor for opennav_docking::Navigator.
~Navigator()=default
A destructor for opennav_docking::Navigator.
void goToPose(const geometry_msgs::msg::PoseStamped &pose, rclcpp::Duration remaining_staging_duration, std::function< bool()> isPreempted, bool recursed=false)
An method to go to a particular pose May throw exception if fails to navigate or communicate Blocks u...
void deactivate()
An deactivation method.