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 
65 
72  bool on_configure();
73 
78  bool on_activate();
79 
84  bool on_deactivate();
85 
90  bool on_cleanup();
91 
97  void setGrootMonitoring(const bool enable, const unsigned server_port);
98 
105  bool loadBehaviorTree(const std::string & bt_xml_filename = "");
106 
111  BT::Blackboard::Ptr getBlackboard() const
112  {
113  return blackboard_;
114  }
115 
120  std::string getCurrentBTFilename() const
121  {
122  return current_bt_xml_filename_;
123  }
124 
129  std::string getDefaultBTFilename() const
130  {
131  return default_bt_xml_filename_;
132  }
133 
138  const std::shared_ptr<const typename ActionT::Goal> acceptPendingGoal()
139  {
140  return action_server_->accept_pending_goal();
141  }
142 
147  {
148  action_server_->terminate_pending_goal();
149  }
150 
155  const std::shared_ptr<const typename ActionT::Goal> getCurrentGoal() const
156  {
157  return action_server_->get_current_goal();
158  }
159 
164  const std::shared_ptr<const typename ActionT::Goal> getPendingGoal() const
165  {
166  return action_server_->get_pending_goal();
167  }
168 
172  void publishFeedback(typename std::shared_ptr<typename ActionT::Feedback> feedback)
173  {
174  action_server_->publish_feedback(feedback);
175  }
176 
181  const BT::Tree & getTree() const
182  {
183  return tree_;
184  }
185 
191  void haltTree()
192  {
193  tree_.haltTree();
194  }
195 
201  void setInternalError(uint16_t error_code, const std::string & error_msg);
202 
206  void resetInternalError(void);
207 
213  bool populateInternalError(typename std::shared_ptr<typename ActionT::Result> result);
214 
215 protected:
219  void executeCallback();
220 
226  void populateErrorCode(typename std::shared_ptr<typename ActionT::Result> result);
227 
231  void cleanErrorCodes();
232 
233  // Action name
234  std::string action_name_;
235 
236  // Our action server implements the template action
237  typename ActionServer::SharedPtr action_server_;
238 
239  // Behavior Tree to be executed when goal is received
240  BT::Tree tree_;
241 
242  // The blackboard shared by all of the nodes in the tree
243  BT::Blackboard::Ptr blackboard_;
244 
245  // The XML file that contains the Behavior Tree to create
246  std::string current_bt_xml_filename_;
247  std::string default_bt_xml_filename_;
248 
249  // The wrapper class for the BT functionality
250  std::unique_ptr<nav2_behavior_tree::BehaviorTreeEngine> bt_;
251 
252  // Libraries to pull plugins (BT Nodes) from
253  std::vector<std::string> plugin_lib_names_;
254 
255  // Error code name prefixes
256  std::vector<std::string> error_code_name_prefixes_;
257 
258  // A regular, non-spinning ROS node that we can use for calls to the action client
259  nav2::LifecycleNode::SharedPtr client_node_;
260 
261  // Parent node
262  typename NodeT::WeakPtr node_;
263 
264  // Clock
265  rclcpp::Clock::SharedPtr clock_;
266 
267  // Logger
268  rclcpp::Logger logger_{rclcpp::get_logger("BtActionServer")};
269 
270  // To publish BT logs
271  std::unique_ptr<RosTopicLogger> topic_logger_;
272 
273  // Duration for each iteration of BT execution
274  std::chrono::milliseconds bt_loop_duration_;
275 
276  // Default timeout value while waiting for response from a server
277  std::chrono::milliseconds default_server_timeout_;
278 
279  // The timeout value for waiting for a service to response
280  std::chrono::milliseconds wait_for_service_timeout_;
281 
282  // should the BT be reloaded even if the same xml filename is requested?
283  bool always_reload_bt_xml_ = false;
284 
285  // Parameters for Groot2 monitoring
286  bool enable_groot_monitoring_ = false;
287  int groot_server_port_ = 1667;
288 
289  // User-provided callbacks
290  OnGoalReceivedCallback on_goal_received_callback_;
291  OnLoopCallback on_loop_callback_;
292  OnPreemptCallback on_preempt_callback_;
293  OnCompletionCallback on_completion_callback_;
294 
295  // internal error tracking (IOW not behaviorTree blackboard errors)
296  uint16_t internal_error_code_;
297  std::string internal_error_msg_;
298 };
299 
300 } // namespace nav2_behavior_tree
301 
302 #include <nav2_behavior_tree/bt_action_server_impl.hpp> // NOLINT(build/include_order)
303 #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.
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.
std::string getDefaultBTFilename() const
Getter function for default BT XML filename.
bool loadBehaviorTree(const std::string &bt_xml_filename="")
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.
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)
A constructor for nav2_behavior_tree::BtActionServer class.
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 getCurrentBTFilename() 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.