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();
45 if (!node->has_parameter(
"waypoint_statuses_blackboard_id")) {
46 node->declare_parameter(
"waypoint_statuses_blackboard_id", std::string(
"waypoint_statuses"));
49 waypoint_statuses_blackboard_id_ =
50 node->get_parameter(
"waypoint_statuses_blackboard_id").as_string();
53 odom_smoother_ = odom_smoother;
55 if (!node->has_parameter(
getName() +
".enable_groot_monitoring")) {
56 node->declare_parameter(
getName() +
".enable_groot_monitoring",
false);
59 if (!node->has_parameter(
getName() +
".groot_server_port")) {
60 node->declare_parameter(
getName() +
".groot_server_port", 1669);
63 bt_action_server_->setGrootMonitoring(
64 node->get_parameter(
getName() +
".enable_groot_monitoring").as_bool(),
65 node->get_parameter(
getName() +
".groot_server_port").as_int());
72 rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node)
74 std::string default_bt_xml_filename;
75 auto node = parent_node.lock();
77 if (!node->has_parameter(
"default_nav_through_poses_bt_xml")) {
78 std::string pkg_share_dir =
79 ament_index_cpp::get_package_share_directory(
"nav2_bt_navigator");
80 node->declare_parameter<std::string>(
81 "default_nav_through_poses_bt_xml",
83 "/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml");
86 node->get_parameter(
"default_nav_through_poses_bt_xml", default_bt_xml_filename);
88 return default_bt_xml_filename;
94 auto bt_xml_filename = goal->behavior_tree;
96 if (!bt_action_server_->loadBehaviorTree(bt_xml_filename)) {
97 bt_action_server_->setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
98 "Error loading XML file: " + bt_xml_filename +
". Navigation canceled.");
107 typename ActionT::Result::SharedPtr result,
108 const nav2_behavior_tree::BtStatus final_bt_status)
110 if (result->error_code == 0) {
111 if (bt_action_server_->populateInternalError(result)) {
113 "NavigateThroughPosesNavigator::goalCompleted, internal error %d:'%s'.",
115 result->error_msg.c_str());
118 RCLCPP_WARN(logger_,
"NavigateThroughPosesNavigator::goalCompleted error %d:'%s'.",
120 result->error_msg.c_str());
124 auto blackboard = bt_action_server_->getBlackboard();
125 auto waypoint_statuses =
126 blackboard->get<std::vector<nav2_msgs::msg::WaypointStatus>>(waypoint_statuses_blackboard_id_);
129 auto integrate_waypoint_status = final_bt_status == nav2_behavior_tree::BtStatus::SUCCEEDED ?
130 nav2_msgs::msg::WaypointStatus::COMPLETED : nav2_msgs::msg::WaypointStatus::FAILED;
131 for (
auto & waypoint_status : waypoint_statuses) {
132 if (waypoint_status.waypoint_status == nav2_msgs::msg::WaypointStatus::PENDING) {
133 waypoint_status.waypoint_status = integrate_waypoint_status;
137 result->waypoint_statuses = std::move(waypoint_statuses);
143 using namespace nav2_util::geometry_utils;
147 auto feedback_msg = std::make_shared<ActionT::Feedback>();
149 auto blackboard = bt_action_server_->getBlackboard();
151 nav_msgs::msg::Goals goal_poses;
152 [[maybe_unused]]
auto res = blackboard->get(goals_blackboard_id_, goal_poses);
154 feedback_msg->waypoint_statuses =
155 blackboard->get<std::vector<nav2_msgs::msg::WaypointStatus>>(waypoint_statuses_blackboard_id_);
157 if (goal_poses.goals.size() == 0) {
158 bt_action_server_->publishFeedback(feedback_msg);
162 geometry_msgs::msg::PoseStamped current_pose;
163 if (!nav2_util::getCurrentPose(
164 current_pose, *feedback_utils_.tf,
165 feedback_utils_.global_frame, feedback_utils_.robot_frame,
166 feedback_utils_.transform_tolerance))
168 RCLCPP_ERROR(logger_,
"Robot pose is not available.");
173 nav_msgs::msg::Path current_path;
174 res = blackboard->get(path_blackboard_id_, current_path);
175 if (res && current_path.poses.size() > 0u) {
177 auto find_closest_pose_idx =
178 [¤t_pose, ¤t_path]() {
179 size_t closest_pose_idx = 0;
180 double curr_min_dist = std::numeric_limits<double>::max();
181 for (
size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
182 double curr_dist = nav2_util::geometry_utils::euclidean_distance(
183 current_pose, current_path.poses[curr_idx]);
184 if (curr_dist < curr_min_dist) {
185 curr_min_dist = curr_dist;
186 closest_pose_idx = curr_idx;
189 return closest_pose_idx;
193 double distance_remaining =
194 nav2_util::geometry_utils::calculate_path_length(current_path, find_closest_pose_idx());
197 rclcpp::Duration estimated_time_remaining = rclcpp::Duration::from_seconds(0.0);
200 geometry_msgs::msg::Twist current_odom = odom_smoother_->getTwist();
201 double current_linear_speed = std::hypot(current_odom.linear.x, current_odom.linear.y);
205 if ((std::abs(current_linear_speed) > 0.01) && (distance_remaining > 0.1)) {
206 estimated_time_remaining =
207 rclcpp::Duration::from_seconds(distance_remaining / std::abs(current_linear_speed));
210 feedback_msg->distance_remaining = distance_remaining;
211 feedback_msg->estimated_time_remaining = estimated_time_remaining;
214 int recovery_count = 0;
215 res = blackboard->get(
"number_recoveries", recovery_count);
216 feedback_msg->number_of_recoveries = recovery_count;
217 feedback_msg->current_pose = current_pose;
218 feedback_msg->navigation_time = clock_->now() - start_time_;
219 feedback_msg->number_of_poses_remaining = goal_poses.goals.size();
221 bt_action_server_->publishFeedback(feedback_msg);
227 RCLCPP_INFO(logger_,
"Received goal preemption request");
229 if (goal->behavior_tree == bt_action_server_->getCurrentBTFilename() ||
230 (goal->behavior_tree.empty() &&
231 bt_action_server_->getCurrentBTFilename() == bt_action_server_->getDefaultBTFilename()))
239 "Preemption request was rejected since the goal poses could not be "
240 "transformed. For now, continuing to track the last goal until completion.");
241 bt_action_server_->terminatePendingGoal();
246 "Preemption request was rejected since the requested BT XML file is not the same "
247 "as the one that the current goal is executing. Preemption with a new BT is invalid "
248 "since it would require cancellation of the previous goal instead of true preemption."
249 "\nCancel the current goal and send a new action request if you want to use a "
250 "different BT XML file. For now, continuing to track the last goal until completion.");
251 bt_action_server_->terminatePendingGoal();
258 geometry_msgs::msg::PoseStamped current_pose;
259 if (!nav2_util::getCurrentPose(
260 current_pose, *feedback_utils_.tf,
261 feedback_utils_.global_frame, feedback_utils_.robot_frame,
262 feedback_utils_.transform_tolerance))
264 bt_action_server_->setInternalError(ActionT::Result::TF_ERROR,
265 "Initial robot pose is not available.");
269 nav_msgs::msg::Goals goals_array = goal->poses;
271 for (
auto & goal_pose : goals_array.goals) {
272 if (!nav2_util::transformPoseInTargetFrame(
273 goal_pose, goal_pose, *feedback_utils_.tf, feedback_utils_.global_frame,
274 feedback_utils_.transform_tolerance))
276 bt_action_server_->setInternalError(ActionT::Result::TF_ERROR,
277 "Failed to transform a goal pose (" + std::to_string(i) +
") provided with frame_id '" +
278 goal_pose.header.frame_id +
279 "' to the global frame '" +
280 feedback_utils_.global_frame +
287 if (goals_array.goals.size() > 0) {
289 logger_,
"Begin navigating from current location through %zu poses to (%.2f, %.2f)",
290 goals_array.goals.size(), goals_array.goals.back().pose.position.x,
291 goals_array.goals.back().pose.position.y);
295 start_time_ = clock_->now();
296 auto blackboard = bt_action_server_->getBlackboard();
297 blackboard->set(
"number_recoveries", 0);
300 blackboard->set<nav_msgs::msg::Goals>(goals_blackboard_id_,
301 std::move(goals_array));
304 std::vector<nav2_msgs::msg::WaypointStatus> waypoint_statuses(goals_array.goals.size());
305 for (
size_t waypoint_index = 0 ; waypoint_index < goals_array.goals.size() ; ++waypoint_index) {
306 waypoint_statuses[waypoint_index].waypoint_index = waypoint_index;
307 waypoint_statuses[waypoint_index].waypoint_pose = goals_array.goals[waypoint_index];
309 blackboard->set<decltype(waypoint_statuses)>(waypoint_statuses_blackboard_id_,
310 std::move(waypoint_statuses));
317 #include "pluginlib/class_list_macros.hpp"
318 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.
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...
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...