20#include "auto_apms_behavior_tree_core/exceptions.hpp"
21#include "auto_apms_behavior_tree_core/node/ros_node_context.hpp"
22#include "auto_apms_util/string.hpp"
23#include "behaviortree_cpp/condition_node.h"
24#include "rclcpp/qos.hpp"
56template <
class MessageT>
59 using Publisher =
typename rclcpp::Publisher<MessageT>;
62 using MessageType = MessageT;
63 using Config = BT::NodeConfig;
77 const std::string & instance_name,
const Config & config, Context context,
const rclcpp::QoS & qos = {10});
90 BT::PortsList basic = {BT::InputPort<std::string>(
"port",
"Name of the ROS 2 topic to publish to.")};
91 basic.insert(addition.begin(), addition.end());
127 const Context context_;
128 const rclcpp::Logger logger_;
131 BT::NodeStatus tick() override final;
133 const rclcpp::QoS qos_;
134 std::
string topic_name_;
135 bool dynamic_client_instance_ = false;
136 std::shared_ptr<Publisher> publisher_;
143template <class MessageT>
145 const std::
string & instance_name, const Config & config, Context context, const rclcpp::QoS & qos)
146: BT::ConditionNode(instance_name, config),
148 logger_(context.getChildLogger(
auto_apms_util::toSnakeCase(instance_name))),
151 if (
const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(
this)) {
157 dynamic_client_instance_ =
true;
161template <
class MessageT>
164 if (topic_name.empty()) {
165 throw exceptions::RosNodeError(
166 context_.getFullyQualifiedTreeNodeName(
this) +
" - Argument topic_name is empty when trying to create a client.");
170 if (publisher_ && topic_name_ == topic_name)
return true;
172 rclcpp::Node::SharedPtr node = context_.nh_.lock();
174 throw exceptions::RosNodeError(
175 context_.getFullyQualifiedTreeNodeName(
this) +
176 " - The weak pointer to the ROS 2 node expired. The tree node doesn't "
177 "take ownership of it.");
180 publisher_ = node->template create_publisher<MessageT>(topic_name, qos_);
181 topic_name_ = topic_name;
183 logger_,
"%s - Created publisher for topic '%s'.", context_.getFullyQualifiedTreeNodeName(
this).c_str(),
188template <
class MessageT>
189inline BT::NodeStatus RosPublisherNode<MessageT>::tick()
193 return BT::NodeStatus::FAILURE;
198 if (dynamic_client_instance_ && publisher_) {
199 dynamic_client_instance_ =
false;
204 if (status() == BT::NodeStatus::IDLE && dynamic_client_instance_) {
205 const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(
this);
209 throw exceptions::RosNodeError(
210 context_.getFullyQualifiedTreeNodeName(
this) +
211 " - Cannot create the publisher because the topic name couldn't be resolved using "
212 "the communication port expression specified by the node's "
213 "registration parameters (" +
214 NodeRegistrationOptions::PARAM_NAME_PORT +
": " + context_.registration_options_.port +
215 "). Error message: " + expected_name.error());
220 throw exceptions::RosNodeError(context_.getFullyQualifiedTreeNodeName(
this) +
" - publisher_ is nullptr.");
225 return BT::NodeStatus::FAILURE;
227 publisher_->publish(msg);
228 return BT::NodeStatus::SUCCESS;
231template <
class MessageT>
237template <
class MessageT>
Additional parameters specific to ROS 2 determined at runtime by TreeBuilder.
std::string getTopicName() const
Get the name of the topic name this node publishes to.
virtual bool setMessage(MessageT &msg)
Callback invoked when ticked to define the message to be published.
static BT::PortsList providedBasicPorts(BT::PortsList addition)
Derived nodes implementing the static method RosPublisherNode::providedPorts may call this method to ...
RosPublisherNode(const std::string &instance_name, const Config &config, Context context, const rclcpp::QoS &qos={10})
Constructor.
static BT::PortsList providedPorts()
If a behavior tree requires input/output data ports, the developer must define this method accordingl...
bool createPublisher(const std::string &topic_name)
Create the ROS 2 publisher.
Core API for AutoAPMS's behavior tree implementation.
Fundamental helper classes and utility functions.