RobWorkProject  20.10.1-
Public Types | Public Member Functions | List of all members
URRTDE Class Reference

URRTDE class provides a control interface for the UR Robots using RTDE. More...

#include <URRTDE.hpp>

Public Types

typedef rw::core::Ptr< URRTDEPtr
 

Public Member Functions

 URRTDE (std::string robot_ip, std::vector< std::string > variables={})
 
bool reconnect ()
 
bool isConnected ()
 
void stopRobot ()
 
bool reuploadScript ()
 
bool sendCustomScriptFunction (const std::string &function_name, const std::string &script)
 
bool sendCustomScriptFile (const std::string &file_path)
 
bool moveJ (const rw::math::Q &q, double speed, double acceleration)
 Move to joint configuration (linear in joint-space) More...
 
bool moveJ (const rw::trajectory::QPath &q_path)
 Move to each joint configuration specified in a QPath. More...
 
bool moveJ_IK (const rw::math::Transform3D<> &pose, double speed, double acceleration)
 Move to pose (linear in joint-space) More...
 
bool moveL (const rw::math::Transform3D<> &pose, double speed, double acceleration)
 Move to position (linear in tool-space) More...
 
bool moveL (const rw::trajectory::Transform3DPath &pose_path)
 Move to each pose specified in a Transform3DPath. More...
 
bool moveL_FK (const rw::math::Q &q, double speed, double acceleration)
 Move to position (linear in tool-space) More...
 
bool speedJ (const rw::math::Q &qd, double acceleration, double time=0.0)
 Joint speed - Accelerate linearly in joint space and continue with constant joint speed. More...
 
bool speedL (const rw::math::Q &xd, double acceleration, double time=0.0)
 Tool speed - Accelerate linearly in Cartesian space and continue with constant tool speed. The time t is optional;. More...
 
bool servoJ (const rw::math::Q &q, double speed, double acceleration, double time, double lookahead_time, double gain)
 Servo to position (linear in joint-space) More...
 
bool servoStop ()
 
bool speedStop ()
 
bool forceMode (const rw::math::Transform3D<> &task_frame, const rw::math::Q &selection_vector, const rw::math::Wrench6D<> &wrench, int type, const rw::math::Q &limits)
 Set robot to be controlled in force mode. More...
 
bool forceModeStop ()
 
bool zeroFtSensor ()
 
bool setStandardDigitalOut (std::uint8_t output_id, bool signal_level)
 
bool setToolDigitalOut (std::uint8_t output_id, bool signal_level)
 
bool setPayload (double mass, const std::vector< double > &cog={})
 
bool teachMode ()
 
bool endTeachMode ()
 
bool forceModeSetDamping (double damping)
 
bool forceModeSetGainScaling (double scaling)
 
bool setSpeedSlider (double speed)
 
bool setAnalogOutputVoltage (std::uint8_t output_id, double voltage_ratio)
 
bool setAnalogOutputCurrent (std::uint8_t output_id, double current_ratio)
 
bool isProgramRunning ()
 
double getTimestamp ()
 
rw::math::Q getTargetQ ()
 
rw::math::Q getTargetQd ()
 
rw::math::Q getTargetQdd ()
 
rw::math::Q getTargetCurrent ()
 
rw::math::Q getTargetMoment ()
 
rw::math::Q getActualQ ()
 
rw::math::Q getActualQd ()
 
rw::math::Q getActualCurrent ()
 
rw::math::Q getJointControlOutput ()
 
rw::math::Transform3D getActualTCPPose ()
 
rw::math::Q getActualTCPSpeed ()
 
rw::math::Wrench6D getActualTCPForce ()
 
rw::math::Transform3D getTargetTCPPose ()
 
rw::math::Q getTargetTCPSpeed ()
 
uint64_t getActualDigitalInputBits ()
 
rw::math::Q getJointTemperatures ()
 
double getActualExecutionTime ()
 
int32_t getRobotMode ()
 
uint32_t getRobotStatus ()
 
std::vector< int32_t > getJointMode ()
 
int32_t getSafetyMode ()
 
rw::math::Q getActualToolAccelerometer ()
 
double getSpeedScaling ()
 
double getTargetSpeedFraction ()
 
double getActualMomentum ()
 
double getActualMainVoltage ()
 
double getActualRobotVoltage ()
 
double getActualRobotCurrent ()
 
rw::math::Q getActualJointVoltage ()
 
uint64_t getActualDigitalOutputBits ()
 
uint32_t getRuntimeState ()
 
double getStandardAnalogInput0 ()
 
double getStandardAnalogInput1 ()
 
double getStandardAnalogOutput0 ()
 
double getStandardAnalogOutput1 ()
 

Detailed Description

URRTDE class provides a control interface for the UR Robots using RTDE.

Member Function Documentation

◆ endTeachMode()

bool endTeachMode ( )

◆ forceMode()

bool forceMode ( const rw::math::Transform3D<> &  task_frame,
const rw::math::Q selection_vector,
const rw::math::Wrench6D<> &  wrench,
int  type,
const rw::math::Q limits 
)

Set robot to be controlled in force mode.

Parameters
task_frameA Transform3D pose that defines the force frame relative to the base frame.
selection_vectorA 6d Q vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding axis of the task frame
wrenchThe 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
typeAn 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 Q 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.

◆ forceModeSetDamping()

bool forceModeSetDamping ( double  damping)

◆ forceModeSetGainScaling()

bool forceModeSetGainScaling ( double  scaling)

◆ forceModeStop()

bool forceModeStop ( )

◆ getActualCurrent()

rw::math::Q getActualCurrent ( )

◆ getActualDigitalInputBits()

uint64_t getActualDigitalInputBits ( )

◆ getActualDigitalOutputBits()

uint64_t getActualDigitalOutputBits ( )

◆ getActualExecutionTime()

double getActualExecutionTime ( )

◆ getActualJointVoltage()

rw::math::Q getActualJointVoltage ( )

◆ getActualMainVoltage()

double getActualMainVoltage ( )

◆ getActualMomentum()

double getActualMomentum ( )

◆ getActualQ()

rw::math::Q getActualQ ( )

◆ getActualQd()

rw::math::Q getActualQd ( )

◆ getActualRobotCurrent()

double getActualRobotCurrent ( )

◆ getActualRobotVoltage()

double getActualRobotVoltage ( )

◆ getActualTCPForce()

rw::math::Wrench6D getActualTCPForce ( )

◆ getActualTCPPose()

rw::math::Transform3D getActualTCPPose ( )

◆ getActualTCPSpeed()

rw::math::Q getActualTCPSpeed ( )

◆ getActualToolAccelerometer()

rw::math::Q getActualToolAccelerometer ( )

◆ getJointControlOutput()

rw::math::Q getJointControlOutput ( )

◆ getJointMode()

std::vector< int32_t > getJointMode ( )

◆ getJointTemperatures()

rw::math::Q getJointTemperatures ( )

◆ getRobotMode()

int32_t getRobotMode ( )

◆ getRobotStatus()

uint32_t getRobotStatus ( )

◆ getRuntimeState()

uint32_t getRuntimeState ( )

◆ getSafetyMode()

int32_t getSafetyMode ( )

◆ getSpeedScaling()

double getSpeedScaling ( )

◆ getStandardAnalogInput0()

double getStandardAnalogInput0 ( )

◆ getStandardAnalogInput1()

double getStandardAnalogInput1 ( )

◆ getStandardAnalogOutput0()

double getStandardAnalogOutput0 ( )

◆ getStandardAnalogOutput1()

double getStandardAnalogOutput1 ( )

◆ getTargetCurrent()

rw::math::Q getTargetCurrent ( )

◆ getTargetMoment()

rw::math::Q getTargetMoment ( )

◆ getTargetQ()

rw::math::Q getTargetQ ( )

◆ getTargetQd()

rw::math::Q getTargetQd ( )

◆ getTargetQdd()

rw::math::Q getTargetQdd ( )

◆ getTargetSpeedFraction()

double getTargetSpeedFraction ( )

◆ getTargetTCPPose()

rw::math::Transform3D getTargetTCPPose ( )

◆ getTargetTCPSpeed()

rw::math::Q getTargetTCPSpeed ( )

◆ getTimestamp()

double getTimestamp ( )

◆ isConnected()

bool isConnected ( )

◆ isProgramRunning()

bool isProgramRunning ( )

◆ moveJ() [1/2]

bool moveJ ( const rw::math::Q q,
double  speed,
double  acceleration 
)

Move to joint configuration (linear in joint-space)

Parameters
qjoint positions
speedjoint speed of leading axis [rad/s]
accelerationjoint acceleration of leading axis [rad/s^2]

◆ moveJ() [2/2]

bool moveJ ( const rw::trajectory::QPath q_path)

Move to each joint configuration specified in a QPath.

Parameters
q_pathwith joint configurations that includes acceleration, speed and blend for each configuration

◆ moveJ_IK()

bool moveJ_IK ( const rw::math::Transform3D<> &  pose,
double  speed,
double  acceleration 
)

Move to pose (linear in joint-space)

Parameters
posetarget pose as Transform3D
speedjoint speed of leading axis [rad/s]
accelerationjoint acceleration of leading axis [rad/s^2]

◆ moveL() [1/2]

bool moveL ( const rw::math::Transform3D<> &  pose,
double  speed,
double  acceleration 
)

Move to position (linear in tool-space)

Parameters
posetarget pose
speedtool speed [m/s]
accelerationtool acceleration [m/s^2]

◆ moveL() [2/2]

bool moveL ( const rw::trajectory::Transform3DPath pose_path)

Move to each pose specified in a Transform3DPath.

Parameters
pathwith tool poses specified as Transform3D

◆ moveL_FK()

bool moveL_FK ( const rw::math::Q q,
double  speed,
double  acceleration 
)

Move to position (linear in tool-space)

Parameters
qjoint positions
speedtool speed [m/s]
accelerationtool acceleration [m/s^2]

◆ reconnect()

bool reconnect ( )

◆ reuploadScript()

bool reuploadScript ( )

◆ sendCustomScriptFile()

bool sendCustomScriptFile ( const std::string &  file_path)

◆ sendCustomScriptFunction()

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

◆ servoJ()

bool servoJ ( const rw::math::Q q,
double  speed,
double  acceleration,
double  time,
double  lookahead_time,
double  gain 
)

Servo to position (linear in joint-space)

Parameters
qjoint positions [rad]
speedNOT used in current version
accelerationNOT used in current version
timetime where the command is controlling the robot. The function is blocking for time t [S]
lookahead_timetime [S], range [0.03,0.2] smoothens the trajectory with this lookahead time
gainproportional gain for following target position, range [100,2000]

◆ servoStop()

bool servoStop ( )

◆ setAnalogOutputCurrent()

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

◆ setAnalogOutputVoltage()

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

◆ setPayload()

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

◆ setSpeedSlider()

bool setSpeedSlider ( double  speed)

◆ setStandardDigitalOut()

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

◆ setToolDigitalOut()

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

◆ speedJ()

bool speedJ ( const rw::math::Q qd,
double  acceleration,
double  time = 0.0 
)

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

Parameters
qdjoint speeds [rad/s]
accelerationjoint acceleration [rad/s^2] (of leading axis)
timetime [s] before the function returns (optional)

◆ speedL()

bool speedL ( const rw::math::Q xd,
double  acceleration,
double  time = 0.0 
)

Tool speed - Accelerate linearly in Cartesian space and continue with constant tool speed. The time t is optional;.

Parameters
xdtool speed [m/s] (spatial vector)
accelerationtool position acceleration [m/s^2]
timetime [s] before the function returns (optional)

◆ speedStop()

bool speedStop ( )

◆ stopRobot()

void stopRobot ( )

◆ teachMode()

bool teachMode ( )

◆ zeroFtSensor()

bool zeroFtSensor ( )


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