20 #include "nav2_bt_navigator/navigators/navigate_through_poses.hpp"
22 namespace nav2_bt_navigator
27 nav2::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 goals_blackboard_id_ =
34 node->declare_or_get_parameter(
"goals_blackboard_id", std::string(
"goals"));
36 node->declare_or_get_parameter(
"path_blackboard_id", std::string(
"path"));
37 waypoint_statuses_blackboard_id_ =
38 node->declare_or_get_parameter(
"waypoint_statuses_blackboard_id",
39 std::string(
"waypoint_statuses"));
42 odom_smoother_ = odom_smoother;
44 bool enable_groot_monitoring =
45 node->declare_or_get_parameter(
getName() +
".enable_groot_monitoring",
false);
46 int groot_server_port =
47 node->declare_or_get_parameter(
getName() +
".groot_server_port", 1669);
49 bt_action_server_->setGrootMonitoring(
50 enable_groot_monitoring,
58 nav2::LifecycleNode::WeakPtr parent_node)
60 auto node = parent_node.lock();
61 std::string pkg_share_dir =
62 ament_index_cpp::get_package_share_directory(
"nav2_bt_navigator");
64 auto default_bt_xml_filename = node->declare_or_get_parameter(
65 "default_nav_through_poses_bt_xml",
67 "/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml");
69 return default_bt_xml_filename;
75 auto bt_xml_filename = goal->behavior_tree;
77 if (!bt_action_server_->loadBehaviorTree(bt_xml_filename)) {
78 bt_action_server_->setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
79 "Error loading XML file: " + bt_xml_filename +
". Navigation canceled.");
88 typename ActionT::Result::SharedPtr result,
89 const nav2_behavior_tree::BtStatus final_bt_status)
91 if (result->error_code == 0) {
92 if (bt_action_server_->populateInternalError(result)) {
94 "NavigateThroughPosesNavigator::goalCompleted, internal error %d:'%s'.",
96 result->error_msg.c_str());
99 RCLCPP_WARN(logger_,
"NavigateThroughPosesNavigator::goalCompleted error %d:'%s'.",
101 result->error_msg.c_str());
105 auto blackboard = bt_action_server_->getBlackboard();
106 auto waypoint_statuses =
107 blackboard->get<std::vector<nav2_msgs::msg::WaypointStatus>>(waypoint_statuses_blackboard_id_);
110 auto integrate_waypoint_status = final_bt_status == nav2_behavior_tree::BtStatus::SUCCEEDED ?
111 nav2_msgs::msg::WaypointStatus::COMPLETED : nav2_msgs::msg::WaypointStatus::FAILED;
112 for (
auto & waypoint_status : waypoint_statuses) {
113 if (waypoint_status.waypoint_status == nav2_msgs::msg::WaypointStatus::PENDING) {
114 waypoint_status.waypoint_status = integrate_waypoint_status;
118 result->waypoint_statuses = std::move(waypoint_statuses);
124 using namespace nav2_util::geometry_utils;
128 auto feedback_msg = std::make_shared<ActionT::Feedback>();
130 auto blackboard = bt_action_server_->getBlackboard();
132 nav_msgs::msg::Goals goal_poses;
133 [[maybe_unused]]
auto res = blackboard->get(goals_blackboard_id_, goal_poses);
135 feedback_msg->waypoint_statuses =
136 blackboard->get<std::vector<nav2_msgs::msg::WaypointStatus>>(waypoint_statuses_blackboard_id_);
138 if (goal_poses.goals.size() == 0) {
139 bt_action_server_->publishFeedback(feedback_msg);
143 geometry_msgs::msg::PoseStamped current_pose;
144 if (!nav2_util::getCurrentPose(
145 current_pose, *feedback_utils_.tf,
146 feedback_utils_.global_frame, feedback_utils_.robot_frame,
147 feedback_utils_.transform_tolerance))
149 RCLCPP_ERROR(logger_,
"Robot pose is not available.");
154 nav_msgs::msg::Path current_path;
155 res = blackboard->get(path_blackboard_id_, current_path);
156 if (res && current_path.poses.size() > 0u) {
158 auto find_closest_pose_idx =
159 [¤t_pose, ¤t_path]() {
160 size_t closest_pose_idx = 0;
161 double curr_min_dist = std::numeric_limits<double>::max();
162 for (
size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
163 double curr_dist = nav2_util::geometry_utils::euclidean_distance(
164 current_pose, current_path.poses[curr_idx]);
165 if (curr_dist < curr_min_dist) {
166 curr_min_dist = curr_dist;
167 closest_pose_idx = curr_idx;
170 return closest_pose_idx;
174 double distance_remaining =
175 nav2_util::geometry_utils::calculate_path_length(current_path, find_closest_pose_idx());
178 rclcpp::Duration estimated_time_remaining = rclcpp::Duration::from_seconds(0.0);
181 geometry_msgs::msg::Twist current_odom = odom_smoother_->getTwist();
182 double current_linear_speed = std::hypot(current_odom.linear.x, current_odom.linear.y);
186 if ((std::abs(current_linear_speed) > 0.01) && (distance_remaining > 0.1)) {
187 estimated_time_remaining =
188 rclcpp::Duration::from_seconds(distance_remaining / std::abs(current_linear_speed));
191 feedback_msg->distance_remaining = distance_remaining;
192 feedback_msg->estimated_time_remaining = estimated_time_remaining;
195 int recovery_count = 0;
196 res = blackboard->get(
"number_recoveries", recovery_count);
197 feedback_msg->number_of_recoveries = recovery_count;
198 feedback_msg->current_pose = current_pose;
199 feedback_msg->navigation_time = clock_->now() - start_time_;
200 feedback_msg->number_of_poses_remaining = goal_poses.goals.size();
202 bt_action_server_->publishFeedback(feedback_msg);
208 RCLCPP_INFO(logger_,
"Received goal preemption request");
210 if (goal->behavior_tree == bt_action_server_->getCurrentBTFilename() ||
211 (goal->behavior_tree.empty() &&
212 bt_action_server_->getCurrentBTFilename() == bt_action_server_->getDefaultBTFilename()))
220 "Preemption request was rejected since the goal poses could not be "
221 "transformed. For now, continuing to track the last goal until completion.");
222 bt_action_server_->terminatePendingGoal();
227 "Preemption request was rejected since the requested BT XML file is not the same "
228 "as the one that the current goal is executing. Preemption with a new BT is invalid "
229 "since it would require cancellation of the previous goal instead of true preemption."
230 "\nCancel the current goal and send a new action request if you want to use a "
231 "different BT XML file. For now, continuing to track the last goal until completion.");
232 bt_action_server_->terminatePendingGoal();
239 geometry_msgs::msg::PoseStamped current_pose;
240 if (!nav2_util::getCurrentPose(
241 current_pose, *feedback_utils_.tf,
242 feedback_utils_.global_frame, feedback_utils_.robot_frame,
243 feedback_utils_.transform_tolerance))
245 bt_action_server_->setInternalError(ActionT::Result::TF_ERROR,
246 "Initial robot pose is not available.");
250 nav_msgs::msg::Goals goals_array = goal->poses;
252 for (
auto & goal_pose : goals_array.goals) {
253 if (!nav2_util::transformPoseInTargetFrame(
254 goal_pose, goal_pose, *feedback_utils_.tf, feedback_utils_.global_frame,
255 feedback_utils_.transform_tolerance))
257 bt_action_server_->setInternalError(ActionT::Result::TF_ERROR,
258 "Failed to transform a goal pose (" + std::to_string(i) +
") provided with frame_id '" +
259 goal_pose.header.frame_id +
260 "' to the global frame '" +
261 feedback_utils_.global_frame +
268 if (goals_array.goals.size() > 0) {
270 logger_,
"Begin navigating from current location through %zu poses to (%.2f, %.2f)",
271 goals_array.goals.size(), goals_array.goals.back().pose.position.x,
272 goals_array.goals.back().pose.position.y);
276 start_time_ = clock_->now();
277 auto blackboard = bt_action_server_->getBlackboard();
278 blackboard->set(
"number_recoveries", 0);
281 blackboard->set<nav_msgs::msg::Goals>(goals_blackboard_id_,
282 std::move(goals_array));
285 std::vector<nav2_msgs::msg::WaypointStatus> waypoint_statuses(goals_array.goals.size());
286 for (
size_t waypoint_index = 0 ; waypoint_index < goals_array.goals.size() ; ++waypoint_index) {
287 waypoint_statuses[waypoint_index].waypoint_index = waypoint_index;
288 waypoint_statuses[waypoint_index].waypoint_pose = goals_array.goals[waypoint_index];
290 blackboard->set<decltype(waypoint_statuses)>(waypoint_statuses_blackboard_id_,
291 std::move(waypoint_statuses));
298 #include "pluginlib/class_list_macros.hpp"
299 PLUGINLIB_EXPORT_CLASS(
A navigator for navigating to a a bunch of intermediary poses.
bool configure(nav2::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.
std::string getName() override
Get action name for this navigator.
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...
bool initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal)
Goal pose initialization on the blackboard.
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...
Navigator interface to allow navigators to be stored in a vector and accessed via pluginlib due to te...