API Reference

The ur_rtde library API consists of the following parts:

RTDE Control Interface API

class ur_rtde::RTDEControlInterface

Public Functions

void disconnect()

Return

Can be used to disconnect from the robot. To reconnect you have to call the reconnect() function.

bool reconnect()

Return

Can be used to reconnect to the robot after a lost connection.

bool isConnected()

Return

Connection status for RTDE, useful for checking for lost connection.

bool reuploadScript()

In the event of an error, this function can be used to resume operation by reuploading the RTDE control script.

This will only happen if a script is not already running on the controller.

bool sendCustomScriptFunction(const std::string &function_name, const std::string &script)

Send a custom ur script to the controller.

Parameters
  • function_name: specify a name for the custom script function

  • script: the custom ur script to be sent to the controller specified as a string, each line must be terminated with a newline. The code will automatically be indented with one tab to fit with the function body.

bool sendCustomScriptFile(const std::string &file_path)

Send a custom ur script file to the controller.

Parameters
  • file_path: the file path to the custom ur script file

void stopScript()

This function will terminate the script on controller.

void stopL(double a = 10.0)

Stop (linear in tool space) - decelerate tool speed to zero.

Parameters
  • a: tool acceleration [m/s^2] (rate of deceleration of the tool)

void stopJ(double a = 2.0)

Stop (linear in joint space) - decelerate joint speeds to zero.

Parameters
  • a: joint acceleration [rad/s^2] (rate of deceleration of the leading axis).

bool moveJ(const std::vector<double> &q, double speed = 1.05, double acceleration = 1.4, bool async = false)

Move to joint position (linear in joint-space)

Parameters
  • q: joint positions

  • speed: joint speed of leading axis [rad/s]

  • acceleration: joint acceleration of leading axis [rad/s^2]

  • async: a bool specifying if the move command should be asynchronous. If async is true it is possible to stop a move command using either the stopJ or stopL function. Default is false, this means the function will block until the movement has completed.

bool moveJ(const std::vector<std::vector<double>> &path)

Move to each joint position specified in a path.

Parameters
  • path: with joint positions that includes acceleration, speed and blend for each position

bool moveJ_IK(const std::vector<double> &pose, double speed = 1.05, double acceleration = 1.4, bool async = false)

Move to pose (linear in joint-space)

Parameters
  • pose: target pose

  • speed: joint speed of leading axis [rad/s]

  • acceleration: joint acceleration of leading axis [rad/s^2]

  • async: a bool specifying if the move command should be asynchronous. If async is true it is possible to stop a move command using either the stopJ or stopL function. Default is false, this means the function will block until the movement has completed.

bool moveL(const std::vector<double> &pose, double speed = 0.25, double acceleration = 1.2, bool async = false)

Move to position (linear in tool-space)

Parameters
  • pose: target pose

  • speed: tool speed [m/s]

  • acceleration: tool acceleration [m/s^2]

  • async: a bool specifying if the move command should be asynchronous. If async is true it is possible to stop a move command using either the stopJ or stopL function. Default is false, this means the function will block until the movement has completed.

bool moveL(const std::vector<std::vector<double>> &path)

Move to each pose specified in a path.

Parameters
  • path: with tool poses that includes acceleration, speed and blend for each position

bool moveL_FK(const std::vector<double> &q, double speed = 0.25, double acceleration = 1.2, bool async = false)

Move to position (linear in tool-space)

Parameters
  • q: joint positions

  • speed: tool speed [m/s]

  • acceleration: tool acceleration [m/s^2]

  • async: a bool specifying if the move command should be asynchronous. If async is true it is possible to stop a move command using either the stopJ or stopL function. Default is false, this means the function will block until the movement has completed.

bool moveC(const std::vector<double> &pose_via, const std::vector<double> &pose_to, double speed = 0.25, double acceleration = 1.2, double blend = 0.0, int mode = 0)

Move Circular: Move to position (circular in tool-space)

Parameters
  • pose_via: path point (note: only position is used)

  • pose_to: target pose (note: only position is used in Fixed orientation mode).

  • speed: tool speed [m/s]

  • acceleration: tool acceleration [m/s^2]

  • blend: blend radius [m]

  • mode: 0: Unconstrained mode. Interpolate orientation from current pose to target pose (pose_to) 1: Fixed mode. Keep orientation constant relative to the tangent of the circular arc (starting from current pose)

bool moveP(const std::vector<double> &pose, double speed = 0.25, double acceleration = 1.2, double blend = 0.0)

Move Process: Blend circular (in tool-space) and move linear (in tool-space) to position.

Accelerates to and moves with constant tool speed v.

Parameters
  • pose: target pose

  • speed: tool speed [m/s]

  • acceleration: tool acceleration [m/s^2]

  • blend: blend radius [m]

bool speedJ(const std::vector<double> &qd, double acceleration = 0.5, double time = 0.0)

Joint speed - Accelerate linearly in joint space and continue with constant joint speed.

Parameters
  • qd: joint speeds [rad/s]

  • acceleration: joint acceleration [rad/s^2] (of leading axis)

  • time: time [s] before the function returns (optional)

bool speedL(const std::vector<double> &xd, double acceleration = 0.25, double time = 0.0)

Tool speed - Accelerate linearly in Cartesian space and continue with constant tool speed.

The time t is optional;

Parameters
  • xd: tool speed [m/s] (spatial vector)

  • acceleration: tool position acceleration [m/s^2]

  • time: time [s] before the function returns (optional)

bool servoJ(const std::vector<double> &q, double speed, double acceleration, double time, double lookahead_time, double gain)

Servo to position (linear in joint-space)

Parameters
  • q: joint positions [rad]

  • speed: NOT used in current version

  • acceleration: NOT used in current version

  • time: time where the command is controlling the robot. The function is blocking for time t [S]

  • lookahead_time: time [S], range [0.03,0.2] smoothens the trajectory with this lookahead time

  • gain: proportional gain for following target position, range [100,2000]

bool servoL(const std::vector<double> &pose, double speed, double acceleration, double time, double lookahead_time, double gain)

Servo to position (linear in tool-space)

Parameters
  • pose: target pose

  • speed: NOT used in current version

  • acceleration: NOT used in current version

  • time: time where the command is controlling the robot. The function is blocking for time t [S]

  • lookahead_time: time [S], range [0.03,0.2] smoothens the trajectory with this lookahead time

  • gain: proportional gain for following target position, range [100,2000]

bool servoStop()

Stop servos.

bool speedStop()

Stop speeding.

bool servoC(const std::vector<double> &pose, double speed = 0.25, double acceleration = 1.2, double blend = 0.0)

Servo to position (circular in tool-space).

Accelerates to and moves with constant tool speed v.

Parameters
  • pose: target pose

  • speed: tool speed [m/s]

  • acceleration: tool acceleration [m/s^2]

  • blend: blend radius (of target pose) [m]

bool forceMode(const std::vector<double> &task_frame, const std::vector<int> &selection_vector, const std::vector<double> &wrench, int type, const std::vector<double> &limits)

Set robot to be controlled in force mode.

Parameters
  • task_frame: A pose vector that defines the force frame relative to the base frame.

  • selection_vector: A 6d vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding axis of the task frame

  • wrench: The forces/torques the robot will apply to its environment. The robot adjusts its position along/about compliant axis in order to achieve the specified force/torque. Values have no effect for non-compliant axes

  • type: An integer [1;3] specifying how the robot interprets the force frame. 1: The force frame is transformed in a way such that its y-axis is aligned with a vector pointing from the robot tcp towards the origin of the force frame. 2: The force frame is not transformed. 3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp velocity vector onto the x-y plane of the force frame.

  • limits: (Float) 6d vector. For compliant axes, these values are the maximum allowed tcp speed along/about the axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis between the actual tcp position and the one set by the program.

bool forceModeStop()

Resets the robot mode from force mode to normal operation.

bool zeroFtSensor()

Zeroes the TCP force/torque measurement from the builtin force/torque sensor by subtracting the current measurement from the subsequent.

bool setPayload(double mass, const std::vector<double> &cog = {})

Set payload.

Parameters
  • mass: Mass in kilograms

  • cog: Center of Gravity, a vector [CoGx, CoGy, CoGz] specifying the displacement (in meters) from the toolmount. If not specified the current CoG will be used.

bool teachMode()

Set robot in freedrive mode.

In this mode the robot can be moved around by hand in the same way as by pressing the “freedrive” button. The robot will not be able to follow a trajectory (eg. a movej) in this mode.

bool endTeachMode()

Set robot back in normal position control mode after freedrive mode.

bool forceModeSetDamping(double damping)

Sets the damping parameter in force mode.

A value of 1 is full damping, so the robot will decellerate quickly if no force is present. A value of 0 is no damping, here the robot will maintain the speed.

Parameters
  • damping: Between 0 and 1, default value is 0.005

The value is stored until this function is called again. Call this function before force mode is entered (otherwise default value will be used).

bool forceModeSetGainScaling(double scaling)

Scales the gain in force mode.

A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard surfaces.

Parameters
  • scaling: scaling parameter between 0 and 2, default is 1.

The value is stored until this function is called again. Call this function before force mode is entered (otherwise default value will be used)

int toolContact(const std::vector<double> &direction)

Detects when a contact between the tool and an object happens.

Return

The returned value is the number of time steps back to just before the contact have started. A value larger than 0 means that a contact is detected. A value of 0 means no contact.

Parameters
  • direction: The first three elements are interpreted as a 3D vector (in the robot base coordinate system) giving the direction in which contacts should be detected. If all elements of the list are zero, contacts from all directions are considered.

double getStepTime()

Returns the duration of the robot time step in seconds.

In every time step, the robot controller will receive measured joint positions and velocities from the robot, and send desired joint positions and velocities back to the robot. This happens with a predetermined frequency, in regular intervals. This interval length is the robot time step.

Return

Duration of the robot step in seconds

std::vector<double> getActualJointPositionsHistory(int steps = 0)

Detects when a contact between the tool and an object happens.

Return

The returned value is the number of time steps back to just before the contact have started. A value larger than 0 means that a contact is detected. A value of 0 means no contact.

Parameters
  • direction: The first three elements are interpreted as a 3D vector (in the robot base coordinate system) giving the direction in which contacts should be detected. If all elements of the list are zero, contacts from all directions are considered.

std::vector<double> getTargetWaypoint()

Returns the target waypoint of the active move.

This is different from the target tcp pose which returns the target pose for each time step. The get_target_waypoint() returns the same target pose for movel, movej, movep or movec during the motion. It returns the target tcp pose, if none of the mentioned move functions are running.

This method is useful for calculating relative movements where the previous move command uses blends.

Return

The desired waypoint TCP vector [X, Y, Z, Rx, Ry, Rz]

bool setTcp(const std::vector<double> &tcp_offset)

Sets the active tcp offset, i.e.

the transformation from the output flange coordinate system to the TCP as a pose.

Parameters
  • tcp_offset: A pose describing the transformation of the tcp offset.

std::vector<double> getInverseKinematics(const std::vector<double> &x, const std::vector<double> &qnear, double max_position_error = 1e-10, double max_orientation_error = 1e-10)

Calculate the inverse kinematic transformation (tool space -> jointspace).

If qnear is defined, the solution closest to qnear is returned.Otherwise, the solution closest to the current joint positions is returned. If no tcp is provided the currently active tcp of the controller will be used.

Return

joint positions

Parameters
  • x: tool pose

  • qnear: list of joint positions (Optional)

  • maxPositionError: the maximum allowed positionerror (Optional)

  • maxOrientationError: the maximum allowed orientationerror (Optional)

std::vector<double> poseTrans(const std::vector<double> &p_from, const std::vector<double> &p_from_to)

Pose transformation to move with respect to a tool or w.r.t.

a custom feature/frame The first argument, p_from, is used to transform the second argument, p_from_to, and the result is then returned. This means that the result is the resulting pose, when starting at the coordinate system of p_from, and then in that coordinate system moving p_from_to. This function can be seen in two different views. Either the function transforms, that is translates and rotates, p_from_to by the parameters of p_from. Or the function is used to get the resulting pose, when first making a move of p_from and then from there, a move of p_from_to. If the poses were regarded as transformation matrices, it would look like:

* T_world->to = T_world->from * T_from->to
* T_x->to = T_x->from * T_from->to
*
Return

resulting pose (spatial vector)

Parameters
  • p_from: starting pose (spatial vector)

  • p_from_to: pose change relative to starting pose (spatial vector)

bool triggerProtectiveStop()

Triggers a protective stop on the robot.

Can be used for testing and debugging.

bool isProgramRunning()

Returns true if a program is running on the controller, otherwise it returns false.

bool setWatchdog(double min_frequency = 10.0)

Enable a watchdog for the communication with a specified minimum frequency for which an input update is expected to arrive.

The watchdog is useful for safety critical realtime applications eg. servoing. The default action taken is to shutdown the control, if the watchdog is not kicked with the minimum frequency.

Preferably you would call this function right after the RTDEControlInterface has been constructed.

Parameters
  • min_frequency: The minimum frequency an input update is expected to arrive defaults to 10Hz.

bool kickWatchdog()

Kicks the watchdog safeguarding the communication.

Normally you would kick the watchdog in your control loop. Be sure to kick it as often as specified by the minimum frequency of the watchdog.

bool isPoseWithinSafetyLimits(const std::vector<double> &pose)

Checks if the given pose is reachable and within the current safety limits of the robot.

It checks safety planes limits, TCP orientation deviation limits and range of the robot. If a solution is found when applying the inverse kinematics to the given target TCP pose, this pose is considered reachable.

Return

a bool indicating if the pose is within the safety limits.

Parameters
  • pose: target pose

bool isJointsWithinSafetyLimits(const std::vector<double> &q)

Checks if the given joint position is reachable and within the current safety limits of the robot.

This check considers joint limits (if the target pose is specified as joint positions), safety planes limits, TCP orientation deviation limits and range of the robot. If a solution is found when applying the inverse kinematics to the given target TCP pose, this pose is considered reachable

Return

a bool indicating if the joint positions are within the safety limits.

Parameters
  • q: joint positions

std::vector<double> getJointTorques()

Returns the torques of all joints.

The torque on the joints, corrected by the torque needed to move the robot itself (gravity, friction, etc.), returned as a vector of length 6.

Return

The joint torque vector in Nm: [Base, Shoulder, Elbow, Wrist1, Wrist2, Wrist3]

std::vector<double> getTCPOffset()

Gets the active tcp offset, i.e.

the transformation from the output flange coordinate system to the TCP as a pose.

Return

the TCP offset as a pose

RTDE Receive Interface API

class ur_rtde::RTDEReceiveInterface

Public Types

enum SafetyStatus

Values:

enumerator IS_NORMAL_MODE = 0
enumerator IS_REDUCED_MODE = 1
enumerator IS_PROTECTIVE_STOPPED = 2
enumerator IS_RECOVERY_MODE = 3
enumerator IS_SAFEGUARD_STOPPED = 4
enumerator IS_SYSTEM_EMERGENCY_STOPPED = 5
enumerator IS_ROBOT_EMERGENCY_STOPPED = 6
enumerator IS_EMERGENCY_STOPPED = 7
enumerator IS_VIOLATION = 8
enumerator IS_FAULT = 9
enumerator IS_STOPPED_DUE_TO_SAFETY = 10

Public Functions

RTDEReceiveInterface(std::string hostname, std::vector<std::string> variables = {}, int port = 30004, bool verbose = false)
~RTDEReceiveInterface()
void disconnect()

Return

Can be used to disconnect from the robot. To reconnect you have to call the reconnect() function.

bool reconnect()

Return

Can be used to reconnect to the robot after a lost connection.

bool isConnected()

Return

Connection status for RTDE, useful for checking for lost connection.

double getTimestamp()

Return

Time elapsed since the controller was started [s]

std::vector<double> getTargetQ()

Return

Target joint positions

std::vector<double> getTargetQd()

Return

Target joint velocities

std::vector<double> getTargetQdd()

Return

Target joint accelerations

std::vector<double> getTargetCurrent()

Return

Target joint currents

std::vector<double> getTargetMoment()

Return

Target joint moments (torques)

std::vector<double> getActualQ()

Return

Actual joint positions

std::vector<double> getActualQd()

Return

Actual joint velocities

std::vector<double> getActualCurrent()

Return

Actual joint currents

std::vector<double> getJointControlOutput()

Return

Joint control currents

std::vector<double> getActualTCPPose()

Return

Actual Cartesian coordinates of the tool: (x,y,z,rx,ry,rz), where rx, ry and rz is a rotation vector representation of the tool orientation

std::vector<double> getActualTCPSpeed()

Return

Actual speed of the tool given in Cartesian coordinates

std::vector<double> getActualTCPForce()

Return

Generalized forces in the TCP

std::vector<double> getTargetTCPPose()

Return

Target Cartesian coordinates of the tool: (x,y,z,rx,ry,rz), where rx, ry and rz is a rotation vector representation of the tool orientation

std::vector<double> getTargetTCPSpeed()

Return

Target speed of the tool given in Cartesian coordinates

uint64_t getActualDigitalInputBits()

Return

Current state of the digital inputs. 0-7: Standard, 8-15: Configurable, 16-17: Tool

std::vector<double> getJointTemperatures()

Return

Temperature of each joint in degrees Celsius

double getActualExecutionTime()

Return

Controller real-time thread execution time

int32_t getRobotMode()

Return

Robot mode -1 = ROBOT_MODE_NO_CONTROLLER 0 = ROBOT_MODE_DISCONNECTED 1 = ROBOT_MODE_CONFIRM_SAFETY 2 = ROBOT_MODE_BOOTING 3 = ROBOT_MODE_POWER_OFF 4 = ROBOT_MODE_POWER_ON 5 = ROBOT_MODE_IDLE 6 = ROBOT_MODE_BACKDRIVE 7 = ROBOT_MODE_RUNNING 8 = ROBOT_MODE_UPDATING_FIRMWARE

uint32_t getRobotStatus()

Return

Robot status Bits 0-3: Is power on | Is program running | Is teach button pressed | Is power button pressed

std::vector<int32_t> getJointMode()

Return

Joint control modes

int32_t getSafetyMode()

Return

Safety mode

uint32_t getSafetyStatusBits()

Return

Safety status bits Bits 0-10: Is normal mode | Is reduced mode | Is protective stopped | Is recovery mode | Is safeguard stopped | Is system emergency stopped | Is robot emergency stopped | Is emergency stopped | Is violation | Is fault | Is stopped due to safety

std::vector<double> getActualToolAccelerometer()

Return

Tool x, y and z accelerometer values

double getSpeedScaling()

Return

Speed scaling of the trajectory limiter

double getTargetSpeedFraction()

Return

Target speed fraction

double getActualMomentum()

Return

Norm of Cartesian linear momentum

double getActualMainVoltage()

Return

Safety Control Board: Main voltage

double getActualRobotVoltage()

Return

Safety Control Board: Robot voltage (48V)

double getActualRobotCurrent()

Return

Safety Control Board: Robot current

std::vector<double> getActualJointVoltage()

Return

Actual joint voltages

uint64_t getActualDigitalOutputBits()

Return

Current state of the digital outputs. 0-7: Standard, 8-15: Configurable, 16-17: Tool

bool getDigitalOutState(std::uint8_t output_id)

Test if a digital output is set ‘high’ or ‘low’ the range is 0-7: Standard, 8-15: Configurable, 16-17: Tool.

Return

a bool indicating the state of the digital output

Parameters
  • output_id: the id of the digital output to test

uint32_t getRuntimeState()

Return

Program state

double getStandardAnalogInput0()

Return

Standard analog input 0 [A or V]

double getStandardAnalogInput1()

Return

Standard analog input 1 [A or V]

double getStandardAnalogOutput0()

Return

Standard analog output 0 [A or V]

double getStandardAnalogOutput1()

Return

Standard analog output 1 [A or V]

bool isProtectiveStopped()

Return

a bool indicating if the robot is in ‘Protective stop’

bool isEmergencyStopped()

Return

a bool indicating if the robot is in ‘Emergency stop’

void receiveCallback()

RTDE IO Interface API

class ur_rtde::RTDEIOInterface

Public Functions

bool reconnect()

Return

Can be used to reconnect to the robot after a lost connection.

bool setStandardDigitalOut(std::uint8_t output_id, bool signal_level)

Set standard digital output signal level.

Parameters
  • output_id: The number (id) of the output, integer: [0:7]

  • signal_level: The signal level. (boolean)

bool setToolDigitalOut(std::uint8_t output_id, bool signal_level)

Set tool digital output signal level.

Parameters
  • output_id: The number (id) of the output, integer: [0:1]

  • signal_level: The signal level. (boolean)

bool setSpeedSlider(double speed)

Set the speed slider on the controller.

Parameters
  • speed: set the speed slider on the controller as a fraction value between 0 and 1 (1 is 100%)

bool setAnalogOutputVoltage(std::uint8_t output_id, double voltage_ratio)

Set Analog output voltage.

Parameters
  • output_id: The number (id) of the output, integer: [0:1]

  • voltage_ratio: voltage set as a (ratio) of the voltage span [0..1], 1 means full voltage.

bool setAnalogOutputCurrent(std::uint8_t output_id, double current_ratio)

Set Analog output current.

Parameters
  • output_id: The number (id) of the output, integer: [0:1]

  • current_ratio: current set as a (ratio) of the current span [0..1], 1 means full current.

RTDE Class API

class ur_rtde::RTDE

Public Types

enum RTDECommand

Values:

enumerator RTDE_REQUEST_PROTOCOL_VERSION = 86
enumerator RTDE_GET_URCONTROL_VERSION = 118
enumerator RTDE_TEXT_MESSAGE = 77
enumerator RTDE_DATA_PACKAGE = 85
enumerator RTDE_CONTROL_PACKAGE_SETUP_OUTPUTS = 79
enumerator RTDE_CONTROL_PACKAGE_SETUP_INPUTS = 73
enumerator RTDE_CONTROL_PACKAGE_START = 83
enumerator RTDE_CONTROL_PACKAGE_PAUSE = 80
enum ConnectionState

Values:

enumerator DISCONNECTED = 0
enumerator CONNECTED = 1
enumerator STARTED = 2
enumerator PAUSED = 3

Public Functions

RTDE(const std::string hostname, int port = 30004, bool verbose = false)
~RTDE()
void connect()
void disconnect()
bool isConnected()
bool isStarted()
bool negotiateProtocolVersion()
std::tuple<std::uint32_t, std::uint32_t, std::uint32_t, std::uint32_t> getControllerVersion()
void receive()
void receiveData(std::shared_ptr<RobotState> &robot_state)
void send(const RobotCommand &robot_cmd)
void sendAll(const std::uint8_t &command, std::string payload = "")
void sendStart()
void sendPause()
bool sendOutputSetup(const std::vector<std::string> &output_names, double frequency)
bool sendInputSetup(const std::vector<std::string> &input_names)
class RobotCommand

Public Types

enum Type

Values:

enumerator NO_CMD = 0
enumerator MOVEJ = 1
enumerator MOVEJ_IK = 2
enumerator MOVEL = 3
enumerator MOVEL_FK = 4
enumerator MOVEC = 5
enumerator FORCE_MODE = 6
enumerator FORCE_MODE_STOP = 7
enumerator ZERO_FT_SENSOR = 8
enumerator SPEEDJ = 9
enumerator SPEEDL = 10
enumerator SERVOJ = 11
enumerator SERVOC = 12
enumerator SET_STD_DIGITAL_OUT = 13
enumerator SET_TOOL_DIGITAL_OUT = 14
enumerator SPEED_STOP = 15
enumerator SERVO_STOP = 16
enumerator SET_PAYLOAD = 17
enumerator TEACH_MODE = 18
enumerator END_TEACH_MODE = 19
enumerator FORCE_MODE_SET_DAMPING = 20
enumerator FORCE_MODE_SET_GAIN_SCALING = 21
enumerator SET_SPEED_SLIDER = 22
enumerator SET_STD_ANALOG_OUT = 23
enumerator SERVOL = 24
enumerator TOOL_CONTACT = 25
enumerator GET_STEPTIME = 26
enumerator GET_ACTUAL_JOINT_POSITIONS_HISTORY = 27
enumerator GET_TARGET_WAYPOINT = 28
enumerator SET_TCP = 29
enumerator GET_INVERSE_KINEMATICS = 30
enumerator PROTECTIVE_STOP = 31
enumerator MOVEP = 32
enumerator STOPL = 33
enumerator STOPJ = 34
enumerator SET_WATCHDOG = 35
enumerator IS_POSE_WITHIN_SAFETY_LIMITS = 36
enumerator IS_JOINTS_WITHIN_SAFETY_LIMITS = 37
enumerator GET_JOINT_TORQUES = 38
enumerator POSE_TRANS = 39
enumerator GET_TCP_OFFSET = 40
enumerator STOP_SCRIPT = 255
enum Recipe

Values:

enumerator RECIPE_1 = 1
enumerator RECIPE_2 = 2
enumerator RECIPE_3 = 3
enumerator RECIPE_4 = 4
enumerator RECIPE_5 = 5
enumerator RECIPE_6 = 6
enumerator RECIPE_7 = 7
enumerator RECIPE_8 = 8
enumerator RECIPE_9 = 9
enumerator RECIPE_10 = 10
enumerator RECIPE_11 = 11
enumerator RECIPE_12 = 12
enumerator RECIPE_13 = 13

Public Functions

RobotCommand()

Public Members

Type type_ = NO_CMD
std::uint8_t recipe_id_
std::int32_t async_
std::vector<double> val_
std::vector<int> selection_vector_
std::int32_t movec_mode_
std::int32_t force_mode_type_
std::uint8_t std_digital_out_
std::uint8_t std_digital_out_mask_
std::uint8_t std_tool_out_
std::uint8_t std_tool_out_mask_
std::uint8_t std_analog_output_mask_
std::uint8_t std_analog_output_type_
double std_analog_output_0_
double std_analog_output_1_
std::int32_t speed_slider_mask_
double speed_slider_fraction_
std::uint32_t steps_

Script Client API

class ur_rtde::ScriptClient

Public Types

enum ConnectionState

Values:

enumerator DISCONNECTED = 0
enumerator CONNECTED = 1

Public Functions

ScriptClient(std::string hostname, uint32_t major_control_version, uint32_t minor_control_version, int port = 30002, bool verbose = false)
~ScriptClient()
void connect()
void disconnect()
bool isConnected()
bool sendScript()
bool sendScript(const std::string &file_name)
bool sendScriptCommand(const std::string &cmd_str)

Dashboard Client API

class ur_rtde::DashboardClient

Public Types

enum ConnectionState

Values:

enumerator DISCONNECTED = 0
enumerator CONNECTED = 1

Public Functions

DashboardClient(std::string hostname, int port = 29999, bool verbose = false)
~DashboardClient()
void connect()
bool isConnected()
void disconnect()
void send(const std::string &str)
std::string receive()
void loadURP(const std::string &urp_name)
void play()
void stop()
void pause()
void quit()
void shutdown()
bool running()
void popup(const std::string &message)
void closePopup()
void closeSafetyPopup()
void powerOn()
void powerOff()
void brakeRelease()
void unlockProtectiveStop()
void restartSafety()
std::string polyscopeVersion()
std::string programState()
std::string robotmode()
std::string getLoadedProgram()
std::string safetymode()
std::string safetystatus()
void addToLog(const std::string &message)
bool isProgramSaved()
bool isInRemoteControl()
void setUserRole(const UserRole &role)