Structure for configuration parameters of a UrDriver object. More...
#include <ur_driver.h>
Public Attributes | |
std::function< void(bool)> | handle_program_state |
Function handle to a callback on program state changes. More... | |
bool | headless_mode |
Parameter to control if the driver should be started in headless mode. More... | |
std::string | input_recipe_file |
Filename where the input recipe is stored in. More... | |
bool | non_blocking_read = false |
std::string | output_recipe_file |
Filename where the output recipe is stored in. More... | |
std::string | reverse_ip = "" |
IP address that the reverse_port will get bound to. More... | |
uint32_t | reverse_port = 50001 |
Port that will be opened by the driver to allow direct communication between the driver and the robot controller. More... | |
std::string | robot_ip |
IP-address under which the robot is reachable. More... | |
size_t | rtde_initialization_attempts = 3 |
Number of attempts to initialize (given a successful socket connection) the RTDE interface. More... | |
std::chrono::milliseconds | rtde_initialization_timeout = std::chrono::seconds(5) |
Time in between initialization attempts of the RTDE interface. More... | |
uint32_t | script_command_port = 50004 |
Port used for forwarding script commands to the robot. More... | |
std::string | script_file |
URScript file that should be sent to the robot. More... | |
uint32_t | script_sender_port = 50002 |
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. More... | |
int | servoj_gain = 2000 |
Proportional gain for arm joints following target position, range [100,2000]. More... | |
double | servoj_lookahead_time = 0.03 |
Time [S], range [0.03,0.2] smoothens servoj calls with this lookahead time. More... | |
size_t | socket_reconnect_attempts = 0 |
Number of attempts to reconnect to sockets such as the primary or RTDE interface. More... | |
std::chrono::milliseconds | socket_reconnection_timeout = std::chrono::seconds(10) |
Time in between connection attempts to sockets such as the primary or RTDE interface. More... | |
std::unique_ptr< ToolCommSetup > | tool_comm_setup = nullptr |
Configuration for using the tool communication. More... | |
uint32_t | trajectory_port = 50003 |
Port used for sending trajectory points to the robot in case of trajectory forwarding. More... | |
Private Attributes | |
std::string | calibration_checksum = "" |
double | force_mode_damping = 0.025 |
double | force_mode_gain_scaling = 0.5 |
Structure for configuration parameters of a UrDriver object.
Definition at line 52 of file ur_driver.h.
|
private |
Definition at line 141 of file ur_driver.h.
|
private |
Definition at line 143 of file ur_driver.h.
|
private |
Definition at line 145 of file ur_driver.h.
std::function<void(bool)> urcl::UrDriverConfiguration::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
.
Definition at line 65 of file ur_driver.h.
bool urcl::UrDriverConfiguration::headless_mode |
Parameter to control if the driver should be started in headless mode.
Definition at line 66 of file ur_driver.h.
std::string urcl::UrDriverConfiguration::input_recipe_file |
Filename where the input recipe is stored in.
Definition at line 57 of file ur_driver.h.
bool urcl::UrDriverConfiguration::non_blocking_read = false |
Definition at line 136 of file ur_driver.h.
std::string urcl::UrDriverConfiguration::output_recipe_file |
Filename where the output recipe is stored in.
Definition at line 56 of file ur_driver.h.
std::string urcl::UrDriverConfiguration::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.
Definition at line 100 of file ur_driver.h.
uint32_t urcl::UrDriverConfiguration::reverse_port = 50001 |
Port that will be opened by the driver to allow direct communication between the driver and the robot controller.
Definition at line 74 of file ur_driver.h.
std::string urcl::UrDriverConfiguration::robot_ip |
IP-address under which the robot is reachable.
Definition at line 54 of file ur_driver.h.
size_t urcl::UrDriverConfiguration::rtde_initialization_attempts = 3 |
Number of attempts to initialize (given a successful socket connection) the RTDE interface.
If set to 0, the driver will try to initialize the RTDE interface indefinitely.
Definition at line 129 of file ur_driver.h.
std::chrono::milliseconds urcl::UrDriverConfiguration::rtde_initialization_timeout = std::chrono::seconds(5) |
Time in between initialization attempts of the RTDE interface.
Definition at line 134 of file ur_driver.h.
uint32_t urcl::UrDriverConfiguration::script_command_port = 50004 |
Port used for forwarding script commands to the robot.
This interface supports a set of predefined commands. The script commands will be executed locally on the robot.
Definition at line 92 of file ur_driver.h.
std::string urcl::UrDriverConfiguration::script_file |
URScript file that should be sent to the robot.
Definition at line 55 of file ur_driver.h.
uint32_t urcl::UrDriverConfiguration::script_sender_port = 50002 |
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.
Definition at line 79 of file ur_driver.h.
int urcl::UrDriverConfiguration::servoj_gain = 2000 |
Proportional gain for arm joints following target position, range [100,2000].
Definition at line 105 of file ur_driver.h.
double urcl::UrDriverConfiguration::servoj_lookahead_time = 0.03 |
Time [S], range [0.03,0.2] smoothens servoj calls with this lookahead time.
Definition at line 110 of file ur_driver.h.
size_t urcl::UrDriverConfiguration::socket_reconnect_attempts = 0 |
Number of attempts to reconnect to sockets such as the primary or RTDE interface.
If set to 0, the driver will try to reconnect indefinitely.
Definition at line 117 of file ur_driver.h.
std::chrono::milliseconds urcl::UrDriverConfiguration::socket_reconnection_timeout = std::chrono::seconds(10) |
Time in between connection attempts to sockets such as the primary or RTDE interface.
Definition at line 122 of file ur_driver.h.
std::unique_ptr<ToolCommSetup> urcl::UrDriverConfiguration::tool_comm_setup = nullptr |
Configuration for using the tool communication.
Definition at line 68 of file ur_driver.h.
uint32_t urcl::UrDriverConfiguration::trajectory_port = 50003 |
Port used for sending trajectory points to the robot in case of trajectory forwarding.
Definition at line 84 of file ur_driver.h.