Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
navigate_through_poses.cpp
1 // Copyright (c) 2021 Samsung Research
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include <vector>
16 #include <string>
17 #include <set>
18 #include <memory>
19 #include <limits>
20 #include "nav2_bt_navigator/navigators/navigate_through_poses.hpp"
21 
22 namespace nav2_bt_navigator
23 {
24 
25 bool
27  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
28  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
29 {
30  start_time_ = rclcpp::Time(0);
31  auto node = parent_node.lock();
32 
33  if (!node->has_parameter("goals_blackboard_id")) {
34  node->declare_parameter("goals_blackboard_id", std::string("goals"));
35  }
36 
37  goals_blackboard_id_ = node->get_parameter("goals_blackboard_id").as_string();
38 
39  if (!node->has_parameter("path_blackboard_id")) {
40  node->declare_parameter("path_blackboard_id", std::string("path"));
41  }
42 
43  path_blackboard_id_ = node->get_parameter("path_blackboard_id").as_string();
44 
45  // Odometry smoother object for getting current speed
46  odom_smoother_ = odom_smoother;
47 
48  return true;
49 }
50 
51 std::string
53  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node)
54 {
55  std::string default_bt_xml_filename;
56  auto node = parent_node.lock();
57 
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",
63  pkg_share_dir +
64  "/behavior_trees/navigate_through_poses_w_replanning_and_recovery.xml");
65  }
66 
67  node->get_parameter("default_nav_through_poses_bt_xml", default_bt_xml_filename);
68 
69  return default_bt_xml_filename;
70 }
71 
72 bool
73 NavigateThroughPosesNavigator::goalReceived(ActionT::Goal::ConstSharedPtr goal)
74 {
75  auto bt_xml_filename = goal->behavior_tree;
76 
77  if (!bt_action_server_->loadBehaviorTree(bt_xml_filename)) {
78  RCLCPP_ERROR(
79  logger_, "Error loading XML file: %s. Navigation canceled.",
80  bt_xml_filename.c_str());
81  return false;
82  }
83 
84  return initializeGoalPoses(goal);
85 }
86 
87 void
89  typename ActionT::Result::SharedPtr /*result*/,
90  const nav2_behavior_tree::BtStatus /*final_bt_status*/)
91 {
92 }
93 
94 void
96 {
97  using namespace nav2_util::geometry_utils; // NOLINT
98 
99  // action server feedback (pose, duration of task,
100  // number of recoveries, and distance remaining to goal, etc)
101  auto feedback_msg = std::make_shared<ActionT::Feedback>();
102 
103  auto blackboard = bt_action_server_->getBlackboard();
104 
105  Goals goal_poses;
106  [[maybe_unused]] auto res = blackboard->get(goals_blackboard_id_, goal_poses);
107 
108  if (goal_poses.size() == 0) {
109  bt_action_server_->publishFeedback(feedback_msg);
110  return;
111  }
112 
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))
118  {
119  RCLCPP_ERROR(logger_, "Robot pose is not available.");
120  return;
121  }
122 
123  try {
124  // Get current path points
125  nav_msgs::msg::Path current_path;
126  if (!blackboard->get(path_blackboard_id_, current_path) || current_path.poses.size() == 0u) {
127  // If no path set yet or not meaningful, can't compute ETA or dist remaining yet.
128  throw std::exception();
129  }
130 
131  // Find the closest pose to current pose on global path
132  auto find_closest_pose_idx =
133  [&current_pose, &current_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;
142  }
143  }
144  return closest_pose_idx;
145  };
146 
147  // Calculate distance on the path
148  double distance_remaining =
149  nav2_util::geometry_utils::calculate_path_length(current_path, find_closest_pose_idx());
150 
151  // Default value for time remaining
152  rclcpp::Duration estimated_time_remaining = rclcpp::Duration::from_seconds(0.0);
153 
154  // Get current speed
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);
157 
158  // Calculate estimated time taken to goal if speed is higher than 1cm/s
159  // and at least 10cm to go
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));
163  }
164 
165  feedback_msg->distance_remaining = distance_remaining;
166  feedback_msg->estimated_time_remaining = estimated_time_remaining;
167  } catch (...) {
168  // Ignore
169  }
170 
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();
177 
178  bt_action_server_->publishFeedback(feedback_msg);
179 }
180 
181 void
182 NavigateThroughPosesNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
183 {
184  RCLCPP_INFO(logger_, "Received goal preemption request");
185 
186  if (goal->behavior_tree == bt_action_server_->getCurrentBTFilename() ||
187  (goal->behavior_tree.empty() &&
188  bt_action_server_->getCurrentBTFilename() == bt_action_server_->getDefaultBTFilename()))
189  {
190  // if pending goal requests the same BT as the current goal, accept the pending goal
191  // if pending goal has an empty behavior_tree field, it requests the default BT file
192  // accept the pending goal if the current goal is running the default BT file
193  if (!initializeGoalPoses(bt_action_server_->acceptPendingGoal())) {
194  RCLCPP_WARN(
195  logger_,
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();
199  }
200  } else {
201  RCLCPP_WARN(
202  logger_,
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();
209  }
210 }
211 
212 bool
213 NavigateThroughPosesNavigator::initializeGoalPoses(ActionT::Goal::ConstSharedPtr goal)
214 {
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))
220  {
221  RCLCPP_ERROR(
222  logger_,
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());
225  return false;
226  }
227  }
228 
229  if (goal_poses.size() > 0) {
230  RCLCPP_INFO(
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);
233  }
234 
235  // Reset state for new action feedback
236  start_time_ = clock_->now();
237  auto blackboard = bt_action_server_->getBlackboard();
238  blackboard->set("number_recoveries", 0); // NOLINT
239 
240  // Update the goal pose on the blackboard
241  blackboard->set<Goals>(goals_blackboard_id_, std::move(goal_poses));
242 
243  return true;
244 }
245 
246 } // namespace nav2_bt_navigator
247 
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...