Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
bt_action_server.hpp
1 // Copyright (c) 2020 Sarthak Mittal
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 #ifndef NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_HPP_
16 #define NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_HPP_
17 
18 #include <chrono>
19 #include <functional>
20 #include <memory>
21 #include <string>
22 #include <vector>
23 
24 #include "geometry_msgs/msg/pose_stamped.hpp"
25 #include "nav2_behavior_tree/behavior_tree_engine.hpp"
26 #include "nav2_behavior_tree/ros_topic_logger.hpp"
27 #include "nav2_ros_common/lifecycle_node.hpp"
28 #include "nav2_ros_common/simple_action_server.hpp"
29 
30 namespace nav2_behavior_tree
31 {
36 template<class ActionT, class NodeT>
38 {
39 public:
41 
42  typedef std::function<bool (typename ActionT::Goal::ConstSharedPtr)> OnGoalReceivedCallback;
43  typedef std::function<void ()> OnLoopCallback;
44  typedef std::function<void (typename ActionT::Goal::ConstSharedPtr)> OnPreemptCallback;
45  typedef std::function<void (typename ActionT::Result::SharedPtr,
46  nav2_behavior_tree::BtStatus)> OnCompletionCallback;
47 
51  explicit BtActionServer(
52  const typename NodeT::WeakPtr & parent,
53  const std::string & action_name,
54  const std::vector<std::string> & plugin_lib_names,
55  const std::string & default_bt_xml_filename,
56  OnGoalReceivedCallback on_goal_received_callback,
57  OnLoopCallback on_loop_callback,
58  OnPreemptCallback on_preempt_callback,
59  OnCompletionCallback on_completion_callback,
60  const std::vector<std::string> & search_directories = std::vector<std::string>{});
61 
66 
73  bool on_configure();
74 
79  bool on_activate();
80 
85  bool on_deactivate();
86 
91  bool on_cleanup();
92 
98  void setGrootMonitoring(const bool enable, const unsigned server_port);
99 
106  bool loadBehaviorTree(
107  const std::string & bt_xml_filename_or_id = "");
108 
113  std::string extractBehaviorTreeID(const std::string & file_or_id);
114 
119  BT::Blackboard::Ptr getBlackboard() const
120  {
121  return blackboard_;
122  }
123 
128  std::string getCurrentBTFilenameOrID() const
129  {
130  return current_bt_file_or_id_;
131  }
132 
137  std::string getDefaultBTFilenameOrID() const
138  {
139  return default_bt_xml_filename_or_id_;
140  }
141 
146  const std::shared_ptr<const typename ActionT::Goal> acceptPendingGoal()
147  {
148  return action_server_->accept_pending_goal();
149  }
150 
155  {
156  action_server_->terminate_pending_goal();
157  }
158 
163  const std::shared_ptr<const typename ActionT::Goal> getCurrentGoal() const
164  {
165  return action_server_->get_current_goal();
166  }
167 
172  const std::shared_ptr<const typename ActionT::Goal> getPendingGoal() const
173  {
174  return action_server_->get_pending_goal();
175  }
176 
180  void publishFeedback(typename std::shared_ptr<typename ActionT::Feedback> feedback)
181  {
182  action_server_->publish_feedback(feedback);
183  }
184 
189  const BT::Tree & getTree() const
190  {
191  return tree_;
192  }
193 
199  void haltTree()
200  {
201  tree_.haltTree();
202  }
203 
209  void setInternalError(uint16_t error_code, const std::string & error_msg);
210 
214  void resetInternalError(void);
215 
221  bool populateInternalError(typename std::shared_ptr<typename ActionT::Result> result);
222 
223 protected:
227  void executeCallback();
228 
234  void populateErrorCode(typename std::shared_ptr<typename ActionT::Result> result);
235 
239  void cleanErrorCodes();
240 
241  // Action name
242  std::string action_name_;
243 
244  // Our action server implements the template action
245  typename ActionServer::SharedPtr action_server_;
246 
247  // Behavior Tree to be executed when goal is received
248  BT::Tree tree_;
249 
250  // The blackboard shared by all of the nodes in the tree
251  BT::Blackboard::Ptr blackboard_;
252 
253  // The XML file that contains the Behavior Tree to create
254  std::string current_bt_file_or_id_;
255  std::string default_bt_xml_filename_or_id_;
256  std::vector<std::string> search_directories_;
257 
258  // The wrapper class for the BT functionality
259  std::unique_ptr<nav2_behavior_tree::BehaviorTreeEngine> bt_;
260 
261  // Libraries to pull plugins (BT Nodes) from
262  std::vector<std::string> plugin_lib_names_;
263 
264  // Error code name prefixes
265  std::vector<std::string> error_code_name_prefixes_;
266 
267  // A regular, non-spinning ROS node that we can use for calls to the action client
268  nav2::LifecycleNode::SharedPtr client_node_;
269 
270  // Parent node
271  typename NodeT::WeakPtr node_;
272 
273  // Clock
274  rclcpp::Clock::SharedPtr clock_;
275 
276  // Logger
277  rclcpp::Logger logger_{rclcpp::get_logger("BtActionServer")};
278 
279  // To publish BT logs
280  std::unique_ptr<RosTopicLogger> topic_logger_;
281 
282  // Duration for each iteration of BT execution
283  std::chrono::milliseconds bt_loop_duration_;
284 
285  // Default timeout value while waiting for response from a server
286  std::chrono::milliseconds default_server_timeout_;
287 
288  // The timeout value for waiting for a service to response
289  std::chrono::milliseconds wait_for_service_timeout_;
290 
291  // should the BT be reloaded even if the same xml filename is requested?
292  bool always_reload_bt_ = false;
293 
294  // Parameters for Groot2 monitoring
295  bool enable_groot_monitoring_ = false;
296  int groot_server_port_ = 1667;
297 
298  // User-provided callbacks
299  OnGoalReceivedCallback on_goal_received_callback_;
300  OnLoopCallback on_loop_callback_;
301  OnPreemptCallback on_preempt_callback_;
302  OnCompletionCallback on_completion_callback_;
303 
304  // internal error tracking (IOW not behaviorTree blackboard errors)
305  uint16_t internal_error_code_;
306  std::string internal_error_msg_;
307 };
308 
309 } // namespace nav2_behavior_tree
310 
311 #include <nav2_behavior_tree/bt_action_server_impl.hpp> // NOLINT(build/include_order)
312 #endif // NAV2_BEHAVIOR_TREE__BT_ACTION_SERVER_HPP_
An action server wrapper to make applications simpler using Actions.
An action server that uses behavior tree to execute an action.
std::string extractBehaviorTreeID(const std::string &file_or_id)
Extract BehaviorTree ID from XML file.
BtActionServer(const typename NodeT::WeakPtr &parent, const std::string &action_name, const std::vector< std::string > &plugin_lib_names, const std::string &default_bt_xml_filename, OnGoalReceivedCallback on_goal_received_callback, OnLoopCallback on_loop_callback, OnPreemptCallback on_preempt_callback, OnCompletionCallback on_completion_callback, const std::vector< std::string > &search_directories=std::vector< std::string >{})
A constructor for nav2_behavior_tree::BtActionServer class.
bool on_cleanup()
Resets member variables.
void setGrootMonitoring(const bool enable, const unsigned server_port)
Enable (or disable) Groot2 monitoring of BT.
const std::shared_ptr< const typename ActionT::Goal > acceptPendingGoal()
Wrapper function to accept pending goal if a preempt has been requested.
bool loadBehaviorTree(const std::string &bt_xml_filename_or_id="")
Replace current BT with another one.
void haltTree()
Function to halt the current tree. It will interrupt the execution of RUNNING nodes by calling their ...
BT::Blackboard::Ptr getBlackboard() const
Getter function for BT Blackboard.
bool populateInternalError(typename std::shared_ptr< typename ActionT::Result > result)
populate result with internal error code and error_msg if not NONE
bool on_deactivate()
Deactivates action server.
const std::shared_ptr< const typename ActionT::Goal > getCurrentGoal() const
Wrapper function to get current goal.
~BtActionServer()
A destructor for nav2_behavior_tree::BtActionServer class.
const BT::Tree & getTree() const
Getter function for the current BT tree.
bool on_configure()
Configures member variables Initializes action server for, builds behavior tree from xml file,...
const std::shared_ptr< const typename ActionT::Goal > getPendingGoal() const
Wrapper function to get pending goal.
void terminatePendingGoal()
Wrapper function to terminate pending goal if a preempt has been requested.
std::string getDefaultBTFilenameOrID() const
Getter function for default BT XML filename or ID.
void publishFeedback(typename std::shared_ptr< typename ActionT::Feedback > feedback)
Wrapper function to publish action feedback.
void resetInternalError(void)
reset internal error code and message
void executeCallback()
Action server callback.
void cleanErrorCodes()
Setting BT error codes to success. Used to clean blackboard between different BT runs.
void populateErrorCode(typename std::shared_ptr< typename ActionT::Result > result)
updates the action server result to the highest priority error code posted on the blackboard
bool on_activate()
Activates action server.
std::string getCurrentBTFilenameOrID() const
Getter function for current BT XML filename.
void setInternalError(uint16_t error_code, const std::string &error_msg)
Set internal error code and message.