Public Member Functions | Static Private Member Functions | Private Attributes | List of all members
urcl::UrDriver Class Reference

This is the main class for interfacing the driver. More...

#include <ur_driver.h>

Public Member Functions

bool checkCalibration (const std::string &checksum)
 Checks if the kinematics information in the used model fits the actual robot. More...
 
bool endForceMode ()
 Stop force mode and put the robot into normal operation mode. More...
 
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. More...
 
uint32_t getControlFrequency () const
 
std::unique_ptr< rtde_interface::DataPackagegetDataPackage ()
 Access function to receive the latest data package sent from the robot through RTDE interface. More...
 
std::vector< std::string > getRTDEOutputRecipe ()
 Getter for the RTDE output recipe used in the RTDE client. More...
 
rtde_interface::RTDEWritergetRTDEWriter ()
 Getter for the RTDE writer used to write to the robot's RTDE interface. More...
 
const VersionInformationgetVersion ()
 Returns version information about the currently connected robot. More...
 
void registerToolContactResultCallback (std::function< void(control::ToolContactResult)> tool_contact_result_cb)
 Register a callback for the robot-based tool contact execution completion. More...
 
void registerTrajectoryDoneCallback (std::function< void(control::TrajectoryResult)> trajectory_done_cb)
 Register a callback for the robot-based trajectory execution completion. More...
 
bool sendRobotProgram ()
 Sends the external control program to the robot. More...
 
bool sendScript (const std::string &program)
 Sends a custom script program to the robot. More...
 
void setKeepaliveCount (const uint32_t count)
 Set the Keepalive count. This will set the number of allowed timeout reads on the robot. More...
 
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. More...
 
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. More...
 
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. More...
 
void startRTDECommunication ()
 Starts the RTDE communication. More...
 
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. More...
 
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. More...
 
 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. More...
 
 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. More...
 
 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. More...
 
bool writeFreedriveControlMessage (const control::FreedriveControlMessage freedrive_action, const RobotReceiveTimeout &robot_receive_timeout=RobotReceiveTimeout::millisec(200))
 Writes a control message in freedrive mode. More...
 
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. More...
 
bool writeKeepalive (const RobotReceiveTimeout &robot_receive_timeout=RobotReceiveTimeout::millisec(1000))
 Write a keepalive signal only. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
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. More...
 
virtual ~UrDriver ()=default
 

Static Private Member Functions

static std::string readScriptFile (const std::string &filename)
 

Private Attributes

std::string full_robot_program_
 
int get_packet_timeout_
 
std::function< void(bool)> handle_program_state_
 
bool in_headless_mode_
 
bool non_blocking_read_
 
comm::INotifier notifier_
 
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > primary_stream_
 
std::unique_ptr< control::ReverseInterfacereverse_interface_
 
std::string robot_ip_
 
VersionInformation robot_version_
 
std::unique_ptr< rtde_interface::RTDEClientrtde_client_
 
int rtde_frequency_
 
std::unique_ptr< control::ScriptCommandInterfacescript_command_interface_
 
std::unique_ptr< control::ScriptSenderscript_sender_
 
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > secondary_stream_
 
uint32_t servoj_gain_
 
double servoj_lookahead_time_
 
std::chrono::milliseconds step_time_
 
std::unique_ptr< control::TrajectoryPointInterfacetrajectory_interface_
 

Detailed Description

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.

Definition at line 53 of file ur_driver.h.

Constructor & Destructor Documentation

◆ UrDriver() [1/3]

urcl::UrDriver::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_ipIP-address under which the robot is reachable.
script_fileURScript file that should be sent to the robot.
output_recipe_fileFilename where the output recipe is stored in.
input_recipe_fileFilename where the input recipe is stored in.
handle_program_stateFunction 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_modeParameter to control if the driver should be started in headless mode.
tool_comm_setupConfiguration for using the tool communication. calibration reported by the robot.
reverse_portPort that will be opened by the driver to allow direct communication between the driver and the robot controller.
script_sender_portThe 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_readEnable non-blocking mode for read (useful when used with combined_robot_hw)
servoj_gainProportional gain for arm joints following target position, range [100,2000]
servoj_lookahead_timeTime [S], range [0.03,0.2] smoothens the trajectory with this lookahead time
reverse_ipIP 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_portPort used for sending trajectory points to the robot in case of trajectory forwarding.
script_command_portPort used for forwarding script commands to the robot. The script commands will be executed locally on the robot.
force_mode_dampingThe damping parameter used when the robot is in force mode, range [0,1]
force_mode_gain_scalingScales the gain used when the robot is in force mode, range [0,2] (only e-series)

Definition at line 55 of file ur_driver.cpp.

◆ UrDriver() [2/3]

urcl::UrDriver::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_ipIP-address under which the robot is reachable.
script_fileURScript file that should be sent to the robot.
output_recipe_fileFilename where the output recipe is stored in.
input_recipe_fileFilename where the input recipe is stored in.
handle_program_stateFunction 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_modeParameter to control if the driver should be started in headless mode.
tool_comm_setupConfiguration for using the tool communication.
calibration_checksumExpected checksum of calibration. Will be matched against the calibration reported by the robot.
reverse_portPort that will be opened by the driver to allow direct communication between the driver and the robot controller.
script_sender_portThe 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_readEnable non-blocking mode for read (useful when used with combined_robot_hw)
servoj_gainProportional gain for arm joints following target position, range [100,2000]
servoj_lookahead_timeTime [S], range [0.03,0.2] smoothens the trajectory with this lookahead time
reverse_ipIP 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_portPort used for sending trajectory points to the robot in case of trajectory forwarding.
script_command_portPort used for forwarding script commands to the robot. The script commands will be executed locally on the robot.
force_mode_dampingThe damping parameter used when the robot is in force mode, range [0,1]
force_mode_gain_scalingScales the gain used when the robot is in force mode, range [0,2] (only e-series)

Definition at line 220 of file ur_driver.cpp.

◆ UrDriver() [3/3]

urcl::UrDriver::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 
)
inline

Constructs a new UrDriver object.

Parameters
robot_ipIP-address under which the robot is reachable.
script_fileURScript file that should be sent to the robot.
output_recipe_fileFilename where the output recipe is stored in.
input_recipe_fileFilename where the input recipe is stored in.
handle_program_stateFunction 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_modeParameter to control if the driver should be started in headless mode.
calibration_checksumExpected checksum of calibration. Will be matched against the calibration reported by the robot.
reverse_portPort that will be opened by the driver to allow direct communication between the driver and the robot controller
script_sender_portThe 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_readEnable non-blocking mode for read (useful when used with combined_robot_hw)
servoj_gainProportional gain for arm joints following target position, range [100,2000]
servoj_lookahead_timeTime [S], range [0.03,0.2] smoothens the trajectory with this lookahead time
reverse_ipIP 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_portPort used for sending trajectory points to the robot in case of trajectory forwarding.
script_command_portPort used for forwarding script commands to the robot. The script commands will be executed locally on the robot.
force_mode_dampingThe damping parameter used when the robot is in force mode, range [0,1]
force_mode_gain_scalingScales the gain used when the robot is in force mode, range [0,2] (only e-series)

Definition at line 171 of file ur_driver.h.

◆ ~UrDriver()

virtual urcl::UrDriver::~UrDriver ( )
virtualdefault

Member Function Documentation

◆ checkCalibration()

bool urcl::UrDriver::checkCalibration ( const std::string &  checksum)

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

Parameters
checksumHash 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.

Definition at line 511 of file ur_driver.cpp.

◆ endForceMode()

bool urcl::UrDriver::endForceMode ( )

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

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

Definition at line 420 of file ur_driver.cpp.

◆ endToolContact()

bool urcl::UrDriver::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.

Definition at line 456 of file ur_driver.cpp.

◆ getControlFrequency()

uint32_t urcl::UrDriver::getControlFrequency ( ) const
inline

Definition at line 196 of file ur_driver.h.

◆ getDataPackage()

std::unique_ptr< rtde_interface::DataPackage > urcl::UrDriver::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.

Definition at line 252 of file ur_driver.cpp.

◆ getRTDEOutputRecipe()

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

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

Returns
The used RTDE output recipe

Definition at line 581 of file ur_driver.cpp.

◆ getRTDEWriter()

rtde_interface::RTDEWriter & urcl::UrDriver::getRTDEWriter ( )

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

Returns
The active RTDE writer

Definition at line 536 of file ur_driver.cpp.

◆ getVersion()

const VersionInformation& urcl::UrDriver::getVersion ( )
inline

Returns version information about the currently connected robot.

Definition at line 442 of file ur_driver.h.

◆ readScriptFile()

std::string urcl::UrDriver::readScriptFile ( const std::string &  filename)
staticprivate

Definition at line 496 of file ur_driver.cpp.

◆ registerToolContactResultCallback()

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

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_cbCallback function that will be triggered when the robot enters tool contact

Definition at line 485 of file ur_driver.h.

◆ registerTrajectoryDoneCallback()

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

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_cbCallback function that will be triggered in the event of finishing a trajectory execution

Definition at line 472 of file ur_driver.h.

◆ sendRobotProgram()

bool urcl::UrDriver::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

Definition at line 568 of file ur_driver.cpp.

◆ sendScript()

bool urcl::UrDriver::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
programURScript code that shall be executed by the robot.
Returns
true on successful upload, false otherwise.

Definition at line 541 of file ur_driver.cpp.

◆ setKeepaliveCount()

void urcl::UrDriver::setKeepaliveCount ( const uint32_t  count)

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

Parameters
countNumber of allowed timeout reads on the robot.

Definition at line 586 of file ur_driver.cpp.

◆ setPayload()

bool urcl::UrDriver::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
massmass in kilograms
cogCenter of Gravity, a vector [CoGx, CoGy, CoGz] specifying the displacement (in meters) from the toolmount
Returns
True on successful write.

Definition at line 331 of file ur_driver.cpp.

◆ setToolVoltage()

bool urcl::UrDriver::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
voltagetool voltage.
Returns
True on successful write.

Definition at line 350 of file ur_driver.cpp.

◆ startForceMode()

bool urcl::UrDriver::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_frameA pose vector that defines the force frame relative to the base frame
selection_vectorA 6d vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding axis of the task frame
wrench6d 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.
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(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.

Definition at line 382 of file ur_driver.cpp.

◆ startRTDECommunication()

void urcl::UrDriver::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.

Definition at line 485 of file ur_driver.cpp.

◆ startToolContact()

bool urcl::UrDriver::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.

Definition at line 433 of file ur_driver.cpp.

◆ stopControl()

bool urcl::UrDriver::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.

Definition at line 490 of file ur_driver.cpp.

◆ writeFreedriveControlMessage()

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

Writes a control message in freedrive mode.

Parameters
freedrive_actionThe action to be taken, such as starting or stopping freedrive
robot_receive_timeoutThe 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.

Definition at line 297 of file ur_driver.cpp.

◆ writeJointCommand()

bool urcl::UrDriver::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
valuesDesired joint positions
control_modeControl mode this command is assigned to.
robot_receive_timeoutThe 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.

Definition at line 262 of file ur_driver.cpp.

◆ writeKeepalive()

bool urcl::UrDriver::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_timeoutThe 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.

Definition at line 479 of file ur_driver.cpp.

◆ writeTrajectoryControlMessage()

bool urcl::UrDriver::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_actionThe action to be taken, such as starting a new trajectory
point_numberThe number of points of a new trajectory to be sent
robot_receive_timeoutThe 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.

Definition at line 291 of file ur_driver.cpp.

◆ writeTrajectoryPoint()

bool urcl::UrDriver::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
positionsDesired joint or cartesian positions
cartesianTrue, if the point sent is cartesian, false if joint-based
goal_timeTime for the robot to reach this point
blend_radiusThe radius to be used for blending between control points
Returns
True on successful write.

Definition at line 268 of file ur_driver.cpp.

◆ writeTrajectorySplinePoint() [1/3]

bool urcl::UrDriver::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
positionsDesired joint positions
goal_timeTime for the robot to reach this point
Returns
True on successful write.

Definition at line 286 of file ur_driver.cpp.

◆ writeTrajectorySplinePoint() [2/3]

bool urcl::UrDriver::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
positionsDesired joint positions
velocitiesDesired joint velocities
goal_timeTime for the robot to reach this point
Returns
True on successful write.

Definition at line 280 of file ur_driver.cpp.

◆ writeTrajectorySplinePoint() [3/3]

bool urcl::UrDriver::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
positionsDesired joint positions
velocitiesDesired joint velocities
accelerationsDesired joint accelerations
goal_timeTime for the robot to reach this point
Returns
True on successful write.

Definition at line 274 of file ur_driver.cpp.

◆ zeroFTSensor()

bool urcl::UrDriver::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.

Definition at line 303 of file ur_driver.cpp.

Member Data Documentation

◆ full_robot_program_

std::string urcl::UrDriver::full_robot_program_
private

Definition at line 511 of file ur_driver.h.

◆ get_packet_timeout_

int urcl::UrDriver::get_packet_timeout_
private

Definition at line 513 of file ur_driver.h.

◆ handle_program_state_

std::function<void(bool)> urcl::UrDriver::handle_program_state_
private

Definition at line 507 of file ur_driver.h.

◆ in_headless_mode_

bool urcl::UrDriver::in_headless_mode_
private

Definition at line 510 of file ur_driver.h.

◆ non_blocking_read_

bool urcl::UrDriver::non_blocking_read_
private

Definition at line 514 of file ur_driver.h.

◆ notifier_

comm::INotifier urcl::UrDriver::notifier_
private

Definition at line 494 of file ur_driver.h.

◆ primary_stream_

std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage> > urcl::UrDriver::primary_stream_
private

Definition at line 500 of file ur_driver.h.

◆ reverse_interface_

std::unique_ptr<control::ReverseInterface> urcl::UrDriver::reverse_interface_
private

Definition at line 496 of file ur_driver.h.

◆ robot_ip_

std::string urcl::UrDriver::robot_ip_
private

Definition at line 509 of file ur_driver.h.

◆ robot_version_

VersionInformation urcl::UrDriver::robot_version_
private

Definition at line 516 of file ur_driver.h.

◆ rtde_client_

std::unique_ptr<rtde_interface::RTDEClient> urcl::UrDriver::rtde_client_
private

Definition at line 495 of file ur_driver.h.

◆ rtde_frequency_

int urcl::UrDriver::rtde_frequency_
private

Definition at line 493 of file ur_driver.h.

◆ script_command_interface_

std::unique_ptr<control::ScriptCommandInterface> urcl::UrDriver::script_command_interface_
private

Definition at line 498 of file ur_driver.h.

◆ script_sender_

std::unique_ptr<control::ScriptSender> urcl::UrDriver::script_sender_
private

Definition at line 499 of file ur_driver.h.

◆ secondary_stream_

std::unique_ptr<comm::URStream<primary_interface::PrimaryPackage> > urcl::UrDriver::secondary_stream_
private

Definition at line 501 of file ur_driver.h.

◆ servoj_gain_

uint32_t urcl::UrDriver::servoj_gain_
private

Definition at line 503 of file ur_driver.h.

◆ servoj_lookahead_time_

double urcl::UrDriver::servoj_lookahead_time_
private

Definition at line 504 of file ur_driver.h.

◆ step_time_

std::chrono::milliseconds urcl::UrDriver::step_time_
private

Definition at line 505 of file ur_driver.h.

◆ trajectory_interface_

std::unique_ptr<control::TrajectoryPointInterface> urcl::UrDriver::trajectory_interface_
private

Definition at line 497 of file ur_driver.h.


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


ur_client_library
Author(s): Thomas Timm Andersen, Simon Rasmussen, Felix Exner, Lea Steffen, Tristan Schnell
autogenerated on Wed Jun 5 2024 02:35:50