AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
get_parameter.cpp
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#include <type_traits>
16
17#include "auto_apms_behavior_tree/util/parameter.hpp"
18#include "auto_apms_behavior_tree_core/node.hpp"
19#include "rcl_interfaces/msg/parameter_value.hpp"
20#include "rcl_interfaces/srv/get_parameters.hpp"
21#include "rclcpp/parameter_value.hpp"
22
23#define INPUT_KEY_PARAM_NAME "parameter"
24#define OUTPUT_KEY_PARAM_VALUE "value"
25#define INPUT_KEY_NODE_NAME "node"
26
28{
29
30template <typename T>
31class GetParameterTemplate : public core::RosServiceNode<rcl_interfaces::srv::GetParameters>
32{
33public:
34 GetParameterTemplate(const std::string & instance_name, const Config & config, const Context & context)
35 : RosServiceNode(instance_name, config, context)
36 {
37 if (
38 config.input_ports.find(INPUT_KEY_NODE_NAME) == config.input_ports.end() ||
39 config.input_ports.at(INPUT_KEY_NODE_NAME).empty()) {
40 // Refer to this ROS 2 node as the target if respective input port is empty
41 createClient(context_.getFullyQualifiedRosNodeName() + "/get_parameters");
42 }
43 }
44
45 static BT::PortsList providedPorts()
46 {
47 // We do not use the default port for the service name
48
49 // There is no string conversion function for variables that are type initialized using the value port if the
50 // BT::Any version is used. To prevent errors when using these variables in e.g. the scripting language we have to
51 // set the type to BT::AnyTypeAllowed to truly indicate that the type is not set by this port
52 // NOTE: Currently setOutput<BT::Any> is not allowed when port was declared with some other type (See
53 // https://github.com/BehaviorTree/BehaviorTree.CPP/issues/893). Therefore, GetParameter doesn't work currently...
54 // use one of the statically typed versions instead
55 using AnyType = typename std::conditional_t<std::is_same_v<BT::Any, T>, BT::AnyTypeAllowed, T>;
56 return {
57 BT::InputPort<std::string>(
58 INPUT_KEY_NODE_NAME, "Name of the targeted ROS 2 node. Leave empty to target this executor's node."),
59 BT::OutputPort<AnyType>(OUTPUT_KEY_PARAM_VALUE, "Output port for the parameter's value."),
60 BT::InputPort<std::string>(INPUT_KEY_PARAM_NAME, "Name of the parameter to get.")};
61 }
62
63 bool setRequest(Request::SharedPtr & request) override final
64 {
65 const BT::Expected<std::string> expected_name = getInput<std::string>(INPUT_KEY_PARAM_NAME);
66 if (!expected_name || expected_name.value().empty()) {
67 RCLCPP_ERROR(
68 logger_, "%s - Parameter name must not be empty.", context_.getFullyQualifiedTreeNodeName(this).c_str());
69 RCLCPP_DEBUG_EXPRESSION(
70 logger_, !expected_name, "%s - Error message: %s", context_.getFullyQualifiedTreeNodeName(this).c_str(),
71 expected_name.error().c_str());
72 return false;
73 }
74 requested_parameter_name_ = expected_name.value();
75 request->names.push_back(requested_parameter_name_);
76 return true;
77 }
78
79 BT::NodeStatus onResponseReceived(const Response::SharedPtr & response) override final
80 {
81 if (response->values.empty()) {
82 throw std::logic_error(
83 context_.getFullyQualifiedTreeNodeName(this) + " - Response vector doesn't contain any values.");
84 }
85 rclcpp::ParameterValue val(response->values[0]);
86 if (val.get_type() == rclcpp::PARAMETER_NOT_SET) {
87 RCLCPP_WARN(
88 logger_, "%s - Tried to get undeclared parameter '%s'.", context_.getFullyQualifiedTreeNodeName(this).c_str(),
89 requested_parameter_name_.c_str());
90 return BT::NodeStatus::FAILURE;
91 }
92
93 BT::Result set_ouput_result;
94 if constexpr (std::is_same_v<BT::Any, T>) {
95 // If ouput port type is BT::Any, we must try to infer the underlying type of the blackboard entry from received
96 // the parameter message
97 const BT::Expected<BT::Any> expected = createAnyFromParameterValue(val);
98 if (!expected) {
99 RCLCPP_ERROR(
100 logger_, "%s - %s", context_.getFullyQualifiedTreeNodeName(this).c_str(), expected.error().c_str());
101 return BT::NodeStatus::FAILURE;
102 }
103 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, expected.value());
104 } else {
105 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, val.get<T>());
106 }
107
108 if (!set_ouput_result) {
109 RCLCPP_ERROR(
110 logger_, "%s - %s", context_.getFullyQualifiedTreeNodeName(this).c_str(), set_ouput_result.error().c_str());
111 return BT::NodeStatus::FAILURE;
112 }
113
114 return BT::NodeStatus::SUCCESS;
115 }
116
117private:
118 std::string requested_parameter_name_;
119};
120
121// This version allows to infer the blackboard entry type from the type of the parameter. Behavior trees trying to read
122// the entry must know the current type and cast correspondingly.
123class GetParameter : public GetParameterTemplate<BT::Any>
124{
125public:
126 using GetParameterTemplate::GetParameterTemplate;
127};
128
129class GetParameterBool : public GetParameterTemplate<bool>
130{
131public:
132 using GetParameterTemplate::GetParameterTemplate;
133};
134
135class GetParameterInt : public GetParameterTemplate<int64_t>
136{
137public:
138 using GetParameterTemplate::GetParameterTemplate;
139};
140
141class GetParameterDouble : public GetParameterTemplate<double>
142{
143public:
144 using GetParameterTemplate::GetParameterTemplate;
145};
146
147class GetParameterString : public GetParameterTemplate<std::string>
148{
149public:
150 using GetParameterTemplate::GetParameterTemplate;
151};
152
153class GetParameterByteVec : public GetParameterTemplate<std::vector<uint8_t>>
154{
155public:
156 using GetParameterTemplate::GetParameterTemplate;
157};
158
159class GetParameterBoolVec : public GetParameterTemplate<std::vector<bool>>
160{
161public:
162 using GetParameterTemplate::GetParameterTemplate;
163};
164
165class GetParameterIntVec : public GetParameterTemplate<std::vector<int64_t>>
166{
167public:
168 using GetParameterTemplate::GetParameterTemplate;
169};
170
171class GetParameterDoubleVec : public GetParameterTemplate<std::vector<double>>
172{
173public:
174 using GetParameterTemplate::GetParameterTemplate;
175};
176
177class GetParameterStringVec : public GetParameterTemplate<std::vector<std::string>>
178{
179public:
180 using GetParameterTemplate::GetParameterTemplate;
181};
182
183} // namespace auto_apms_behavior_tree
184
185AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameter)
186AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterBool)
187AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterInt)
188AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterDouble)
189AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterString)
190AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterByteVec)
191AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterBoolVec)
192AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterIntVec)
193AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterDoubleVec)
194AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterStringVec)
Generic behavior tree node wrapper for a ROS 2 service client.
RosServiceNode(const std::string &instance_name, const Config &config, Context context)
#define AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(type)
Macro for registering a behavior tree node plugin.
Definition node.hpp:40
Useful tooling for incorporating behavior trees for task development.
Definition builder.hpp:30
BT::Expected< BT::Any > createAnyFromParameterValue(const rclcpp::ParameterValue &val)
Convert a ROS 2 parameter value to a BT::Any object.
Definition parameter.cpp:20