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

Base Robot ROS 2 interface class. More...

#include <RRRobotROS2Interface.h>

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

Public Member Functions

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 void Initialize (AActor *Owner) override
 Initialize robot's ROS 2 interface by calling InitRobotROS2Node, InitPublishers, InitSubscriptions and ARRBaseRobot::InitSensors. More...
 
virtual void InitInterfaces () override
 Init publishers, subscribers, service clients, service servers, action clients, and action servers. More...
 
virtual void DeInitialize () override
 DeInitialize robot's ROS 2 interface by stopping publisher. More...
 
virtual void InitROS2NodeParam (AActor *Owner) override
 Spawn ROS2 Node, and initialize it if ROS2 Node = nullptr. More...
 
virtual void JointCmdCallback (const UROS2GenericMsg *Msg)
 Move robot joints by setting position or velocity to Pawn(=Robot) with given ROS 2 msg. More...
 
void UpdateJointState (UROS2GenericMsg *InMessage)
 Update Joint State msg. More...
 
virtual bool InitPublishers () override
 Initialize non sensor basic publishers such as odometry. More...
 
virtual bool InitSubscriptions () override
 Initialize subscriptions for cmd_vel & joint_states topics. More...
 
virtual void MovementCallback (const UROS2GenericMsg *Msg)
 MoveRobot by setting velocity to Pawn(=Robot) with given ROS 2 msg. More...
 
- Public Member Functions inherited from URRBaseROS2Interface
virtual bool IsSupportedForNetworking () const override
 
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...
 
void BPInitialize ()
 AdditionalInitialization implemented in BP. More...
 
virtual void InitRobotROS2Node (AActor *Owner)
 Spawn ROS2Node and initialize it. More...
 
virtual void SetupROSParams ()
 Setup ROS Params, overridable by child classes to config custom ROS 2 Interface's params. More...
 
void BPSetupROSParams ()
 Setup ROS params called after SetupROSParams. override by BP child class to config custom ROS 2 Interface's params. More...
 
void SetupROSParamsAll ()
 Call SetupROSParams and BPSetupROSParams. More...
 
virtual void StopPublishers ()
 Stop all publishers. More...
 
virtual bool InitServiceClients ()
 Initialize service clients. More...
 
virtual bool InitServiceServers ()
 Initialize service servers. More...
 
virtual bool InitActionClients ()
 Initialize action clients. More...
 
virtual bool InitActionServers ()
 Initialize action servers. More...
 

Public Attributes

TObjectPtr< ARRBaseRobotRobot = nullptr
 Target robot. More...
 
TObjectPtr< URRBaseOdomComponentOdomComponent = nullptr
 Odometry source. More...
 
bool bPublishOdom = true
 
bool bPublishOdomTf = false
 
float OdomPublicationFrequencyHz = 30
 
FString CmdVelTopicName = TEXT("cmd_vel")
 Movement command topic. If empty is given, subscriber will not be initiated. More...
 
FString JointCmdTopicName = TEXT("ue_joint_commands")
 Joint control command topic. If empty is given, subscriber will not be initiated. More...
 
TObjectPtr< UROS2Publisher > JointStatePublisher = nullptr
 JointState Publisher. More...
 
float JointStatePublicationFrequencyHz = 30.f
 Joint control command topic. If empty is given, subscriber will not be initiated. More...
 
FString JointStateTopicName = TEXT("ue_joint_states")
 Joint state topic. More...
 
bool bWarnAboutMissingLink = true
 
TObjectPtr< URRROS2TFsPublisherJointsTFPublisher = nullptr
 
bool bPublishJointTf = false
 
float JointTfPublicationFrequencyHz = 1.f
 
TObjectPtr< URRROS2OdomPublisherOdomPublisher = nullptr
 Odom publisher. More...
 
- Public Attributes inherited from URRBaseROS2Interface
TObjectPtr< UROS2NodeComponent > RobotROS2Node = nullptr
 ROS 2 node of this interface created by InitRobotROS2Node. More...
 
TObjectPtr< UROS2SpawnableROSSpawnParameters = nullptr
 ROS2SpawnParameters which is created when robot is spawn from /SpawnEntity srv provided by ASimulationState. More...
 
FString DefautlROSNamespace = TEXT("")
 Defautl ROS namespace. More...
 
TMap< FString, UROS2Publisher * > Publishers
 You can add your publishers here to ask ROS2Interface to manage. More...
 
TMap< FString, UROS2Subscriber * > Subscribers
 You can add your subscribers here to ask ROS2Interface to manage. More...
 
TMap< FString, UROS2ServiceClient * > ServiceClients
 You can add your publishers here to ask ROS2Interface to manage. More...
 
TMap< FString, UROS2ServiceServer * > ServiceServers
 You can add your publishers here to ask ROS2Interface to manage. More...
 
TMap< FString, UROS2ActionClient * > ActionClients
 You can add your publishers here to ask ROS2Interface to manage. More...
 
TMap< FString, UROS2ActionServer * > ActionServers
 You can add your publishers here to ask ROS2Interface to manage. More...
 

Protected Member Functions

template<typename TROS2Message , typename TROS2MessageData , typename TRobot , typename TRobotMemFuncType = void (TRobot::*)(const TROS2MessageData&)>
FORCEINLINE void OnMessageReceived (const TROS2Message *InMsg, const TRobotMemFuncType &InMemFunc)
 
template<typename TROS2Message , typename TROS2MessageData , typename TRobot >
FORCEINLINE void OnMessageReceivedFunc (const TROS2Message *InMsg, const TFunction< void(const TROS2MessageData &)> &InFunc)
 
template<typename TService , typename TServiceRequest >
void MakeServiceRequest (const FString &InServiceName, const TServiceRequest &InRequest)
 

Detailed Description

Base Robot ROS 2 interface class.

This class owns ROS2Node and controls ROS 2 interfaces of the Robot, by

Please create child class of this class to custom ROS2Interface which have your own ROS2Interfaces.

Todo:
add handling of service and action.

UCLASS(Blueprintable, EditInlineNew)

Member Function Documentation

◆ DeInitialize()

virtual void URRRobotROS2Interface::DeInitialize ( )
overridevirtual

DeInitialize robot's ROS 2 interface by stopping publisher.

Parameters
InRobot

Reimplemented from URRBaseROS2Interface.

◆ GetLifetimeReplicatedProps()

virtual void URRRobotROS2Interface::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

◆ Initialize()

virtual void URRRobotROS2Interface::Initialize ( AActor *  Owner)
overridevirtual

Initialize robot's ROS 2 interface by calling InitRobotROS2Node, InitPublishers, InitSubscriptions and ARRBaseRobot::InitSensors.

This method is mainly used by #ARRBaseoRbotROSController via ARRBaseRobot::InitROS2Interface.

Parameters
InRobot

Reimplemented from URRBaseROS2Interface.

◆ InitInterfaces()

virtual void URRRobotROS2Interface::InitInterfaces ( )
overridevirtual

Init publishers, subscribers, service clients, service servers, action clients, and action servers.

Reimplemented from URRBaseROS2Interface.

◆ InitPublishers()

virtual bool URRRobotROS2Interface::InitPublishers ( )
overridevirtual

Initialize non sensor basic publishers such as odometry.

Overidden in child robot ROS 2 interface classes for specialized publishers.

Reimplemented from URRBaseROS2Interface.

◆ InitROS2NodeParam()

virtual void URRRobotROS2Interface::InitROS2NodeParam ( AActor *  Owner)
overridevirtual

Spawn ROS2 Node, and initialize it if ROS2 Node = nullptr.

Parameters
Owner

Reimplemented from URRBaseROS2Interface.

◆ InitSubscriptions()

virtual bool URRRobotROS2Interface::InitSubscriptions ( )
overridevirtual

Initialize subscriptions for cmd_vel & joint_states topics.

Overidden in child robot ROS 2 interface classes for specialized topic subscriptions.

Reimplemented from URRBaseROS2Interface.

◆ JointCmdCallback()

virtual void URRRobotROS2Interface::JointCmdCallback ( const UROS2GenericMsg *  Msg)
virtual

Move robot joints by setting position or velocity to Pawn(=Robot) with given ROS 2 msg.

Supports only 1 DOF joints.

Effort control is not supported.

See also
sensor_msgs/JointState

UFUNCTION()

◆ MakeServiceRequest()

template<typename TService , typename TServiceRequest >
void URRRobotROS2Interface::MakeServiceRequest ( const FString &  InServiceName,
const TServiceRequest &  InRequest 
)
inlineprotected

◆ MovementCallback()

virtual void URRRobotROS2Interface::MovementCallback ( const UROS2GenericMsg *  Msg)
virtual

MoveRobot by setting velocity to Pawn(=Robot) with given ROS 2 msg.

Typically this receive Twist msg to move robot.

UFUNCTION()

◆ OnMessageReceived()

template<typename TROS2Message , typename TROS2MessageData , typename TRobot , typename TRobotMemFuncType = void (TRobot::*)(const TROS2MessageData&)>
FORCEINLINE void URRRobotROS2Interface::OnMessageReceived ( const TROS2Message *  InMsg,
const TRobotMemFuncType &  InMemFunc 
)
inlineprotected

◆ OnMessageReceivedFunc()

template<typename TROS2Message , typename TROS2MessageData , typename TRobot >
FORCEINLINE void URRRobotROS2Interface::OnMessageReceivedFunc ( const TROS2Message *  InMsg,
const TFunction< void(const TROS2MessageData &)> &  InFunc 
)
inlineprotected

◆ UpdateJointState()

void URRRobotROS2Interface::UpdateJointState ( UROS2GenericMsg *  InMessage)

Update Joint State msg.

Parameters
InMessage

UFUNCTION()

Member Data Documentation

◆ bPublishJointTf

bool URRRobotROS2Interface::bPublishJointTf = false

◆ bPublishOdom

bool URRRobotROS2Interface::bPublishOdom = true

◆ bPublishOdomTf

bool URRRobotROS2Interface::bPublishOdomTf = false

◆ bWarnAboutMissingLink

bool URRRobotROS2Interface::bWarnAboutMissingLink = true

◆ CmdVelTopicName

FString URRRobotROS2Interface::CmdVelTopicName = TEXT("cmd_vel")

Movement command topic. If empty is given, subscriber will not be initiated.

UPROPERTY(EditAnywhere, BlueprintReadWrite, Replicated)

◆ JointCmdTopicName

FString URRRobotROS2Interface::JointCmdTopicName = TEXT("ue_joint_commands")

Joint control command topic. If empty is given, subscriber will not be initiated.

UPROPERTY(EditAnywhere, BlueprintReadWrite, Replicated)

◆ JointStatePublicationFrequencyHz

float URRRobotROS2Interface::JointStatePublicationFrequencyHz = 30.f

Joint control command topic. If empty is given, subscriber will not be initiated.

UPROPERTY(EditAnywhere, BlueprintReadWrite, Replicated)

◆ JointStatePublisher

TObjectPtr<UROS2Publisher> URRRobotROS2Interface::JointStatePublisher = nullptr

◆ JointStateTopicName

FString URRRobotROS2Interface::JointStateTopicName = TEXT("ue_joint_states")

◆ JointsTFPublisher

TObjectPtr<URRROS2TFsPublisher> URRRobotROS2Interface::JointsTFPublisher = nullptr

◆ JointTfPublicationFrequencyHz

float URRRobotROS2Interface::JointTfPublicationFrequencyHz = 1.f

◆ OdomComponent

TObjectPtr<URRBaseOdomComponent> URRRobotROS2Interface::OdomComponent = nullptr

◆ OdomPublicationFrequencyHz

float URRRobotROS2Interface::OdomPublicationFrequencyHz = 30

◆ OdomPublisher

TObjectPtr<URRROS2OdomPublisher> URRRobotROS2Interface::OdomPublisher = nullptr

◆ Robot

TObjectPtr<ARRBaseRobot> URRRobotROS2Interface::Robot = nullptr

The documentation for this class was generated from the following file: