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()
52 using AnyType =
typename std::conditional_t<std::is_same_v<BT::Any, T>, BT::AnyTypeAllowed, T>;
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.")};
60 bool setRequest(Request::SharedPtr & request)
override final
62 const BT::Expected<std::string> expected_name = getInput<std::string>(INPUT_KEY_PARAM_NAME);
63 if (!expected_name || expected_name.value().empty()) {
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());
71 requested_parameter_name_ = expected_name.value();
72 request->names.push_back(requested_parameter_name_);
76 BT::NodeStatus onResponseReceived(
const Response::SharedPtr & response)
override final
78 if (response->values.empty()) {
79 throw std::logic_error(
80 context_.getFullyQualifiedTreeNodeName(
this) +
" - Response vector doesn't contain any values.");
82 rclcpp::ParameterValue val(response->values[0]);
83 if (val.get_type() == rclcpp::PARAMETER_NOT_SET) {
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;
90 BT::Result set_ouput_result;
91 if constexpr (std::is_same_v<BT::Any, T>) {
97 logger_,
"%s - %s", context_.getFullyQualifiedTreeNodeName(
this).c_str(), expected.error().c_str());
98 return BT::NodeStatus::FAILURE;
100 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, expected.value());
102 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, val.get<T>());
105 if (!set_ouput_result) {
107 logger_,
"%s - %s", context_.getFullyQualifiedTreeNodeName(
this).c_str(), set_ouput_result.error().c_str());
108 return BT::NodeStatus::FAILURE;
111 return BT::NodeStatus::SUCCESS;
115 std::string requested_parameter_name_;
120class GetParameter :
public GetParameterTemplate<BT::Any>
123 using GetParameterTemplate::GetParameterTemplate;
126class GetParameterBool :
public GetParameterTemplate<bool>
129 using GetParameterTemplate::GetParameterTemplate;
132class GetParameterInt :
public GetParameterTemplate<int64_t>
135 using GetParameterTemplate::GetParameterTemplate;
138class GetParameterDouble :
public GetParameterTemplate<double>
141 using GetParameterTemplate::GetParameterTemplate;
144class GetParameterString :
public GetParameterTemplate<std::string>
147 using GetParameterTemplate::GetParameterTemplate;
150class GetParameterByteVec :
public GetParameterTemplate<std::vector<uint8_t>>
153 using GetParameterTemplate::GetParameterTemplate;
156class GetParameterBoolVec :
public GetParameterTemplate<std::vector<bool>>
159 using GetParameterTemplate::GetParameterTemplate;
162class GetParameterIntVec :
public GetParameterTemplate<std::vector<int64_t>>
165 using GetParameterTemplate::GetParameterTemplate;
168class GetParameterDoubleVec :
public GetParameterTemplate<std::vector<double>>
171 using GetParameterTemplate::GetParameterTemplate;
174class GetParameterStringVec :
public GetParameterTemplate<std::vector<std::string>>
177 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.