This is the main class for interfacing the driver. More...
#include <ur_driver.h>
Public Member Functions | |
void | checkCalibration (const std::string &checksum) |
Checks if the kinematics information in the used model fits the actual robot. More... | |
uint32_t | getControlFrequency () const |
std::unique_ptr< rtde_interface::DataPackage > | getDataPackage () |
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::RTDEWriter & | getRTDEWriter () |
Getter for the RTDE writer used to write to the robot's RTDE interface. More... | |
const VersionInformation & | getVersion () |
Returns version information about the currently connected robot. 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... | |
void | startRTDECommunication () |
Starts the RTDE communication. 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, 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) | |
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... | |
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) | |
Constructs a new UrDriver object. More... | |
bool | writeJointCommand (const vector6d_t &values, const comm::ControlMode control_mode) |
Writes a joint command together with a keepalive signal onto the socket being sent to the robot. More... | |
bool | writeKeepalive () |
Write a keepalive signal only. More... | |
virtual | ~UrDriver ()=default |
Private Member Functions | |
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< comm::ReverseInterface > | reverse_interface_ |
std::string | robot_ip_ |
VersionInformation | robot_version_ |
std::unique_ptr< rtde_interface::RTDEClient > | rtde_client_ |
int | rtde_frequency_ |
std::unique_ptr< comm::ScriptSender > | script_sender_ |
std::unique_ptr< comm::URStream< primary_interface::PrimaryPackage > > | secondary_stream_ |
uint32_t | servoj_gain_ |
double | servoj_lookahead_time_ |
double | servoj_time_ |
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 49 of file ur_driver.h.
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 |
||
) |
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.
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_sending_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 |
Definition at line 50 of file ur_driver.cpp.
|
inline |
Constructs a new UrDriver object.
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_sending_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 |
Definition at line 113 of file ur_driver.h.
|
virtualdefault |
void urcl::UrDriver::checkCalibration | ( | const std::string & | checksum | ) |
Checks if the kinematics information in the used model fits the actual robot.
checksum | Hash of the used kinematics information |
Definition at line 196 of file ur_driver.cpp.
|
inline |
Definition at line 135 of file ur_driver.h.
std::unique_ptr< rtde_interface::DataPackage > urcl::UrDriver::getDataPackage | ( | ) |
Access function to receive the latest data package sent from the robot through RTDE interface.
Definition at line 156 of file ur_driver.cpp.
std::vector< std::string > urcl::UrDriver::getRTDEOutputRecipe | ( | ) |
Getter for the RTDE output recipe used in the RTDE client.
Definition at line 264 of file ur_driver.cpp.
rtde_interface::RTDEWriter & urcl::UrDriver::getRTDEWriter | ( | ) |
Getter for the RTDE writer used to write to the robot's RTDE interface.
Definition at line 220 of file ur_driver.cpp.
|
inline |
Returns version information about the currently connected robot.
Definition at line 214 of file ur_driver.h.
|
private |
Definition at line 188 of file ur_driver.cpp.
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.
Definition at line 251 of file ur_driver.cpp.
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.
program | URScript code that shall be executed by the robot. |
Definition at line 225 of file ur_driver.cpp.
void urcl::UrDriver::setKeepaliveCount | ( | const uint32_t & | count | ) |
Set the Keepalive count. This will set the number of allowed timeout reads on the robot.
count | Number of allowed timeout reads on the robot. |
Definition at line 269 of file ur_driver.cpp.
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 177 of file ur_driver.cpp.
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.
Definition at line 182 of file ur_driver.cpp.
bool urcl::UrDriver::writeJointCommand | ( | const vector6d_t & | values, |
const comm::ControlMode | control_mode | ||
) |
Writes a joint command together with a keepalive signal onto the socket being sent to the robot.
values | Desired joint positions |
control_mode | Control mode this command is assigned to. |
Definition at line 166 of file ur_driver.cpp.
bool urcl::UrDriver::writeKeepalive | ( | ) |
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.)
Definition at line 171 of file ur_driver.cpp.
|
private |
Definition at line 252 of file ur_driver.h.
|
private |
Definition at line 254 of file ur_driver.h.
|
private |
Definition at line 248 of file ur_driver.h.
|
private |
Definition at line 251 of file ur_driver.h.
|
private |
Definition at line 255 of file ur_driver.h.
|
private |
Definition at line 237 of file ur_driver.h.
|
private |
Definition at line 241 of file ur_driver.h.
|
private |
Definition at line 239 of file ur_driver.h.
|
private |
Definition at line 250 of file ur_driver.h.
|
private |
Definition at line 257 of file ur_driver.h.
|
private |
Definition at line 238 of file ur_driver.h.
|
private |
Definition at line 236 of file ur_driver.h.
|
private |
Definition at line 240 of file ur_driver.h.
|
private |
Definition at line 242 of file ur_driver.h.
|
private |
Definition at line 245 of file ur_driver.h.
|
private |
Definition at line 246 of file ur_driver.h.
|
private |
Definition at line 244 of file ur_driver.h.