Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
urcl::rtde_interface::RTDEClient Class Reference

The RTDEClient class manages communication over the RTDE interface. It contains the RTDE handshake and read and write functionality to and from the robot. More...

#include <rtde_client.h>

Public Member Functions

std::unique_ptr< rtde_interface::DataPackagegetDataPackage (std::chrono::milliseconds timeout)
 Reads the pipeline to fetch the next data package. More...
 
std::string getIP () const
 Returns the IP address (of the machine running this driver) used for the socket connection. More...
 
double getMaxFrequency () const
 Getter for the maximum frequency the robot can publish RTDE data packages with. More...
 
std::vector< std::string > getOutputRecipe ()
 Getter for the RTDE output recipe. More...
 
double getTargetFrequency () const
 Getter for the target frequency that the robot will publish RTDE data packages with. More...
 
VersionInformation getVersion ()
 Getter for the UR control version received from the robot. More...
 
RTDEWritergetWriter ()
 Getter for the RTDE writer, which is used to send data via the RTDE interface to the robot. More...
 
bool init ()
 Sets up RTDE communication with the robot. The handshake includes negotiation of the used protocol version and setting of input and output recipes. More...
 
bool pause ()
 Pauses RTDE data package communication. More...
 
 RTDEClient ()=delete
 
 RTDEClient (std::string robot_ip, comm::INotifier &notifier, const std::string &output_recipe_file, const std::string &input_recipe_file, double target_frequency=0.0)
 Creates a new RTDEClient object, including a used URStream and Pipeline to handle the communication with the robot. More...
 
bool start ()
 Triggers the robot to start sending RTDE data packages in the negotiated format. More...
 
 ~RTDEClient ()
 

Private Member Functions

void disconnect ()
 
bool isRobotBooted ()
 Checks whether the robot is booted, this is done by looking at the timestamp from the robot controller, this will show the time in seconds since the controller was started. If the timestamp is below 40, we will read from the stream for approximately 1 second to ensure that the RTDE interface is up and running. This will ensure that we don't finalize setting up communication, before the controller is up and running. Else we could end up connecting to the RTDE interface, before a restart occurs during robot boot which would then destroy the connection established. More...
 
bool negotiateProtocolVersion (const uint16_t protocol_version)
 
void queryURControlVersion ()
 
std::vector< std::string > readRecipe (const std::string &recipe_file)
 
bool sendPause ()
 
bool sendStart ()
 
void setupCommunication ()
 
void setupInputs ()
 
void setupOutputs (const uint16_t protocol_version)
 
std::vector< std::string > splitVariableTypes (const std::string &variable_types) const
 Splits a variable_types string as reported from the robot into single variable type strings. More...
 

Private Attributes

ClientState client_state_
 
std::vector< std::string > input_recipe_
 
double max_frequency_
 
std::vector< std::string > output_recipe_
 
RTDEParser parser_
 
comm::Pipeline< RTDEPackagepipeline_
 
comm::URProducer< RTDEPackageprod_
 
comm::URStream< RTDEPackagestream_
 
double target_frequency_
 
VersionInformation urcontrol_version_
 
RTDEWriter writer_
 

Static Private Attributes

static constexpr const double CB3_MAX_FREQUENCY = 125.0
 
static constexpr const double URE_MAX_FREQUENCY = 500.0
 

Detailed Description

The RTDEClient class manages communication over the RTDE interface. It contains the RTDE handshake and read and write functionality to and from the robot.

Definition at line 92 of file rtde_client.h.

Constructor & Destructor Documentation

◆ RTDEClient() [1/2]

urcl::rtde_interface::RTDEClient::RTDEClient ( )
delete

◆ RTDEClient() [2/2]

urcl::rtde_interface::RTDEClient::RTDEClient ( std::string  robot_ip,
comm::INotifier notifier,
const std::string &  output_recipe_file,
const std::string &  input_recipe_file,
double  target_frequency = 0.0 
)

Creates a new RTDEClient object, including a used URStream and Pipeline to handle the communication with the robot.

Parameters
robot_ipThe IP of the robot
notifierThe notifier to use in the pipeline
output_recipe_filePath to the file containing the output recipe
input_recipe_filePath to the file containing the input recipe
target_frequencyFrequency to run at. Defaults to 0.0 which means maximum frequency.

Definition at line 37 of file src/rtde/rtde_client.cpp.

◆ ~RTDEClient()

urcl::rtde_interface::RTDEClient::~RTDEClient ( )

Definition at line 52 of file src/rtde/rtde_client.cpp.

Member Function Documentation

◆ disconnect()

void urcl::rtde_interface::RTDEClient::disconnect ( )
private

Definition at line 384 of file src/rtde/rtde_client.cpp.

◆ getDataPackage()

std::unique_ptr< rtde_interface::DataPackage > urcl::rtde_interface::RTDEClient::getDataPackage ( std::chrono::milliseconds  timeout)

Reads the pipeline to fetch the next data package.

Parameters
timeoutTime to wait if no data package is currently in the queue
Returns
Unique ptr to the package, if a package was fetched successfully, nullptr otherwise

Definition at line 570 of file src/rtde/rtde_client.cpp.

◆ getIP()

std::string urcl::rtde_interface::RTDEClient::getIP ( ) const

Returns the IP address (of the machine running this driver) used for the socket connection.

Returns
The IP address as a string (e.g. "192.168.0.1")

Definition at line 585 of file src/rtde/rtde_client.cpp.

◆ getMaxFrequency()

double urcl::rtde_interface::RTDEClient::getMaxFrequency ( ) const
inline

Getter for the maximum frequency the robot can publish RTDE data packages with.

Returns
The maximum frequency

Definition at line 142 of file rtde_client.h.

◆ getOutputRecipe()

std::vector<std::string> urcl::rtde_interface::RTDEClient::getOutputRecipe ( )
inline

Getter for the RTDE output recipe.

Returns
The output recipe

Definition at line 187 of file rtde_client.h.

◆ getTargetFrequency()

double urcl::rtde_interface::RTDEClient::getTargetFrequency ( ) const
inline

Getter for the target frequency that the robot will publish RTDE data packages with.

Returns
The target frequency

Definition at line 152 of file rtde_client.h.

◆ getVersion()

VersionInformation urcl::rtde_interface::RTDEClient::getVersion ( )
inline

Getter for the UR control version received from the robot.

Returns
The VersionInformation received from the robot

Definition at line 162 of file rtde_client.h.

◆ getWriter()

RTDEWriter & urcl::rtde_interface::RTDEClient::getWriter ( )

Getter for the RTDE writer, which is used to send data via the RTDE interface to the robot.

Returns
A reference to the used RTDEWriter

Definition at line 590 of file src/rtde/rtde_client.cpp.

◆ init()

bool urcl::rtde_interface::RTDEClient::init ( )

Sets up RTDE communication with the robot. The handshake includes negotiation of the used protocol version and setting of input and output recipes.

Returns
Success of the handshake

Definition at line 57 of file src/rtde/rtde_client.cpp.

◆ isRobotBooted()

bool urcl::rtde_interface::RTDEClient::isRobotBooted ( )
private

Checks whether the robot is booted, this is done by looking at the timestamp from the robot controller, this will show the time in seconds since the controller was started. If the timestamp is below 40, we will read from the stream for approximately 1 second to ensure that the RTDE interface is up and running. This will ensure that we don't finalize setting up communication, before the controller is up and running. Else we could end up connecting to the RTDE interface, before a restart occurs during robot boot which would then destroy the connection established.

Returns
true if the robot is booted, false otherwise which will essentially trigger a reconnection.

Definition at line 393 of file src/rtde/rtde_client.cpp.

◆ negotiateProtocolVersion()

bool urcl::rtde_interface::RTDEClient::negotiateProtocolVersion ( const uint16_t  protocol_version)
private

Definition at line 143 of file src/rtde/rtde_client.cpp.

◆ pause()

bool urcl::rtde_interface::RTDEClient::pause ( )

Pauses RTDE data package communication.

Returns
Whether the RTDE data package communication was paused successfully

Definition at line 456 of file src/rtde/rtde_client.cpp.

◆ queryURControlVersion()

void urcl::rtde_interface::RTDEClient::queryURControlVersion ( )
private

Definition at line 191 of file src/rtde/rtde_client.cpp.

◆ readRecipe()

std::vector< std::string > urcl::rtde_interface::RTDEClient::readRecipe ( const std::string &  recipe_file)
private

Definition at line 551 of file src/rtde/rtde_client.cpp.

◆ sendPause()

bool urcl::rtde_interface::RTDEClient::sendPause ( )
private

Definition at line 519 of file src/rtde/rtde_client.cpp.

◆ sendStart()

bool urcl::rtde_interface::RTDEClient::sendStart ( )
private

Definition at line 477 of file src/rtde/rtde_client.cpp.

◆ setupCommunication()

void urcl::rtde_interface::RTDEClient::setupCommunication ( )
private

Definition at line 80 of file src/rtde/rtde_client.cpp.

◆ setupInputs()

void urcl::rtde_interface::RTDEClient::setupInputs ( )
private

Definition at line 317 of file src/rtde/rtde_client.cpp.

◆ setupOutputs()

void urcl::rtde_interface::RTDEClient::setupOutputs ( const uint16_t  protocol_version)
private

Definition at line 237 of file src/rtde/rtde_client.cpp.

◆ splitVariableTypes()

std::vector< std::string > urcl::rtde_interface::RTDEClient::splitVariableTypes ( const std::string &  variable_types) const
private

Splits a variable_types string as reported from the robot into single variable type strings.

Parameters
variable_typesString as reported from the robot
Returns
A vector of variable variable_names

Definition at line 595 of file src/rtde/rtde_client.cpp.

◆ start()

bool urcl::rtde_interface::RTDEClient::start ( )

Triggers the robot to start sending RTDE data packages in the negotiated format.

Returns
Success of the requested start

Definition at line 432 of file src/rtde/rtde_client.cpp.

Member Data Documentation

◆ CB3_MAX_FREQUENCY

constexpr const double urcl::rtde_interface::RTDEClient::CB3_MAX_FREQUENCY = 125.0
staticprivate

Definition at line 208 of file rtde_client.h.

◆ client_state_

ClientState urcl::rtde_interface::RTDEClient::client_state_
private

Definition at line 206 of file rtde_client.h.

◆ input_recipe_

std::vector<std::string> urcl::rtde_interface::RTDEClient::input_recipe_
private

Definition at line 195 of file rtde_client.h.

◆ max_frequency_

double urcl::rtde_interface::RTDEClient::max_frequency_
private

Definition at line 203 of file rtde_client.h.

◆ output_recipe_

std::vector<std::string> urcl::rtde_interface::RTDEClient::output_recipe_
private

Definition at line 194 of file rtde_client.h.

◆ parser_

RTDEParser urcl::rtde_interface::RTDEClient::parser_
private

Definition at line 196 of file rtde_client.h.

◆ pipeline_

comm::Pipeline<RTDEPackage> urcl::rtde_interface::RTDEClient::pipeline_
private

Definition at line 198 of file rtde_client.h.

◆ prod_

comm::URProducer<RTDEPackage> urcl::rtde_interface::RTDEClient::prod_
private

Definition at line 197 of file rtde_client.h.

◆ stream_

comm::URStream<RTDEPackage> urcl::rtde_interface::RTDEClient::stream_
private

Definition at line 193 of file rtde_client.h.

◆ target_frequency_

double urcl::rtde_interface::RTDEClient::target_frequency_
private

Definition at line 204 of file rtde_client.h.

◆ urcontrol_version_

VersionInformation urcl::rtde_interface::RTDEClient::urcontrol_version_
private

Definition at line 201 of file rtde_client.h.

◆ URE_MAX_FREQUENCY

constexpr const double urcl::rtde_interface::RTDEClient::URE_MAX_FREQUENCY = 500.0
staticprivate

Definition at line 209 of file rtde_client.h.

◆ writer_

RTDEWriter urcl::rtde_interface::RTDEClient::writer_
private

Definition at line 199 of file rtde_client.h.


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


ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Tue Jul 4 2023 02:09:47