Class UrDriver

Class Documentation

class UrDriver

This is the main class for interfacing the driver.

It sets up all the necessary socket connections and handles the data exchange with the robot. Use this classes methods to access and write data.

Public Functions

UrDriver(const std::string &robot_ip, const std::string &script_file, const std::string &output_recipe_file, const std::string &input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode, std::unique_ptr<ToolCommSetup> tool_comm_setup, const uint32_t reverse_port = 50001, const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03, bool non_blocking_read = false, const std::string &reverse_ip = "", const uint32_t trajectory_port = 50003, const uint32_t script_command_port = 50004, double force_mode_damping = 0.025, double force_mode_gain_scaling = 0.5)

Constructs a new UrDriver object. Upon initialization this class will check the calibration checksum reported from the robot and compare it to a checksum given by the user. If the checksums don’t match, the driver will output an error message. This is critical if you want to do forward or inverse kinematics based on the model that the given calibration checksum matches to.

An RTDE connection to the robot will be established using the given recipe files. However, RTDE communication will not be started automatically, as this requires an external structure to read data from the RTDE client using the getDataPackage() method periodically. Once this is setup, please use the startRTDECommunication() method to actually start RTDE communication.

Furthermore, initialization creates a ScriptSender member object that will read a URScript file from script_file, perform a number of replacements to populate the script with dynamic data. See the implementation for details.

Parameters:
  • robot_ip – IP-address under which the robot is reachable.

  • script_file – URScript file that should be sent to the robot.

  • output_recipe_file – Filename where the output recipe is stored in.

  • input_recipe_file – Filename where the input recipe is stored in.

  • handle_program_state – Function handle to a callback on program state changes. For this to work, the URScript program will have to send keepalive signals to the reverse_port. I no keepalive signal can be read, program state will be false.

  • headless_mode – Parameter to control if the driver should be started in headless mode.

  • tool_comm_setup – Configuration for using the tool communication. calibration reported by the robot.

  • reverse_port – Port that will be opened by the driver to allow direct communication between the driver and the robot controller.

  • script_sender_port – The driver will offer an interface to receive the program’s URScript on this port. If the robot cannot connect to this port, External Control will stop immediately.

  • non_blocking_read – Enable non-blocking mode for read (useful when used with combined_robot_hw)

  • servoj_gain – Proportional gain for arm joints following target position, range [100,2000]

  • servoj_lookahead_time – Time [S], range [0.03,0.2] smoothens the trajectory with this lookahead time

  • reverse_ip – IP address that the reverse_port will get bound to. If not specified, the IP address of the interface that is used for connecting to the robot’s RTDE port will be used.

  • trajectory_port – Port used for sending trajectory points to the robot in case of trajectory forwarding.

  • script_command_port – Port used for forwarding script commands to the robot. The script commands will be executed locally on the robot.

  • force_mode_damping – The damping parameter used when the robot is in force mode, range [0,1]

  • force_mode_gain_scaling – Scales the gain used when the robot is in force mode, range [0,2] (only e-series)

UrDriver(const std::string &robot_ip, const std::string &script_file, const std::string &output_recipe_file, const std::string &input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode, std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string &calibration_checksum = "", const uint32_t reverse_port = 50001, const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03, bool non_blocking_read = false, const std::string &reverse_ip = "", const uint32_t trajectory_port = 50003, const uint32_t script_command_port = 50004, double force_mode_damping = 0.025, double force_mode_gain_scaling = 0.5)

Constructs a new UrDriver object.

Parameters:
  • robot_ip – IP-address under which the robot is reachable.

  • script_file – URScript file that should be sent to the robot.

  • output_recipe_file – Filename where the output recipe is stored in.

  • input_recipe_file – Filename where the input recipe is stored in.

  • handle_program_state – Function handle to a callback on program state changes. For this to work, the URScript program will have to send keepalive signals to the reverse_port. I no keepalive signal can be read, program state will be false.

  • headless_mode – Parameter to control if the driver should be started in headless mode.

  • tool_comm_setup – Configuration for using the tool communication.

  • calibration_checksum – Expected checksum of calibration. Will be matched against the calibration reported by the robot.

  • reverse_port – Port that will be opened by the driver to allow direct communication between the driver and the robot controller.

  • script_sender_port – The driver will offer an interface to receive the program’s URScript on this port. If the robot cannot connect to this port, External Control will stop immediately.

  • non_blocking_read – Enable non-blocking mode for read (useful when used with combined_robot_hw)

  • servoj_gain – Proportional gain for arm joints following target position, range [100,2000]

  • servoj_lookahead_time – Time [S], range [0.03,0.2] smoothens the trajectory with this lookahead time

  • reverse_ip – IP address that the reverse_port will get bound to. If not specified, the IP address of the interface that is used for connecting to the robot’s RTDE port will be used.

  • trajectory_port – Port used for sending trajectory points to the robot in case of trajectory forwarding.

  • script_command_port – Port used for forwarding script commands to the robot. The script commands will be executed locally on the robot.

  • force_mode_damping – The damping parameter used when the robot is in force mode, range [0,1]

  • force_mode_gain_scaling – Scales the gain used when the robot is in force mode, range [0,2] (only e-series)

inline UrDriver(const std::string &robot_ip, const std::string &script_file, const std::string &output_recipe_file, const std::string &input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode, const std::string &calibration_checksum = "", const uint32_t reverse_port = 50001, const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03, bool non_blocking_read = false, const std::string &reverse_ip = "", const uint32_t trajectory_port = 50003, const uint32_t script_command_port = 50004, double force_mode_damping = 0.025, double force_mode_gain_scaling = 0.5)

Constructs a new UrDriver object.

Parameters:
  • robot_ip – IP-address under which the robot is reachable.

  • script_file – URScript file that should be sent to the robot.

  • output_recipe_file – Filename where the output recipe is stored in.

  • input_recipe_file – Filename where the input recipe is stored in.

  • handle_program_state – Function handle to a callback on program state changes. For this to work, the URScript program will have to send keepalive signals to the reverse_port. I no keepalive signal can be read, program state will be false.

  • headless_mode – Parameter to control if the driver should be started in headless mode.

  • calibration_checksum – Expected checksum of calibration. Will be matched against the calibration reported by the robot.

  • reverse_port – Port that will be opened by the driver to allow direct communication between the driver and the robot controller

  • script_sender_port – The driver will offer an interface to receive the program’s URScript on this port. If the robot cannot connect to this port, External Control will stop immediately.

  • non_blocking_read – Enable non-blocking mode for read (useful when used with combined_robot_hw)

  • servoj_gain – Proportional gain for arm joints following target position, range [100,2000]

  • servoj_lookahead_time – Time [S], range [0.03,0.2] smoothens the trajectory with this lookahead time

  • reverse_ip – IP address that the reverse_port will get bound to. If not specified, the IP address of the interface that is used for connecting to the robot’s RTDE port will be used.

  • trajectory_port – Port used for sending trajectory points to the robot in case of trajectory forwarding.

  • script_command_port – Port used for forwarding script commands to the robot. The script commands will be executed locally on the robot.

  • force_mode_damping – The damping parameter used when the robot is in force mode, range [0,1]

  • force_mode_gain_scaling – Scales the gain used when the robot is in force mode, range [0,2] (only e-series)

virtual ~UrDriver() = default
std::unique_ptr<rtde_interface::DataPackage> getDataPackage()

Access function to receive the latest data package sent from the robot through RTDE interface.

Returns:

The latest data package on success, a nullptr if no package can be found inside a preconfigured time window.

inline uint32_t getControlFrequency() const
bool writeJointCommand(const vector6d_t &values, const comm::ControlMode control_mode, const RobotReceiveTimeout &robot_receive_timeout = RobotReceiveTimeout::millisec(20))

Writes a joint command together with a keepalive signal onto the socket being sent to the robot.

Parameters:
  • values – Desired joint positions

  • control_mode – Control mode this command is assigned to.

  • robot_receive_timeout – The read timeout configuration for the reverse socket running in the external control script on the robot. Use with caution when dealing with realtime commands as the robot expects to get a new control signal each control cycle. Note the timeout cannot be higher than 1 second for realtime commands.

Returns:

True on successful write.

bool writeTrajectoryPoint(const vector6d_t &positions, const bool cartesian, const float goal_time = 0.0, const float blend_radius = 0.052)

Writes a trajectory point onto the dedicated socket.

Parameters:
  • positions – Desired joint or cartesian positions

  • cartesian – True, if the point sent is cartesian, false if joint-based

  • goal_time – Time for the robot to reach this point

  • blend_radius – The radius to be used for blending between control points

Returns:

True on successful write.

bool writeTrajectorySplinePoint(const vector6d_t &positions, const vector6d_t &velocities, const vector6d_t &accelerations, const float goal_time = 0.0)

Writes a trajectory spline point for quintic spline interpolation onto the dedicated socket.

Parameters:
  • positions – Desired joint positions

  • velocities – Desired joint velocities

  • accelerations – Desired joint accelerations

  • goal_time – Time for the robot to reach this point

Returns:

True on successful write.

bool writeTrajectorySplinePoint(const vector6d_t &positions, const vector6d_t &velocities, const float goal_time = 0.0)

Writes a trajectory spline point for cubic spline interpolation onto the dedicated socket.

Parameters:
  • positions – Desired joint positions

  • velocities – Desired joint velocities

  • goal_time – Time for the robot to reach this point

Returns:

True on successful write.

bool writeTrajectorySplinePoint(const vector6d_t &positions, const float goal_time = 0.0)

Writes a trajectory spline point for quadratic spline interpolation onto the dedicated socket.

Parameters:
  • positions – Desired joint positions

  • goal_time – Time for the robot to reach this point

Returns:

True on successful write.

bool writeTrajectoryControlMessage(const control::TrajectoryControlMessage trajectory_action, const int point_number = 0, const RobotReceiveTimeout &robot_receive_timeout = RobotReceiveTimeout::millisec(200))

Writes a control message in trajectory forward mode.

Parameters:
  • trajectory_action – The action to be taken, such as starting a new trajectory

  • point_number – The number of points of a new trajectory to be sent

  • robot_receive_timeout – The read timeout configuration for the reverse socket running in the external control script on the robot. If you want to make the read function blocking then use RobotReceiveTimeout::off() function to create the RobotReceiveTimeout object

Returns:

True on successful write.

bool writeFreedriveControlMessage(const control::FreedriveControlMessage freedrive_action, const RobotReceiveTimeout &robot_receive_timeout = RobotReceiveTimeout::millisec(200))

Writes a control message in freedrive mode.

Parameters:
  • freedrive_action – The action to be taken, such as starting or stopping freedrive

  • robot_receive_timeout – The read timeout configuration for the reverse socket running in the external control script on the robot. If you want to make the read function blocking then use RobotReceiveTimeout::off() function to create the RobotReceiveTimeout object

Returns:

True on successful write.

bool zeroFTSensor()

Zero the force torque sensor (only availbe on e-Series). Note: It requires the external control script to be running or the robot to be in headless mode.

Returns:

True on successful write.

bool setPayload(const float mass, const vector3d_t &cog)

Set the payload mass and center of gravity. Note: It requires the external control script to be running or the robot to be in headless mode.

Parameters:
  • mass – mass in kilograms

  • cog – Center of Gravity, a vector [CoGx, CoGy, CoGz] specifying the displacement (in meters) from the toolmount

Returns:

True on successful write.

bool setToolVoltage(const ToolVoltage voltage)

Set the tool voltage. Note: It requires the external control script to be running or the robot to be in headless mode.

Parameters:

voltage – tool voltage.

Returns:

True on successful write.

bool startForceMode(const vector6d_t &task_frame, const vector6uint32_t &selection_vector, const vector6d_t &wrench, const unsigned int type, const vector6d_t &limits)

Start the 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 – 6d vector of forces/torques [x,y,z,rotX,rotY,rotZ] that 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 – (double) 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

Returns:

True, if the write was performed successfully, false otherwise.

bool endForceMode()

Stop force mode and put the robot into normal operation mode.

Returns:

True, if the write was performed successfully, false otherwise.

bool startToolContact()

This will make the robot look for tool contact in the tcp directions that the robot is currently moving. Once a tool contact has been detected all movements will be canceled. Call endToolContact to enable movements again.

Returns:

True, if the write was performed successfully, false otherwise.

bool endToolContact()

This will stop the robot from looking for a tool contact, it will also enable sending move commands to the robot again if the robot’s tool is in contact.

Returns:

True, if the write was performed successfully, false otherwise.

bool writeKeepalive(const RobotReceiveTimeout &robot_receive_timeout = RobotReceiveTimeout::millisec(1000))

Write a keepalive signal only.

This signals the robot that the connection is still active in times when no commands are to be sent (e.g. no controller is active.)

Parameters:

robot_receive_timeout – The read timeout configuration for the reverse socket running in the external control script on the robot. If you want to make the read function blocking then use RobotReceiveTimeout::off() function to create the RobotReceiveTimeout object

Returns:

True on successful write.

void startRTDECommunication()

Starts the RTDE communication.

After initialization, the cyclic RTDE communication is not started automatically, so that data consumers can be started also at a later point.

bool stopControl()

Sends a stop command to the socket interface which will signal the program running on the robot to no longer listen for commands sent from the remote pc.

Returns:

True on successful write.

bool checkCalibration(const std::string &checksum)

Checks if the kinematics information in the used model fits the actual robot.

Parameters:

checksum – Hash of the used kinematics information

Returns:

True if the robot’s calibration checksum matches the one given to the checker. False if it doesn’t match or the check was not yet performed.

rtde_interface::RTDEWriter &getRTDEWriter()

Getter for the RTDE writer used to write to the robot’s RTDE interface.

Returns:

The active RTDE writer

bool sendScript(const std::string &program)

Sends a custom script program to the robot.

The given code must be valid according the UR Scripting Manual.

Parameters:

program – URScript code that shall be executed by the robot.

Returns:

true on successful upload, false otherwise.

bool sendRobotProgram()

Sends the external control program to the robot.

Only for use in headless mode, as it replaces the use of the URCaps program.

Returns:

true on successful upload, false otherwise

inline const VersionInformation &getVersion()

Returns version information about the currently connected robot.

std::vector<std::string> getRTDEOutputRecipe()

Getter for the RTDE output recipe used in the RTDE client.

Returns:

The used RTDE output recipe

void setKeepaliveCount(const uint32_t count)

Set the Keepalive count. This will set the number of allowed timeout reads on the robot.

Parameters:

count – Number of allowed timeout reads on the robot.

inline void registerTrajectoryDoneCallback(std::function<void(control::TrajectoryResult)> trajectory_done_cb)

Register a callback for the robot-based trajectory execution completion.

One mode of robot control is to forward a complete trajectory to the robot for execution. When the execution is done, the callback function registered here will be triggered.

Parameters:

trajectory_done_cb – Callback function that will be triggered in the event of finishing a trajectory execution

inline void registerToolContactResultCallback(std::function<void(control::ToolContactResult)> tool_contact_result_cb)

Register a callback for the robot-based tool contact execution completion.

If a tool contact is detected or tool contact is canceled, this callback function will be triggered mode of robot control is to move until tool contact. It requires that tool contact has been started using startToolContact()

Parameters:

tool_contact_result_cb – Callback function that will be triggered when the robot enters tool contact