Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
urcl Namespace Reference

Namespaces

 comm
 
 control
 
 primary_interface
 
 rtde_interface
 

Classes

class  CalibrationChecker
 The CalibrationChecker class consumes primary packages ignoring all but KinematicsInfo packages. These are then checked against the used kinematics to see if the correct calibration is used. More...
 
class  DashboardClient
 This class is a wrapper around the dashboard server. More...
 
class  DefaultLogHandler
 LogHandler object for default handling of logging messages. This class is used when no other LogHandler is registered. More...
 
class  ExampleRobotWrapper
 This class is a high-level abstraction around UrDriver and DashboardClient. It's main purpose is to help us avoiding repetitive robot initialization code in our examples and tests. More...
 
class  IncompatibleRobotVersion
 
class  InstructionExecutor
 
class  InvalidRange
 
class  Limited
 Helper class that represents a numeric value with a lower and an upper boundary. More...
 
class  Logger
 
class  LogHandler
 Inherit from this class to change the behavior when logging messages. More...
 
class  MissingArgument
 
struct  Pose
 
class  RobotReceiveTimeout
 RobotReceiveTimeout class containing a timeout configuration. More...
 
class  TimeoutException
 A specialized exception representing that communication to the tool is not possible. More...
 
class  ToolCommNotAvailable
 A specialized exception representing that communication to the tool is not possible. More...
 
class  ToolCommSetup
 Class holding a tool communication configuration. More...
 
class  UnsupportedMotionType
 
class  UrDriver
 This is the main class for interfacing the driver. More...
 
struct  UrDriverConfiguration
 Structure for configuration parameters of a UrDriver object. More...
 
class  UrException
 Our base class for exceptions. Specialized exceptions should inherit from those. More...
 
class  VersionInformation
 Struct containing a robot's version information. More...
 
class  VersionMismatch
 A specialized exception representing detection of a not supported UR control version. More...
 

Typedefs

using vector3d_t = std::array< double, 3 >
 
using vector6d_t = std::array< double, 6 >
 
using vector6int32_t = std::array< int32_t, 6 >
 
using vector6uint32_t = std::array< uint32_t, 6 >
 

Enumerations

enum  AnalogOutputType : int8_t { AnalogOutputType::SET_ON_TEACH_PENDANT = -1, AnalogOutputType::CURRENT = 0, AnalogOutputType::VOLTAGE = 1 }
 
enum  LogLevel {
  LogLevel::DEBUG = 0, LogLevel::INFO, LogLevel::WARN, LogLevel::ERROR,
  LogLevel::FATAL, LogLevel::NONE
}
 Different log levels. More...
 
enum  Parity : int { Parity::NONE = 0, Parity::ODD = 1, Parity::EVEN = 2 }
 Possible values for th parity flag. More...
 
enum  RobotMode : int8_t {
  RobotMode::UNKNOWN = -128, RobotMode::NO_CONTROLLER = -1, RobotMode::DISCONNECTED = 0, RobotMode::CONFIRM_SAFETY = 1,
  RobotMode::BOOTING = 2, RobotMode::POWER_OFF = 3, RobotMode::POWER_ON = 4, RobotMode::IDLE = 5,
  RobotMode::BACKDRIVE = 6, RobotMode::RUNNING = 7, RobotMode::UPDATING_FIRMWARE = 8
}
 
enum  RobotType : int8_t {
  RobotType::UNDEFINED = -128, RobotType::UR5 = 1, RobotType::UR10 = 2, RobotType::UR3 = 3,
  RobotType::UR16 = 4, RobotType::UR20 = 7, RobotType::UR30 = 8, RobotType::UR15 = 9
}
 
enum  SafetyMode : int8_t {
  SafetyMode::NORMAL = 1, SafetyMode::REDUCED = 2, SafetyMode::PROTECTIVE_STOP = 3, SafetyMode::RECOVERY = 4,
  SafetyMode::SAFEGUARD_STOP = 5, SafetyMode::SYSTEM_EMERGENCY_STOP = 6, SafetyMode::ROBOT_EMERGENCY_STOP = 7, SafetyMode::VIOLATION = 8,
  SafetyMode::FAULT = 9, SafetyMode::VALIDATE_JOINT_ID = 10, SafetyMode::UNDEFINED_SAFETY_MODE = 11
}
 
enum  SafetyStatus : int8_t {
  SafetyStatus::NORMAL = 1, SafetyStatus::REDUCED = 2, SafetyStatus::PROTECTIVE_STOP = 3, SafetyStatus::RECOVERY = 4,
  SafetyStatus::SAFEGUARD_STOP = 5, SafetyStatus::SYSTEM_EMERGENCY_STOP = 6, SafetyStatus::ROBOT_EMERGENCY_STOP = 7, SafetyStatus::VIOLATION = 8,
  SafetyStatus::FAULT = 9, SafetyStatus::VALIDATE_JOINT_ID = 10, SafetyStatus::UNDEFINED_SAFETY_MODE = 11, SafetyStatus::AUTOMATIC_MODE_SAFEGUARD_STOP = 12,
  SafetyStatus::SYSTEM_THREE_POSITION_ENABLING_STOP = 13
}
 
enum  ToolVoltage : int { ToolVoltage::OFF = 0, ToolVoltage::_12V = 12, ToolVoltage::_24V = 24 }
 Possible values for the tool voltage. More...
 

Functions

static const std::string BEGIN_REPLACE ("{{BEGIN_REPLACE}}")
 
static const std::string FORCE_MODE_SET_DAMPING_REPLACE ("{{FORCE_MODE_SET_DAMPING_REPLACE}}")
 
static const std::string FORCE_MODE_SET_GAIN_SCALING_REPLACE ("{{FORCE_MODE_SET_GAIN_SCALING_REPLACE}}")
 
static const std::string JOINT_STATE_REPLACE ("{{JOINT_STATE_REPLACE}}")
 
void log (const char *file, int line, LogLevel level, const char *fmt,...)
 Log a message, this is used internally by the macros to unpack the log message. Use the macros instead of this function directly. More...
 
bool operator!= (const VersionInformation &v1, const VersionInformation &v2)
 
bool operator< (const VersionInformation &v1, const VersionInformation &v2)
 
template<class T , std::size_t N>
std::ostream & operator<< (std::ostream &out, const std::array< T, N > &item)
 
bool operator<= (const VersionInformation &v1, const VersionInformation &v2)
 
bool operator== (const VersionInformation &v1, const VersionInformation &v2)
 
bool operator> (const VersionInformation &v1, const VersionInformation &v2)
 
bool operator>= (const VersionInformation &v1, const VersionInformation &v2)
 
void registerLogHandler (std::unique_ptr< LogHandler > loghandler)
 Register a new LogHandler object, for handling log messages. More...
 
std::string robotModeString (const RobotMode &mode)
 
std::string robotTypeString (const RobotType &type)
 
std::string safetyModeString (const SafetyMode &mode)
 
std::string safetyStatusString (const SafetyStatus &status)
 
static const std::string SCRIPT_COMMAND_PORT_REPLACE ("{{SCRIPT_COMMAND_SERVER_PORT_REPLACE}}")
 
static const std::string SERVER_IP_REPLACE ("{{SERVER_IP_REPLACE}}")
 
static const std::string SERVER_PORT_REPLACE ("{{SERVER_PORT_REPLACE}}")
 
static const std::string SERVO_J_REPLACE ("{{SERVO_J_REPLACE}}")
 
bool setFiFoScheduling (pthread_t &thread, const int priority)
 
void setLogLevel (LogLevel level)
 Set log level this will disable messages with lower log level. More...
 
std::vector< std::string > splitString (std::string input, const std::string &delimiter=".")
 
static const std::string TIME_REPLACE ("{{TIME_REPLACE}}")
 
template<typename E >
constexpr std::underlying_type< E >::type toUnderlying (const E e) noexcept
 Converts an enum type to its underlying type. More...
 
static const std::string TRAJECTORY_PORT_REPLACE ("{{TRAJECTORY_SERVER_PORT_REPLACE}}")
 
void unregisterLogHandler ()
 Unregister current log handler, this will enable default log handler. More...
 
void waitFor (std::function< bool()> condition, const std::chrono::milliseconds timeout, const std::chrono::milliseconds check_interval=std::chrono::milliseconds(50))
 Wait for a condition to be true. More...
 

Variables

Logger g_logger
 

Typedef Documentation

◆ vector3d_t

using urcl::vector3d_t = typedef std::array<double, 3>

Definition at line 29 of file types.h.

◆ vector6d_t

using urcl::vector6d_t = typedef std::array<double, 6>

Definition at line 30 of file types.h.

◆ vector6int32_t

using urcl::vector6int32_t = typedef std::array<int32_t, 6>

Definition at line 31 of file types.h.

◆ vector6uint32_t

using urcl::vector6uint32_t = typedef std::array<uint32_t, 6>

Definition at line 32 of file types.h.

Enumeration Type Documentation

◆ AnalogOutputType

enum urcl::AnalogOutputType : int8_t
strong
Enumerator
SET_ON_TEACH_PENDANT 
CURRENT 
VOLTAGE 

Definition at line 83 of file datatypes.h.

◆ LogLevel

enum urcl::LogLevel
strong

Different log levels.

Enumerator
DEBUG 
INFO 
WARN 
ERROR 
FATAL 
NONE 

Definition at line 34 of file log.h.

◆ Parity

enum urcl::Parity : int
strong

Possible values for th parity flag.

Enumerator
NONE 
ODD 
EVEN 

Definition at line 51 of file tool_communication.h.

◆ RobotMode

enum urcl::RobotMode : int8_t
strong
Enumerator
UNKNOWN 
NO_CONTROLLER 
DISCONNECTED 
CONFIRM_SAFETY 
BOOTING 
POWER_OFF 
POWER_ON 
IDLE 
BACKDRIVE 
RUNNING 
UPDATING_FIRMWARE 

Definition at line 36 of file datatypes.h.

◆ RobotType

enum urcl::RobotType : int8_t
strong
Enumerator
UNDEFINED 
UR5 
UR10 
UR3 
UR16 
UR20 
UR30 
UR15 

Definition at line 90 of file datatypes.h.

◆ SafetyMode

enum urcl::SafetyMode : int8_t
strong
Enumerator
NORMAL 
REDUCED 
PROTECTIVE_STOP 
RECOVERY 
SAFEGUARD_STOP 
SYSTEM_EMERGENCY_STOP 
ROBOT_EMERGENCY_STOP 
VIOLATION 
FAULT 
VALIDATE_JOINT_ID 
UNDEFINED_SAFETY_MODE 

Definition at line 51 of file datatypes.h.

◆ SafetyStatus

enum urcl::SafetyStatus : int8_t
strong
Enumerator
NORMAL 
REDUCED 
PROTECTIVE_STOP 
RECOVERY 
SAFEGUARD_STOP 
SYSTEM_EMERGENCY_STOP 
ROBOT_EMERGENCY_STOP 
VIOLATION 
FAULT 
VALIDATE_JOINT_ID 
UNDEFINED_SAFETY_MODE 
AUTOMATIC_MODE_SAFEGUARD_STOP 
SYSTEM_THREE_POSITION_ENABLING_STOP 

Definition at line 66 of file datatypes.h.

◆ ToolVoltage

enum urcl::ToolVoltage : int
strong

Possible values for the tool voltage.

Enumerator
OFF 

0V

_12V 

12V

_24V 

24V

Definition at line 41 of file tool_communication.h.

Function Documentation

◆ BEGIN_REPLACE()

static const std::string urcl::BEGIN_REPLACE ( "{{BEGIN_REPLACE}}"  )
static

◆ FORCE_MODE_SET_DAMPING_REPLACE()

static const std::string urcl::FORCE_MODE_SET_DAMPING_REPLACE ( "{{FORCE_MODE_SET_DAMPING_REPLACE}}"  )
static

◆ FORCE_MODE_SET_GAIN_SCALING_REPLACE()

static const std::string urcl::FORCE_MODE_SET_GAIN_SCALING_REPLACE ( "{{FORCE_MODE_SET_GAIN_SCALING_REPLACE}}"  )
static

◆ JOINT_STATE_REPLACE()

static const std::string urcl::JOINT_STATE_REPLACE ( "{{JOINT_STATE_REPLACE}}"  )
static

◆ log()

void urcl::log ( const char *  file,
int  line,
LogLevel  level,
const char *  fmt,
  ... 
)

Log a message, this is used internally by the macros to unpack the log message. Use the macros instead of this function directly.

Parameters
fileThe log message comes from this file
lineThe log message comes from this line
levelSeverity of the log message
fmtFormat string

Definition at line 106 of file log.cpp.

◆ operator!=()

bool urcl::operator!= ( const VersionInformation v1,
const VersionInformation v2 
)

Definition at line 98 of file version_information.cpp.

◆ operator<()

bool urcl::operator< ( const VersionInformation v1,
const VersionInformation v2 
)

Definition at line 103 of file version_information.cpp.

◆ operator<<()

template<class T , std::size_t N>
std::ostream& urcl::operator<< ( std::ostream &  out,
const std::array< T, N > &  item 
)

Definition at line 57 of file types.h.

◆ operator<=()

bool urcl::operator<= ( const VersionInformation v1,
const VersionInformation v2 
)

Definition at line 133 of file version_information.cpp.

◆ operator==()

bool urcl::operator== ( const VersionInformation v1,
const VersionInformation v2 
)

Definition at line 93 of file version_information.cpp.

◆ operator>()

bool urcl::operator> ( const VersionInformation v1,
const VersionInformation v2 
)

Definition at line 138 of file version_information.cpp.

◆ operator>=()

bool urcl::operator>= ( const VersionInformation v1,
const VersionInformation v2 
)

Definition at line 143 of file version_information.cpp.

◆ registerLogHandler()

void urcl::registerLogHandler ( std::unique_ptr< LogHandler loghandler)

Register a new LogHandler object, for handling log messages.

Parameters
loghandlerPointer to the new object

Definition at line 91 of file log.cpp.

◆ robotModeString()

std::string urcl::robotModeString ( const RobotMode mode)
inline

Definition at line 102 of file datatypes.h.

◆ robotTypeString()

std::string urcl::robotTypeString ( const RobotType type)
inline

Definition at line 203 of file datatypes.h.

◆ safetyModeString()

std::string urcl::safetyModeString ( const SafetyMode mode)
inline

Definition at line 133 of file datatypes.h.

◆ safetyStatusString()

std::string urcl::safetyStatusString ( const SafetyStatus status)
inline

Definition at line 166 of file datatypes.h.

◆ SCRIPT_COMMAND_PORT_REPLACE()

static const std::string urcl::SCRIPT_COMMAND_PORT_REPLACE ( "{{SCRIPT_COMMAND_SERVER_PORT_REPLACE}}"  )
static

◆ SERVER_IP_REPLACE()

static const std::string urcl::SERVER_IP_REPLACE ( "{{SERVER_IP_REPLACE}}"  )
static

◆ SERVER_PORT_REPLACE()

static const std::string urcl::SERVER_PORT_REPLACE ( "{{SERVER_PORT_REPLACE}}"  )
static

◆ SERVO_J_REPLACE()

static const std::string urcl::SERVO_J_REPLACE ( "{{SERVO_J_REPLACE}}"  )
static

◆ setFiFoScheduling()

bool urcl::setFiFoScheduling ( pthread_t &  thread,
const int  priority 
)

Definition at line 46 of file helpers.cpp.

◆ setLogLevel()

void urcl::setLogLevel ( LogLevel  level)

Set log level this will disable messages with lower log level.

Parameters
leveldesired log level

Definition at line 101 of file log.cpp.

◆ splitString()

std::vector< std::string > urcl::splitString ( std::string  input,
const std::string &  delimiter = "." 
)

Definition at line 34 of file version_information.cpp.

◆ TIME_REPLACE()

static const std::string urcl::TIME_REPLACE ( "{{TIME_REPLACE}}"  )
static

◆ toUnderlying()

template<typename E >
constexpr std::underlying_type<E>::type urcl::toUnderlying ( const E  e)
constexprnoexcept

Converts an enum type to its underlying type.

Parameters
eEnum value that should be converted
Returns
Enum value converted to underlying type

Definition at line 80 of file types.h.

◆ TRAJECTORY_PORT_REPLACE()

static const std::string urcl::TRAJECTORY_PORT_REPLACE ( "{{TRAJECTORY_SERVER_PORT_REPLACE}}"  )
static

◆ unregisterLogHandler()

void urcl::unregisterLogHandler ( )

Unregister current log handler, this will enable default log handler.

Definition at line 96 of file log.cpp.

◆ waitFor()

void urcl::waitFor ( std::function< bool()>  condition,
const std::chrono::milliseconds  timeout,
const std::chrono::milliseconds  check_interval = std::chrono::milliseconds(50) 
)

Wait for a condition to be true.

This function will wait for a condition to be true. The condition is checked in intervals of check_interval. If the condition is not met after timeout, the function will throw a urcl::TimeoutException.

Parameters
conditionThe condition to be checked.
timeoutThe maximum time to wait for the condition to be true.
check_intervalThe interval in which the condition is checked.

Definition at line 105 of file helpers.cpp.

Variable Documentation

◆ g_logger

Logger urcl::g_logger

Definition at line 89 of file log.cpp.



ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Mon May 26 2025 02:35:58