154 const Context context_;
155 const rclcpp::Logger logger_;
158 BT::NodeStatus tick() override final;
160 static std::mutex & registryMutex();
163 static SubscribersRegistry & getRegistry();
165 const rclcpp::QoS qos_;
166 std::
string topic_name_;
167 bool dynamic_client_instance_ = false;
168 std::shared_ptr<SubscriberInstance> sub_instance_;
169 std::shared_ptr<MessageT> last_msg_;
170 boost::signals2::connection signal_connection_;
171 std::
string subscriber_key_;
178template <class MessageT>
180 rclcpp::Node::SharedPtr node, rclcpp::CallbackGroup::SharedPtr group, const std::
string & topic_name,
181 const rclcpp::QoS & qos)
183 rclcpp::SubscriptionOptions option;
184 option.callback_group = group;
187 auto callback = [
this](
const std::shared_ptr<MessageT> msg) {
188 this->last_msg = msg;
189 this->broadcaster(msg);
191 subscriber = node->create_subscription<MessageT>(topic_name, qos, callback, option);
195template <
class MessageT>
197 const std::string & instance_name,
const Config & config, Context context,
const rclcpp::QoS & qos)
198: BT::ConditionNode{instance_name, config},
200 logger_(context.getChildLogger(
auto_apms_util::toSnakeCase(instance_name))),
203 if (
const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(
this)) {
204 createSubscriber(expected_name.value());
209 dynamic_client_instance_ = true;
213template <
class MessageT>
216 if (topic_name.empty()) {
217 throw exceptions::RosNodeError(
218 context_.getFullyQualifiedTreeNodeName(
this) +
" - Argument topic_name is empty when trying to create a client.");
222 if (sub_instance_ && topic_name == sub_instance_->name)
return true;
224 std::unique_lock lk(registryMutex());
226 rclcpp::Node::SharedPtr node = context_.nh_.lock();
228 throw exceptions::RosNodeError(
229 context_.getFullyQualifiedTreeNodeName(
this) +
230 " - The weak pointer to the ROS 2 node expired. The tree node doesn't "
231 "take ownership of it.");
233 rclcpp::CallbackGroup::SharedPtr group = context_.cb_group_.lock();
235 throw exceptions::RosNodeError(
236 context_.getFullyQualifiedTreeNodeName(
this) +
237 " - The weak pointer to the ROS 2 callback group expired. The tree node doesn't "
238 "take ownership of it.");
240 subscriber_key_ = std::string(node->get_fully_qualified_name()) +
"/" + topic_name;
242 auto & registry = getRegistry();
243 auto it = registry.find(subscriber_key_);
244 if (it == registry.end() || it->second.expired()) {
245 sub_instance_ = std::make_shared<SubscriberInstance>(node, group, topic_name, qos_);
246 registry.insert({subscriber_key_, sub_instance_});
248 logger_,
"%s - Created subscriber for topic '%s'.", context_.getFullyQualifiedTreeNodeName(
this).c_str(),
251 sub_instance_ = it->second.lock();
255 if (sub_instance_->last_msg) {
256 last_msg_ = sub_instance_->last_msg;
261 sub_instance_->broadcaster.connect([
this](
const std::shared_ptr<MessageT> msg) { last_msg_ = msg; });
266template <
class MessageT>
267inline BT::NodeStatus RosSubscriberNode<MessageT>::tick()
271 return BT::NodeStatus::FAILURE;
276 if (dynamic_client_instance_ && sub_instance_) {
277 dynamic_client_instance_ =
false;
282 if (status() == BT::NodeStatus::IDLE && dynamic_client_instance_) {
283 const BT::Expected<std::string> expected_name = context_.getCommunicationPortName(
this);
285 createSubscriber(expected_name.value());
287 throw exceptions::RosNodeError(
289 " - Cannot create the subscriber because the topic name couldn't be resolved using "
290 "the communication port expression specified by the node's "
291 "registration parameters (" +
292 NodeRegistrationOptions::PARAM_NAME_PORT +
": " + context_.registration_options_.
port +
293 "). Error message: " + expected_name.error());
297 if (!sub_instance_) {
301 auto check_status = [
this](BT::NodeStatus status) {
302 if (!isStatusCompleted(status)) {
303 throw exceptions::RosNodeError(
308 auto status = check_status(onTick(last_msg_));
313template <
class MessageT>
316 if (!last_msg_ptr)
return BT::NodeStatus::FAILURE;
320template <
class MessageT>
323 return BT::NodeStatus::SUCCESS;
326template <
class MessageT>
329 if (sub_instance_)
return sub_instance_->name;