29 #include "Components/ActorComponent.h"
31 #include "Containers/Map.h"
33 #include "CoreMinimal.h"
35 #include "GameFramework/Actor.h"
51 #include "ROS2NodeComponent.generated.h"
69 DECLARE_LOG_CATEGORY_EXTERN(LogROS2Node, Log, All);
77 DECLARE_DYNAMIC_DELEGATE(FSimpleCallback);
119 #define ROS2_CREATE_LOOP_PUBLISHER( \
121 InROS2Node, InUserObject, InTopicName, InPublisherClass, InMsgClass, InPubFrequency, InCallback, OutPublisher) \
123 if (ensure(IsValid(InROS2Node))) \
129 cb.BindDynamic(InUserObject, InCallback); \
131 OutPublisher = InROS2Node->CreateLoopPublisher(InTopicName, InPublisherClass, InMsgClass, InPubFrequency, cb); \
169 #define ROS2_CREATE_LOOP_PUBLISHER_WITH_QOS( \
171 InROS2Node, InUserObject, InTopicName, InPublisherClass, InMsgClass, InPubFrequency, InCallback, InQoS, OutPublisher) \
173 if (ensure(IsValid(InROS2Node))) \
179 cb.BindDynamic(InUserObject, InCallback); \
181 OutPublisher = InROS2Node->CreateLoopPublisher(InTopicName, InPublisherClass, InMsgClass, InPubFrequency, cb, InQoS); \
209 #define ROS2_CREATE_SUBSCRIBER(InROS2Node, InUserObject, InTopicName, InMsgClass, InCallback) \
211 if (ensure(IsValid(InROS2Node))) \
215 FSubscriptionCallback cb; \
217 cb.BindDynamic(InUserObject, InCallback); \
219 InROS2Node->CreateSubscriber(InTopicName, InMsgClass, cb); \
249 #define ROS2_CREATE_SUBSCRIBERW_WITH_QOS(InROS2Node, InUserObject, InTopicName, InMsgClass, InCallback, InQoS) \
251 if (ensure(IsValid(InROS2Node))) \
255 FSubscriptionCallback cb; \
257 cb.BindDynamic(InUserObject, InCallback); \
259 InROS2Node->CreateSubscriber(InTopicName, InMsgClass, cb, InQoS); \
289 #define ROS2_CREATE_SERVICE_CLIENT(InROS2Node, InUserObject, InServiceName, InSrvClass, InRequestCallback, OutClient) \
291 if (ensure(IsValid(InROS2Node))) \
295 FServiceCallback req; \
297 req.BindDynamic(InUserObject, InRequestCallback); \
299 OutClient = InROS2Node->CreateServiceClient(InServiceName, InSrvClass, req); \
331 #define ROS2_CREATE_SERVICE_CLIENT_WITH_QOS( \
333 InROS2Node, InUserObject, InServiceName, InSrvClass, InRequestCallback, InQoS, OutClient) \
335 if (ensure(IsValid(InROS2Node))) \
339 FServiceCallback req; \
341 req.BindDynamic(InUserObject, InRequestCallback); \
343 OutClient = InROS2Node->CreateServiceClient(InServiceName, InSrvClass, req, InQoS); \
371 #define ROS2_CREATE_SERVICE_SERVER(InROS2Node, InUserObject, InServiceName, InSrvClass, InResponseCallback) \
373 if (ensure(IsValid(InROS2Node))) \
377 FServiceCallback res; \
379 res.BindDynamic(InUserObject, InResponseCallback); \
381 InROS2Node->CreateServiceServer(InServiceName, InSrvClass, res); \
411 #define ROS2_CREATE_SERVICE_SERVER_WITH_QOS(InROS2Node, InUserObject, InServiceName, InSrvClass, InQoS, InResponseCallback) \
413 if (ensure(IsValid(InROS2Node))) \
417 FServiceCallback res; \
419 res.BindDynamic(InUserObject, InResponseCallback); \
421 InROS2Node->CreateServiceServer(InServiceName, InSrvClass, res, InQoS); \
457 #define ROS2_CREATE_ACTION_CLIENT(InROS2Node, \
465 InGoalResponseDelegate, \
467 InResultResponseDelegate, \
469 InFeedbackDelegate, \
471 InCancelResponseDelegate, \
475 if (ensure(IsValid(InROS2Node))) \
479 FActionCallback Feedback, Result, Goal; \
481 FSimpleCallback Cancel; \
483 Goal.BindDynamic(InUserObject, InGoalResponseDelegate); \
485 Result.BindDynamic(InUserObject, InResultResponseDelegate); \
487 Feedback.BindDynamic(InUserObject, InFeedbackDelegate); \
489 Cancel.BindDynamic(InUserObject, InCancelResponseDelegate); \
491 OutClient = InROS2Node->CreateActionClient(InActionName, InActionClass, Goal, Result, Feedback, Cancel); \
535 #define ROS2_CREATE_ACTION_CLIENT_WITH_QOS(InROS2Node, \
543 InGoalResponseDelegate, \
545 InResultResponseDelegate, \
547 InFeedbackDelegate, \
549 InCancelResponseDelegate, \
561 if (ensure(IsValid(InROS2Node))) \
565 FActionCallback Feedback, Result, Goal; \
567 FSimpleCallback Cancel; \
569 Goal.BindDynamic(InUserObject, InGoalResponseDelegate); \
571 Result.BindDynamic(InUserObject, InResultResponseDelegate); \
573 Feedback.BindDynamic(InUserObject, InFeedbackDelegate); \
575 Cancel.BindDynamic(InUserObject, InCancelResponseDelegate); \
577 OutClient = InROS2Node->CreateActionClient( \
579 InActionName, InActionClass, Goal, Result, Feedback, Cancel, InGoalQoS, InResultQoS, InFeedbackQoS, InCancelQoS); \
613 #define ROS2_CREATE_ACTION_SERVER( \
615 InROS2Node, InUserObject, InActionName, InActionClass, InGoalDelegate, InResultDelegate, InCancelDelegate, OutServer) \
617 if (ensure(IsValid(InROS2Node))) \
621 FActionCallback Goal; \
623 FSimpleCallback Result, Cancel; \
625 Goal.BindDynamic(InUserObject, InGoalDelegate); \
627 Result.BindDynamic(InUserObject, InResultDelegate); \
629 Cancel.BindDynamic(InUserObject, InCancelDelegate); \
631 OutServer = InROS2Node->CreateActionServer(InActionName, InActionClass, Goal, Result, Cancel); \
673 #define ROS2_CREATE_ACTION_SERVER_WITH_QOS(InROS2Node, \
697 if (ensure(IsValid(InROS2Node))) \
701 FActionCallback Goal; \
703 FSimpleCallback Result, Cancel; \
705 Goal.BindDynamic(InUserObject, InGoalDelegate); \
707 Result.BindDynamic(InUserObject, InResultDelegate); \
709 Cancel.BindDynamic(InUserObject, InCancelDelegate); \
711 OutServer = InROS2Node->CreateActionServer( \
713 InActionName, InActionClass, Goal, Result, Cancel, InGoalQoS, InResultQoS, InFeedbackQoS, InCancelQoS); \
731 #define IS_ROS2NODE_INITED(InNode, InName, OutRes) \
733 if (!IsValid(InNode)) \
737 UE_LOG_WITH_INFO(LogROS2Node, Warning, TEXT(
"[%s] ROS2 Node is nullptr. Please set OwnerNode."), *InName); \
749 LogROS2Node, Warning, TEXT(
"[%s] ROS2 Node is not initialized yet. Please initialize OwnerNode."), *InName); \
813 const FString& InNodeName,
815 const FString& InNodeNamespace,
817 const FString& InCompName = TEXT(
"ROS2NodeComponent"),
819 const bool Init =
true);
841 virtual void EndPlay(
const EEndPlayReason::Type EndPlayReason)
override;
861 virtual void TickComponent(
float DeltaTime, ELevelTick TickType, FActorComponentTickFunction* ThisTickFunction)
override;
888 rcl_node_t* GetNode();
930 UROS2Publisher* CreateLoopPublisherWithClass(
const FString& InTopicName,
932 const TSubclassOf<UROS2Publisher>& InPublisherClass,
934 const float InPubFrequency);
965 const TSubclassOf<UROS2Publisher>& InPublisherClass,
967 const TSubclassOf<UROS2GenericMsg>& InMsgClass,
969 const float InPubFrequency,
971 const FTopicCallback& InUpdateDelegate,
973 const UROS2QoS InQoS = UROS2QoS::Default);
996 UROS2Publisher* CreatePublisherWithClass(
const TSubclassOf<UROS2Publisher>& InPublisherClass,
998 const FString& InTopicName = TEXT(
""));
1025 const TSubclassOf<UROS2Publisher>& InPublisherClass,
1027 const TSubclassOf<UROS2GenericMsg>& InMsgClass,
1029 const UROS2QoS InQoS = UROS2QoS::Default);
1077 const TSubclassOf<UROS2GenericMsg>& InMsgClass,
1079 const FSubscriptionCallback& InCallback,
1081 const UROS2QoS InQoS = UROS2QoS::Default);
1131 const TSubclassOf<UROS2GenericSrv>& InSrvClass,
1133 const FServiceCallback& InResponseDelegate,
1183 const TSubclassOf<UROS2GenericSrv>& InSrvClass,
1185 const FServiceCallback& InCallback,
1242 const TSubclassOf<UROS2GenericAction>& InActionClass,
1244 const FActionCallback& InGoalResponseDelegate,
1246 const FActionCallback& InResultResponseDelegate,
1248 const FActionCallback& InFeedbackDelegate,
1250 const FSimpleCallback& InCancelResponseDelegate,
1256 const UROS2QoS InFeedbackQoS = UROS2QoS::Default,
1309 const TSubclassOf<UROS2GenericAction>& InActionClass,
1311 const FActionCallback& InGoalDelegate,
1313 const FSimpleCallback& InResultDelegate,
1315 const FSimpleCallback& InCancelDelegate,
1321 const UROS2QoS InFeedbackQoS = UROS2QoS::Default,
1334 TEnumAsByte<UROS2State> State = UROS2State::Created;
1343 FString Name = TEXT(
"node");
1352 FString Namespace = TEXT(
"");
1363 int NGuardConditions = 0;
1406 rcl_wait_set_t wait_set;
1484 float LogLastHit = 0.f;
1505 void HandleSubscriptions();
1524 void HandleServiceServers();
1543 void HandleServiceClients();
1562 void HandleActionClients();
1581 void HandleActionServers();
1602 void InvalidateWaitSet();