16 #include "opennav_docking/navigator.hpp"
18 namespace opennav_docking
21 using namespace std::chrono_literals;
26 auto node = node_.lock();
27 nav2_util::declare_parameter_if_not_declared(
28 node,
"navigator_bt_xml", rclcpp::ParameterValue(std::string(
"")));
29 node->get_parameter(
"navigator_bt_xml", navigator_bt_xml_);
35 auto node = node_.lock();
36 callback_group_ = node->create_callback_group(
37 rclcpp::CallbackGroupType::MutuallyExclusive,
39 executor_.add_callback_group(callback_group_, node->get_node_base_interface());
40 nav_to_pose_client_ = rclcpp_action::create_client<Nav2Pose>(
41 node->get_node_base_interface(),
42 node->get_node_graph_interface(),
43 node->get_node_logging_interface(),
44 node->get_node_waitables_interface(),
45 "navigate_to_pose", callback_group_);
50 nav_to_pose_client_.reset();
54 const geometry_msgs::msg::PoseStamped & pose,
55 rclcpp::Duration remaining_staging_duration,
56 std::function<
bool()> isPreempted,
59 auto node = node_.lock();
63 goal.behavior_tree = navigator_bt_xml_;
64 const auto start_time = node->now();
67 nav_to_pose_client_->wait_for_action_server(1s);
68 auto future_goal_handle = nav_to_pose_client_->async_send_goal(goal);
69 if (executor_.spin_until_future_complete(
70 future_goal_handle, 2s) == rclcpp::FutureReturnCode::SUCCESS)
72 auto future_result = nav_to_pose_client_->async_get_result(future_goal_handle.get());
74 while (rclcpp::ok()) {
76 auto cancel_future = nav_to_pose_client_->async_cancel_goal(future_goal_handle.get());
77 executor_.spin_until_future_complete(cancel_future, 1s);
81 if (node->now() - start_time > remaining_staging_duration) {
82 auto cancel_future = nav_to_pose_client_->async_cancel_goal(future_goal_handle.get());
83 executor_.spin_until_future_complete(cancel_future, 1s);
87 if (executor_.spin_until_future_complete(
88 future_result, 10ms) == rclcpp::FutureReturnCode::SUCCESS)
90 auto result = future_result.get();
91 if (result.code == rclcpp_action::ResultCode::SUCCEEDED &&
92 result.result->error_code == 0)
96 RCLCPP_WARN(node->get_logger(),
"Navigation request to staging pose failed.");
105 auto elapsed_time = node->now() - start_time;
106 remaining_staging_duration = remaining_staging_duration - elapsed_time;
107 goToPose(pose, remaining_staging_duration, isPreempted,
true);
Navigator(const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent)
A constructor for opennav_docking::Navigator.
void activate()
An activation method.
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.
Failed to navigate to the staging pose.