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