Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
navigate_to_pose.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 <memory>
18 #include <limits>
19 #include "nav2_bt_navigator/navigators/navigate_to_pose.hpp"
20 
21 namespace nav2_bt_navigator
22 {
23 
24 bool
26  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node,
27  std::shared_ptr<nav2_util::OdomSmoother> odom_smoother)
28 {
29  start_time_ = rclcpp::Time(0);
30  auto node = parent_node.lock();
31 
32  if (!node->has_parameter("goal_blackboard_id")) {
33  node->declare_parameter("goal_blackboard_id", std::string("goal"));
34  }
35 
36  goal_blackboard_id_ = node->get_parameter("goal_blackboard_id").as_string();
37 
38  if (!node->has_parameter("path_blackboard_id")) {
39  node->declare_parameter("path_blackboard_id", std::string("path"));
40  }
41 
42  path_blackboard_id_ = node->get_parameter("path_blackboard_id").as_string();
43 
44  // Odometry smoother object for getting current speed
45  odom_smoother_ = odom_smoother;
46 
47  self_client_ = rclcpp_action::create_client<ActionT>(node, getName());
48 
49  goal_sub_ = node->create_subscription<geometry_msgs::msg::PoseStamped>(
50  "goal_pose",
51  rclcpp::SystemDefaultsQoS(),
52  std::bind(&NavigateToPoseNavigator::onGoalPoseReceived, this, std::placeholders::_1));
53  return true;
54 }
55 
56 std::string
58  rclcpp_lifecycle::LifecycleNode::WeakPtr parent_node)
59 {
60  std::string default_bt_xml_filename;
61  auto node = parent_node.lock();
62 
63  if (!node->has_parameter("default_nav_to_pose_bt_xml")) {
64  std::string pkg_share_dir =
65  ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
66  node->declare_parameter<std::string>(
67  "default_nav_to_pose_bt_xml",
68  pkg_share_dir +
69  "/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml");
70  }
71 
72  node->get_parameter("default_nav_to_pose_bt_xml", default_bt_xml_filename);
73 
74  return default_bt_xml_filename;
75 }
76 
77 bool
79 {
80  goal_sub_.reset();
81  self_client_.reset();
82  return true;
83 }
84 
85 bool
86 NavigateToPoseNavigator::goalReceived(ActionT::Goal::ConstSharedPtr goal)
87 {
88  auto bt_xml_filename = goal->behavior_tree;
89 
90  if (!bt_action_server_->loadBehaviorTree(bt_xml_filename)) {
91  RCLCPP_ERROR(
92  logger_, "BT file not found: %s. Navigation canceled.",
93  bt_xml_filename.c_str());
94  return false;
95  }
96 
97  return initializeGoalPose(goal);
98 }
99 
100 void
102  typename ActionT::Result::SharedPtr /*result*/,
103  const nav2_behavior_tree::BtStatus /*final_bt_status*/)
104 {
105 }
106 
107 void
109 {
110  // action server feedback (pose, duration of task,
111  // number of recoveries, and distance remaining to goal)
112  auto feedback_msg = std::make_shared<ActionT::Feedback>();
113 
114  geometry_msgs::msg::PoseStamped current_pose;
115  if (!nav2_util::getCurrentPose(
116  current_pose, *feedback_utils_.tf,
117  feedback_utils_.global_frame, feedback_utils_.robot_frame,
118  feedback_utils_.transform_tolerance))
119  {
120  RCLCPP_ERROR(logger_, "Robot pose is not available.");
121  return;
122  }
123 
124  auto blackboard = bt_action_server_->getBlackboard();
125 
126  try {
127  // Get current path points
128  nav_msgs::msg::Path current_path;
129  if (!blackboard->get(path_blackboard_id_, current_path) || current_path.poses.size() == 0u) {
130  // If no path set yet or not meaningful, can't compute ETA or dist remaining yet.
131  throw std::exception();
132  }
133 
134  // Find the closest pose to current pose on global path
135  auto find_closest_pose_idx =
136  [&current_pose, &current_path]() {
137  size_t closest_pose_idx = 0;
138  double curr_min_dist = std::numeric_limits<double>::max();
139  for (size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
140  double curr_dist = nav2_util::geometry_utils::euclidean_distance(
141  current_pose, current_path.poses[curr_idx]);
142  if (curr_dist < curr_min_dist) {
143  curr_min_dist = curr_dist;
144  closest_pose_idx = curr_idx;
145  }
146  }
147  return closest_pose_idx;
148  };
149 
150  // Calculate distance on the path
151  double distance_remaining =
152  nav2_util::geometry_utils::calculate_path_length(current_path, find_closest_pose_idx());
153 
154  // Default value for time remaining
155  rclcpp::Duration estimated_time_remaining = rclcpp::Duration::from_seconds(0.0);
156 
157  // Get current speed
158  geometry_msgs::msg::Twist current_odom = odom_smoother_->getTwist();
159  double current_linear_speed = std::hypot(current_odom.linear.x, current_odom.linear.y);
160 
161  // Calculate estimated time taken to goal if speed is higher than 1cm/s
162  // and at least 10cm to go
163  if ((std::abs(current_linear_speed) > 0.01) && (distance_remaining > 0.1)) {
164  estimated_time_remaining =
165  rclcpp::Duration::from_seconds(distance_remaining / std::abs(current_linear_speed));
166  }
167 
168  feedback_msg->distance_remaining = distance_remaining;
169  feedback_msg->estimated_time_remaining = estimated_time_remaining;
170  } catch (...) {
171  // Ignore
172  }
173 
174  int recovery_count = 0;
175  [[maybe_unused]] auto 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_;
179 
180  bt_action_server_->publishFeedback(feedback_msg);
181 }
182 
183 void
184 NavigateToPoseNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
185 {
186  RCLCPP_INFO(logger_, "Received goal preemption request");
187 
188  if (goal->behavior_tree == bt_action_server_->getCurrentBTFilename() ||
189  (goal->behavior_tree.empty() &&
190  bt_action_server_->getCurrentBTFilename() == bt_action_server_->getDefaultBTFilename()))
191  {
192  // if pending goal requests the same BT as the current goal, accept the pending goal
193  // if pending goal has an empty behavior_tree field, it requests the default BT file
194  // accept the pending goal if the current goal is running the default BT file
195  if (!initializeGoalPose(bt_action_server_->acceptPendingGoal())) {
196  RCLCPP_WARN(
197  logger_,
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();
201  }
202  } else {
203  RCLCPP_WARN(
204  logger_,
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();
211  }
212 }
213 
214 bool
215 NavigateToPoseNavigator::initializeGoalPose(ActionT::Goal::ConstSharedPtr goal)
216 {
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))
222  {
223  RCLCPP_ERROR(logger_, "Initial robot pose is not available.");
224  return false;
225  }
226 
227  geometry_msgs::msg::PoseStamped goal_pose;
228  if (!nav2_util::transformPoseInTargetFrame(
229  goal->pose, goal_pose, *feedback_utils_.tf, feedback_utils_.global_frame,
230  feedback_utils_.transform_tolerance))
231  {
232  RCLCPP_ERROR(
233  logger_,
234  "Failed to transform a goal pose provided with frame_id '%s' to the global frame '%s'.",
235  goal->pose.header.frame_id.c_str(), feedback_utils_.global_frame.c_str());
236  return false;
237  }
238 
239  RCLCPP_INFO(
240  logger_, "Begin navigating from current location (%.2f, %.2f) to (%.2f, %.2f)",
241  current_pose.pose.position.x, current_pose.pose.position.y,
242  goal_pose.pose.position.x, goal_pose.pose.position.y);
243 
244  // Reset state for new action feedback
245  start_time_ = clock_->now();
246  auto blackboard = bt_action_server_->getBlackboard();
247  blackboard->set("number_recoveries", 0); // NOLINT
248 
249  // Update the goal pose on the blackboard
250  blackboard->set(goal_blackboard_id_, goal_pose);
251 
252  return true;
253 }
254 
255 void
256 NavigateToPoseNavigator::onGoalPoseReceived(const geometry_msgs::msg::PoseStamped::SharedPtr pose)
257 {
258  ActionT::Goal goal;
259  goal.pose = *pose;
260  self_client_->async_send_goal(goal);
261 }
262 
263 } // namespace nav2_bt_navigator
264 
265 #include "pluginlib/class_list_macros.hpp"
266 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(rclcpp_lifecycle::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(rclcpp_lifecycle::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...