17#include "auto_apms_behavior_tree/util/parameter.hpp"
18#include "auto_apms_behavior_tree_core/node.hpp"
19#include "rcl_interfaces/msg/parameter.hpp"
20#include "rcl_interfaces/msg/parameter_type.hpp"
21#include "rcl_interfaces/msg/parameter_value.hpp"
22#include "rcl_interfaces/srv/set_parameters.hpp"
24#define INPUT_KEY_PARAM_NAME "parameter"
25#define INPUT_KEY_PARAM_VALUE "value"
26#define INPUT_KEY_NODE_NAME "node"
35 SetParameterTemplate(
const std::string & instance_name,
const Config & config,
const Context & context)
39 config.input_ports.find(INPUT_KEY_NODE_NAME) == config.input_ports.end() ||
40 config.input_ports.at(INPUT_KEY_NODE_NAME).empty()) {
42 createClient(context_.getFullyQualifiedRosNodeName() +
"/set_parameters");
46 static BT::PortsList providedPorts()
53 using AnyType =
typename std::conditional_t<std::is_same_v<BT::Any, T>, BT::AnyTypeAllowed, T>;
55 BT::InputPort<std::string>(
56 INPUT_KEY_NODE_NAME,
"Name of the targeted ROS 2 node. Leave empty to target this executor's node."),
57 BT::InputPort<AnyType>(INPUT_KEY_PARAM_VALUE,
"Value of the parameter to be set."),
58 BT::InputPort<std::string>(INPUT_KEY_PARAM_NAME,
"Name of the parameter to be set."),
62 bool setRequest(Request::SharedPtr & request)
override final
64 rcl_interfaces::msg::Parameter parameter;
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 parameter.name = expected_name.value();
76 rclcpp::ParameterType inferred_param_type = rclcpp::PARAMETER_NOT_SET;
77 if constexpr (!std::is_same_v<BT::Any, T>) {
78 inferred_param_type = rclcpp::ParameterValue(T()).get_type();
81 rcl_interfaces::msg::ParameterValue param_val;
82 const BT::PortsRemapping::iterator it = config().input_ports.find(INPUT_KEY_PARAM_VALUE);
83 if (it == config().input_ports.end() || it->second.empty()) {
84 if constexpr (std::is_same_v<BT::Any, T>) {
85 throw exceptions::RosNodeError(
86 context_.getFullyQualifiedTreeNodeName(
this) +
" - Parameter value must not be empty.");
89 param_val.type = inferred_param_type;
94 if (!isBlackboardPointer(it->second) && std::is_same_v<BT::Any, T>) {
95 throw exceptions::RosNodeError(
96 context_.getFullyQualifiedTreeNodeName(
this) +
97 " - Cannot infer type from literal string. Use one of the type specialized versions of SetParameter "
101 const BT::Expected<T> expected_entry = getInput<T>(INPUT_KEY_PARAM_VALUE);
102 if (!expected_entry) {
104 logger_,
"%s - %s", context_.getFullyQualifiedTreeNodeName(
this).c_str(), expected_entry.error().c_str());
107 const BT::Expected<rclcpp::ParameterValue> expected_param_val =
109 if (!expected_param_val) {
112 logger_,
"%s - %s", context_.getFullyQualifiedTreeNodeName(
this).c_str(), expected_param_val.error().c_str());
115 param_val = expected_param_val.value().to_value_msg();
118 parameter.value = param_val;
119 requested_parameter_ = rclcpp::Parameter(parameter.name, parameter.value);
120 request->parameters.push_back(parameter);
124 BT::NodeStatus onResponseReceived(
const Response::SharedPtr & response)
override final
126 const rcl_interfaces::msg::SetParametersResult & result = response->results[0];
127 if (!result.successful) {
129 logger_,
"Failed to set parameter %s = %s (Type: %s) via service '%s': %s",
130 requested_parameter_.get_name().c_str(), requested_parameter_.value_to_string().c_str(),
131 requested_parameter_.get_type_name().c_str(),
getServiceName().c_str(), result.reason.c_str());
132 return BT::NodeStatus::FAILURE;
134 return BT::NodeStatus::SUCCESS;
138 rclcpp::Parameter requested_parameter_;
142class SetParameter :
public SetParameterTemplate<BT::Any>
145 using SetParameterTemplate::SetParameterTemplate;
148class SetParameterBool :
public SetParameterTemplate<bool>
151 using SetParameterTemplate::SetParameterTemplate;
154class SetParameterInt :
public SetParameterTemplate<int64_t>
157 using SetParameterTemplate::SetParameterTemplate;
160class SetParameterDouble :
public SetParameterTemplate<double>
163 using SetParameterTemplate::SetParameterTemplate;
166class SetParameterString :
public SetParameterTemplate<std::string>
169 using SetParameterTemplate::SetParameterTemplate;
172class SetParameterByteVec :
public SetParameterTemplate<std::vector<uint8_t>>
175 using SetParameterTemplate::SetParameterTemplate;
178class SetParameterBoolVec :
public SetParameterTemplate<std::vector<bool>>
181 using SetParameterTemplate::SetParameterTemplate;
184class SetParameterIntVec :
public SetParameterTemplate<std::vector<int64_t>>
187 using SetParameterTemplate::SetParameterTemplate;
190class SetParameterDoubleVec :
public SetParameterTemplate<std::vector<double>>
193 using SetParameterTemplate::SetParameterTemplate;
196class SetParameterStringVec :
public SetParameterTemplate<std::vector<std::string>>
199 using SetParameterTemplate::SetParameterTemplate;
Generic behavior tree node wrapper for a ROS 2 service client.
std::string getServiceName() const
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< rclcpp::ParameterValue > createParameterValueFromAny(const BT::Any &any, rclcpp::ParameterType type)
Convert a BT::Any object to a ROS 2 parameter value.