12#include "ROSIntegration/Classes/ROSIntegrationGameInstance.h"
13#include <geometry_msgs/Twist.h>
15#include "Async/Async.h"
18UMovementSubscriber::UMovementSubscriber()
20 PrimaryComponentTick.bCanEverTick =
false;
23void UMovementSubscriber::BeginPlay()
32 RosHandle->
OnROSStateChanged.AddUniqueDynamic(
this, &UMovementSubscriber::ROSBridgeStateChanged);
36void UMovementSubscriber::OnUnregister()
38 Super::OnUnregister();
45 RosHandle->
OnROSStateChanged.RemoveDynamic(
this, &UMovementSubscriber::ROSBridgeStateChanged);
49void UMovementSubscriber::ROSBridgeStateChanged(
EROSState rosState)
63void UMovementSubscriber::CreateROSTopic()
72 if (ROSInstance && ROSInstance->IsROSConnected())
74 FString VehicleName =
"Vehicle";
77 AActor* OwnerActor = GetOwner();
82 AVehicle* VehiclePtr = Cast<AVehicle>(OwnerActor);
89 VehicleName = OwnerActor->GetName();
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();
97 std::function<void(TSharedPtr<FROSBaseMsg>)> SubscribeCallback = [
this](TSharedPtr<FROSBaseMsg> msg) ->
void
99 auto Concrete = StaticCastSharedPtr<ROSMessages::geometry_msgs::Twist>(msg);
100 if (Concrete.IsValid())
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);
106 AsyncTask(ENamedThreads::GameThread, [
this, Movement]()
108 OnMessageReceived.Broadcast(Movement);
115 MovementTopic->Subscribe(SubscribeCallback);
119void UMovementSubscriber::DestroyROSTopic()
123 MovementTopic->Unadvertise();
124 MovementTopic->Unsubscribe();
125 MovementTopic->MarkAsDisconnected();
126 MovementTopic->ConditionalBeginDestroy();
127 MovementTopic =
nullptr;
virtual FString GetActorID_Implementation() const override
static UROSIntegrationGameInstance * GetROSGameInstance(const UObject *WorldContextObject)
static UROSHandler * GetROSHandle(const UObject *WorldContextObject)
FROSDelegate_ROState OnROSStateChanged