16 #include "opennav_docking/navigator.hpp"
18 namespace opennav_docking
21 using namespace std::chrono_literals;
26 auto node = node_.lock();
27 nav2::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_ = node->create_action_client<Nav2Pose>(
41 "navigate_to_pose", callback_group_);
46 nav_to_pose_client_.reset();
50 const geometry_msgs::msg::PoseStamped & pose,
51 rclcpp::Duration remaining_staging_duration,
52 std::function<
bool()> isPreempted,
55 auto node = node_.lock();
59 goal.behavior_tree = navigator_bt_xml_;
60 const auto start_time = node->now();
63 nav_to_pose_client_->wait_for_action_server(1s);
64 auto future_goal_handle = nav_to_pose_client_->async_send_goal(goal);
65 if (executor_.spin_until_future_complete(
66 future_goal_handle, 2s) == rclcpp::FutureReturnCode::SUCCESS)
68 auto future_result = nav_to_pose_client_->async_get_result(future_goal_handle.get());
70 while (rclcpp::ok()) {
72 auto cancel_future = nav_to_pose_client_->async_cancel_goal(future_goal_handle.get());
73 executor_.spin_until_future_complete(cancel_future, 1s);
77 if (node->now() - start_time > remaining_staging_duration) {
78 auto cancel_future = nav_to_pose_client_->async_cancel_goal(future_goal_handle.get());
79 executor_.spin_until_future_complete(cancel_future, 1s);
83 if (executor_.spin_until_future_complete(
84 future_result, 10ms) == rclcpp::FutureReturnCode::SUCCESS)
86 auto result = future_result.get();
87 if (result.code == rclcpp_action::ResultCode::SUCCEEDED &&
88 result.result->error_code == 0)
92 RCLCPP_WARN(node->get_logger(),
"Navigation request to staging pose failed.");
101 auto elapsed_time = node->now() - start_time;
102 remaining_staging_duration = remaining_staging_duration - elapsed_time;
103 goToPose(pose, remaining_staging_duration, isPreempted,
true);
void activate()
An activation method.
Navigator(const nav2::LifecycleNode::WeakPtr &parent)
A constructor 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.
Failed to navigate to the staging pose.