20 #include "nav2_bt_navigator/navigators/navigate_through_poses.hpp"
22 namespace nav2_bt_navigator
27 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
28 std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
30 start_time_ = rclcpp::Time(0);
31 auto node = parent_node.lock();
33 if (!node->has_parameter(
"goals_blackboard_id")) {
34 node->declare_parameter(
"goals_blackboard_id", std::string(
"goals"));
37 goals_blackboard_id_ = node->get_parameter(
"goals_blackboard_id").as_string();
39 if (!node->has_parameter(
"path_blackboard_id")) {
40 node->declare_parameter(
"path_blackboard_id", std::string(
"path"));
43 path_blackboard_id_ = node->get_parameter(
"path_blackboard_id").as_string();
46 odom_smoother_ = odom_smoother;
53 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node)
55 std::string default_bt_xml_filename;
56 auto node = parent_node.lock();
58 if (!node->has_parameter(
"default_nav_through_poses_bt_xml")) {
59 std::string pkg_share_dir =
60 ament_index_cpp::get_package_share_directory(
"nav2_bt_navigator");
61 node->declare_parameter<std::string>(
62 "default_nav_through_poses_bt_xml",
64 "/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml");
67 node->get_parameter(
"default_nav_through_poses_bt_xml", default_bt_xml_filename);
69 return default_bt_xml_filename;
75 auto bt_xml_filename = goal->behavior_tree;
77 if (!bt_action_server_->loadBehaviorTree(bt_xml_filename)) {
79 logger_,
"Error loading XML file: %s. Navigation canceled.",
80 bt_xml_filename.c_str());
89 typename ActionT::Result::SharedPtr ,
90 const nav2_behavior_tree::BtStatus )
97 using namespace nav2_util::geometry_utils;
101 auto feedback_msg = std::make_shared<ActionT::Feedback>();
103 auto blackboard = bt_action_server_->getBlackboard();
106 [[maybe_unused]]
auto res = blackboard->get(goals_blackboard_id_, goal_poses);
108 if (goal_poses.size() == 0) {
109 bt_action_server_->publishFeedback(feedback_msg);
113 geometry_msgs::msg::PoseStamped current_pose;
114 if (!nav2_util::getCurrentPose(
115 current_pose, *feedback_utils_.tf,
116 feedback_utils_.global_frame, feedback_utils_.robot_frame,
117 feedback_utils_.transform_tolerance))
119 RCLCPP_ERROR(logger_,
"Robot pose is not available.");
125 nav_msgs::msg::Path current_path;
126 if (!blackboard->get(path_blackboard_id_, current_path) || current_path.poses.size() == 0u) {
128 throw std::exception();
132 auto find_closest_pose_idx =
133 [¤t_pose, ¤t_path]() {
134 size_t closest_pose_idx = 0;
135 double curr_min_dist = std::numeric_limits<double>::max();
136 for (
size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
137 double curr_dist = nav2_util::geometry_utils::euclidean_distance(
138 current_pose, current_path.poses[curr_idx]);
139 if (curr_dist < curr_min_dist) {
140 curr_min_dist = curr_dist;
141 closest_pose_idx = curr_idx;
144 return closest_pose_idx;
148 double distance_remaining =
149 nav2_util::geometry_utils::calculate_path_length(current_path, find_closest_pose_idx());
152 rclcpp::Duration estimated_time_remaining = rclcpp::Duration::from_seconds(0.0);
155 geometry_msgs::msg::Twist current_odom = odom_smoother_->getTwist();
156 double current_linear_speed = std::hypot(current_odom.linear.x, current_odom.linear.y);
160 if ((std::abs(current_linear_speed) > 0.01) && (distance_remaining > 0.1)) {
161 estimated_time_remaining =
162 rclcpp::Duration::from_seconds(distance_remaining / std::abs(current_linear_speed));
165 feedback_msg->distance_remaining = distance_remaining;
166 feedback_msg->estimated_time_remaining = estimated_time_remaining;
171 int recovery_count = 0;
172 res = blackboard->get(
"number_recoveries", recovery_count);
173 feedback_msg->number_of_recoveries = recovery_count;
174 feedback_msg->current_pose = current_pose;
175 feedback_msg->navigation_time = clock_->now() - start_time_;
176 feedback_msg->number_of_poses_remaining = goal_poses.size();
178 bt_action_server_->publishFeedback(feedback_msg);
184 RCLCPP_INFO(logger_,
"Received goal preemption request");
186 if (goal->behavior_tree == bt_action_server_->getCurrentBTFilename() ||
187 (goal->behavior_tree.empty() &&
188 bt_action_server_->getCurrentBTFilename() == bt_action_server_->getDefaultBTFilename()))
196 "Preemption request was rejected since the goal poses could not be "
197 "transformed. For now, continuing to track the last goal until completion.");
198 bt_action_server_->terminatePendingGoal();
203 "Preemption request was rejected since the requested BT XML file is not the same "
204 "as the one that the current goal is executing. Preemption with a new BT is invalid "
205 "since it would require cancellation of the previous goal instead of true preemption."
206 "\nCancel the current goal and send a new action request if you want to use a "
207 "different BT XML file. For now, continuing to track the last goal until completion.");
208 bt_action_server_->terminatePendingGoal();
215 Goals goal_poses = goal->poses;
216 for (
auto & goal_pose : goal_poses) {
217 if (!nav2_util::transformPoseInTargetFrame(
218 goal_pose, goal_pose, *feedback_utils_.tf, feedback_utils_.global_frame,
219 feedback_utils_.transform_tolerance))
223 "Failed to transform a goal pose provided with frame_id '%s' to the global frame '%s'.",
224 goal_pose.header.frame_id.c_str(), feedback_utils_.global_frame.c_str());
229 if (goal_poses.size() > 0) {
231 logger_,
"Begin navigating from current location through %zu poses to (%.2f, %.2f)",
232 goal_poses.size(), goal_poses.back().pose.position.x, goal_poses.back().pose.position.y);
236 start_time_ = clock_->now();
237 auto blackboard = bt_action_server_->getBlackboard();
238 blackboard->set(
"number_recoveries", 0);
241 blackboard->set<Goals>(goals_blackboard_id_, std::move(goal_poses));
248 #include "pluginlib/class_list_macros.hpp"
249 PLUGINLIB_EXPORT_CLASS(
A navigator for navigating to a a bunch of intermediary poses.
bool configure(rclcpp_lifecycle::LifecycleNode::WeakPtr node, std::shared_ptr< nav2_util::OdomSmoother > odom_smoother) override
A configure state transition to configure navigator's state.
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...
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...
std::string getDefaultBTFilepath(rclcpp_lifecycle::LifecycleNode::WeakPtr node) override
Get navigator's default BT.
bool initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal)
Goal pose initialization on the blackboard.
void onLoop() override
A callback that defines execution that happens on one iteration through the BT Can be used to publish...
Navigator interface to allow navigators to be stored in a vector and accessed via pluginlib due to te...