195 const Context context_;
196 const rclcpp::Logger logger_;
198 BT::NodeStatus tick() override final;
200 void halt() override final;
203 static std::mutex & getMutex();
205 static ClientsRegistry & getRegistry();
207 bool dynamic_client_instance_ = false;
208 std::shared_ptr<ServiceClientInstance> client_instance_;
209 typename ServiceClient::SharedFuture future_;
211 rclcpp::Time time_request_sent_;
212 BT::NodeStatus on_feedback_state_change_;
213 typename Response::SharedPtr response_;
220template <class ServiceT>
221inline
RosServiceNode<ServiceT>::ServiceClientInstance::ServiceClientInstance(
222 rclcpp::Node::SharedPtr node, rclcpp::CallbackGroup::SharedPtr group, const std::
string & service_name)
224 service_client = node->create_client<ServiceT>(service_name, rclcpp::ServicesQoS(), group);
228template <
class ServiceT>
230 const std::string & instance_name,
const Config & config, Context context)
231: BT::ActionNodeBase(instance_name, config),
233 logger_(context.getChildLogger(
auto_apms_util::toSnakeCase(instance_name)))
236 this->modifyPortsRemapping(context_.copyAliasedPortValuesToOriginalPorts(
this));
239 if (
const BT::Expected<std::string> expected_name = context_.getTopicName(
this)) {
245 dynamic_client_instance_ =
true;
249template <
class ServiceT>
250inline BT::NodeStatus RosServiceNode<ServiceT>::tick()
254 return BT::NodeStatus::FAILURE;
259 if (dynamic_client_instance_ && client_instance_) {
260 dynamic_client_instance_ =
false;
265 if (status() == BT::NodeStatus::IDLE && dynamic_client_instance_) {
266 const BT::Expected<std::string> expected_name = context_.getTopicName(
this);
268 createClient(expected_name.value());
270 throw exceptions::RosNodeError(
272 " - Cannot create the service client because the service name couldn't be resolved using "
273 "the expression specified by the node's registration parameters (" +
274 NodeRegistrationOptions::PARAM_NAME_ROS2TOPIC +
": " + context_.registration_options_.
topic +
275 "). Error message: " + expected_name.error());
279 if (!client_instance_) {
283 auto & service_client = client_instance_->service_client;
285 auto check_status = [
this](BT::NodeStatus status) {
286 if (!isStatusCompleted(status)) {
287 throw exceptions::RosNodeError(
294 if (status() == BT::NodeStatus::IDLE) {
295 setStatus(BT::NodeStatus::RUNNING);
297 on_feedback_state_change_ = BT::NodeStatus::RUNNING;
300 typename Request::SharedPtr request = std::make_shared<Request>();
302 if (!setRequest(request)) {
303 return check_status(onFailure(INVALID_REQUEST));
307 if (!service_client->service_is_ready()) {
308 return onFailure(SERVICE_UNREACHABLE);
311 const auto future_and_request_id =
312 service_client->async_send_request(request, [
this](
typename ServiceClient::SharedFuture response) {
313 if (response.wait_for(std::chrono::seconds(0)) != std::future_status::ready) {
314 throw exceptions::RosNodeError(
317 this->response_ = response.get();
319 future_ = future_and_request_id.future;
320 request_id_ = future_and_request_id.request_id;
324 return BT::NodeStatus::RUNNING;
327 if (status() == BT::NodeStatus::RUNNING) {
333 client_instance_->service_client->remove_pending_request(request_id_);
334 return check_status(onFailure(SERVICE_TIMEOUT));
336 return BT::NodeStatus::RUNNING;
337 }
else if (future_.valid()) {
345 return check_status(onResponseReceived(response_));
347 return BT::NodeStatus::RUNNING;
350template <
class ServiceT>
351inline void RosServiceNode<ServiceT>::halt()
353 if (status() == BT::NodeStatus::RUNNING) {
358template <
class ServiceT>
364template <
class ServiceT>
367 return BT::NodeStatus::SUCCESS;
370template <
class ServiceT>
373 const std::string msg = context_.getFullyQualifiedTreeNodeName(
this) +
" - Unexpected error " +
374 std::to_string(error) +
": " +
toStr(error) +
".";
375 RCLCPP_ERROR_STREAM(logger_, msg);
376 throw exceptions::RosNodeError(msg);
379template <
class ServiceT>
382 if (service_name.empty()) {
383 throw exceptions::RosNodeError(
384 context_.getFullyQualifiedTreeNodeName(
this) +
385 " - Argument service_name is empty when trying to create the client.");
390 client_instance_ && service_name == client_instance_->name &&
391 client_instance_->service_client->service_is_ready()) {
395 std::unique_lock lk(getMutex());
397 rclcpp::Node::SharedPtr node = context_.nh_.lock();
399 throw exceptions::RosNodeError(
400 context_.getFullyQualifiedTreeNodeName(
this) +
401 " - The weak pointer to the ROS 2 node expired. The tree node doesn't "
402 "take ownership of it.");
404 rclcpp::CallbackGroup::SharedPtr group = context_.cb_group_.lock();
406 throw exceptions::RosNodeError(
407 context_.getFullyQualifiedTreeNodeName(
this) +
408 " - The weak pointer to the ROS 2 callback group expired. The tree node doesn't "
409 "take ownership of it.");
411 auto client_key = std::string(node->get_fully_qualified_name()) +
"/" + service_name;
413 auto & registry = getRegistry();
414 auto it = registry.find(client_key);
415 if (it == registry.end() || it->second.expired()) {
416 client_instance_ = std::make_shared<ServiceClientInstance>(node, group, service_name);
417 registry.insert({client_key, client_instance_});
419 logger_,
"%s - Created client for service '%s'.", context_.getFullyQualifiedTreeNodeName(
this).c_str(),
420 service_name.c_str());
422 client_instance_ = it->second.lock();
425 bool found = client_instance_->service_client->wait_for_service(context_.registration_options_.wait_timeout);
427 std::string msg = context_.getFullyQualifiedTreeNodeName(
this) +
" - Service with name '" + client_instance_->name +
428 "' is not reachable.";
429 if (context_.registration_options_.allow_unreachable) {
430 RCLCPP_WARN_STREAM(logger_, msg);
432 RCLCPP_ERROR_STREAM(logger_, msg);
433 throw exceptions::RosNodeError(msg);
439template <
class ServiceT>
442 if (client_instance_)
return client_instance_->name;