AutoAPMS
Resilient Robot Mission Management
All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Modules Pages
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 using AnyType = typename std::conditional_t<std::is_same_v<BT::Any, T>, BT::AnyTypeAllowed, T>;
53 return {
54 BT::InputPort<std::string>(
55 INPUT_KEY_NODE_NAME, "Name of the targeted ROS 2 node. Leave empty to target this executor's node."),
56 BT::OutputPort<AnyType>(OUTPUT_KEY_PARAM_VALUE, "Output port for the parameter's value."),
57 BT::InputPort<std::string>(INPUT_KEY_PARAM_NAME, "Name of the parameter to get.")};
58 }
59
60 bool setRequest(Request::SharedPtr & request) override final
61 {
62 const BT::Expected<std::string> expected_name = getInput<std::string>(INPUT_KEY_PARAM_NAME);
63 if (!expected_name || expected_name.value().empty()) {
64 RCLCPP_ERROR(
65 logger_, "%s - Parameter name must not be empty.", context_.getFullyQualifiedTreeNodeName(this).c_str());
66 RCLCPP_DEBUG_EXPRESSION(
67 logger_, !expected_name, "%s - Error message: %s", context_.getFullyQualifiedTreeNodeName(this).c_str(),
68 expected_name.error().c_str());
69 return false;
70 }
71 requested_parameter_name_ = expected_name.value();
72 request->names.push_back(requested_parameter_name_);
73 return true;
74 }
75
76 BT::NodeStatus onResponseReceived(const Response::SharedPtr & response) override final
77 {
78 if (response->values.empty()) {
79 throw std::logic_error(
80 context_.getFullyQualifiedTreeNodeName(this) + " - Response vector doesn't contain any values.");
81 }
82 rclcpp::ParameterValue val(response->values[0]);
83 if (val.get_type() == rclcpp::PARAMETER_NOT_SET) {
84 RCLCPP_WARN(
85 logger_, "%s - Tried to get undeclared parameter '%s'.", context_.getFullyQualifiedTreeNodeName(this).c_str(),
86 requested_parameter_name_.c_str());
87 return BT::NodeStatus::FAILURE;
88 }
89
90 BT::Result set_ouput_result;
91 if constexpr (std::is_same_v<BT::Any, T>) {
92 // If ouput port type is BT::Any, we must try to infer the underlying type of the blackboard entry from received
93 // the parameter message
94 const BT::Expected<BT::Any> expected = createAnyFromParameterValue(val);
95 if (!expected) {
96 RCLCPP_ERROR(
97 logger_, "%s - %s", context_.getFullyQualifiedTreeNodeName(this).c_str(), expected.error().c_str());
98 return BT::NodeStatus::FAILURE;
99 }
100 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, expected.value());
101 } else {
102 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, val.get<T>());
103 }
104
105 if (!set_ouput_result) {
106 RCLCPP_ERROR(
107 logger_, "%s - %s", context_.getFullyQualifiedTreeNodeName(this).c_str(), set_ouput_result.error().c_str());
108 return BT::NodeStatus::FAILURE;
109 }
110
111 return BT::NodeStatus::SUCCESS;
112 }
113
114private:
115 std::string requested_parameter_name_;
116};
117
118// This version allows to infer the blackboard entry type from the type of the parameter. Behavior trees trying to read
119// the entry must know the current type and cast correspondingly.
120class GetParameter : public GetParameterTemplate<BT::Any>
121{
122public:
123 using GetParameterTemplate::GetParameterTemplate;
124};
125
126class GetParameterBool : public GetParameterTemplate<bool>
127{
128public:
129 using GetParameterTemplate::GetParameterTemplate;
130};
131
132class GetParameterInt : public GetParameterTemplate<int64_t>
133{
134public:
135 using GetParameterTemplate::GetParameterTemplate;
136};
137
138class GetParameterDouble : public GetParameterTemplate<double>
139{
140public:
141 using GetParameterTemplate::GetParameterTemplate;
142};
143
144class GetParameterString : public GetParameterTemplate<std::string>
145{
146public:
147 using GetParameterTemplate::GetParameterTemplate;
148};
149
150class GetParameterByteVec : public GetParameterTemplate<std::vector<uint8_t>>
151{
152public:
153 using GetParameterTemplate::GetParameterTemplate;
154};
155
156class GetParameterBoolVec : public GetParameterTemplate<std::vector<bool>>
157{
158public:
159 using GetParameterTemplate::GetParameterTemplate;
160};
161
162class GetParameterIntVec : public GetParameterTemplate<std::vector<int64_t>>
163{
164public:
165 using GetParameterTemplate::GetParameterTemplate;
166};
167
168class GetParameterDoubleVec : public GetParameterTemplate<std::vector<double>>
169{
170public:
171 using GetParameterTemplate::GetParameterTemplate;
172};
173
174class GetParameterStringVec : public GetParameterTemplate<std::vector<std::string>>
175{
176public:
177 using GetParameterTemplate::GetParameterTemplate;
178};
179
180} // namespace auto_apms_behavior_tree
181
182AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameter)
183AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterBool)
184AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterInt)
185AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterDouble)
186AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterString)
187AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterByteVec)
188AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterBoolVec)
189AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterIntVec)
190AUTO_APMS_BEHAVIOR_TREE_DECLARE_NODE(auto_apms_behavior_tree::GetParameterDoubleVec)
191AUTO_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:43
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