AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
ros_node_context.hpp
Go to the documentation of this file.
1// Copyright 2024 Robin Müller
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// https://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#pragma once
16
17#include <chrono>
18#include <string>
19
20#include "rclcpp/node.hpp"
21#include "behaviortree_cpp/tree_node.h"
23
25{
26
28{
29 RosNodeContext(rclcpp::Node::SharedPtr node_ptr, const NodeRegistrationParams& tree_node_params);
30
32 std::weak_ptr<rclcpp::Node> nh;
42 std::string default_port_name;
44 std::chrono::duration<double> wait_for_server_timeout;
46 std::chrono::duration<double> request_timeout;
47
48 rclcpp::Logger getLogger() const;
49
50 rclcpp::Time getCurrentTime() const;
51};
52
53} // namespace auto_apms_behavior_tree
Behavior tree node registration parameters.
RosNodeContext(rclcpp::Node::SharedPtr node_ptr, const NodeRegistrationParams &tree_node_params)
std::chrono::duration< double > request_timeout
Timeout [s] for waiting for a response for the requested service or goal.
std::chrono::duration< double > wait_for_server_timeout
Timeout [s] for initially discovering the associated ROS2 node.
std::weak_ptr< rclcpp::Node > nh
Handle for the ROS2 node.
std::string default_port_name
Default port name of the corresponding ROS 2 communication interface.