14#include "ROSIntegration/Classes/ROSIntegrationGameInstance.h"
15#include <geometry_msgs/Twist.h>
17#include "Async/Async.h"
20UDroneMovementSubscriber::UDroneMovementSubscriber()
22 PrimaryComponentTick.bCanEverTick =
false;
25void UDroneMovementSubscriber::BeginPlay()
34 RosHandle->
OnROSStateChanged.AddUniqueDynamic(
this, &UDroneMovementSubscriber::ROSBridgeStateChanged);
38void UDroneMovementSubscriber::OnUnregister()
40 Super::OnUnregister();
47 RosHandle->
OnROSStateChanged.RemoveDynamic(
this, &UDroneMovementSubscriber::ROSBridgeStateChanged);
51void UDroneMovementSubscriber::ROSBridgeStateChanged(
EROSState rosState)
65void UDroneMovementSubscriber::CreateROSTopic()
74 if (ROSInstance && ROSInstance->IsROSConnected())
76 FString VehicleName =
"Vehicle";
79 AActor* OwnerActor = GetOwner();
84 AVehicle* VehiclePtr = Cast<AVehicle>(OwnerActor);
87 VehicleName = IActorInformation::Execute_GetActorID(VehiclePtr);
91 VehicleName = OwnerActor->GetName();
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();
99 std::function<void(TSharedPtr<FROSBaseMsg>)> SubscribeCallback = [
this](TSharedPtr<FROSBaseMsg> msg) ->
void
101 auto Concrete = StaticCastSharedPtr<ROSMessages::geometry_msgs::Twist>(msg);
102 if (Concrete.IsValid())
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);
108 AsyncTask(ENamedThreads::GameThread, [
this, Movement]()
110 OnDroneMessageReceived.Broadcast(Movement);
117 MovementTopic->Subscribe(SubscribeCallback);
121void UDroneMovementSubscriber::DestroyROSTopic()
125 MovementTopic->Unadvertise();
126 MovementTopic->Unsubscribe();
127 MovementTopic->MarkAsDisconnected();
128 MovementTopic->ConditionalBeginDestroy();
129 MovementTopic =
nullptr;
static UROSIntegrationGameInstance * GetROSGameInstance(const UObject *WorldContextObject)
static UROSHandler * GetROSHandle(const UObject *WorldContextObject)
FROSDelegate_ROState OnROSStateChanged