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

Namespaces

 comm
 
 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  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  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  UrDriver
 This is the main class for interfacing the driver. More...
 
class  UrException
 Our base class for exceptions. Specialized exceptions should inherit from those. More...
 
struct  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  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  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 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...
 
template<class T , std::size_t N>
std::ostream & operator<< (std::ostream &out, const std::array< T, N > &item)
 
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 safetyModeString (const SafetyMode &mode)
 
std::string safetyStatusString (const SafetyStatus &status)
 
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}}")
 
void setLogLevel (LogLevel level)
 Set log level this will disable messages with lower log level. More...
 
template<typename E >
constexpr std::underlying_type< E >::type toUnderlying (const E e) noexcept
 Converts an enum type to its underlying type. More...
 
void unregisterLogHandler ()
 Unregister current log handler, this will enable default log handler. More...
 

Variables

Logger g_logger
 
static const int32_t MULT_JOINTSTATE = 1000000
 

Typedef Documentation

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

Definition at line 29 of file types.h.

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

Definition at line 30 of file types.h.

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

Definition at line 31 of file types.h.

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

Definition at line 32 of file types.h.

Enumeration Type Documentation

enum urcl::LogLevel
strong

Different log levels.

Enumerator
DEBUG 
INFO 
WARN 
ERROR 
FATAL 
NONE 

Definition at line 47 of file log.h.

enum urcl::Parity : int
strong

Possible values for th parity flag.

Enumerator
NONE 
ODD 
EVEN 

Definition at line 50 of file tool_communication.h.

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 34 of file datatypes.h.

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 49 of file datatypes.h.

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 64 of file datatypes.h.

enum urcl::ToolVoltage : int
strong

Possible values for the tool voltage.

Enumerator
OFF 

0V

_12V 

12V

_24V 

24V

Definition at line 40 of file tool_communication.h.

Function Documentation

static const std::string urcl::BEGIN_REPLACE ( "{{BEGIN_REPLACE}}"  )
static
static const std::string urcl::JOINT_STATE_REPLACE ( "{{JOINT_STATE_REPLACE}}"  )
static
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 105 of file log.cpp.

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

Definition at line 35 of file types.h.

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 90 of file log.cpp.

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

Definition at line 81 of file datatypes.h.

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

Definition at line 112 of file datatypes.h.

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

Definition at line 145 of file datatypes.h.

static const std::string urcl::SERVER_IP_REPLACE ( "{{SERVER_IP_REPLACE}}"  )
static
static const std::string urcl::SERVER_PORT_REPLACE ( "{{SERVER_PORT_REPLACE}}"  )
static
static const std::string urcl::SERVO_J_REPLACE ( "{{SERVO_J_REPLACE}}"  )
static
void urcl::setLogLevel ( LogLevel  level)

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

Parameters
leveldesired log level

Definition at line 100 of file log.cpp.

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

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 58 of file types.h.

void urcl::unregisterLogHandler ( )

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

Definition at line 95 of file log.cpp.

Variable Documentation

Logger urcl::g_logger

Definition at line 88 of file log.cpp.

const int32_t urcl::MULT_JOINTSTATE = 1000000
static

Definition at line 43 of file ur_driver.cpp.



ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Sun May 9 2021 02:16:26