Nav2 Navigation Stack - rolling  main
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  nav2::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  goal_blackboard_id_ =
33  node->declare_or_get_parameter("goal_blackboard_id", std::string("goal"));
34  path_blackboard_id_ =
35  node->declare_or_get_parameter("path_blackboard_id", std::string("path"));
36 
37  // Odometry smoother object for getting current speed
38  odom_smoother_ = odom_smoother;
39 
40  self_client_ = node->create_action_client<ActionT>(getName());
41 
42  goal_sub_ = node->create_subscription<geometry_msgs::msg::PoseStamped>(
43  "goal_pose",
44  std::bind(&NavigateToPoseNavigator::onGoalPoseReceived, this, std::placeholders::_1));
45 
46  bool enable_groot_monitoring =
47  node->declare_or_get_parameter(getName() + ".enable_groot_monitoring", false);
48  int groot_server_port =
49  node->declare_or_get_parameter(getName() + ".groot_server_port", 1669);
50 
51  bt_action_server_->setGrootMonitoring(
52  enable_groot_monitoring,
53  groot_server_port);
54 
55  return true;
56 }
57 
58 std::string
60  nav2::LifecycleNode::WeakPtr parent_node)
61 {
62  auto node = parent_node.lock();
63  std::string pkg_share_dir =
64  ament_index_cpp::get_package_share_directory("nav2_bt_navigator");
65 
66  auto default_bt_xml_filename = node->declare_or_get_parameter(
67  "default_nav_to_pose_bt_xml",
68  pkg_share_dir +
69  "/behavior_trees/navigate_to_pose_w_replanning_and_recovery.xml");
70 
71  return default_bt_xml_filename;
72 }
73 
74 bool
76 {
77  goal_sub_.reset();
78  self_client_.reset();
79  return true;
80 }
81 
82 bool
83 NavigateToPoseNavigator::goalReceived(ActionT::Goal::ConstSharedPtr goal)
84 {
85  auto bt_xml_filename = goal->behavior_tree;
86 
87  if (!bt_action_server_->loadBehaviorTree(bt_xml_filename)) {
88  bt_action_server_->setInternalError(ActionT::Result::FAILED_TO_LOAD_BEHAVIOR_TREE,
89  std::string("Error loading XML file: ") + bt_xml_filename + ". Navigation canceled.");
90  return false;
91  }
92 
93  return initializeGoalPose(goal);
94 }
95 
96 void
98  typename ActionT::Result::SharedPtr result,
99  const nav2_behavior_tree::BtStatus /*final_bt_status*/)
100 {
101  if (result->error_code == 0) {
102  if (bt_action_server_->populateInternalError(result)) {
103  RCLCPP_WARN(logger_,
104  "NavigateToPoseNavigator::goalCompleted, internal error %d:%s.",
105  result->error_code,
106  result->error_msg.c_str());
107  }
108  } else {
109  RCLCPP_WARN(logger_, "NavigateToPoseNavigator::goalCompleted error %d:%s.",
110  result->error_code,
111  result->error_msg.c_str());
112  }
113 }
114 
115 void
117 {
118  // action server feedback (pose, duration of task,
119  // number of recoveries, and distance remaining to goal)
120  auto feedback_msg = std::make_shared<ActionT::Feedback>();
121 
122  geometry_msgs::msg::PoseStamped current_pose;
123  if (!nav2_util::getCurrentPose(
124  current_pose, *feedback_utils_.tf,
125  feedback_utils_.global_frame, feedback_utils_.robot_frame,
126  feedback_utils_.transform_tolerance))
127  {
128  RCLCPP_ERROR(logger_, "Robot pose is not available.");
129  return;
130  }
131 
132  auto blackboard = bt_action_server_->getBlackboard();
133 
134  // Get current path points
135  nav_msgs::msg::Path current_path;
136  auto res = blackboard->get(path_blackboard_id_, current_path);
137  if (res && current_path.poses.size() > 0u) {
138  // Find the closest pose to current pose on global path
139  auto find_closest_pose_idx =
140  [&current_pose, &current_path]() {
141  size_t closest_pose_idx = 0;
142  double curr_min_dist = std::numeric_limits<double>::max();
143  for (size_t curr_idx = 0; curr_idx < current_path.poses.size(); ++curr_idx) {
144  double curr_dist = nav2_util::geometry_utils::euclidean_distance(
145  current_pose, current_path.poses[curr_idx]);
146  if (curr_dist < curr_min_dist) {
147  curr_min_dist = curr_dist;
148  closest_pose_idx = curr_idx;
149  }
150  }
151  return closest_pose_idx;
152  };
153 
154  // Calculate distance on the path
155  double distance_remaining =
156  nav2_util::geometry_utils::calculate_path_length(current_path, find_closest_pose_idx());
157 
158  // Default value for time remaining
159  rclcpp::Duration estimated_time_remaining = rclcpp::Duration::from_seconds(0.0);
160 
161  // Get current speed
162  geometry_msgs::msg::Twist current_odom = odom_smoother_->getTwist();
163  double current_linear_speed = std::hypot(current_odom.linear.x, current_odom.linear.y);
164 
165  // Calculate estimated time taken to goal if speed is higher than 1cm/s
166  // and at least 10cm to go
167  if ((std::abs(current_linear_speed) > 0.01) && (distance_remaining > 0.1)) {
168  estimated_time_remaining =
169  rclcpp::Duration::from_seconds(distance_remaining / std::abs(current_linear_speed));
170  }
171 
172  feedback_msg->distance_remaining = distance_remaining;
173  feedback_msg->estimated_time_remaining = estimated_time_remaining;
174  }
175 
176  int recovery_count = 0;
177  res = blackboard->get("number_recoveries", recovery_count);
178  feedback_msg->number_of_recoveries = recovery_count;
179  feedback_msg->current_pose = current_pose;
180  feedback_msg->navigation_time = clock_->now() - start_time_;
181 
182  bt_action_server_->publishFeedback(feedback_msg);
183 }
184 
185 void
186 NavigateToPoseNavigator::onPreempt(ActionT::Goal::ConstSharedPtr goal)
187 {
188  RCLCPP_INFO(logger_, "Received goal preemption request");
189 
190  if (goal->behavior_tree == bt_action_server_->getCurrentBTFilename() ||
191  (goal->behavior_tree.empty() &&
192  bt_action_server_->getCurrentBTFilename() == bt_action_server_->getDefaultBTFilename()))
193  {
194  // if pending goal requests the same BT as the current goal, accept the pending goal
195  // if pending goal has an empty behavior_tree field, it requests the default BT file
196  // accept the pending goal if the current goal is running the default BT file
197  if (!initializeGoalPose(bt_action_server_->acceptPendingGoal())) {
198  RCLCPP_WARN(
199  logger_,
200  "Preemption request was rejected since the goal pose could not be "
201  "transformed. For now, continuing to track the last goal until completion.");
202  bt_action_server_->terminatePendingGoal();
203  }
204  } else {
205  RCLCPP_WARN(
206  logger_,
207  "Preemption request was rejected since the requested BT XML file is not the same "
208  "as the one that the current goal is executing. Preemption with a new BT is invalid "
209  "since it would require cancellation of the previous goal instead of true preemption."
210  "\nCancel the current goal and send a new action request if you want to use a "
211  "different BT XML file. For now, continuing to track the last goal until completion.");
212  bt_action_server_->terminatePendingGoal();
213  }
214 }
215 
216 bool
217 NavigateToPoseNavigator::initializeGoalPose(ActionT::Goal::ConstSharedPtr goal)
218 {
219  geometry_msgs::msg::PoseStamped current_pose;
220  if (!nav2_util::getCurrentPose(
221  current_pose, *feedback_utils_.tf,
222  feedback_utils_.global_frame, feedback_utils_.robot_frame,
223  feedback_utils_.transform_tolerance))
224  {
225  bt_action_server_->setInternalError(ActionT::Result::TF_ERROR,
226  "Initial robot pose is not available.");
227  return false;
228  }
229 
230  geometry_msgs::msg::PoseStamped goal_pose;
231  if (!nav2_util::transformPoseInTargetFrame(
232  goal->pose, goal_pose, *feedback_utils_.tf, feedback_utils_.global_frame,
233  feedback_utils_.transform_tolerance))
234  {
235  bt_action_server_->setInternalError(ActionT::Result::TF_ERROR,
236  "Failed to transform a goal pose provided with frame_id '" +
237  goal->pose.header.frame_id +
238  "' to the global frame '" +
239  feedback_utils_.global_frame +
240  "'.");
241  return false;
242  }
243 
244  RCLCPP_INFO(
245  logger_, "Begin navigating from current location (%.2f, %.2f) to (%.2f, %.2f)",
246  current_pose.pose.position.x, current_pose.pose.position.y,
247  goal_pose.pose.position.x, goal_pose.pose.position.y);
248 
249  // Reset state for new action feedback
250  start_time_ = clock_->now();
251  auto blackboard = bt_action_server_->getBlackboard();
252  blackboard->set("number_recoveries", 0); // NOLINT
253 
254  // Update the goal pose on the blackboard
255  blackboard->set(goal_blackboard_id_, goal_pose);
256 
257  return true;
258 }
259 
260 void
261 NavigateToPoseNavigator::onGoalPoseReceived(const geometry_msgs::msg::PoseStamped::SharedPtr pose)
262 {
263  ActionT::Goal goal;
264  goal.pose = *pose;
265  self_client_->async_send_goal(goal);
266 }
267 
268 } // namespace nav2_bt_navigator
269 
270 #include "pluginlib/class_list_macros.hpp"
271 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(nav2::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(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...
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...