RapyutaSimulationPlugins
|
Base Robot class. Other robot class should inherit from this class. More...
#include <RRBaseRobot.h>
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< URRRobotROS2Interface > | ROS2InterfaceClass = nullptr |
Default class to use when ROS 2 Interface is setup for robot. More... | |
TObjectPtr< URRRobotROS2Interface > | ROS2Interface = nullptr |
bool | bStartStopROS2Interface = false |
Flag to start/stop ROS2Interfaces. Since RPC can't be used, use replication to trigger initialization. More... | |
TObjectPtr< UROS2Spawnable > | ROSSpawnParameters = nullptr |
ROSSpawn parameters which is passed to ROS2Interface. More... | |
TObjectPtr< ARRBaseRobot > | ServerRobot = 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< URobotVehicleMovementComponent > | RobotVehicleMoveComponent |
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< URRUIWidgetComponent > | UIWidgetComp = 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< FRRActorSpawnInfo > | ActorInfo = nullptr |
ARRGameState * | RRGameState = nullptr |
Pointer for convinience. Since this pointer can be nullptr, you need null check before using. More... | |
URRGameSingleton * | RRGameSingleton = nullptr |
Pointer for convinience. Since this pointer can be nullptr, you need null check before using. More... | |
ARRGameMode * | RRGameMode = nullptr |
Pointer for convinience. Since this pointer can be nullptr, you need null check before using. More... | |
ARRPlayerController * | RRPlayerController = nullptr |
Pointer for convinience. Since this pointer can be nullptr, you need null check before using. More... | |
int8 | SceneInstanceId = URRActorCommon::DEFAULT_SCENE_INSTANCE_ID |
URRActorCommon * | ActorCommon = 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 |
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.
ARRBaseRobot::ARRBaseRobot | ( | ) |
Construct a new ARRBaseRobot object.
ARRBaseRobot::ARRBaseRobot | ( | const FObjectInitializer & | ObjectInitializer | ) |
Construct a new ARRBaseRobot object.
ObjectInitializer |
|
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
InParentLinkName | |
InChildLinkName | |
InJointName | |
InJoint |
|
virtual |
Add UStaticMeshComponent to Links.
InLinkName is used for frame name of tf.
InLinkName | |
InMesh |
|
overridevirtual |
BeginPlay.
void ARRBaseRobot::BPConfigureMovementComponent | ( | ) |
This method is called inside PostInitializeComponents.
Custom initialization of child BP class can be done by overwritting this method.
void ARRBaseRobot::BPInitPropertiesFromJSON | ( | ) |
This method is called inside PreInitializeComponents.
Custom initialization of child BP class can be done by overwritting this method.
|
protected |
This method is called inside PreInitializeComponents.
Custom initialization of child BP class can be done by overwritting this method.
|
protected |
This method is called inside PreInitializeComponents.
Custom initialization of child BP class can be done by overwritting this method.
|
virtual |
bool ARRBaseRobot::CheckUIUserWidget | ( | ) | const |
Check whether #UIUserWidget is valid.
|
virtual |
Calls both InitPropertiesFromJSON and BPInitPropertiesFromJSON.
void ARRBaseRobot::CreateROS2Interface | ( | ) |
Instantiate ROS 2 Interface without initializing yet.
void ARRBaseRobot::DeInitROS2Interface | ( | ) |
Stop ROS 2 Interface. Directly call URRRobotROS2Interface::DeInitialize or execute in client via OnRep_bStartStopROS2Interface.
FString ARRBaseRobot::GetDynamicResourceAssetPath | ( | const ERRResourceDataType | InDataType | ) | const |
Get UE asset path of an already-stored dynamic robot resource (mesh, skeleton, physics asset, etc.)
InDataType |
FString ARRBaseRobot::GetDynamicResourceName | ( | const ERRResourceDataType | InDataType | ) | const |
Get name of an already-stored dynamic robot resource (mesh, skeleton, physics asset, etc.)
InDataType |
|
overridevirtual |
Returns the properties used for network replication, this needs to be overridden by all actor classes with native.
replicated properties
OutLifetimeProps | Output lifetime properties |
Reimplemented from ARRBaseActor.
Reimplemented in ARobotVehicle, and ATurtlebotBurgerVehicle.
|
inline |
Get robot ID.
|
inlinevirtual |
|
protectedvirtual |
Create and Initialize MovementComponent if VehicleMoveComponentClass != nullptr.
If VehicleMoveComponentClass == nullptr, it is expected that MovementComponent is set from BP or user code.
|
virtual |
Parse Json parameters in ROSSpawnParameters.
This function is called in PreInitializeComponents
Please overwrite this function to parse your custom parameters
|
inlinevirtual |
void ARRBaseRobot::InitROS2Interface | ( | ) |
Initialize ROS 2 Interface. Directly call URRRobotROS2Interface::Initialize or execute in client via OnRep_bStartStopROS2Interface.
bool ARRBaseRobot::InitROS2InterfaceImpl | ( | ) |
|
virtual |
Initialize sensors components which are child class of URRROS2BaseSensorComponent.
InROS2Node | ROS2Node which sensor publishers belongs to. |
|
virtual |
Create & init UIWidgetComp.
bool ARRBaseRobot::IsAuthorizedInThisClient | ( | ) |
Check necessary variables has initialized and PlayerId which spawned robot is match to this client PlayerId.
|
inline |
Is static built robot model by the Editor.
|
inline |
DynamicRuntime robot: Implemented purely in cpp, built & loaded up at runtime from raw CAD + metadata (URDF/SDF)
|
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.)
|
virtual |
Function called with bStartStopROS2Interface replication. Start/stop ROS2Interface if it is ready.
|
virtual |
Function called with ROS2Interface replication. Start ROS2Interface if bStartStopROS2Interface=true.
|
overrideprotectedvirtual |
Post Initialization process of actor. Initialize RobotVehicleMoveComponent by calling InitMoveComponent.
Reimplemented in ATurtlebotBurgerBase.
|
overrideprotectedvirtual |
Instantiate default child components.
Reimplemented from ARRBaseActor.
Reimplemented in ATurtlebotBurgerVehicle, and ARobotVehicle.
|
overridevirtual |
Allows a component to replicate other subobject on the actor.
|
virtual |
Set angular velocity to RobotVehicleMoveComponent.
Calls SetLocalAngularVel for setting velocity to RobotVehicleMoveComponent and
SyncServerAngularMovement to sync movement of the robot in the server.
InAngularVel |
void ARRBaseRobot::SetBaseMeshComp | ( | UMeshComponent * | InBaseMeshComp, |
bool | bInMakeAsRoot = true , |
||
bool | bInDestroyDefaultRoot = true |
||
) |
Set BaseMeshComp, optionally making it the new Root, replacing DefaultRoot.
InBaseMeshComp | |
bInMakeAsRoot | |
bInDestroyDefaultRoot | Whether or not destroying DefaultRoot upon (bInMakeAsRoot == true), in which case if kept it is only to support compatibility in users' child-BP class |
|
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.
IsEnable |
|
virtual |
|
virtual |
Set velocity to RobotVehicleMoveComponent.
Calls SetLocalLinearVel for setting velocity to RobotVehicleMoveComponent and
SyncServerLinearMovement to sync movement of the robot in the server.
InLinearVel |
|
virtual |
Set angular velocity to RobotVehicleMoveComponent in the client.
|
virtual |
Set linear velocity to RobotVehicleMoveComponent in the client.
|
virtual |
|
inline |
Set robot ID.
|
inlinevirtual |
|
inline |
Set robot unique name.
|
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
InRootOffset |
void ARRBaseRobot::SetupDefault | ( | ) |
Initialize default components being configurable in child BP classes.
Could only be called in constructor.
|
virtual |
|
virtual |
Stop robot movement, resetting all vel inputs.
|
virtual |
Set rotation and angular velocity to the robot in the server.
InClientTimeStamp | |
InClientRobotRotation | |
InAngularVel |
|
virtual |
Set position and linear velocity to the robot in the server.
InClientTimeStamp | |
InClientRobotPosition | |
InLinearVel |
|
overridevirtual |
Wake rigid body in addition to Super::Tick()
DeltaSeconds |
TObjectPtr<UMeshComponent> ARRBaseRobot::BaseMeshComp = nullptr |
Base mesh comp, normally also as the root comp.
bool ARRBaseRobot::bInitializeJoints = true |
Initialize Joints or not. Initial pose are set in each joint.
bool ARRBaseRobot::bInitializingJoints = false |
Initialize Joints or not. Initial pose are set in each joint.
bool ARRBaseRobot::bInitRobotVehicleMoveComponent = true |
Call ConfigureMovecomponent and RobotVehicleMoveComponent::Initialize() in InitMoveComponent in PostInitializeComponents or not.
bool ARRBaseRobot::bJointControl = true |
Control Joint by ROS2 o rnot.
bool ARRBaseRobot::bMobileRobot = true |
Mobile robot or not. If this is false, movecomponent=nullptr and ROS 2 odom and cmd_vel interface are disabled.
bool ARRBaseRobot::bStartStopROS2Interface = false |
Flag to start/stop ROS2Interfaces. Since RPC can't be used, use replication to trigger initialization.
uint8 ARRBaseRobot::bUIWidgetEnabled |
Enable widget or not.
TObjectPtr<USceneComponent> ARRBaseRobot::DefaultRoot = nullptr |
TMap<FString, URRJointComponent*> ARRBaseRobot::Joints |
TMap<FString, UStaticMeshComponent*> ARRBaseRobot::Links |
TObjectPtr<UMovementComponent> ARRBaseRobot::MovementComponent = nullptr |
Main robot movement component (kinematics/diff-drive or wheels-drive comp)
MovementComponent and RobotVehicleMoveComponent should point to same pointer.
ERRNetworkAuthorityType ARRBaseRobot::NetworkAuthorityType = ERRNetworkAuthorityType::CLIENT |
Network Authority Type.
FOnRobotCreationDone ARRBaseRobot::OnRobotCreationDone |
Robot creation done delegate.
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.
uint64 ARRBaseRobot::RobotID = 0 |
Robot ID No.
FString ARRBaseRobot::RobotModelName |
Robot Model Name (loaded from URDF/SDF)
should be same as EntityModelName in ARRBaseActor
UPROPERTY(VisibleAnyWhere, BlueprintReadOnly, meta = (ExposeOnSpawn = "true"), Replicated)
FString ARRBaseRobot::RobotUniqueName |
UPROPERTY(EditAnywhere, BlueprintReadWrite, meta = (ExposeOnSpawn = "true"), Replicated)
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)
FTransform ARRBaseRobot::RootOffset = FTransform::Identity |
Offset transform between the Actor root component and the pose that will be published in /odom topic.
FTimerHandle ARRBaseRobot::ROS2InitTimer |
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.
TSubclassOf<URRRobotROS2Interface> ARRBaseRobot::ROS2InterfaceClass = nullptr |
Default class to use when ROS 2 Interface is setup for robot.
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.
TObjectPtr<ARRBaseRobot> ARRBaseRobot::ServerRobot = nullptr |
Pointer to the robot's server-owned version.
FVector ARRBaseRobot::TargetAngularVel = FVector::ZeroVector |
[deg/s] Local target angular vel [X:Roll - Y:Pitch - Z: Yaw]
FVector ARRBaseRobot::TargetLinearVel = FVector::ZeroVector |
[cm/s] Local target linear vel
TSubclassOf<UUserWidget> ARRBaseRobot::UIUserWidgetClass |
TObjectPtr<URRUIWidgetComponent> ARRBaseRobot::UIWidgetComp = nullptr |
UI widget component.
FTransform ARRBaseRobot::UIWidgetOffset = FTransform(FVector(0.f, 0.f, 100.f)) |
Relative pose of the UI widget from the owner robot.
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.