AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
ros_publisher_node.hpp
1// Copyright 2024 Robin Müller
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// https://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#pragma once
16
17#include <memory>
18#include <string>
19
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"
25
27{
28
56template <class MessageT>
57class RosPublisherNode : public BT::ConditionNode
58{
59 using Publisher = typename rclcpp::Publisher<MessageT>;
60
61public:
62 using MessageType = MessageT;
63 using Config = BT::NodeConfig;
64 using Context = RosNodeContext;
65
76 explicit RosPublisherNode(
77 const std::string & instance_name, const Config & config, Context context, const rclcpp::QoS & qos = {10});
78
79 virtual ~RosPublisherNode() = default;
80
88 static BT::PortsList providedBasicPorts(BT::PortsList addition)
89 {
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());
92 return basic;
93 }
94
99 static BT::PortsList providedPorts() { return providedBasicPorts({}); }
100
111 virtual bool setMessage(MessageT & msg);
112
118 bool createPublisher(const std::string & topic_name);
119
124 std::string getTopicName() const;
125
126protected:
127 const Context context_;
128 const rclcpp::Logger logger_;
129
130private:
131 BT::NodeStatus tick() override final;
132
133 const rclcpp::QoS qos_;
134 std::string topic_name_;
135 bool dynamic_client_instance_ = false;
136 std::shared_ptr<Publisher> publisher_;
137};
138
139// #####################################################################################################################
140// ################################ DEFINITIONS ##############################################
141// #####################################################################################################################
142
143template <class MessageT>
145 const std::string & instance_name, const Config & config, Context context, const rclcpp::QoS & qos)
146: BT::ConditionNode(instance_name, config),
147 context_(context),
148 logger_(context.getChildLogger(auto_apms_util::toSnakeCase(instance_name))),
149 qos_{qos}
150{
151 if (const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(this)) {
152 createPublisher(expected_name.value());
153 } else {
154 // We assume that determining the communication port requires a blackboard pointer, which cannot be evaluated at
155 // construction time. The expression will be evaluated each time before the node is ticked the first time after
156 // successful execution.
157 dynamic_client_instance_ = true;
158 }
159}
160
161template <class MessageT>
162inline bool RosPublisherNode<MessageT>::createPublisher(const std::string & topic_name)
163{
164 if (topic_name.empty()) {
165 throw exceptions::RosNodeError(
166 context_.getFullyQualifiedTreeNodeName(this) + " - Argument topic_name is empty when trying to create a client.");
167 }
168
169 // Check if the publisher with given name is already set up
170 if (publisher_ && topic_name_ == topic_name) return true;
171
172 rclcpp::Node::SharedPtr node = context_.nh_.lock();
173 if (!node) {
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.");
178 }
179
180 publisher_ = node->template create_publisher<MessageT>(topic_name, qos_);
181 topic_name_ = topic_name;
182 RCLCPP_DEBUG(
183 logger_, "%s - Created publisher for topic '%s'.", context_.getFullyQualifiedTreeNodeName(this).c_str(),
184 topic_name.c_str());
185 return true;
186}
187
188template <class MessageT>
189inline BT::NodeStatus RosPublisherNode<MessageT>::tick()
190{
191 if (!rclcpp::ok()) {
192 halt();
193 return BT::NodeStatus::FAILURE;
194 }
195
196 // If client has been set up in derived constructor, event though this constructor couldn't, we discard the intention
197 // of dynamically creating the client
198 if (dynamic_client_instance_ && publisher_) {
199 dynamic_client_instance_ = false;
200 }
201
202 // Try again to create the client on first tick if this was not possible during construction or if client should be
203 // created from a blackboard entry on the start of every iteration
204 if (status() == BT::NodeStatus::IDLE && dynamic_client_instance_) {
205 const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(this);
206 if (expected_name) {
207 createPublisher(expected_name.value());
208 } else {
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());
216 }
217 }
218
219 if (!publisher_) {
220 throw exceptions::RosNodeError(context_.getFullyQualifiedTreeNodeName(this) + " - publisher_ is nullptr.");
221 }
222
223 MessageT msg;
224 if (!setMessage(msg)) {
225 return BT::NodeStatus::FAILURE;
226 }
227 publisher_->publish(msg);
228 return BT::NodeStatus::SUCCESS;
229}
230
231template <class MessageT>
232inline bool RosPublisherNode<MessageT>::setMessage(MessageT & /*msg*/)
233{
234 return true;
235}
236
237template <class MessageT>
239{
240 return topic_name_;
241}
242
243} // namespace auto_apms_behavior_tree::core
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.
Definition builder.hpp:30
Fundamental helper classes and utility functions.