AutoAPMS
Streamlining behaviors in ROS 2
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// 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#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 input port is empty or not provided, refer to this ROS 2 node as the target
38 std::string node_name = context_.getFullyQualifiedRosNodeName();
39 if (
40 config.input_ports.find(INPUT_KEY_NODE_NAME) != config.input_ports.end() &&
41 !config.input_ports.at(INPUT_KEY_NODE_NAME).empty()) {
42 node_name = config.input_ports.at(INPUT_KEY_NODE_NAME);
43 }
44 createClient(node_name + "/get_parameters");
45 }
46
47 static BT::PortsList providedPorts()
48 {
49 // We do not use the default port for the service name
50
51 // There is no string conversion function for variables that are type initialized using the value port if the
52 // BT::Any version is used. To prevent errors when using these variables in e.g. the scripting language we have to
53 // set the type to BT::AnyTypeAllowed to truly indicate that the type is not set by this port
54 using AnyType = typename std::conditional_t<std::is_same_v<BT::Any, T>, BT::AnyTypeAllowed, T>;
55 return {
56 BT::InputPort<std::string>(
57 INPUT_KEY_NODE_NAME, "Name of the targeted ROS 2 node. Leave empty to target this executor's node."),
58 BT::OutputPort<AnyType>(OUTPUT_KEY_PARAM_VALUE, "Output port for the parameter's value."),
59 BT::InputPort<std::string>(INPUT_KEY_PARAM_NAME, "Name of the parameter to get.")};
60 }
61
62 bool setRequest(Request::SharedPtr & request) override final
63 {
64 const BT::Expected<std::string> expected_name = getInput<std::string>(INPUT_KEY_PARAM_NAME);
65 if (!expected_name || expected_name.value().empty()) {
66 RCLCPP_ERROR(
67 logger_, "%s - Parameter name must not be empty.", context_.getFullyQualifiedTreeNodeName(this).c_str());
68 RCLCPP_DEBUG_EXPRESSION(
69 logger_, !expected_name, "%s - Error message: %s", context_.getFullyQualifiedTreeNodeName(this).c_str(),
70 expected_name.error().c_str());
71 return false;
72 }
73 requested_parameter_name_ = expected_name.value();
74 request->names.push_back(requested_parameter_name_);
75 return true;
76 }
77
78 BT::NodeStatus onResponseReceived(const Response::SharedPtr & response) override final
79 {
80 if (response->values.empty()) {
81 RCLCPP_DEBUG(
82 logger_, "%s - Parameter '%s' not found on the targeted node.",
83 context_.getFullyQualifiedTreeNodeName(this).c_str(), requested_parameter_name_.c_str());
84 return BT::NodeStatus::FAILURE;
85 }
86 rclcpp::ParameterValue val(response->values[0]);
87 if (val.get_type() == rclcpp::PARAMETER_NOT_SET) {
88 RCLCPP_DEBUG(
89 logger_, "%s - Tried to get undeclared parameter '%s'.", context_.getFullyQualifiedTreeNodeName(this).c_str(),
90 requested_parameter_name_.c_str());
91 return BT::NodeStatus::FAILURE;
92 }
93
94 BT::Result set_ouput_result;
95 if constexpr (std::is_same_v<BT::Any, T>) {
96 // If ouput port type is BT::Any, we must try to infer the underlying type of the blackboard entry from received
97 // the parameter message
98 const BT::Expected<BT::Any> expected = createAnyFromParameterValue(val);
99 if (!expected) {
100 RCLCPP_ERROR(
101 logger_, "%s - %s", context_.getFullyQualifiedTreeNodeName(this).c_str(), expected.error().c_str());
102 return BT::NodeStatus::FAILURE;
103 }
104 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, expected.value());
105 } else {
106 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, val.get<T>());
107 }
108
109 if (!set_ouput_result) {
110 RCLCPP_ERROR(
111 logger_, "%s - %s", context_.getFullyQualifiedTreeNodeName(this).c_str(), set_ouput_result.error().c_str());
112 return BT::NodeStatus::FAILURE;
113 }
114
115 return BT::NodeStatus::SUCCESS;
116 }
117
118private:
119 std::string requested_parameter_name_;
120};
121
122// This version allows to infer the blackboard entry type from the type of the parameter. Behavior trees trying to read
123// the entry must know the current type and cast correspondingly.
124class GetParameter : public GetParameterTemplate<BT::Any>
125{
126public:
127 using GetParameterTemplate::GetParameterTemplate;
128};
129
130class GetParameterBool : public GetParameterTemplate<bool>
131{
132public:
133 using GetParameterTemplate::GetParameterTemplate;
134};
135
136class GetParameterInt : public GetParameterTemplate<int>
137{
138public:
139 using GetParameterTemplate::GetParameterTemplate;
140};
141
142class GetParameterDouble : public GetParameterTemplate<double>
143{
144public:
145 using GetParameterTemplate::GetParameterTemplate;
146};
147
148class GetParameterString : public GetParameterTemplate<std::string>
149{
150public:
151 using GetParameterTemplate::GetParameterTemplate;
152};
153
154class GetParameterByteVec : public GetParameterTemplate<std::vector<uint8_t>>
155{
156public:
157 using GetParameterTemplate::GetParameterTemplate;
158};
159
160class GetParameterBoolVec : public GetParameterTemplate<std::vector<bool>>
161{
162public:
163 using GetParameterTemplate::GetParameterTemplate;
164};
165
166class GetParameterIntVec : public GetParameterTemplate<std::vector<int>>
167{
168public:
169 using GetParameterTemplate::GetParameterTemplate;
170};
171
172class GetParameterDoubleVec : public GetParameterTemplate<std::vector<double>>
173{
174public:
175 using GetParameterTemplate::GetParameterTemplate;
176};
177
178class GetParameterStringVec : public GetParameterTemplate<std::vector<std::string>>
179{
180public:
181 using GetParameterTemplate::GetParameterTemplate;
182};
183
184} // namespace auto_apms_behavior_tree
185
186AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::GetParameter)
187AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::GetParameterBool)
188AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::GetParameterInt)
189AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::GetParameterDouble)
190AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::GetParameterString)
191AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::GetParameterByteVec)
192AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::GetParameterBoolVec)
193AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::GetParameterIntVec)
194AUTO_APMS_BEHAVIOR_TREE_REGISTER_NODE(auto_apms_behavior_tree::GetParameterDoubleVec)
195AUTO_APMS_BEHAVIOR_TREE_REGISTER_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_REGISTER_NODE(type)
Macro for registering a behavior tree node plugin.
Definition node.hpp:43
Powerful tooling for incorporating behavior trees for task development.
Definition behavior.hpp:32
BT::Expected< BT::Any > createAnyFromParameterValue(const rclcpp::ParameterValue &val)
Convert a ROS 2 parameter value to a BT::Any object.
Definition parameter.cpp:20