Agrarsense
MovementSubscriber.cpp
Go to the documentation of this file.
1// Copyright (c) 2023 FrostBit Software Lab at the Lapland University of Applied Sciences
2//
3// This work is licensed under the terms of the MIT license.
4// For a copy, see <https://opensource.org/licenses/MIT>.
5
7
11
12#include "ROSIntegration/Classes/ROSIntegrationGameInstance.h"
13#include <geometry_msgs/Twist.h>
14
15#include "Async/Async.h"
16#include "AITypes.h"
17
18UMovementSubscriber::UMovementSubscriber()
19{
20 PrimaryComponentTick.bCanEverTick = false;
21}
22
23void UMovementSubscriber::BeginPlay()
24{
25 Super::BeginPlay();
26
27 CreateROSTopic();
28
29 UROSHandler* RosHandle = UAgrarsenseStatics::GetROSHandle(GetWorld());
30 if (RosHandle)
31 {
32 RosHandle->OnROSStateChanged.AddUniqueDynamic(this, &UMovementSubscriber::ROSBridgeStateChanged);
33 }
34}
35
36void UMovementSubscriber::OnUnregister()
37{
38 Super::OnUnregister();
39
40 DestroyROSTopic();
41
42 UROSHandler* RosHandle = UAgrarsenseStatics::GetROSHandle(GetWorld());
43 if (RosHandle)
44 {
45 RosHandle->OnROSStateChanged.RemoveDynamic(this, &UMovementSubscriber::ROSBridgeStateChanged);
46 }
47}
48
49void UMovementSubscriber::ROSBridgeStateChanged(EROSState rosState)
50{
51 switch (rosState)
52 {
54 CreateROSTopic();
55 break;
56
58 DestroyROSTopic();
59 break;
60 }
61}
62
63void UMovementSubscriber::CreateROSTopic()
64{
65 if (MovementTopic)
66 {
67 return;
68 }
69
70 UROSIntegrationGameInstance* ROSInstance = UAgrarsenseStatics::GetROSGameInstance(GetWorld());
71
72 if (ROSInstance && ROSInstance->IsROSConnected())
73 {
74 FString VehicleName = "Vehicle";
75
76 // Get this Actor this component is attached to
77 AActor* OwnerActor = GetOwner();
78 if (OwnerActor)
79 {
80 // Try to cast the owning actor into AVehicle and
81 // get its ID and use the ID as the vehicle name
82 AVehicle* VehiclePtr = Cast<AVehicle>(OwnerActor);
83 if (VehiclePtr)
84 {
85 VehicleName = VehiclePtr->GetActorID_Implementation();
86 }
87 else
88 {
89 VehicleName = OwnerActor->GetName();
90 }
91 }
92
93 MovementTopic = NewObject<UTopic>(UTopic::StaticClass());
94 MovementTopic->Init(ROSInstance->ROSIntegrationCore, FString::Printf(TEXT("/agrarsense/in/vehicles/%s/movement"), *VehicleName), TEXT("geometry_msgs/Twist"));
95 MovementTopic->Advertise();
96
97 std::function<void(TSharedPtr<FROSBaseMsg>)> SubscribeCallback = [this](TSharedPtr<FROSBaseMsg> msg) -> void
98 {
99 auto Concrete = StaticCastSharedPtr<ROSMessages::geometry_msgs::Twist>(msg);
100 if (Concrete.IsValid())
101 {
102 FMessageParser Movement;
103 Movement.linear = FVector(Concrete->linear.x, Concrete->linear.y, Concrete->linear.z);
104 Movement.angular = FVector(Concrete->angular.x, Concrete->angular.y, Concrete->angular.z);
105
106 AsyncTask(ENamedThreads::GameThread, [this, Movement]()
107 {
108 OnMessageReceived.Broadcast(Movement);
109 });
110
111 }
112 return;
113 };
114
115 MovementTopic->Subscribe(SubscribeCallback);
116 }
117}
118
119void UMovementSubscriber::DestroyROSTopic()
120{
121 if (MovementTopic)
122 {
123 MovementTopic->Unadvertise();
124 MovementTopic->Unsubscribe();
125 MovementTopic->MarkAsDisconnected();
126 MovementTopic->ConditionalBeginDestroy();
127 MovementTopic = nullptr;
128 }
129}
EROSState
Definition: ROSState.h:16
virtual FString GetActorID_Implementation() const override
Definition: Vehicle.h:203
static UROSIntegrationGameInstance * GetROSGameInstance(const UObject *WorldContextObject)
static UROSHandler * GetROSHandle(const UObject *WorldContextObject)
FROSDelegate_ROState OnROSStateChanged
Definition: ROSHandler.h:81