RapyutaSimulationPlugins
Public Member Functions | Public Attributes | Protected Member Functions | List of all members
ARRBaseRobot Class Reference

Base Robot class. Other robot class should inherit from this class. More...

#include <RRBaseRobot.h>

Inheritance diagram for ARRBaseRobot:
Inheritance graph
[legend]
Collaboration diagram for ARRBaseRobot:
Collaboration graph
[legend]

Public Member Functions

 ARRBaseRobot ()
 Construct a new ARRBaseRobot object. More...
 
 ARRBaseRobot (const FObjectInitializer &ObjectInitializer)
 Construct a new ARRBaseRobot object. More...
 
virtual void BeginPlay () override
 BeginPlay. More...
 
virtual void Tick (float DeltaSeconds) override
 Wake rigid body in addition to Super::Tick() More...
 
void SetupDefault ()
 Initialize default components being configurable in child BP classes. More...
 
virtual void SetRootOffset (const FTransform &InRootOffset)
 Set the root offset for RobotVehicleMoveComponent. More...
 
FORCEINLINE bool IsDynamicRuntimeRobot () const
 DynamicRuntime robot: Implemented purely in cpp, built & loaded up at runtime from raw CAD + metadata (URDF/SDF) More...
 
FORCEINLINE bool IsStaticBPRobot () const
 Static BP robot: implemented in BP, possibly inheriting from #ARBaseRobot or its children classes,. More...
 
FString GetDynamicResourceName (const ERRResourceDataType InDataType) const
 Get name of an already-stored dynamic robot resource (mesh, skeleton, physics asset, etc.) More...
 
FString GetDynamicResourceAssetPath (const ERRResourceDataType InDataType) const
 Get UE asset path of an already-stored dynamic robot resource (mesh, skeleton, physics asset, etc.) More...
 
virtual void OnRep_ROS2Interface ()
 Function called with ROS2Interface replication. Start ROS2Interface if bStartStopROS2Interface=true. More...
 
virtual void OnRep_bStartStopROS2Interface ()
 Function called with bStartStopROS2Interface replication. Start/stop ROS2Interface if it is ready. More...
 
bool IsAuthorizedInThisClient ()
 Check necessary variables has initialized and PlayerId which spawned robot is match to this client PlayerId. More...
 
void CreateROS2Interface ()
 Instantiate ROS 2 Interface without initializing yet. More...
 
void InitROS2Interface ()
 Initialize ROS 2 Interface. Directly call URRRobotROS2Interface::Initialize or execute in client via OnRep_bStartStopROS2Interface. More...
 
bool InitROS2InterfaceImpl ()
 
void DeInitROS2Interface ()
 Stop ROS 2 Interface. Directly call URRRobotROS2Interface::DeInitialize or execute in client via OnRep_bStartStopROS2Interface. More...
 
void SetRobotName (const FString &InRobotName)
 Set robot unique name. More...
 
virtual void SetRobotModelName (const FString InName)
 
virtual FString GetRobotModelName ()
 
FORCEINLINE bool IsBuiltInRobotModel () const
 Is static built robot model by the Editor. More...
 
uint64 GetRobotID () const
 Get robot ID. More...
 
void SetRobotID (uint64 InRobotID)
 Set robot ID. More...
 
virtual bool AddLink (const FString &InLinkName, UStaticMeshComponent *InMesh)
 Add UStaticMeshComponent to Links. More...
 
void SetBaseMeshComp (UMeshComponent *InBaseMeshComp, bool bInMakeAsRoot=true, bool bInDestroyDefaultRoot=true)
 Set BaseMeshComp, optionally making it the new Root, replacing DefaultRoot. More...
 
virtual bool AddJoint (const FString &InParentLinkName, const FString &InChildLinkName, const FString &InJointName, URRJointComponent *InJoint)
 Add URRJointComponent to Joints and set Joint's parent and child link from name in Links. More...
 
virtual void StartJointsInitialization ()
 
virtual void CheckJointsInitialization ()
 
virtual void SetChildComponentsCollisionEnabled (const bool IsEnable)
 Set the ChildComponents Collision Enabled. More...
 
virtual bool InitSensors (UROS2NodeComponent *InROS2Node)
 Initialize sensors components which are child class of URRROS2BaseSensorComponent. More...
 
virtual void GetLifetimeReplicatedProps (TArray< FLifetimeProperty > &OutLifetimeProps) const override
 Returns the properties used for network replication, this needs to be overridden by all actor classes with native. More...
 
virtual bool ReplicateSubobjects (UActorChannel *Channel, FOutBunch *Bunch, FReplicationFlags *RepFlags) override
 Allows a component to replicate other subobject on the actor. More...
 
virtual void SetJointState (const TMap< FString, TArray< float >> &InJointState, const ERRJointControlType InJointControlType)
 Set Joints state to Joints. More...
 
virtual void StopMovement ()
 Stop robot movement, resetting all vel inputs. More...
 
virtual void SetMoveComponent (UMovementComponent *InMoveComponent)
 
virtual void SetLinearVel (const FVector &InLinearVel)
 Set velocity to RobotVehicleMoveComponent. More...
 
virtual void SetAngularVel (const FVector &InAngularVel)
 Set angular velocity to RobotVehicleMoveComponent. More...
 
virtual void SyncServerLinearMovement (float InClientTimeStamp, const FTransform &InClientRobotTransform, const FVector &InLinearVel)
 Set position and linear velocity to the robot in the server. More...
 
virtual void SyncServerAngularMovement (float InClientTimeStamp, const FRotator &InClientRobotRotation, const FVector &InAngularVel)
 Set rotation and angular velocity to the robot in the server. More...
 
virtual void SetLocalLinearVel (const FVector &InLinearVel)
 Set linear velocity to RobotVehicleMoveComponent in the client. More...
 
virtual void SetLocalAngularVel (const FVector &InAngularVel)
 Set angular velocity to RobotVehicleMoveComponent in the client. More...
 
void BPConfigureMovementComponent ()
 This method is called inside PostInitializeComponents. More...
 
bool CheckUIUserWidget () const
 Check whether #UIUserWidget is valid. More...
 
virtual bool InitPropertiesFromJSON ()
 Parse Json parameters in ROSSpawnParameters. More...
 
void BPInitPropertiesFromJSON ()
 This method is called inside PreInitializeComponents. More...
 
virtual void ConfigureMovementComponent ()
 Calls both InitPropertiesFromJSON and BPInitPropertiesFromJSON. More...
 
virtual void InitUIWidget ()
 Create & init UIWidgetComp. More...
 
virtual bool InitPropertiesFromJSONAll ()
 
- Public Member Functions inherited from ARRBaseActor
 ARRBaseActor ()
 Construct a new ARRBaseActor object. More...
 
 ARRBaseActor (const FObjectInitializer &ObjectInitializer)
 Construct a new ARRBaseActor object. More...
 
void SetupDefaultBase ()
 Initialize default components being configurable in child BP classes. More...
 
void SetEntityModelName (const FString &InEntityModelName)
 
bool IsDataSynthEntity () const
 
template<typename TActorSpawnInfo >
bool InitializeWithSpawnInfo (const TActorSpawnInfo &InActorInfo)
 ACTOR INTIALIZING GENERAL INFO (Unique name, mesh list, material list, etc.) More...
 
virtual bool Initialize ()
 Set #GameMode #GameState #GameSingleton #PlayerController. More...
 
virtual bool HasInitialized (bool bIsLogged=false) const
 
virtual void Reset ()
 Rest. Calls #ActorInfo::ClearMeshInfo. More...
 
void SetTickEnabled (bool bInIsTickEnabled)
 Use URRUObjectUtils::SetupActorTick. More...
 

Public Attributes

TObjectPtr< USceneComponent > DefaultRoot = nullptr
 
FOnRobotCreationDone OnRobotCreationDone
 Robot creation done delegate. More...
 
TSubclassOf< URRRobotROS2InterfaceROS2InterfaceClass = nullptr
 Default class to use when ROS 2 Interface is setup for robot. More...
 
TObjectPtr< URRRobotROS2InterfaceROS2Interface = nullptr
 
bool bStartStopROS2Interface = false
 Flag to start/stop ROS2Interfaces. Since RPC can't be used, use replication to trigger initialization. More...
 
TObjectPtr< UROS2SpawnableROSSpawnParameters = nullptr
 ROSSpawn parameters which is passed to ROS2Interface. More...
 
TObjectPtr< ARRBaseRobotServerRobot = nullptr
 Pointer to the robot's server-owned version. More...
 
FTimerHandle ROS2InitTimer
 
FString RobotUniqueName
 
FString RobotModelName
 Robot Model Name (loaded from URDF/SDF) More...
 
uint64 RobotID = 0
 Robot ID No. More...
 
TMap< FString, UStaticMeshComponent * > Links
 
TObjectPtr< UMeshComponent > BaseMeshComp = nullptr
 Base mesh comp, normally also as the root comp. More...
 
TMap< FString, URRJointComponent * > Joints
 
bool bInitializeJoints = true
 
ERRNetworkAuthorityType NetworkAuthorityType = ERRNetworkAuthorityType::CLIENT
 Network Authority Type. More...
 
FVector TargetLinearVel = FVector::ZeroVector
 [cm/s] Local target linear vel More...
 
FVector TargetAngularVel = FVector::ZeroVector
 [deg/s] Local target angular vel [X:Roll - Y:Pitch - Z: Yaw] More...
 
TObjectPtr< UMovementComponent > MovementComponent = nullptr
 Main robot movement component (kinematics/diff-drive or wheels-drive comp) More...
 
TObjectPtr< URobotVehicleMovementComponentRobotVehicleMoveComponent
 Movecomponent casted to URobotVehicleMovementComponent for utility. More...
 
TSubclassOf< UMovementComponent > VehicleMoveComponentClass
 Class of the main robot movement component, configurable in child class. More...
 
FTransform RootOffset = FTransform::Identity
 Offset transform between the Actor root component and the pose that will be published in /odom topic. More...
 
bool bInitRobotVehicleMoveComponent = true
 Call ConfigureMovecomponent and RobotVehicleMoveComponent::Initialize() in InitMoveComponent in PostInitializeComponents or not. More...
 
bool bMobileRobot = true
 Mobile robot or not. If this is false, movecomponent=nullptr and ROS 2 odom and cmd_vel interface are disabled. More...
 
bool bJointControl = true
 Control Joint by ROS2 o rnot. More...
 
uint8 bUIWidgetEnabled: 1
 Enable widget or not. More...
 
TObjectPtr< URRUIWidgetComponentUIWidgetComp = nullptr
 UI widget component. More...
 
FTransform UIWidgetOffset = FTransform(FVector(0.f, 0.f, 100.f))
 Relative pose of the UI widget from the owner robot. More...
 
TSubclassOf< UUserWidget > UIUserWidgetClass
 Widget class. More...
 
bool bInitializingJoints = false
 
TMap< UPrimitiveComponent *, FName > OriginalCollisionProfiles
 Children UPrimitives components orignal collision profiles. More...
 
- Public Attributes inherited from ARRBaseActor
TSharedPtr< FRRActorSpawnInfoActorInfo = nullptr
 
ARRGameStateRRGameState = nullptr
 Pointer for convinience. Since this pointer can be nullptr, you need null check before using. More...
 
URRGameSingletonRRGameSingleton = nullptr
 Pointer for convinience. Since this pointer can be nullptr, you need null check before using. More...
 
ARRGameModeRRGameMode = nullptr
 Pointer for convinience. Since this pointer can be nullptr, you need null check before using. More...
 
ARRPlayerControllerRRPlayerController = nullptr
 Pointer for convinience. Since this pointer can be nullptr, you need null check before using. More...
 
int8 SceneInstanceId = URRActorCommon::DEFAULT_SCENE_INSTANCE_ID
 
URRActorCommonActorCommon = nullptr
 
FString EntityUniqueName
 Actually Object's Name is also unique as noted by UE, but we just do not want to rely on it. More...
 
FString EntityModelName
 
FTimerHandle GenericTimerHandle
 

Protected Member Functions

virtual void PreInitializeComponents () override
 Instantiate default child components. More...
 
virtual void PostInitializeComponents () override
 Post Initialization process of actor. Initialize RobotVehicleMoveComponent by calling InitMoveComponent. More...
 
virtual bool InitMoveComponent ()
 Create and Initialize MovementComponent if VehicleMoveComponentClass != nullptr. More...
 
void BPPreInitializeComponents ()
 This method is called inside PreInitializeComponents. More...
 
void BPPostInitializeComponents ()
 This method is called inside PreInitializeComponents. More...
 
- Protected Member Functions inherited from ARRBaseActor
virtual void PrintSimConfig () const
 Print class members' values configured in RapyutaSimSettings.ini. More...
 
virtual void DoGlobalConfig ()
 Globally config custom setups (eg. Exec() cmds) applied for all instances of this class. More...
 

Additional Inherited Members

- Static Public Attributes inherited from ARRBaseActor
static TMap< UClass *, TUniquePtr< std::once_flag > > OnceFlagList
 [std::once_flag] also applies even in case of consecutive PIE runs, More...
 
static std::once_flag OnceFlag
 Used for class having single-branch child classes (linear inheritance tree) More...
 
static int8 SSceneInstanceId
 

Detailed Description

Base Robot class. Other robot class should inherit from this class.

This actor use URRRobotROS2Interface as the main ROS 2 communication tool.

This actor has basic functionality to use with client-server, e.g. replication setting

You can find example at ATurtlebotBurger.

UCLASS()

Constructor & Destructor Documentation

◆ ARRBaseRobot() [1/2]

ARRBaseRobot::ARRBaseRobot ( )

Construct a new ARRBaseRobot object.

◆ ARRBaseRobot() [2/2]

ARRBaseRobot::ARRBaseRobot ( const FObjectInitializer &  ObjectInitializer)

Construct a new ARRBaseRobot object.

Parameters
ObjectInitializer

Member Function Documentation

◆ AddJoint()

virtual bool ARRBaseRobot::AddJoint ( const FString &  InParentLinkName,
const FString &  InChildLinkName,
const FString &  InJointName,
URRJointComponent InJoint 
)
virtual

Add URRJointComponent to Joints and set Joint's parent and child link from name in Links.

InParentLinkName and InChildLinkName need to be in Links beforehand.

InJointName is used for joint name of joint_states topic

Parameters
InParentLinkName
InChildLinkName
InJointName
InJoint
Returns
true
false

UFUNCTION(BlueprintCallable)

◆ AddLink()

virtual bool ARRBaseRobot::AddLink ( const FString &  InLinkName,
UStaticMeshComponent *  InMesh 
)
virtual

Add UStaticMeshComponent to Links.

InLinkName is used for frame name of tf.

Parameters
InLinkName
InMesh
Returns
true
false

UFUNCTION(BlueprintCallable)

◆ BeginPlay()

virtual void ARRBaseRobot::BeginPlay ( )
overridevirtual

BeginPlay.

◆ BPConfigureMovementComponent()

void ARRBaseRobot::BPConfigureMovementComponent ( )

This method is called inside PostInitializeComponents.

Custom initialization of child BP class can be done by overwritting this method.

UFUNCTION(BlueprintImplementableEvent, BlueprintCallable)

◆ BPInitPropertiesFromJSON()

void ARRBaseRobot::BPInitPropertiesFromJSON ( )

This method is called inside PreInitializeComponents.

Custom initialization of child BP class can be done by overwritting this method.

Note
BlueprintImplementableEvent can't return value

UFUNCTION(BlueprintImplementableEvent, BlueprintCallable)

◆ BPPostInitializeComponents()

void ARRBaseRobot::BPPostInitializeComponents ( )
protected

This method is called inside PreInitializeComponents.

Custom initialization of child BP class can be done by overwritting this method.

Note
BlueprintImplementableEvent can't return value

UFUNCTION(BlueprintImplementableEvent, BlueprintCallable)

◆ BPPreInitializeComponents()

void ARRBaseRobot::BPPreInitializeComponents ( )
protected

This method is called inside PreInitializeComponents.

Custom initialization of child BP class can be done by overwritting this method.

Note
BlueprintImplementableEvent can't return value

UFUNCTION(BlueprintImplementableEvent, BlueprintCallable)

◆ CheckJointsInitialization()

virtual void ARRBaseRobot::CheckJointsInitialization ( )
virtual

◆ CheckUIUserWidget()

bool ARRBaseRobot::CheckUIUserWidget ( ) const

Check whether #UIUserWidget is valid.

◆ ConfigureMovementComponent()

virtual void ARRBaseRobot::ConfigureMovementComponent ( )
virtual

◆ CreateROS2Interface()

void ARRBaseRobot::CreateROS2Interface ( )

Instantiate ROS 2 Interface without initializing yet.

Note
Not uses RPC but replication since the robot is not always owned by the same connection with the client's PlayerController.
See also
ARRBaseRobotROSController::OnPossess
Connection

UFUNCTION(BlueprintCallable)

◆ DeInitROS2Interface()

void ARRBaseRobot::DeInitROS2Interface ( )

Stop ROS 2 Interface. Directly call URRRobotROS2Interface::DeInitialize or execute in client via OnRep_bStartStopROS2Interface.

Note
Not uses RPC but replication since the robot is not always owned by the same connection with the client's PlayerController.
See also
Connection

UFUNCTION(BlueprintCallable)

◆ GetDynamicResourceAssetPath()

FString ARRBaseRobot::GetDynamicResourceAssetPath ( const ERRResourceDataType  InDataType) const

Get UE asset path of an already-stored dynamic robot resource (mesh, skeleton, physics asset, etc.)

Parameters
InDataType
Returns
FString

◆ GetDynamicResourceName()

FString ARRBaseRobot::GetDynamicResourceName ( const ERRResourceDataType  InDataType) const

Get name of an already-stored dynamic robot resource (mesh, skeleton, physics asset, etc.)

Parameters
InDataType
Returns
FString

◆ GetLifetimeReplicatedProps()

virtual void ARRBaseRobot::GetLifetimeReplicatedProps ( TArray< FLifetimeProperty > &  OutLifetimeProps) const
overridevirtual

Returns the properties used for network replication, this needs to be overridden by all actor classes with native.

replicated properties

Parameters
OutLifetimePropsOutput lifetime properties

Reimplemented from ARRBaseActor.

Reimplemented in ARobotVehicle, and ATurtlebotBurgerVehicle.

◆ GetRobotID()

uint64 ARRBaseRobot::GetRobotID ( ) const
inline

Get robot ID.

◆ GetRobotModelName()

virtual FString ARRBaseRobot::GetRobotModelName ( )
inlinevirtual

◆ InitMoveComponent()

virtual bool ARRBaseRobot::InitMoveComponent ( )
protectedvirtual

Create and Initialize MovementComponent if VehicleMoveComponentClass != nullptr.

If VehicleMoveComponentClass == nullptr, it is expected that MovementComponent is set from BP or user code.

Returns
true MovementComponent is created and initialized.
false VehicleMoveComponentClass == nullptr.

◆ InitPropertiesFromJSON()

virtual bool ARRBaseRobot::InitPropertiesFromJSON ( )
virtual

Parse Json parameters in ROSSpawnParameters.

This function is called in PreInitializeComponents

Please overwrite this function to parse your custom parameters

{Example Implementation of Json parser:}
if (false == Super::InitPropertiesFromJSON())
{
return false;
}
TSharedRef<TJsonReader<TCHAR>> jsonReader = TJsonReaderFactory<TCHAR>::Create(ROSSpawnParameters->ActorJsonConfigs);
TSharedPtr<FJsonObject> jsonObj = MakeShareable(new FJsonObject());
if (!FJsonSerializer::Deserialize(jsonReader, jsonObj) && jsonObj.IsValid())
{
UE_LOG_WITH_INFO_NAMED(LogRapyutaCore, Error, TEXT("Failed to deserialize json to object"));
return false;
}
// Parse single value
bool bParam = false;
if (URRGeneralUtils::GetJsonField(jsonObj, TEXT("bool_value"), bParam))
{
UE_LOG_WITH_INFO_NAMED(LogRapyutaCore, Log, TEXT("bool value: %d"), bParam);
}
else
{
UE_LOG_WITH_INFO_NAMED(LogRapyutaCore, Warning, TEXT("%s [bool_value] not found in json config"));
}
// Parse array
const TArray<TSharedPtr<FJsonValue>>* paramArray;
if (!jsonObj->TryGetArrayField(TEXT("array_value"), paramArray))
{
return false;
}
for (const auto& param : *paramArray)
{
const TSharedPtr<FJsonObject>* jObj;
if (!param->TryGetObject(jObj))
{
UE_LOG_WITH_INFO_NAMED(LogRapyutaCore, Warning, TEXT("%s Not an object !!"));
continue;
}
// Parse value in array
float valueInParam = 0.0;
if (URRGeneralUtils::GetJsonField(*jObj, TEXT("value_in_array"), valueInParam, 0.0f))
{
UE_LOG_WITH_INFO_NAMED(LogRapyutaCore, Log, TEXT("value_in_array : %f"), valueInParam);
}
else
{
UE_LOG_WITH_INFO_NAMED(LogRapyutaCore, Warning, TEXT("%s [value_in_array] not found in json config"));
}
}
return true;
Returns
true/false

UFUNCTION(BlueprintCallable)

◆ InitPropertiesFromJSONAll()

virtual bool ARRBaseRobot::InitPropertiesFromJSONAll ( )
inlinevirtual

◆ InitROS2Interface()

void ARRBaseRobot::InitROS2Interface ( )

Initialize ROS 2 Interface. Directly call URRRobotROS2Interface::Initialize or execute in client via OnRep_bStartStopROS2Interface.

Note
Not uses RPC but replication since the robot is not always owned by the same connection with the client's PlayerController.
See also
ARRBaseRobotROSController::OnPossess
Connection

UFUNCTION(BlueprintCallable)

◆ InitROS2InterfaceImpl()

bool ARRBaseRobot::InitROS2InterfaceImpl ( )

◆ InitSensors()

virtual bool ARRBaseRobot::InitSensors ( UROS2NodeComponent *  InROS2Node)
virtual

Initialize sensors components which are child class of URRROS2BaseSensorComponent.

Parameters
InROS2NodeROS2Node which sensor publishers belongs to.
Returns
true
false Given ROS2Node is invalid.
See also
TInlineComponentArray
GetComponents

◆ InitUIWidget()

virtual void ARRBaseRobot::InitUIWidget ( )
virtual

Create & init UIWidgetComp.

◆ IsAuthorizedInThisClient()

bool ARRBaseRobot::IsAuthorizedInThisClient ( )

Check necessary variables has initialized and PlayerId which spawned robot is match to this client PlayerId.

Returns
true if playerId matches robot spawn playerId

◆ IsBuiltInRobotModel()

FORCEINLINE bool ARRBaseRobot::IsBuiltInRobotModel ( ) const
inline

Is static built robot model by the Editor.

◆ IsDynamicRuntimeRobot()

FORCEINLINE bool ARRBaseRobot::IsDynamicRuntimeRobot ( ) const
inline

DynamicRuntime robot: Implemented purely in cpp, built & loaded up at runtime from raw CAD + metadata (URDF/SDF)

Note
Experimental

◆ IsStaticBPRobot()

FORCEINLINE bool ARRBaseRobot::IsStaticBPRobot ( ) const
inline

Static BP robot: implemented in BP, possibly inheriting from #ARBaseRobot or its children classes,.

built from pre-designed static UE assets (StaticMesh, SkeletalMesh, Skeleton, Physics Asset, etc.)

Note
Experimental

◆ OnRep_bStartStopROS2Interface()

virtual void ARRBaseRobot::OnRep_bStartStopROS2Interface ( )
virtual

Function called with bStartStopROS2Interface replication. Start/stop ROS2Interface if it is ready.

UFUNCTION(BlueprintCallable)

◆ OnRep_ROS2Interface()

virtual void ARRBaseRobot::OnRep_ROS2Interface ( )
virtual

Function called with ROS2Interface replication. Start ROS2Interface if bStartStopROS2Interface=true.

UFUNCTION(BlueprintCallable)

◆ PostInitializeComponents()

virtual void ARRBaseRobot::PostInitializeComponents ( )
overrideprotectedvirtual

Post Initialization process of actor. Initialize RobotVehicleMoveComponent by calling InitMoveComponent.

See also
ActorLifecycle
PostInitializeComponents

Reimplemented in ATurtlebotBurgerBase.

◆ PreInitializeComponents()

virtual void ARRBaseRobot::PreInitializeComponents ( )
overrideprotectedvirtual

Instantiate default child components.

Reimplemented from ARRBaseActor.

Reimplemented in ATurtlebotBurgerVehicle, and ARobotVehicle.

◆ ReplicateSubobjects()

virtual bool ARRBaseRobot::ReplicateSubobjects ( UActorChannel *  Channel,
FOutBunch *  Bunch,
FReplicationFlags *  RepFlags 
)
overridevirtual

Allows a component to replicate other subobject on the actor.

◆ SetAngularVel()

virtual void ARRBaseRobot::SetAngularVel ( const FVector &  InAngularVel)
virtual

Set angular velocity to RobotVehicleMoveComponent.

Calls SetLocalAngularVel for setting velocity to RobotVehicleMoveComponent and

SyncServerAngularMovement to sync movement of the robot in the server.

Parameters
InAngularVel

UFUNCTION(BlueprintCallable)

◆ SetBaseMeshComp()

void ARRBaseRobot::SetBaseMeshComp ( UMeshComponent *  InBaseMeshComp,
bool  bInMakeAsRoot = true,
bool  bInDestroyDefaultRoot = true 
)

Set BaseMeshComp, optionally making it the new Root, replacing DefaultRoot.

Parameters
InBaseMeshComp
bInMakeAsRoot
bInDestroyDefaultRootWhether or not destroying DefaultRoot upon (bInMakeAsRoot == true), in which case if kept it is only to support compatibility in users' child-BP class

UFUNCTION(BlueprintCallable)

◆ SetChildComponentsCollisionEnabled()

virtual void ARRBaseRobot::SetChildComponentsCollisionEnabled ( const bool  IsEnable)
virtual

Set the ChildComponents Collision Enabled.

if IsEnabled=false Set all children UPrimitiveComponents collision profile to "OverlapAll". Original profiles are saved in OriginalCollisionProfiles.

if IsEnabled=false Revert all children UPrimitiveComponents collision profile to back to original.

Parameters
IsEnable

UFUNCTION(BlueprintCallable)

◆ SetJointState()

virtual void ARRBaseRobot::SetJointState ( const TMap< FString, TArray< float >> &  InJointState,
const ERRJointControlType  InJointControlType 
)
virtual

Set Joints state to Joints.

Todo:
Provide a simillar method which can be used from Blueprint

◆ SetLinearVel()

virtual void ARRBaseRobot::SetLinearVel ( const FVector &  InLinearVel)
virtual

Set velocity to RobotVehicleMoveComponent.

Calls SetLocalLinearVel for setting velocity to RobotVehicleMoveComponent and

SyncServerLinearMovement to sync movement of the robot in the server.

Parameters
InLinearVel

UFUNCTION(BlueprintCallable)

◆ SetLocalAngularVel()

virtual void ARRBaseRobot::SetLocalAngularVel ( const FVector &  InAngularVel)
virtual

Set angular velocity to RobotVehicleMoveComponent in the client.

Note
Not uses RPC since the robot is not always owned by the same connection with the client's PlayerController.
See also
Connection

UFUNCTION(BlueprintCallable)

◆ SetLocalLinearVel()

virtual void ARRBaseRobot::SetLocalLinearVel ( const FVector &  InLinearVel)
virtual

Set linear velocity to RobotVehicleMoveComponent in the client.

Note
Not uses RPC since the robot is not always owned by the same connection with the client's PlayerController.
See also
Connection

UFUNCTION(BlueprintCallable)

◆ SetMoveComponent()

virtual void ARRBaseRobot::SetMoveComponent ( UMovementComponent *  InMoveComponent)
virtual

◆ SetRobotID()

void ARRBaseRobot::SetRobotID ( uint64  InRobotID)
inline

Set robot ID.

◆ SetRobotModelName()

virtual void ARRBaseRobot::SetRobotModelName ( const FString  InName)
inlinevirtual

◆ SetRobotName()

void ARRBaseRobot::SetRobotName ( const FString &  InRobotName)
inline

Set robot unique name.

◆ SetRootOffset()

virtual void ARRBaseRobot::SetRootOffset ( const FTransform &  InRootOffset)
virtual

Set the root offset for RobotVehicleMoveComponent.

This will be added to the odometry data published in ros topic /odom

It is used, for example, to allow the robot root pose to remain constant even if we move the skeletal mesh root component for

collisions

Parameters
InRootOffset

UFUNCTION(BlueprintCallable)

◆ SetupDefault()

void ARRBaseRobot::SetupDefault ( )

Initialize default components being configurable in child BP classes.

Could only be called in constructor.

◆ StartJointsInitialization()

virtual void ARRBaseRobot::StartJointsInitialization ( )
virtual

◆ StopMovement()

virtual void ARRBaseRobot::StopMovement ( )
virtual

Stop robot movement, resetting all vel inputs.

UFUNCTION(BlueprintCallable)

◆ SyncServerAngularMovement()

virtual void ARRBaseRobot::SyncServerAngularMovement ( float  InClientTimeStamp,
const FRotator &  InClientRobotRotation,
const FVector &  InAngularVel 
)
virtual

Set rotation and angular velocity to the robot in the server.

Parameters
InClientTimeStamp
InClientRobotRotation
InAngularVel
Note
Not uses RPC since the robot is not always owned by the same connection with the client's PlayerController.
See also
Connection

UFUNCTION(BlueprintCallable)

◆ SyncServerLinearMovement()

virtual void ARRBaseRobot::SyncServerLinearMovement ( float  InClientTimeStamp,
const FTransform &  InClientRobotTransform,
const FVector &  InLinearVel 
)
virtual

Set position and linear velocity to the robot in the server.

Parameters
InClientTimeStamp
InClientRobotPosition
InLinearVel
Note
Not uses RPC since the robot is not always owned by the same connection with the client's PlayerController.
See also
Connection

UFUNCTION(BlueprintCallable)

◆ Tick()

virtual void ARRBaseRobot::Tick ( float  DeltaSeconds)
overridevirtual

Wake rigid body in addition to Super::Tick()

Parameters
DeltaSeconds

Member Data Documentation

◆ BaseMeshComp

TObjectPtr<UMeshComponent> ARRBaseRobot::BaseMeshComp = nullptr

Base mesh comp, normally also as the root comp.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ bInitializeJoints

bool ARRBaseRobot::bInitializeJoints = true

Initialize Joints or not. Initial pose are set in each joint.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ bInitializingJoints

bool ARRBaseRobot::bInitializingJoints = false

Initialize Joints or not. Initial pose are set in each joint.

UPROPERTY(BlueprintReadWrite)

◆ bInitRobotVehicleMoveComponent

bool ARRBaseRobot::bInitRobotVehicleMoveComponent = true

Call ConfigureMovecomponent and RobotVehicleMoveComponent::Initialize() in InitMoveComponent in PostInitializeComponents or not.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ bJointControl

bool ARRBaseRobot::bJointControl = true

Control Joint by ROS2 o rnot.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ bMobileRobot

bool ARRBaseRobot::bMobileRobot = true

Mobile robot or not. If this is false, movecomponent=nullptr and ROS 2 odom and cmd_vel interface are disabled.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ bStartStopROS2Interface

bool ARRBaseRobot::bStartStopROS2Interface = false

Flag to start/stop ROS2Interfaces. Since RPC can't be used, use replication to trigger initialization.

UPROPERTY(VisibleAnywhere, BlueprintReadWrite, Replicated, ReplicatedUsing = OnRep_bStartStopROS2Interface)

◆ bUIWidgetEnabled

uint8 ARRBaseRobot::bUIWidgetEnabled

◆ DefaultRoot

TObjectPtr<USceneComponent> ARRBaseRobot::DefaultRoot = nullptr

◆ Joints

TMap<FString, URRJointComponent*> ARRBaseRobot::Joints

Robot Joints

Todo:
adopt to client-server.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ Links

TMap<FString, UStaticMeshComponent*> ARRBaseRobot::Links

Robot Links

Todo:
adopt to client-server.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ MovementComponent

TObjectPtr<UMovementComponent> ARRBaseRobot::MovementComponent = nullptr

Main robot movement component (kinematics/diff-drive or wheels-drive comp)

MovementComponent and RobotVehicleMoveComponent should point to same pointer.

UPROPERTY(EditAnywhere, BlueprintReadWrite, Instanced)

◆ NetworkAuthorityType

ERRNetworkAuthorityType ARRBaseRobot::NetworkAuthorityType = ERRNetworkAuthorityType::CLIENT

Network Authority Type.

Todo:
Server is not supported yet.

UPROPERTY(EditAnywhere, BlueprintReadWrite, Replicated)

◆ OnRobotCreationDone

FOnRobotCreationDone ARRBaseRobot::OnRobotCreationDone

Robot creation done delegate.

◆ OriginalCollisionProfiles

TMap<UPrimitiveComponent*, FName> ARRBaseRobot::OriginalCollisionProfiles

Children UPrimitives components orignal collision profiles.

Retrive profiles to this variable when SetChildComponentsCollisionEnabled(false) is called

and this values are used when SetChildComponentsCollisionEnabled(true) are called.

UPROPERTY()

◆ RobotID

uint64 ARRBaseRobot::RobotID = 0

◆ RobotModelName

FString ARRBaseRobot::RobotModelName

Robot Model Name (loaded from URDF/SDF)

should be same as EntityModelName in ARRBaseActor

Todo:
move to protected member

UPROPERTY(VisibleAnyWhere, BlueprintReadOnly, meta = (ExposeOnSpawn = "true"), Replicated)

◆ RobotUniqueName

FString ARRBaseRobot::RobotUniqueName

◆ RobotVehicleMoveComponent

TObjectPtr<URobotVehicleMovementComponent> ARRBaseRobot::RobotVehicleMoveComponent

Movecomponent casted to URobotVehicleMovementComponent for utility.

This should be pointing same thing as MovementComponent This should be set from SetMoveComponent

UPROPERTY(EditAnywhere, BlueprintReadWrite, Instanced, Replicated)

◆ RootOffset

FTransform ARRBaseRobot::RootOffset = FTransform::Identity

Offset transform between the Actor root component and the pose that will be published in /odom topic.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ ROS2InitTimer

FTimerHandle ARRBaseRobot::ROS2InitTimer

◆ ROS2Interface

TObjectPtr<URRRobotROS2Interface> ARRBaseRobot::ROS2Interface = nullptr

Robot's ROS 2 Interface.

With the client-server setup, this is created in the server and replicated to the client and initialized only in the client.

UPROPERTY(EditAnywhere, BlueprintReadWrite, Instanced, Replicated, ReplicatedUsing = OnRep_ROS2Interface)

◆ ROS2InterfaceClass

TSubclassOf<URRRobotROS2Interface> ARRBaseRobot::ROS2InterfaceClass = nullptr

◆ ROSSpawnParameters

TObjectPtr<UROS2Spawnable> ARRBaseRobot::ROSSpawnParameters = nullptr

ROSSpawn parameters which is passed to ROS2Interface.

You can change paramter in BP for manually placed robot but Paramerter will be overwirten if you spawn from /SpawnEntity srv.

UPROPERTY(BlueprintReadWrite, Replicated)

◆ ServerRobot

TObjectPtr<ARRBaseRobot> ARRBaseRobot::ServerRobot = nullptr

Pointer to the robot's server-owned version.

Note
Owner can't be used since non-player pawn don't have that.

UPROPERTY(VisibleAnywhere, Replicated)

◆ TargetAngularVel

FVector ARRBaseRobot::TargetAngularVel = FVector::ZeroVector

[deg/s] Local target angular vel [X:Roll - Y:Pitch - Z: Yaw]

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ TargetLinearVel

FVector ARRBaseRobot::TargetLinearVel = FVector::ZeroVector

[cm/s] Local target linear vel

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ UIUserWidgetClass

TSubclassOf<UUserWidget> ARRBaseRobot::UIUserWidgetClass

◆ UIWidgetComp

TObjectPtr<URRUIWidgetComponent> ARRBaseRobot::UIWidgetComp = nullptr

◆ UIWidgetOffset

FTransform ARRBaseRobot::UIWidgetOffset = FTransform(FVector(0.f, 0.f, 100.f))

Relative pose of the UI widget from the owner robot.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ VehicleMoveComponentClass

TSubclassOf<UMovementComponent> ARRBaseRobot::VehicleMoveComponentClass

Class of the main robot movement component, configurable in child class.

If VehicleMoveComponentClass == nullptr, it is expected that MovementComponent is set from BP or user code.

UPROPERTY(EditAnywhere, BlueprintReadWrite, Replicated)


The documentation for this class was generated from the following file:
ARRBaseRobot::ROSSpawnParameters
TObjectPtr< UROS2Spawnable > ROSSpawnParameters
ROSSpawn parameters which is passed to ROS2Interface.
Definition: RRBaseRobot.h:441
URRGeneralUtils::GetJsonField
static FORCEINLINE bool GetJsonField(const TSharedPtr< FJsonObject > &InJsonObj, const FString &InFieldName, FString &OutValue)
Initialize OutValue with the value of the requested field in a FJsonObject.
Definition: RRGeneralUtils.h:1216