Struct UrDriverConfiguration

Struct Documentation

struct UrDriverConfiguration

Structure for configuration parameters of a UrDriver object.

Public Members

std::string robot_ip

IP-address under which the robot is reachable.

std::string script_file

URScript file that should be sent to the robot.

std::string output_recipe_file

Filename where the output recipe is stored in.

std::string input_recipe_file

Filename where the input recipe is stored in.

std::function<void(bool)> 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.

bool headless_mode

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

std::unique_ptr<ToolCommSetup> tool_comm_setup = nullptr

Configuration for using the tool communication.

uint32_t reverse_port = 50001

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

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.

uint32_t trajectory_port = 50003

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

uint32_t 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.

std::string 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.

int servoj_gain = 2000

Proportional gain for arm joints following target position, range [100,2000].

double servoj_lookahead_time = 0.03

Time [S], range [0.03,0.2] smoothens servoj calls with this lookahead time.

bool non_blocking_read = false