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

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

#include <RRAIRobotROSController.h>

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

Public Member Functions

virtual bool SetSpeed (const float InSpeed)
 Set Speed to UFloatingPawnMovement or UCharacterMovementComponent. More...
 
virtual bool SetRotationRate (const float InRotationRate)
 Set RotationRate toUCharacterMovementComponent. More...
 
virtual bool SetAcceleration (const float InAcceleration)
 Set Acceleration to UFloatingPawnMovement. More...
 
virtual FTransform GetOrigin ()
 Return origin transform from OriginActor or Origin. More...
 
bool InitPropertiesFromJSON ()
 Init propertiese from JSON which is used when pawn is spawned from ROS2 spawn entity service. More...
 

Public Attributes

bool bDebug = false
 debug flat More...
 
float OrientationTolerance = 5.f
 [degree] tolerance for orientation control More...
 
float LinearMotionTolerance = 10.f
 
FRotator OrientationTarget = FRotator::ZeroRotator
 Orientation target in ERRAIRobotMode::ROTATING. More...
 
FVector LinearMotionTarget = FVector::ZeroVector
 Linear motion target in ERRAIRobotMode::LINEAR_MOVING. More...
 
bool bTeleportOnFail = true
 Teleport to target pose if robot can't reach target pose. More...
 
TObjectPtr< UROS2Publisher > NavStatusPublisher = nullptr
 Publisher of ERRAIRobotNavStatus. More...
 
float NavStatusPublicationFrequencyHz = 1
 
FString SetSpeedTopicName = TEXT("set_speed")
 
FString SetAngularVelTopicName = TEXT("set_angular_vel")
 
FString SetModeTopicName = TEXT("set_mode")
 
FString NavStatusTopicName = TEXT("nav_status")
 
FString PoseGoalTopicName = TEXT("pose_goal")
 
FString ActorGoalTopicName = TEXT("actor_goal")
 
ERRAIRobotMode Mode = ERRAIRobotMode::MANUAL
 
FVector RandomMoveBoundingBox = FVector::OneVector
 Bounding box for random move. This is used when Mode is ERRAIRobotMode::RANDOM_AREA. More...
 
TArray< FTransform > GoalSequence
 Goal sequence. This is used when Mode is ERRAIRobotMode::SEQUENCE and ERRAIRobotMode::RANDOM_SEQUENCE. More...
 
AActor * OriginActor = nullptr
 Origin actor for move. This is used when Mode is ERRAIRobotMode::RANDOM_AREA, ERRAIRobotMode::SEQUENCE and ERRAIRobotMode::RANDOM_SEQUENCE. More...
 
FTransform Origin = FTransform::Identity
 Origin transform for move. This is used when Mode is ERRAIRobotMode::RANDOM_AREA, ERRAIRobotMode::SEQUENCE and ERRAIRobotMode::RANDOM_SEQUENCE. More...
 

Protected Member Functions

virtual void OnPossess (APawn *InPawn) override
 Initialize robot pawn by calling ARRBaseRobot::InitROS2Interface. More...
 
virtual void OnUnPossess () override
 Deinitialize robot pawn by calling ARRBaseRobot::DeInitROS2Interface. More...
 
virtual void OnMoveCompleted (FAIRequestID RequestID, const FPathFollowingResult &Result) override
 
virtual void SetDelegates (const FMoveCompleteCallback &InOnSuccess, const FMoveCompleteCallback &InOnFail, const float InLinearMotionToleranc=-1.0, const float InOrientationTolerance=-1.0, const float InTimeOut=-1.0f, const bool Verbose=false)
 Set Delegates for move to target. More...
 
virtual EPathFollowingRequestResult::Type MoveToActorWithDelegates (AActor *Goal, const FMoveCompleteCallback &InOnSuccess, const FMoveCompleteCallback &InOnFail, float AcceptanceRadius=-1, bool bStopOnOverlap=true, bool bUsePathfinding=true, bool bCanStrafe=true, TSubclassOf< UNavigationQueryFilter > FilterClass=NULL, bool bAllowPartialPath=true, const float InOrientationTolerance=-1.0, const float InTimeOut=-1.0)
 Rotate after AAIController::MoveToActor is completed and call InOnSuccess or InOnFail. More...
 
virtual EPathFollowingRequestResult::Type MoveToLocationWithDelegates (const FVector &Dest, const FRotator &DestRotator, const FMoveCompleteCallback &InOnSuccess, const FMoveCompleteCallback &InOnFail, float AcceptanceRadius=-1, bool bStopOnOverlap=true, bool bUsePathfinding=true, bool bProjectDestinationToNavigation=false, bool bCanStrafe=true, TSubclassOf< UNavigationQueryFilter > FilterClass=NULL, bool bAllowPartialPath=true, const float InOrientationTolerance=-1.0, const float InTimeOut=-1.0, const FVector &InOriginPosition=FVector::ZeroVector, const FRotator &InOriginRotator=FRotator::ZeroRotator)
 Rotate after AAIController::MoveToLocation is completed and call InOnSuccess or InOnFail. More...
 
virtual bool LinearMoveToLocationWithDelegates (const FVector &Dest, const FRotator &DestRotator, const FMoveCompleteCallback &InOnSuccess, const FMoveCompleteCallback &InOnFail, float AcceptanceRadius=-1, const float InOrientationTolerance=-1.0, const float InTimeOut=-1.0, const FVector &InOriginPosition=FVector::ZeroVector, const FRotator &InOriginRotator=FRotator::ZeroRotator)
 1)Rotate, 2) Move forward to Dest, 3) Rotate to DestRotator and call InOnSuccess or InOnFail. This does not use AIMove in UE but just rotate and linear movement. More...
 
virtual bool HasReachedOrientationTarget (const float InOrientationTolerance=-1.0)
 Check orientation reach the target orientation and call InOnSuccess or InOnFail if it reach target. More...
 
virtual bool HasReachedOrientationTarget (const FRotator InOrientationTarget, const float InOrientationTolerance=-1.0)
 Check orientation reach the target orientation. More...
 
virtual bool OrientationEquals (const FRotator InOrientationTarget1, const FRotator InOrientationTarget2, const float InOrientationTolerance=-1.0)
 Check InOrientationTarget1 and InOrientationTarget2 are equal. More...
 
virtual bool HasReachedLinearMotionTarget (const float InLinearMotionTolerance=-1.0)
 Check location reach the target location and call InOnSuccess or InOnFail if it reach target. More...
 
virtual bool HasReachedLinearMotionTarget (const FVector InLinearMotionTarget, const float InLinearMotionTolerance=-1.0)
 Check location reach the target location. More...
 
virtual bool PositionEquals (const FVector InLinearMotionTarget1, const FVector InLinearMotionTarget2, const float InLinearMotionTolerance=-1.0)
 Check InLinearMotionTarget1 and InLinearMotionTarget2 are equal. More...
 
virtual bool SetOrientationTarget (const FRotator &InOrientation, const bool InReset=true, const FRotator &InOriginRotator=FRotator::ZeroRotator)
 Set the Orientation Target and start rotating. More...
 
virtual bool AddLocalOrientationOffset (const FRotator &InOrientation, const bool InReset=true)
 Set the relative Orientation Target from current location and start rotating. More...
 
virtual bool SetOrientationTargetWthDelegates (const FRotator &InOrientation, const FMoveCompleteCallback &InOnSuccess, const FMoveCompleteCallback &InOnFail, const float InOrientationTolerance=-1.0, const float InTimeOut=-1.0, const FRotator &InOriginRotator=FRotator::ZeroRotator)
 Set the Orientation Target and start rotating. InOnSuccess or InOnFail is called when it completed. More...
 
virtual bool AddLocalOrientationOffsetWthDelegates (const FRotator &InOrientation, const FMoveCompleteCallback &InOnSuccess, const FMoveCompleteCallback &InOnFail, const float InOrientationTolerance=-1.0, const float InTimeOut=-1.0)
 Set the relative Orientation Target from current location and start rotating. InOnSuccess or InOnFail is called when it completed. More...
 
virtual bool SetLinearMotionTarget (const FVector &InPosition, const bool InReset=true, const FVector &InOriginPosition=FVector::ZeroVector, const FRotator &InOriginRotator=FRotator::ZeroRotator)
 Set the Linear Motion Target and start moving. More...
 
virtual bool AddLocalLinearMotionOffset (const FVector &InPosition, const bool InReset=true)
 Set the relative Linear Motion Target from current location and start moving. More...
 
virtual bool SetLinearMotionTargetWthDelegates (const FVector &InPosition, const FMoveCompleteCallback &InOnSuccess, const FMoveCompleteCallback &InOnFail, const float InLinearMotionTolerancee=-1.0, const float InTimeOut=-1.0, const FVector &InOriginPosition=FVector::ZeroVector, const FRotator &InOriginRotator=FRotator::ZeroRotator)
 Set the Linear Motion Target and start moving. InOnSuccess or InOnFail is called when it completed. More...
 
virtual bool AddLocalLinearMotionOffsetWthDelegates (const FVector &InPosition, const FMoveCompleteCallback &InOnSuccess, const FMoveCompleteCallback &InOnFail, const float InLinearMotionTolerancee=-1.0, const float InTimeOut=-1.0)
 Set the relative Linear Motion Target from current location and start moving. InOnSuccess or InOnFail is called when it completed. More...
 
virtual void Tick (float DeltaSeconds) override
 
virtual void UpdateControl (float DeltaSeconds)
 UpdateRotation and UpdateLinearMotion More...
 
virtual void UpdateRotation (float DeltaSeconds)
 Update oorientation motion when NavStatus is ERRAIRobotNavStatus::ROTATING. More...
 
virtual void UpdateLinearMotion (float DeltaSeconds)
 Update linear motion when NavStatus is ERRAIRobotNavStatus::LINEAR_MOVING. More...
 
virtual void ResetControl ()
 Unbind delegates and reset status. More...
 
virtual bool InProgress ()
 is NavStatus IDLE or not More...
 
void InitROS2Interface ()
 Initialize Parameter and start timer to call InitROS2InterfaceImpl. More...
 
bool InitROS2InterfaceImpl ()
 Create publishers and subscribers. More...
 
void UpdateNavStatus (UROS2GenericMsg *InMessage)
 Update NavStatus msg before publishing. More...
 
void PoseGoalCallback (const UROS2GenericMsg *Msg)
 Call MoveToLocationWithDelegates with given msg. More...
 
void ActorGoalCallback (const UROS2GenericMsg *Msg)
 Call MoveToActorWithDelegates with given msg. More...
 
void SetSpeedCallback (const UROS2GenericMsg *Msg)
 Call SetSpeed with given msg. More...
 
void SetAngularVelCallback (const UROS2GenericMsg *Msg)
 Call SetRotationRate with given msg. More...
 
void SetModeCallback (const UROS2GenericMsg *Msg)
 Call SetMode with given msg. More...
 
bool UpdateGoalSequenceIndex (FTransform &OutGoal)
 Increment GoalIndex. More...
 
bool RandomUpdateGoalSequenceIndex (FTransform &OutGoal)
 Update GoalIndex randomly. More...
 
virtual void ModeUpdate ()
 Mode transition function. This is called in Tick. More...
 

Static Protected Member Functions

static ARRAIRobotROSControllerCheckController (APawn *TargetPawn)
 Check controller is child class of ARRAIRobotROSController or not. More...
 

Protected Attributes

FVector AIMovePositionTarget
 Target position for AI movement. More...
 
float RotationRate = 90.f
 
float LinearSpeed = 100.f
 
FVector AngularVelocity = FVector::ZeroVector
 
ERRAIRobotNavStatus NavStatus = ERRAIRobotNavStatus::IDLE
 
FMoveCompleteCallback OnSuccess
 Delegate which is called when joint reach target vel/pose. More...
 
FMoveCompleteCallbackStatic OnSuccessInternal
 Delegate which is called on action completed internally. More...
 
FMoveCompleteCallback OnFail
 Delegate which is called whenjoint failed to reach target vel/pose. More...
 
 Category = "AI|Navigation"
 Rotate after AAIController::MoveToActor is completed and call InOnSuccess or InOnFail. More...
 
 meta
 1)Rotate, 2) Move forward to Dest, 3) Rotate to DestRotator and call InOnSuccess or InOnFail. This does not use AIMove in UE but just rotate and linear movement. More...
 
float MoveStartTime = 0.f
 time when target pose/vel are set. More...
 
float MoveTimeout = -1.0f
 timeout. If Pawn can't reach target in this duration, OnFail should be called. More...
 
FTimerHandle ROS2InitTimer
 Timer to call InitROS2Interface. More...
 
int GoalIndex = 0
 Current goal index in GoalSequence used in ERRAIRobotMode::SEQUENCE and ERRAIRobotMode::RANDOM_SEQUENCE. More...
 
bool bModeUpdate = true
 Mode transition in Tick. More...
 
- Protected Attributes inherited from ARRBaseRobotROSController
URRBaseROS2InterfaceROS2Interface = nullptr
 

Detailed Description

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

This class has authority to start ROS 2 Component in pausses robot.

See also
AAIController
https://answers.unrealengine.com/questions/871116/view.html
https://answers.unrealengine.com/questions/239159/how-many-ai-controllers-should-i-have.html
Todo:
not work in client-server

UCLASS(ClassGroup = (Custom), meta = (BlueprintSpawnableComponent))

Base class for ROS controllers of ARR robots.

This class provides common functionality and properties for controlling ARR robots using ROS.

It inherits from ARRBaseRobotROSController and adds additional properties and functions specific to ROS control.

Member Function Documentation

◆ ActorGoalCallback()

void ARRAIRobotROSController::ActorGoalCallback ( const UROS2GenericMsg *  Msg)
protected

Call MoveToActorWithDelegates with given msg.

Parameters
Msg

UFUNCTION()

◆ AddLocalLinearMotionOffset()

virtual bool ARRAIRobotROSController::AddLocalLinearMotionOffset ( const FVector &  InPosition,
const bool  InReset = true 
)
protectedvirtual

Set the relative Linear Motion Target from current location and start moving.

Parameters
InPosition
InReset
Returns
true
false

◆ AddLocalLinearMotionOffsetWthDelegates()

virtual bool ARRAIRobotROSController::AddLocalLinearMotionOffsetWthDelegates ( const FVector &  InPosition,
const FMoveCompleteCallback &  InOnSuccess,
const FMoveCompleteCallback &  InOnFail,
const float  InLinearMotionTolerancee = -1.0,
const float  InTimeOut = -1.0 
)
protectedvirtual

Set the relative Linear Motion Target from current location and start moving. InOnSuccess or InOnFail is called when it completed.

Parameters
InPosition
InOnSuccess
InOnFail
InLinearMotionTolerancee
InTimeOut
Returns
true
false

◆ AddLocalOrientationOffset()

virtual bool ARRAIRobotROSController::AddLocalOrientationOffset ( const FRotator &  InOrientation,
const bool  InReset = true 
)
protectedvirtual

Set the relative Orientation Target from current location and start rotating.

Parameters
InOrientation
InReset
Returns
true
false

◆ AddLocalOrientationOffsetWthDelegates()

virtual bool ARRAIRobotROSController::AddLocalOrientationOffsetWthDelegates ( const FRotator &  InOrientation,
const FMoveCompleteCallback &  InOnSuccess,
const FMoveCompleteCallback &  InOnFail,
const float  InOrientationTolerance = -1.0,
const float  InTimeOut = -1.0 
)
protectedvirtual

Set the relative Orientation Target from current location and start rotating. InOnSuccess or InOnFail is called when it completed.

Parameters
InOrientation
InOnSuccess
InOnFail
InOrientationTolerance
InTimeOut
Returns
true
false

◆ CheckController()

static ARRAIRobotROSController* ARRAIRobotROSController::CheckController ( APawn *  TargetPawn)
staticprotected

Check controller is child class of ARRAIRobotROSController or not.

Parameters
TargetPawn
Returns
ARRAIRobotROSController*

◆ GetOrigin()

virtual FTransform ARRAIRobotROSController::GetOrigin ( )
virtual

Return origin transform from OriginActor or Origin.

UFUNCTION(BlueprintCallable)

◆ HasReachedLinearMotionTarget() [1/2]

virtual bool ARRAIRobotROSController::HasReachedLinearMotionTarget ( const float  InLinearMotionTolerance = -1.0)
protectedvirtual

Check location reach the target location and call InOnSuccess or InOnFail if it reach target.

Parameters
InLinearMotionToleranceIf minus values are given, LinearMotionTolerance will be used.
Returns
true
false

UFUNCTION(BlueprintCallable)

◆ HasReachedLinearMotionTarget() [2/2]

virtual bool ARRAIRobotROSController::HasReachedLinearMotionTarget ( const FVector  InLinearMotionTarget,
const float  InLinearMotionTolerance = -1.0 
)
protectedvirtual

Check location reach the target location.

Parameters
InLinearMotionTarget
InLinearMotionToleranceIf minus values are given, LinearMotionTolerance will be used.
Returns
true
false

◆ HasReachedOrientationTarget() [1/2]

virtual bool ARRAIRobotROSController::HasReachedOrientationTarget ( const float  InOrientationTolerance = -1.0)
protectedvirtual

Check orientation reach the target orientation and call InOnSuccess or InOnFail if it reach target.

Parameters
InOrientationToleranceIf minus values are given, OrientationTolerance will be used.
Returns
true
false

UFUNCTION(BlueprintCallable)

◆ HasReachedOrientationTarget() [2/2]

virtual bool ARRAIRobotROSController::HasReachedOrientationTarget ( const FRotator  InOrientationTarget,
const float  InOrientationTolerance = -1.0 
)
protectedvirtual

Check orientation reach the target orientation.

Parameters
InOrientationTarget
InOrientationToleranceIf minus values are given, OrientationTolerance will be used.
Returns
true
false

◆ InitPropertiesFromJSON()

bool ARRAIRobotROSController::InitPropertiesFromJSON ( )

Init propertiese from JSON which is used when pawn is spawned from ROS2 spawn entity service.

UFUNCTION(BlueprintCallable)

◆ InitROS2Interface()

void ARRAIRobotROSController::InitROS2Interface ( )
protected

Initialize Parameter and start timer to call InitROS2InterfaceImpl.

UFUNCTION()

◆ InitROS2InterfaceImpl()

bool ARRAIRobotROSController::InitROS2InterfaceImpl ( )
protected

Create publishers and subscribers.

UFUNCTION()

◆ InProgress()

virtual bool ARRAIRobotROSController::InProgress ( )
protectedvirtual

is NavStatus IDLE or not

Returns
virtial

UFUNCTION(BlueprintCallable)

◆ LinearMoveToLocationWithDelegates()

virtual bool ARRAIRobotROSController::LinearMoveToLocationWithDelegates ( const FVector &  Dest,
const FRotator &  DestRotator,
const FMoveCompleteCallback &  InOnSuccess,
const FMoveCompleteCallback &  InOnFail,
float  AcceptanceRadius = -1,
const float  InOrientationTolerance = -1.0,
const float  InTimeOut = -1.0,
const FVector &  InOriginPosition = FVector::ZeroVector,
const FRotator &  InOriginRotator = FRotator::ZeroRotator 
)
protectedvirtual

1)Rotate, 2) Move forward to Dest, 3) Rotate to DestRotator and call InOnSuccess or InOnFail. This does not use AIMove in UE but just rotate and linear movement.

Parameters
Dest
DestRotator
InOnSuccess
InOnFail
AcceptanceRadius
InOrientationTolerance
InTimeOut
InOriginPosition
InOriginRotator
Returns
true
false

◆ ModeUpdate()

virtual void ARRAIRobotROSController::ModeUpdate ( )
protectedvirtual

Mode transition function. This is called in Tick.

UFUNCTION()

◆ MoveToActorWithDelegates()

virtual EPathFollowingRequestResult::Type ARRAIRobotROSController::MoveToActorWithDelegates ( AActor *  Goal,
const FMoveCompleteCallback &  InOnSuccess,
const FMoveCompleteCallback &  InOnFail,
float  AcceptanceRadius = -1,
bool  bStopOnOverlap = true,
bool  bUsePathfinding = true,
bool  bCanStrafe = true,
TSubclassOf< UNavigationQueryFilter >  FilterClass = NULL,
bool  bAllowPartialPath = true,
const float  InOrientationTolerance = -1.0,
const float  InTimeOut = -1.0 
)
protectedvirtual

Rotate after AAIController::MoveToActor is completed and call InOnSuccess or InOnFail.

See also
AAIController::MoveToActor
Parameters
Goal
InOnSuccess
InOnFail
AcceptanceRadius
bStopOnOverlap
bUsePathfinding
bCanStrafe
FilterClass
bAllowPartialPath
InOrientationTolerance
InTimeOut
Returns
EPathFollowingRequestResult::Type

◆ MoveToLocationWithDelegates()

virtual EPathFollowingRequestResult::Type ARRAIRobotROSController::MoveToLocationWithDelegates ( const FVector &  Dest,
const FRotator &  DestRotator,
const FMoveCompleteCallback &  InOnSuccess,
const FMoveCompleteCallback &  InOnFail,
float  AcceptanceRadius = -1,
bool  bStopOnOverlap = true,
bool  bUsePathfinding = true,
bool  bProjectDestinationToNavigation = false,
bool  bCanStrafe = true,
TSubclassOf< UNavigationQueryFilter >  FilterClass = NULL,
bool  bAllowPartialPath = true,
const float  InOrientationTolerance = -1.0,
const float  InTimeOut = -1.0,
const FVector &  InOriginPosition = FVector::ZeroVector,
const FRotator &  InOriginRotator = FRotator::ZeroRotator 
)
protectedvirtual

Rotate after AAIController::MoveToLocation is completed and call InOnSuccess or InOnFail.

See also
AAIController::MoveToLocation
Parameters
Dest
DestRotator
InOnSuccess
InOnFail
AcceptanceRadius
bStopOnOverlap
bUsePathfinding
bProjectDestinationToNavigation
bCanStrafe
FilterClass
bAllowPartialPath
InOrientationTolerance
InTimeOut
InOriginPosition
InOriginRotator
Returns
EPathFollowingRequestResult::Type

◆ OnMoveCompleted()

virtual void ARRAIRobotROSController::OnMoveCompleted ( FAIRequestID  RequestID,
const FPathFollowingResult &  Result 
)
overrideprotectedvirtual

◆ OnPossess()

virtual void ARRAIRobotROSController::OnPossess ( APawn *  InPawn)
overrideprotectedvirtual

Initialize robot pawn by calling ARRBaseRobot::InitROS2Interface.

See also
OnPossess
Parameters
InPawn

Reimplemented from ARRBaseRobotROSController.

◆ OnUnPossess()

virtual void ARRAIRobotROSController::OnUnPossess ( )
overrideprotectedvirtual

Deinitialize robot pawn by calling ARRBaseRobot::DeInitROS2Interface.

See also
OnUnPossess

Reimplemented from ARRBaseRobotROSController.

◆ OrientationEquals()

virtual bool ARRAIRobotROSController::OrientationEquals ( const FRotator  InOrientationTarget1,
const FRotator  InOrientationTarget2,
const float  InOrientationTolerance = -1.0 
)
protectedvirtual

Check InOrientationTarget1 and InOrientationTarget2 are equal.

Parameters
InOrientationTarget1
InOrientationTarget2
InOrientationToleranceIf minus values are given, OrientationTolerance will be used.
Returns
true
false

◆ PoseGoalCallback()

void ARRAIRobotROSController::PoseGoalCallback ( const UROS2GenericMsg *  Msg)
protected

Call MoveToLocationWithDelegates with given msg.

Parameters
Msg

UFUNCTION()

◆ PositionEquals()

virtual bool ARRAIRobotROSController::PositionEquals ( const FVector  InLinearMotionTarget1,
const FVector  InLinearMotionTarget2,
const float  InLinearMotionTolerance = -1.0 
)
protectedvirtual

Check InLinearMotionTarget1 and InLinearMotionTarget2 are equal.

Parameters
InLinearMotionTarget1
InLinearMotionTarget2
InLinearMotionToleranceIf minus values are given, LinearMotionTolerance will be used.
Returns
true
false

◆ RandomUpdateGoalSequenceIndex()

bool ARRAIRobotROSController::RandomUpdateGoalSequenceIndex ( FTransform &  OutGoal)
protected

Update GoalIndex randomly.

Returns
true if GoalSequence is not empty and GoalIndex is > 2
false

UFUNCTION(BlueprintCallable)

◆ ResetControl()

virtual void ARRAIRobotROSController::ResetControl ( )
protectedvirtual

Unbind delegates and reset status.

UFUNCTION(BlueprintCallable)

◆ SetAcceleration()

virtual bool ARRAIRobotROSController::SetAcceleration ( const float  InAcceleration)
virtual

Set Acceleration to UFloatingPawnMovement.

UFUNCTION(BlueprintCallable)

◆ SetAngularVelCallback()

void ARRAIRobotROSController::SetAngularVelCallback ( const UROS2GenericMsg *  Msg)
protected

Call SetRotationRate with given msg.

Parameters
Msg

UFUNCTION()

◆ SetDelegates()

virtual void ARRAIRobotROSController::SetDelegates ( const FMoveCompleteCallback &  InOnSuccess,
const FMoveCompleteCallback &  InOnFail,
const float  InLinearMotionToleranc = -1.0,
const float  InOrientationTolerance = -1.0,
const float  InTimeOut = -1.0f,
const bool  Verbose = false 
)
protectedvirtual

Set Delegates for move to target.

Parameters
InOnControlSuccessDelegatecalled when move to target success
InOnControlFailDelegatecalled when move to target fail
InPositionToleranceupdate #PositionTolerance if this is set >= 0.
InOrientationToleranceupdate OrientationTolerance if this is set >= 0.
InTimeOutif this is set less than 0, timeout won't happen.

◆ SetLinearMotionTarget()

virtual bool ARRAIRobotROSController::SetLinearMotionTarget ( const FVector &  InPosition,
const bool  InReset = true,
const FVector &  InOriginPosition = FVector::ZeroVector,
const FRotator &  InOriginRotator = FRotator::ZeroRotator 
)
protectedvirtual

Set the Linear Motion Target and start moving.

Parameters
InPosition
InReset
InOriginPosition
InOriginRotator
Returns
true
false

◆ SetLinearMotionTargetWthDelegates()

virtual bool ARRAIRobotROSController::SetLinearMotionTargetWthDelegates ( const FVector &  InPosition,
const FMoveCompleteCallback &  InOnSuccess,
const FMoveCompleteCallback &  InOnFail,
const float  InLinearMotionTolerancee = -1.0,
const float  InTimeOut = -1.0,
const FVector &  InOriginPosition = FVector::ZeroVector,
const FRotator &  InOriginRotator = FRotator::ZeroRotator 
)
protectedvirtual

Set the Linear Motion Target and start moving. InOnSuccess or InOnFail is called when it completed.

Parameters
InPosition
InOnSuccess
InOnFail
InLinearMotionTolerancee
InTimeOut
InOriginPosition
InOriginRotator
Returns
true
false

◆ SetModeCallback()

void ARRAIRobotROSController::SetModeCallback ( const UROS2GenericMsg *  Msg)
protected

Call SetMode with given msg.

Parameters
Msg

◆ SetOrientationTarget()

virtual bool ARRAIRobotROSController::SetOrientationTarget ( const FRotator &  InOrientation,
const bool  InReset = true,
const FRotator &  InOriginRotator = FRotator::ZeroRotator 
)
protectedvirtual

Set the Orientation Target and start rotating.

Parameters
InOrientation
InReset
InOriginRotator
Returns
true
false

◆ SetOrientationTargetWthDelegates()

virtual bool ARRAIRobotROSController::SetOrientationTargetWthDelegates ( const FRotator &  InOrientation,
const FMoveCompleteCallback &  InOnSuccess,
const FMoveCompleteCallback &  InOnFail,
const float  InOrientationTolerance = -1.0,
const float  InTimeOut = -1.0,
const FRotator &  InOriginRotator = FRotator::ZeroRotator 
)
protectedvirtual

Set the Orientation Target and start rotating. InOnSuccess or InOnFail is called when it completed.

Parameters
InOrientation
InOnSuccess
InOnFail
InOrientationTolerance
InTimeOut
InOriginRotator
Returns
true
false

◆ SetRotationRate()

virtual bool ARRAIRobotROSController::SetRotationRate ( const float  InRotationRate)
virtual

Set RotationRate toUCharacterMovementComponent.

See also
[UCharacterMovementComponent]https://docs.unrealengine.com/5.3/en-US/API/Runtime/Engine/GameFramework/UCharacterMovementComponent/

UFUNCTION(BlueprintCallable)

◆ SetSpeed()

virtual bool ARRAIRobotROSController::SetSpeed ( const float  InSpeed)
virtual

◆ SetSpeedCallback()

void ARRAIRobotROSController::SetSpeedCallback ( const UROS2GenericMsg *  Msg)
protected

Call SetSpeed with given msg.

Parameters
Msg

UFUNCTION()

◆ Tick()

virtual void ARRAIRobotROSController::Tick ( float  DeltaSeconds)
overrideprotectedvirtual

◆ UpdateControl()

virtual void ARRAIRobotROSController::UpdateControl ( float  DeltaSeconds)
protectedvirtual

UpdateRotation and UpdateLinearMotion

Parameters
DeltaSeconds

◆ UpdateGoalSequenceIndex()

bool ARRAIRobotROSController::UpdateGoalSequenceIndex ( FTransform &  OutGoal)
protected

Increment GoalIndex.

Returns
true
false if GoalSequence is empty.

UFUNCTION(BlueprintCallable)

◆ UpdateLinearMotion()

virtual void ARRAIRobotROSController::UpdateLinearMotion ( float  DeltaSeconds)
protectedvirtual

Update linear motion when NavStatus is ERRAIRobotNavStatus::LINEAR_MOVING.

Parameters
DeltaSeconds

◆ UpdateNavStatus()

void ARRAIRobotROSController::UpdateNavStatus ( UROS2GenericMsg *  InMessage)
protected

Update NavStatus msg before publishing.

Parameters
InMessage

UFUNCTION()

◆ UpdateRotation()

virtual void ARRAIRobotROSController::UpdateRotation ( float  DeltaSeconds)
protectedvirtual

Update oorientation motion when NavStatus is ERRAIRobotNavStatus::ROTATING.

Parameters
DeltaSeconds

Member Data Documentation

◆ ActorGoalTopicName

FString ARRAIRobotROSController::ActorGoalTopicName = TEXT("actor_goal")

◆ AIMovePositionTarget

FVector ARRAIRobotROSController::AIMovePositionTarget
protected

Target position for AI movement.

UPROPERTY(VisibleAnywhere)

◆ AngularVelocity

FVector ARRAIRobotROSController::AngularVelocity = FVector::ZeroVector
protected

◆ bDebug

bool ARRAIRobotROSController::bDebug = false

◆ bModeUpdate

bool ARRAIRobotROSController::bModeUpdate = true
protected

◆ bTeleportOnFail

bool ARRAIRobotROSController::bTeleportOnFail = true

Teleport to target pose if robot can't reach target pose.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ Category

ARRAIRobotROSController::Category = "AI|Navigation"
protected

Rotate after AAIController::MoveToActor is completed and call InOnSuccess or InOnFail.

See also
AAIController::MoveToActor
Parameters
TargetPawn
Goal
InOnSuccess
InOnFail
AcceptanceRadius
bStopOnOverlap
bUsePathfinding
bCanStrafe
FilterClass
bAllowPartialPath
InOrientationTolerance
InTimeOut
Returns
EPathFollowingRequestResult::Type

UFUNCTION(BlueprintCallable,

UFUNCTION(BlueprintCallable,

◆ GoalIndex

int ARRAIRobotROSController::GoalIndex = 0
protected

◆ GoalSequence

TArray<FTransform> ARRAIRobotROSController::GoalSequence

◆ LinearMotionTarget

FVector ARRAIRobotROSController::LinearMotionTarget = FVector::ZeroVector

Linear motion target in ERRAIRobotMode::LINEAR_MOVING.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ LinearMotionTolerance

float ARRAIRobotROSController::LinearMotionTolerance = 10.f

◆ LinearSpeed

float ARRAIRobotROSController::LinearSpeed = 100.f
protected

◆ meta

ARRAIRobotROSController::meta
protected
Initial value:
= (DefaultToSelf = "TargetPawn", AdvancedDisplay = "bStopOnOverlap,bCanStrafe,bAllowPartialPath"))
static EPathFollowingRequestResult::Type MoveToActorWithDelegates(APawn* TargetPawn,
AActor* Goal,
const FMoveCompleteCallback& InOnSuccess,
const FMoveCompleteCallback& InOnFail,
float AcceptanceRadius = -1,
bool bStopOnOverlap = true,
bool bUsePathfinding = true,
bool bCanStrafe = true,
TSubclassOf<UNavigationQueryFilter> FilterClass = NULL,
bool bAllowPartialPath = true,
const float InOrientationTolerance = -1.0,
const float InTimeOut = -1.0)

1)Rotate, 2) Move forward to Dest, 3) Rotate to DestRotator and call InOnSuccess or InOnFail. This does not use AIMove in UE but just rotate and linear movement.

Set the relative Linear Motion Target from current location and start moving. InOnSuccess or InOnFail is called when it completed.

Set the Linear Motion Target and start moving. InOnSuccess or InOnFail is called when it completed.

Set the relative Linear Motion Target from current location and start moving.

Set the Linear Motion Target and start moving.

Set the relative Orientation Target from current location and start rotating. InOnSuccess or InOnFail is called when it completed.

Set the Orientation Target and start rotating. InOnSuccess or InOnFail is called when it completed.

Set the relative Orientation Target from current location and start rotating.

Set the Orientation Target and start rotating.

Parameters
TargetPawn
Dest
DestRotator
InOnSuccess
InOnFail
AcceptanceRadius
InOrientationTolerance
InTimeOut
InOriginPosition
InOriginRotator
Returns
true
false

UFUNCTION(BlueprintCallable,

Parameters
TargetPawn
InOrientation
InReset
InOriginRotator
Returns
true
false

UFUNCTION(BlueprintCallable,

Parameters
TargetPawn
InOrientation
InReset
Returns
true
false

UFUNCTION(BlueprintCallable,

Parameters
TargetPawn
InOrientation
InOnSuccess
InOnFail
InOrientationTolerance
InTimeOut
InOriginRotator
Returns
true
false

UFUNCTION(BlueprintCallable,

Parameters
TargetPawn
InOrientation
InOnSuccess
InOnFail
InOrientationTolerance
InTimeOut
Returns
true
false

UFUNCTION(BlueprintCallable,

Parameters
TargetPawn
InPosition
InReset
InOriginPosition
InOriginRotator
Returns
true
false

UFUNCTION(BlueprintCallable,

Parameters
TargetPawn
InPosition
InReset
Returns
true
false

UFUNCTION(BlueprintCallable,

Parameters
TargetPawn
InPosition
InOnSuccess
InOnFail
InLinearMotionTolerancee
InTimeOut
InOriginPosition
InOriginRotator
Returns
true
false

UFUNCTION(BlueprintCallable,

Parameters
TargetPawn
InPosition
InOnSuccess
InOnFail
InLinearMotionTolerancee
InTimeOut
Returns
true
false

UFUNCTION(BlueprintCallable,

◆ Mode

ERRAIRobotMode ARRAIRobotROSController::Mode = ERRAIRobotMode::MANUAL

◆ MoveStartTime

float ARRAIRobotROSController::MoveStartTime = 0.f
protected

time when target pose/vel are set.

◆ MoveTimeout

float ARRAIRobotROSController::MoveTimeout = -1.0f
protected

timeout. If Pawn can't reach target in this duration, OnFail should be called.

used only with #SetPoseTargetWithDelegate if this is set less than 0, timeout won't happen.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ NavStatus

ERRAIRobotNavStatus ARRAIRobotROSController::NavStatus = ERRAIRobotNavStatus::IDLE
protected

◆ NavStatusPublicationFrequencyHz

float ARRAIRobotROSController::NavStatusPublicationFrequencyHz = 1

◆ NavStatusPublisher

TObjectPtr<UROS2Publisher> ARRAIRobotROSController::NavStatusPublisher = nullptr

Publisher of ERRAIRobotNavStatus.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ NavStatusTopicName

FString ARRAIRobotROSController::NavStatusTopicName = TEXT("nav_status")

◆ OnFail

FMoveCompleteCallback ARRAIRobotROSController::OnFail
protected

Delegate which is called whenjoint failed to reach target vel/pose.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ OnSuccess

FMoveCompleteCallback ARRAIRobotROSController::OnSuccess
protected

Delegate which is called when joint reach target vel/pose.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ OnSuccessInternal

FMoveCompleteCallbackStatic ARRAIRobotROSController::OnSuccessInternal
protected

Delegate which is called on action completed internally.

◆ OrientationTarget

FRotator ARRAIRobotROSController::OrientationTarget = FRotator::ZeroRotator

Orientation target in ERRAIRobotMode::ROTATING.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ OrientationTolerance

float ARRAIRobotROSController::OrientationTolerance = 5.f

[degree] tolerance for orientation control

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ Origin

FTransform ARRAIRobotROSController::Origin = FTransform::Identity

◆ OriginActor

AActor* ARRAIRobotROSController::OriginActor = nullptr

◆ PoseGoalTopicName

FString ARRAIRobotROSController::PoseGoalTopicName = TEXT("pose_goal")

◆ RandomMoveBoundingBox

FVector ARRAIRobotROSController::RandomMoveBoundingBox = FVector::OneVector

Bounding box for random move. This is used when Mode is ERRAIRobotMode::RANDOM_AREA.

UPROPERTY(EditAnywhere, BlueprintReadWrite)

◆ ROS2InitTimer

FTimerHandle ARRAIRobotROSController::ROS2InitTimer
protected

◆ RotationRate

float ARRAIRobotROSController::RotationRate = 90.f
protected

◆ SetAngularVelTopicName

FString ARRAIRobotROSController::SetAngularVelTopicName = TEXT("set_angular_vel")

◆ SetModeTopicName

FString ARRAIRobotROSController::SetModeTopicName = TEXT("set_mode")

◆ SetSpeedTopicName

FString ARRAIRobotROSController::SetSpeedTopicName = TEXT("set_speed")

The documentation for this class was generated from the following file:
ARRAIRobotROSController::MoveToActorWithDelegates
virtual EPathFollowingRequestResult::Type MoveToActorWithDelegates(AActor *Goal, const FMoveCompleteCallback &InOnSuccess, const FMoveCompleteCallback &InOnFail, float AcceptanceRadius=-1, bool bStopOnOverlap=true, bool bUsePathfinding=true, bool bCanStrafe=true, TSubclassOf< UNavigationQueryFilter > FilterClass=NULL, bool bAllowPartialPath=true, const float InOrientationTolerance=-1.0, const float InTimeOut=-1.0)
Rotate after AAIController::MoveToActor is completed and call InOnSuccess or InOnFail.