rclUE
ROS2NodeComponent.h
Go to the documentation of this file.
1 
23 #pragma once
24 
25 
26 
27 // UE
28 
29 #include "Components/ActorComponent.h"
30 
31 #include "Containers/Map.h"
32 
33 #include "CoreMinimal.h"
34 
35 #include "GameFramework/Actor.h"
36 
37 
38 
39 // rclUE
40 
42 
43 #include "Msgs/ROS2GenericMsg.h"
44 
45 #include "ROS2Support.h"
46 
47 #include "Srvs/ROS2GenericSrv.h"
48 
49 
50 
51 #include "ROS2NodeComponent.generated.h"
52 
53 
54 
55 class UROS2Publisher;
56 
57 class UROS2Subscriber;
58 
59 class UROS2ServiceServer;
60 
61 class UROS2ServiceClient;
62 
63 class UROS2ActionServer;
64 
65 class UROS2ActionClient;
66 
67 
68 
69 DECLARE_LOG_CATEGORY_EXTERN(LogROS2Node, Log, All);
70 
71 
72 
73 // Reminder: functions bound to delegates must be UFUNCTION
74 
75 DECLARE_DYNAMIC_DELEGATE_OneParam(FActionCallback, UROS2GenericAction*, InAction /*Action*/);
76 
77 DECLARE_DYNAMIC_DELEGATE(FSimpleCallback);
78 
79 
80 
82 
83 DECLARE_DYNAMIC_DELEGATE_OneParam(FSubscriptionCallback, const UROS2GenericMsg*, InMessage);
84 
85 DECLARE_DYNAMIC_DELEGATE_OneParam(FTopicCallback, UROS2GenericMsg*, InTopicMessage);
86 
87 DECLARE_DYNAMIC_DELEGATE_OneParam(FServiceCallback, UROS2GenericSrv*, InService /*Service*/);
88 
89 
90 
119 #define ROS2_CREATE_LOOP_PUBLISHER( \
120 
121  InROS2Node, InUserObject, InTopicName, InPublisherClass, InMsgClass, InPubFrequency, InCallback, OutPublisher) \
122 
123  if (ensure(IsValid(InROS2Node))) \
124 
125  { \
126 
127  FTopicCallback cb; \
128 
129  cb.BindDynamic(InUserObject, InCallback); \
130 
131  OutPublisher = InROS2Node->CreateLoopPublisher(InTopicName, InPublisherClass, InMsgClass, InPubFrequency, cb); \
132 
133  }
134 
135 
136 
169 #define ROS2_CREATE_LOOP_PUBLISHER_WITH_QOS( \
170 
171  InROS2Node, InUserObject, InTopicName, InPublisherClass, InMsgClass, InPubFrequency, InCallback, InQoS, OutPublisher) \
172 
173  if (ensure(IsValid(InROS2Node))) \
174 
175  { \
176 
177  FTopicCallback cb; \
178 
179  cb.BindDynamic(InUserObject, InCallback); \
180 
181  OutPublisher = InROS2Node->CreateLoopPublisher(InTopicName, InPublisherClass, InMsgClass, InPubFrequency, cb, InQoS); \
182 
183  }
184 
185 
186 
209 #define ROS2_CREATE_SUBSCRIBER(InROS2Node, InUserObject, InTopicName, InMsgClass, InCallback) \
210 
211  if (ensure(IsValid(InROS2Node))) \
212 
213  { \
214 
215  FSubscriptionCallback cb; \
216 
217  cb.BindDynamic(InUserObject, InCallback); \
218 
219  InROS2Node->CreateSubscriber(InTopicName, InMsgClass, cb); \
220 
221  }
222 
223 
224 
249 #define ROS2_CREATE_SUBSCRIBERW_WITH_QOS(InROS2Node, InUserObject, InTopicName, InMsgClass, InCallback, InQoS) \
250 
251  if (ensure(IsValid(InROS2Node))) \
252 
253  { \
254 
255  FSubscriptionCallback cb; \
256 
257  cb.BindDynamic(InUserObject, InCallback); \
258 
259  InROS2Node->CreateSubscriber(InTopicName, InMsgClass, cb, InQoS); \
260 
261  }
262 
263 
264 
289 #define ROS2_CREATE_SERVICE_CLIENT(InROS2Node, InUserObject, InServiceName, InSrvClass, InRequestCallback, OutClient) \
290 
291  if (ensure(IsValid(InROS2Node))) \
292 
293  { \
294 
295  FServiceCallback req; \
296 
297  req.BindDynamic(InUserObject, InRequestCallback); \
298 
299  OutClient = InROS2Node->CreateServiceClient(InServiceName, InSrvClass, req); \
300 
301  }
302 
303 
304 
331 #define ROS2_CREATE_SERVICE_CLIENT_WITH_QOS( \
332 
333  InROS2Node, InUserObject, InServiceName, InSrvClass, InRequestCallback, InQoS, OutClient) \
334 
335  if (ensure(IsValid(InROS2Node))) \
336 
337  { \
338 
339  FServiceCallback req; \
340 
341  req.BindDynamic(InUserObject, InRequestCallback); \
342 
343  OutClient = InROS2Node->CreateServiceClient(InServiceName, InSrvClass, req, InQoS); \
344 
345  }
346 
347 
348 
371 #define ROS2_CREATE_SERVICE_SERVER(InROS2Node, InUserObject, InServiceName, InSrvClass, InResponseCallback) \
372 
373  if (ensure(IsValid(InROS2Node))) \
374 
375  { \
376 
377  FServiceCallback res; \
378 
379  res.BindDynamic(InUserObject, InResponseCallback); \
380 
381  InROS2Node->CreateServiceServer(InServiceName, InSrvClass, res); \
382 
383  }
384 
385 
386 
411 #define ROS2_CREATE_SERVICE_SERVER_WITH_QOS(InROS2Node, InUserObject, InServiceName, InSrvClass, InQoS, InResponseCallback) \
412 
413  if (ensure(IsValid(InROS2Node))) \
414 
415  { \
416 
417  FServiceCallback res; \
418 
419  res.BindDynamic(InUserObject, InResponseCallback); \
420 
421  InROS2Node->CreateServiceServer(InServiceName, InSrvClass, res, InQoS); \
422 
423  }
424 
425 
426 
457 #define ROS2_CREATE_ACTION_CLIENT(InROS2Node, \
458 
459  InUserObject, \
460 
461  InActionName, \
462 
463  InActionClass, \
464 
465  InGoalResponseDelegate, \
466 
467  InResultResponseDelegate, \
468 
469  InFeedbackDelegate, \
470 
471  InCancelResponseDelegate, \
472 
473  OutClient) \
474 
475  if (ensure(IsValid(InROS2Node))) \
476 
477  { \
478 
479  FActionCallback Feedback, Result, Goal; \
480 
481  FSimpleCallback Cancel; \
482 
483  Goal.BindDynamic(InUserObject, InGoalResponseDelegate); \
484 
485  Result.BindDynamic(InUserObject, InResultResponseDelegate); \
486 
487  Feedback.BindDynamic(InUserObject, InFeedbackDelegate); \
488 
489  Cancel.BindDynamic(InUserObject, InCancelResponseDelegate); \
490 
491  OutClient = InROS2Node->CreateActionClient(InActionName, InActionClass, Goal, Result, Feedback, Cancel); \
492 
493  }
494 
495 
496 
535 #define ROS2_CREATE_ACTION_CLIENT_WITH_QOS(InROS2Node, \
536 
537  InUserObject, \
538 
539  InActionName, \
540 
541  InActionClass, \
542 
543  InGoalResponseDelegate, \
544 
545  InResultResponseDelegate, \
546 
547  InFeedbackDelegate, \
548 
549  InCancelResponseDelegate, \
550 
551  InGoalQoS, \
552 
553  InResultQoS, \
554 
555  InFeedbackQoS, \
556 
557  InCancelQoS, \
558 
559  OutClient) \
560 
561  if (ensure(IsValid(InROS2Node))) \
562 
563  { \
564 
565  FActionCallback Feedback, Result, Goal; \
566 
567  FSimpleCallback Cancel; \
568 
569  Goal.BindDynamic(InUserObject, InGoalResponseDelegate); \
570 
571  Result.BindDynamic(InUserObject, InResultResponseDelegate); \
572 
573  Feedback.BindDynamic(InUserObject, InFeedbackDelegate); \
574 
575  Cancel.BindDynamic(InUserObject, InCancelResponseDelegate); \
576 
577  OutClient = InROS2Node->CreateActionClient( \
578 
579  InActionName, InActionClass, Goal, Result, Feedback, Cancel, InGoalQoS, InResultQoS, InFeedbackQoS, InCancelQoS); \
580 
581  }
582 
583 
584 
613 #define ROS2_CREATE_ACTION_SERVER( \
614 
615  InROS2Node, InUserObject, InActionName, InActionClass, InGoalDelegate, InResultDelegate, InCancelDelegate, OutServer) \
616 
617  if (ensure(IsValid(InROS2Node))) \
618 
619  { \
620 
621  FActionCallback Goal; \
622 
623  FSimpleCallback Result, Cancel; \
624 
625  Goal.BindDynamic(InUserObject, InGoalDelegate); \
626 
627  Result.BindDynamic(InUserObject, InResultDelegate); \
628 
629  Cancel.BindDynamic(InUserObject, InCancelDelegate); \
630 
631  OutServer = InROS2Node->CreateActionServer(InActionName, InActionClass, Goal, Result, Cancel); \
632 
633  }
634 
635 
636 
673 #define ROS2_CREATE_ACTION_SERVER_WITH_QOS(InROS2Node, \
674 
675  InUserObject, \
676 
677  InActionName, \
678 
679  InActionClass, \
680 
681  InGoalDelegate, \
682 
683  InResultDelegate, \
684 
685  InCancelDelegate, \
686 
687  InGoalQoS, \
688 
689  InResultQoS, \
690 
691  InFeedbackQoS, \
692 
693  InCancelQoS, \
694 
695  OutServer) \
696 
697  if (ensure(IsValid(InROS2Node))) \
698 
699  { \
700 
701  FActionCallback Goal; \
702 
703  FSimpleCallback Result, Cancel; \
704 
705  Goal.BindDynamic(InUserObject, InGoalDelegate); \
706 
707  Result.BindDynamic(InUserObject, InResultDelegate); \
708 
709  Cancel.BindDynamic(InUserObject, InCancelDelegate); \
710 
711  OutServer = InROS2Node->CreateActionServer( \
712 
713  InActionName, InActionClass, Goal, Result, Cancel, InGoalQoS, InResultQoS, InFeedbackQoS, InCancelQoS); \
714 
715  }
716 
717 
718 
731 #define IS_ROS2NODE_INITED(InNode, InName, OutRes) \
732 
733  if (!IsValid(InNode)) \
734 
735  { \
736 
737  UE_LOG_WITH_INFO(LogROS2Node, Warning, TEXT("[%s] ROS2 Node is nullptr. Please set OwnerNode."), *InName); \
738 
739  OutRes = false; \
740 
741  } \
742 
743  else if (InNode->State != UROS2State::Initialized) \
744 
745  { \
746 
747  UE_LOG_WITH_INFO( \
748 
749  LogROS2Node, Warning, TEXT("[%s] ROS2 Node is not initialized yet. Please initialize OwnerNode."), *InName); \
750 
751  OutRes = false; \
752 
753  } \
754 
755  else \
756 
757  { \
758 
759  OutRes = true; \
760 
761  }
762 
763 
764 
782 class RCLUE_API UROS2NodeComponent : public UActorComponent
783 
784 {
785 
786 
787 
788 public:
789 
811  static UROS2NodeComponent* CreateNewNode(UObject* InOwner,
812 
813  const FString& InNodeName,
814 
815  const FString& InNodeNamespace,
816 
817  const FString& InCompName = TEXT("ROS2NodeComponent"),
818 
819  const bool Init = true);
820 
821 
822 
824 
826 
827 
828 
829 protected:
830 
841  virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
842 
843 
844 
845 public:
846 
861  virtual void TickComponent(float DeltaTime, ELevelTick TickType, FActorComponentTickFunction* ThisTickFunction) override;
862 
863 
864 
865 public:
866 
884  void Init();
885 
886 
887 
888  rcl_node_t* GetNode();
889 
890 
891 
907  void AddPublisher(UROS2Publisher* InPublisher);
908 
909 
910 
930  UROS2Publisher* CreateLoopPublisherWithClass(const FString& InTopicName,
931 
932  const TSubclassOf<UROS2Publisher>& InPublisherClass,
933 
934  const float InPubFrequency);
935 
936 
937 
963  UROS2Publisher* CreateLoopPublisher(const FString& InTopicName,
964 
965  const TSubclassOf<UROS2Publisher>& InPublisherClass,
966 
967  const TSubclassOf<UROS2GenericMsg>& InMsgClass,
968 
969  const float InPubFrequency,
970 
971  const FTopicCallback& InUpdateDelegate,
972 
973  const UROS2QoS InQoS = UROS2QoS::Default);
974 
975 
976 
996  UROS2Publisher* CreatePublisherWithClass(const TSubclassOf<UROS2Publisher>& InPublisherClass,
997 
998  const FString& InTopicName = TEXT(""));
999 
1000 
1001 
1023  UROS2Publisher* CreatePublisher(const FString& InTopicName,
1024 
1025  const TSubclassOf<UROS2Publisher>& InPublisherClass,
1026 
1027  const TSubclassOf<UROS2GenericMsg>& InMsgClass,
1028 
1029  const UROS2QoS InQoS = UROS2QoS::Default);
1030 
1031 
1032 
1050  void AddSubscription(UROS2Subscriber* InSubscriber);
1051 
1052 
1053 
1075  UROS2Subscriber* CreateSubscriber(const FString& InTopicName,
1076 
1077  const TSubclassOf<UROS2GenericMsg>& InMsgClass,
1078 
1079  const FSubscriptionCallback& InCallback,
1080 
1081  const UROS2QoS InQoS = UROS2QoS::Default);
1082 
1083 
1084 
1100  void AddServiceClient(UROS2ServiceClient* InServiceClient);
1101 
1102 
1103 
1129  UROS2ServiceClient* CreateServiceClient(const FString& InServiceName,
1130 
1131  const TSubclassOf<UROS2GenericSrv>& InSrvClass,
1132 
1133  const FServiceCallback& InResponseDelegate,
1134 
1135  const UROS2QoS InQoS = UROS2QoS::Services);
1136 
1137 
1138 
1158  void AddServiceServer(UROS2ServiceServer* InServiceServer);
1159 
1160 
1161 
1181  UROS2ServiceServer* CreateServiceServer(const FString& InServiceName,
1182 
1183  const TSubclassOf<UROS2GenericSrv>& InSrvClass,
1184 
1185  const FServiceCallback& InCallback,
1186 
1187  const UROS2QoS InQoS = UROS2QoS::Services);
1188 
1189 
1190 
1206  void AddActionClient(UROS2ActionClient* InActionClient);
1207 
1208 
1209 
1240  UROS2ActionClient* CreateActionClient(const FString& InActionName,
1241 
1242  const TSubclassOf<UROS2GenericAction>& InActionClass,
1243 
1244  const FActionCallback& InGoalResponseDelegate,
1245 
1246  const FActionCallback& InResultResponseDelegate,
1247 
1248  const FActionCallback& InFeedbackDelegate,
1249 
1250  const FSimpleCallback& InCancelResponseDelegate,
1251 
1252  const UROS2QoS InGoalQoS = UROS2QoS::Services,
1253 
1254  const UROS2QoS InResultQoS = UROS2QoS::Services,
1255 
1256  const UROS2QoS InFeedbackQoS = UROS2QoS::Default,
1257 
1258  const UROS2QoS InCancelQoS = UROS2QoS::Services);
1259 
1275  void AddActionServer(UROS2ActionServer* InActionServer);
1276 
1277 
1278 
1307  UROS2ActionServer* CreateActionServer(const FString& InActionName,
1308 
1309  const TSubclassOf<UROS2GenericAction>& InActionClass,
1310 
1311  const FActionCallback& InGoalDelegate,
1312 
1313  const FSimpleCallback& InResultDelegate,
1314 
1315  const FSimpleCallback& InCancelDelegate,
1316 
1317  const UROS2QoS InGoalQoS = UROS2QoS::Services,
1318 
1319  const UROS2QoS InResultQoS = UROS2QoS::Services,
1320 
1321  const UROS2QoS InFeedbackQoS = UROS2QoS::Default,
1322 
1323  const UROS2QoS InCancelQoS = UROS2QoS::Services);
1324 
1325 
1326 
1328 
1329 
1334  TEnumAsByte<UROS2State> State = UROS2State::Created;
1335 
1336 
1337 
1338 
1343  FString Name = TEXT("node");
1344 
1345 
1346 
1347 
1352  FString Namespace = TEXT("");
1353 
1354 
1355 
1357 
1358 
1363  int NGuardConditions = 0;
1364 
1365 
1366 
1367 
1372  int NTimers = 0;
1373 
1374 
1375 
1376 
1381  int NEvents = 0;
1382 
1383 
1384 
1385 protected:
1386 
1402  void SpinSome();
1403 
1404 
1405 
1406  rcl_wait_set_t wait_set;
1407 
1408 
1409 
1410 
1416 
1417 
1418 
1419  rcl_node_t node;
1420 
1421 
1422 
1423 
1428  TArray<UROS2Subscriber*> Subscriptions;
1429 
1430 
1431 
1432 
1437  TArray<UROS2ServiceServer*> ServiceServers;
1438 
1439 
1440 
1441 
1446  TArray<UROS2Publisher*> Publishers;
1447 
1448 
1449 
1450 
1455  TArray<UROS2ServiceClient*> ServiceClients;
1456 
1457 
1458 
1459 
1464  TArray<UROS2ActionClient*> ActionClients;
1465 
1466 
1467 
1468 
1473  TArray<UROS2ActionServer*> ActionServers;
1474 
1475 
1476 
1478 
1479 
1484  float LogLastHit = 0.f;
1485 
1486 
1487 
1488 private:
1489 
1505  void HandleSubscriptions();
1506 
1507 
1508 
1524  void HandleServiceServers();
1525 
1526 
1527 
1543  void HandleServiceClients();
1544 
1545 
1546 
1562  void HandleActionClients();
1563 
1564 
1565 
1581  void HandleActionServers();
1582 
1583 
1584 
1602  void InvalidateWaitSet();
1603 
1604 };
1605 
UROS2NodeComponent::Publishers
TArray< UROS2Publisher * > Publishers
Definition: ROS2NodeComponent.h:1446
UROS2QoS::Services
@ Services
UMETA(DisplayName = "Parameters"),.
UROS2NodeComponent::Subscriptions
TArray< UROS2Subscriber * > Subscriptions
Definition: ROS2NodeComponent.h:1428
UROS2Publisher
ROS2 Publisher class.
Definition: ROS2Publisher.h:54
ROS2GenericSrv.h
This should be refactored with other generic ROS2 types (Msgs, Sensors, Actions).
UROS2ActionServer
Class implementing ROS2 action servers. Wrapper class of rclc action server. Callbacks are set throug...
Definition: ROS2ActionServer.h:56
UROS2QoS
UROS2QoS
used to set QoS policies
Definition: rclcUtilities.h:177
UROS2NodeComponent::ServiceClients
TArray< UROS2ServiceClient * > ServiceClients
Definition: ROS2NodeComponent.h:1455
ROS2GenericAction.h
This should be refactored with other generic ROS2 types (Msgs, Sensors, Actions).
UROS2GenericSrv
This should be refactored with other generic ROS2 types (Msgs, Sensors, Actions).
Definition: ROS2GenericSrv.h:50
UROS2NodeComponent
Class implementing ROS2 node.
Definition: ROS2NodeComponent.h:782
UROS2NodeComponent::ServiceServers
TArray< UROS2ServiceServer * > ServiceServers
Definition: ROS2NodeComponent.h:1437
DECLARE_DYNAMIC_DELEGATE_OneParam
DECLARE_DYNAMIC_DELEGATE_OneParam(FSubscriptionCallback, const UROS2GenericMsg *, InMessage)
BP requires a custom-made callback thus it must be Dynamic.
UROS2GenericAction
This should be refactored with other generic ROS2 types (Msgs, Sensors, Actions).
Definition: ROS2GenericAction.h:46
ROS2GenericMsg.h
This should be refactored with other generic ROS2 types (Msgs, Sensors, Actions).
UROS2ServiceClient
Class implementing ROS2 service clients.
Definition: ROS2ServiceClient.h:62
UROS2NodeComponent::Support
UROS2Support * Support
Definition: ROS2NodeComponent.h:1415
UROS2ServiceServer
Class implementing ROS2 service server.
Definition: ROS2ServiceServer.h:62
UROS2NodeComponent::ActionServers
TArray< UROS2ActionServer * > ActionServers
Definition: ROS2NodeComponent.h:1473
UROS2NodeComponent::ActionClients
TArray< UROS2ActionClient * > ActionClients
Definition: ROS2NodeComponent.h:1464
ROS2Support.h
class that tracks rclc_support_t (see rclc/types.h)
Initialized
@ Initialized
UMETA(DisplayName = "Created"),.
Definition: rclcUtilities.h:158
UROS2ActionClient
Class implementing ROS2 action clients. Wrapper class of rclc action client. Callbacks are set throug...
Definition: ROS2ActionClient.h:54
UROS2GenericMsg
This should be refactored with other generic ROS2 types (Msgs, Sensors, Actions).
Definition: ROS2GenericMsg.h:46
UROS2Support
class that tracks rclc_support_t (see rclc/types.h)
Definition: ROS2Support.h:46
UROS2Subscriber
ROS2 Subscriber class.
Definition: ROS2Subscriber.h:54