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"
23#define INPUT_KEY_PARAM_NAME "parameter"
24#define OUTPUT_KEY_PARAM_VALUE "value"
25#define INPUT_KEY_NODE_NAME "node"
34 GetParameterTemplate(
const std::string & instance_name,
const Config & config,
const Context & context)
38 config.input_ports.find(INPUT_KEY_NODE_NAME) == config.input_ports.end() ||
39 config.input_ports.at(INPUT_KEY_NODE_NAME).empty()) {
41 createClient(context_.getFullyQualifiedRosNodeName() +
"/get_parameters");
45 static BT::PortsList providedPorts()
55 using AnyType =
typename std::conditional_t<std::is_same_v<BT::Any, T>, BT::AnyTypeAllowed, T>;
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.")};
63 bool setRequest(Request::SharedPtr & request)
override final
65 const BT::Expected<std::string> expected_name = getInput<std::string>(INPUT_KEY_PARAM_NAME);
66 if (!expected_name || expected_name.value().empty()) {
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());
74 requested_parameter_name_ = expected_name.value();
75 request->names.push_back(requested_parameter_name_);
79 BT::NodeStatus onResponseReceived(
const Response::SharedPtr & response)
override final
81 if (response->values.empty()) {
82 throw std::logic_error(
83 context_.getFullyQualifiedTreeNodeName(
this) +
" - Response vector doesn't contain any values.");
85 rclcpp::ParameterValue val(response->values[0]);
86 if (val.get_type() == rclcpp::PARAMETER_NOT_SET) {
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;
93 BT::Result set_ouput_result;
94 if constexpr (std::is_same_v<BT::Any, T>) {
100 logger_,
"%s - %s", context_.getFullyQualifiedTreeNodeName(
this).c_str(), expected.error().c_str());
101 return BT::NodeStatus::FAILURE;
103 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, expected.value());
105 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, val.get<T>());
108 if (!set_ouput_result) {
110 logger_,
"%s - %s", context_.getFullyQualifiedTreeNodeName(
this).c_str(), set_ouput_result.error().c_str());
111 return BT::NodeStatus::FAILURE;
114 return BT::NodeStatus::SUCCESS;
118 std::string requested_parameter_name_;
123class GetParameter :
public GetParameterTemplate<BT::Any>
126 using GetParameterTemplate::GetParameterTemplate;
129class GetParameterBool :
public GetParameterTemplate<bool>
132 using GetParameterTemplate::GetParameterTemplate;
135class GetParameterInt :
public GetParameterTemplate<int64_t>
138 using GetParameterTemplate::GetParameterTemplate;
141class GetParameterDouble :
public GetParameterTemplate<double>
144 using GetParameterTemplate::GetParameterTemplate;
147class GetParameterString :
public GetParameterTemplate<std::string>
150 using GetParameterTemplate::GetParameterTemplate;
153class GetParameterByteVec :
public GetParameterTemplate<std::vector<uint8_t>>
156 using GetParameterTemplate::GetParameterTemplate;
159class GetParameterBoolVec :
public GetParameterTemplate<std::vector<bool>>
162 using GetParameterTemplate::GetParameterTemplate;
165class GetParameterIntVec :
public GetParameterTemplate<std::vector<int64_t>>
168 using GetParameterTemplate::GetParameterTemplate;
171class GetParameterDoubleVec :
public GetParameterTemplate<std::vector<double>>
174 using GetParameterTemplate::GetParameterTemplate;
177class GetParameterStringVec :
public GetParameterTemplate<std::vector<std::string>>
180 using GetParameterTemplate::GetParameterTemplate;
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.
Useful tooling for incorporating behavior trees for task development.
BT::Expected< BT::Any > createAnyFromParameterValue(const rclcpp::ParameterValue &val)
Convert a ROS 2 parameter value to a BT::Any object.