19 #include "nav2_bt_navigator/navigators/navigate_to_pose.hpp"
21 namespace nav2_bt_navigator
26 nav2::LifecycleNode::WeakPtr parent_node,
27 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
29 start_time_ = rclcpp::Time(0);
30 auto node = parent_node.lock();
32 goal_blackboard_id_ = node->declare_or_get_parameter(
getName() +
".goal_blackboard_id",
34 path_blackboard_id_ = node->declare_or_get_parameter(
getName() +
".path_blackboard_id",
38 odom_smoother_ = odom_smoother;
40 self_client_ = node->create_action_client<ActionT>(
getName());
42 goal_sub_ = node->create_subscription<geometry_msgs::msg::PoseStamped>(
46 bool enable_groot_monitoring =
47 node->declare_or_get_parameter(
getName() +
".enable_groot_monitoring",
false);
48 int groot_server_port =
49 node->declare_or_get_parameter(
getName() +
".groot_server_port", 1669);
51 bt_action_server_->setGrootMonitoring(
52 enable_groot_monitoring,
60 nav2::LifecycleNode::WeakPtr parent_node)
62 auto node = parent_node.lock();
63 std::string pkg_share_dir =
64 ament_index_cpp::get_package_share_directory(
"nav2_bt_navigator");
66 auto default_bt_xml_filename = node->declare_or_get_parameter(
67 "default_nav_to_pose_bt_xml",
69 "/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml");
71 return default_bt_xml_filename;
85 if (!bt_action_server_->loadBehaviorTree(goal->behavior_tree)) {
86 bt_action_server_->setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
87 std::string(
"Error loading BT: ") + goal->behavior_tree +
". Navigation canceled.");
96 typename ActionT::Result::SharedPtr result,
97 const nav2_behavior_tree::BtStatus )
99 if (result->error_code == 0) {
100 if (bt_action_server_->populateInternalError(result)) {
102 "NavigateToPoseNavigator::goalCompleted, internal error %d:%s.",
104 result->error_msg.c_str());
107 RCLCPP_WARN(logger_,
"NavigateToPoseNavigator::goalCompleted error %d:%s.",
109 result->error_msg.c_str());
118 auto feedback_msg = std::make_shared<ActionT::Feedback>();
120 geometry_msgs::msg::PoseStamped current_pose;
121 if (!nav2_util::getCurrentPose(
122 current_pose, *feedback_utils_.tf,
123 feedback_utils_.global_frame, feedback_utils_.robot_frame,
124 feedback_utils_.transform_tolerance))
126 RCLCPP_ERROR(logger_,
"Robot pose is not available.");
130 auto blackboard = bt_action_server_->getBlackboard();
133 nav_msgs::msg::Path current_path;
134 auto res = blackboard->get(path_blackboard_id_, current_path);
135 if (res && current_path.poses.size() > 0u) {
137 auto find_closest_pose_idx =
138 [¤t_pose, ¤t_path]() {
139 size_t closest_pose_idx = 0;
140 double curr_min_dist = std::numeric_limits<double>::max();
141 for (
size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
142 double curr_dist = nav2_util::geometry_utils::euclidean_distance(
143 current_pose, current_path.poses[curr_idx]);
144 if (curr_dist < curr_min_dist) {
145 curr_min_dist = curr_dist;
146 closest_pose_idx = curr_idx;
149 return closest_pose_idx;
153 double distance_remaining =
154 nav2_util::geometry_utils::calculate_path_length(current_path, find_closest_pose_idx());
157 rclcpp::Duration estimated_time_remaining = rclcpp::Duration::from_seconds(0.0);
160 geometry_msgs::msg::Twist current_odom = odom_smoother_->getTwist();
161 double current_linear_speed = std::hypot(current_odom.linear.x, current_odom.linear.y);
165 if ((std::abs(current_linear_speed) > 0.01) && (distance_remaining > 0.1)) {
166 estimated_time_remaining =
167 rclcpp::Duration::from_seconds(distance_remaining / std::abs(current_linear_speed));
170 feedback_msg->distance_remaining = distance_remaining;
171 feedback_msg->estimated_time_remaining = estimated_time_remaining;
174 int recovery_count = 0;
175 res = blackboard->get(
"number_recoveries", recovery_count);
176 feedback_msg->number_of_recoveries = recovery_count;
177 feedback_msg->current_pose = current_pose;
178 feedback_msg->navigation_time = clock_->now() - start_time_;
180 bt_action_server_->publishFeedback(feedback_msg);
186 RCLCPP_INFO(logger_,
"Received goal preemption request");
188 if (goal->behavior_tree == bt_action_server_->getCurrentBTFilenameOrID() ||
189 (goal->behavior_tree.empty() &&
190 bt_action_server_->getCurrentBTFilenameOrID() == bt_action_server_->getDefaultBTFilenameOrID()))
198 "Preemption request was rejected since the goal pose could not be "
199 "transformed. For now, continuing to track the last goal until completion.");
200 bt_action_server_->terminatePendingGoal();
205 "Preemption request was rejected since the requested BT XML file is not the same "
206 "as the one that the current goal is executing. Preemption with a new BT is invalid "
207 "since it would require cancellation of the previous goal instead of true preemption."
208 "\nCancel the current goal and send a new action request if you want to use a "
209 "different BT XML file. For now, continuing to track the last goal until completion.");
210 bt_action_server_->terminatePendingGoal();
217 geometry_msgs::msg::PoseStamped current_pose;
218 if (!nav2_util::getCurrentPose(
219 current_pose, *feedback_utils_.tf,
220 feedback_utils_.global_frame, feedback_utils_.robot_frame,
221 feedback_utils_.transform_tolerance))
223 bt_action_server_->setInternalError(ActionT::Result::TF_ERROR,
224 "Initial robot pose is not available.");
228 geometry_msgs::msg::PoseStamped goal_pose;
229 if (!nav2_util::transformPoseInTargetFrame(
230 goal->pose, goal_pose, *feedback_utils_.tf, feedback_utils_.global_frame,
231 feedback_utils_.transform_tolerance))
233 bt_action_server_->setInternalError(ActionT::Result::TF_ERROR,
234 "Failed to transform a goal pose provided with frame_id '" +
235 goal->pose.header.frame_id +
236 "' to the global frame '" +
237 feedback_utils_.global_frame +
243 logger_,
"Begin navigating from current location (%.2f, %.2f) to (%.2f, %.2f)",
244 current_pose.pose.position.x, current_pose.pose.position.y,
245 goal_pose.pose.position.x, goal_pose.pose.position.y);
248 start_time_ = clock_->now();
249 auto blackboard = bt_action_server_->getBlackboard();
250 blackboard->set(
"number_recoveries", 0);
253 blackboard->set(goal_blackboard_id_, goal_pose);
263 self_client_->async_send_goal(goal);
268 #include "pluginlib/class_list_macros.hpp"
269 PLUGINLIB_EXPORT_CLASS(
A navigator for navigating to a specified pose.
void goalCompleted(typename ActionT::Result::SharedPtr result, const nav2_behavior_tree::BtStatus final_bt_status) override
A callback that is called when a the action is completed, can fill in action result message or indica...
void onGoalPoseReceived(const geometry_msgs::msg::PoseStamped::SharedPtr pose)
A subscription and callback to handle the topic-based goal published from rviz.
void onPreempt(ActionT::Goal::ConstSharedPtr goal) override
A callback that is called when a preempt is requested.
bool goalReceived(ActionT::Goal::ConstSharedPtr goal) override
A callback to be called when a new goal is received by the BT action server Can be used to check if g...
bool initializeGoalPose(ActionT::Goal::ConstSharedPtr goal)
Goal pose initialization on the blackboard.
bool configure(nav2::LifecycleNode::WeakPtr node, std::shared_ptr< nav2_util::OdomSmoother > odom_smoother) override
A configure state transition to configure navigator's state.
std::string getName() override
Get action name for this navigator.
std::string getDefaultBTFilepath(nav2::LifecycleNode::WeakPtr node) override
Get navigator's default BT.
void onLoop() override
A callback that defines execution that happens on one iteration through the BT Can be used to publish...
bool cleanup() override
A cleanup state transition to remove memory allocated.
Navigator interface to allow navigators to be stored in a vector and accessed via pluginlib due to te...