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