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 std::string node_name = context_.getFullyQualifiedRosNodeName();
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);
47 static BT::PortsList providedPorts()
54 using AnyType =
typename std::conditional_t<std::is_same_v<BT::Any, T>, BT::AnyTypeAllowed, T>;
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.")};
62 bool setRequest(Request::SharedPtr & request)
override final
64 const BT::Expected<std::string> expected_name = getInput<std::string>(INPUT_KEY_PARAM_NAME);
65 if (!expected_name || expected_name.value().empty()) {
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());
73 requested_parameter_name_ = expected_name.value();
74 request->names.push_back(requested_parameter_name_);
78 BT::NodeStatus onResponseReceived(
const Response::SharedPtr & response)
override final
80 if (response->values.empty()) {
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;
86 rclcpp::ParameterValue val(response->values[0]);
87 if (val.get_type() == rclcpp::PARAMETER_NOT_SET) {
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;
94 BT::Result set_ouput_result;
95 if constexpr (std::is_same_v<BT::Any, T>) {
101 logger_,
"%s - %s", context_.getFullyQualifiedTreeNodeName(
this).c_str(), expected.error().c_str());
102 return BT::NodeStatus::FAILURE;
104 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, expected.value());
106 set_ouput_result = setOutput(OUTPUT_KEY_PARAM_VALUE, val.get<T>());
109 if (!set_ouput_result) {
111 logger_,
"%s - %s", context_.getFullyQualifiedTreeNodeName(
this).c_str(), set_ouput_result.error().c_str());
112 return BT::NodeStatus::FAILURE;
115 return BT::NodeStatus::SUCCESS;
119 std::string requested_parameter_name_;
124class GetParameter :
public GetParameterTemplate<BT::Any>
127 using GetParameterTemplate::GetParameterTemplate;
130class GetParameterBool :
public GetParameterTemplate<bool>
133 using GetParameterTemplate::GetParameterTemplate;
136class GetParameterInt :
public GetParameterTemplate<int>
139 using GetParameterTemplate::GetParameterTemplate;
142class GetParameterDouble :
public GetParameterTemplate<double>
145 using GetParameterTemplate::GetParameterTemplate;
148class GetParameterString :
public GetParameterTemplate<std::string>
151 using GetParameterTemplate::GetParameterTemplate;
154class GetParameterByteVec :
public GetParameterTemplate<std::vector<uint8_t>>
157 using GetParameterTemplate::GetParameterTemplate;
160class GetParameterBoolVec :
public GetParameterTemplate<std::vector<bool>>
163 using GetParameterTemplate::GetParameterTemplate;
166class GetParameterIntVec :
public GetParameterTemplate<std::vector<int>>
169 using GetParameterTemplate::GetParameterTemplate;
172class GetParameterDoubleVec :
public GetParameterTemplate<std::vector<double>>
175 using GetParameterTemplate::GetParameterTemplate;
178class GetParameterStringVec :
public GetParameterTemplate<std::vector<std::string>>
181 using GetParameterTemplate::GetParameterTemplate;
Generic behavior tree node wrapper for a ROS 2 service client.
bool createClient(const std::string &service_name)
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.
Powerful 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.