Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
234 changes: 208 additions & 26 deletions include/ur_client_library/ur/ur_driver.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,81 @@

namespace urcl
{
/*!
* \brief Structure for configuration parameters of a UrDriver object.
*/
struct UrDriverConfiguration
{
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.

/*!
* \brief Function handle to a callback on program state changes.
*
* For this to work, the URScript program will have to send keepalive signals to the \p
* reverse_port.
*/
std::function<void(bool)> handle_program_state;
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.

/*!
* \brief Port that will be opened by the driver to allow direct communication between the driver
* and the robot controller.
*/
uint32_t reverse_port = 50001;

/*! \brief 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 script_sender_port = 50002;

/*!
* \brief Port used for sending trajectory points to the robot in case of trajectory forwarding.
*/
uint32_t trajectory_port = 50003;

/*!
* \brief 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.
*/
uint32_t script_command_port = 50004;

/*!
* \brief 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.
*/
std::string reverse_ip = "";

/*!
* \brief Proportional gain for arm joints following target position, range [100,2000]
*/
int servoj_gain = 2000;

/*!
* \brief Time [S], range [0.03,0.2] smoothens servoj calls with this lookahead time
*/
double servoj_lookahead_time = 0.03;

bool non_blocking_read = false;

// TODO: Remove on 2027-05
// The following parameters are considered deprecated and will be removed in May 2027.
/// @private
std::string calibration_checksum = "";
/// @private
double force_mode_damping = 0.025;
/// @private
double force_mode_gain_scaling = 0.5;
};

/*!
* \brief This is the main class for interfacing the driver.
*
Expand All @@ -56,6 +131,25 @@ class UrDriver
public:
/*!
* \brief Constructs a new UrDriver object.
*
* 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.
*
* \param config Configuration struct for the UrDriver. See it's documentation for details.
*/
explicit UrDriver(const UrDriverConfiguration& config)
{
init(config);
}

/*!
* \brief Constructs a new UrDriver object.
*
* \deprecated Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const
* UrDriverConfiguration& config) instead. This function will be removed in May 2027.
*
* 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
Expand Down Expand Up @@ -94,15 +188,41 @@ class UrDriver
* \param script_command_port Port used for forwarding script commands to the robot. The script commands will be
* executed locally on the robot.
*/
// Called sigA in tests
[[deprecated("Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const "
"UrDriverConfiguration& config) instead. This function will be removed in May 2027.")]]
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);
const uint32_t script_command_port = 50004)
{
UrDriverConfiguration config;
config.robot_ip = robot_ip;
config.script_file = script_file;
config.output_recipe_file = output_recipe_file;
config.input_recipe_file = input_recipe_file;
config.handle_program_state = handle_program_state;
config.headless_mode = headless_mode;
config.tool_comm_setup = std::move(tool_comm_setup);
config.reverse_port = reverse_port;
config.script_sender_port = script_sender_port;
config.servoj_gain = servoj_gain;
config.servoj_lookahead_time = servoj_lookahead_time;
config.non_blocking_read = non_blocking_read;
config.reverse_ip = reverse_ip;
config.trajectory_port = trajectory_port;
config.script_command_port = script_command_port;
init(config);
}

/*!
* \brief Constructs a new UrDriver object.
*
* \deprecated Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const
* UrDriverConfiguration& config) instead. This function will be removed in May 2027.
*
* \param robot_ip IP-address under which the robot is reachable.
* \param script_file URScript file that should be sent to the robot.
* \param output_recipe_file Filename where the output recipe is stored in.
Expand All @@ -129,28 +249,43 @@ class UrDriver
* \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1]
* \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
*/
[[deprecated(
"Specifying the force mode damping factor and the force mode gain scaling factor at driver creation has "
"been deprecated. Force mode parameters should be specified with each activiation of force mode, and "
"can be set in the function call to start force mode.")]] 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,
const uint32_t script_sender_port,
int servoj_gain, double servoj_lookahead_time,
bool non_blocking_read,
const std::string& reverse_ip,
const uint32_t trajectory_port,
const uint32_t script_command_port,
double force_mode_damping,
double force_mode_gain_scaling = 0.5);
// Called sigB in tests
[[deprecated("Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const "
"UrDriverConfiguration& config) instead. This function will be removed in May 2027.")]]
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,
const uint32_t script_sender_port, int servoj_gain, double servoj_lookahead_time, bool non_blocking_read,
const std::string& reverse_ip, const uint32_t trajectory_port, const uint32_t script_command_port,
double force_mode_damping, double force_mode_gain_scaling = 0.5)
{
UrDriverConfiguration config;
config.robot_ip = robot_ip;
config.script_file = script_file;
config.output_recipe_file = output_recipe_file;
config.input_recipe_file = input_recipe_file;
config.handle_program_state = handle_program_state;
config.headless_mode = headless_mode;
config.tool_comm_setup = std::move(tool_comm_setup);
config.reverse_port = reverse_port;
config.script_sender_port = script_sender_port;
config.servoj_gain = servoj_gain;
config.servoj_lookahead_time = servoj_lookahead_time;
config.non_blocking_read = non_blocking_read;
config.reverse_ip = reverse_ip;
config.trajectory_port = trajectory_port;
config.script_command_port = script_command_port;
config.force_mode_damping = force_mode_damping;
config.force_mode_gain_scaling = force_mode_gain_scaling;
init(config);
}

/*!
* \brief Constructs a new UrDriver object.
*
* \deprecated Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const
* UrDriverConfiguration& config) instead. This function will be removed in May 2027.
*
* \param robot_ip IP-address under which the robot is reachable.
* \param script_file URScript file that should be sent to the robot.
* \param output_recipe_file Filename where the output recipe is stored in.
Expand Down Expand Up @@ -178,16 +313,44 @@ class UrDriver
* \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1]
* \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
*/
// Called sigC in tests
[[deprecated("Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const "
"UrDriverConfiguration& config) instead. This function will be removed in May 2027.")]]
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);
double force_mode_damping = 0.025, double force_mode_gain_scaling = 0.5)
{
UrDriverConfiguration config;
config.robot_ip = robot_ip;
config.script_file = script_file;
config.output_recipe_file = output_recipe_file;
config.input_recipe_file = input_recipe_file;
config.handle_program_state = handle_program_state;
config.headless_mode = headless_mode;
config.calibration_checksum = calibration_checksum;
config.tool_comm_setup = std::move(tool_comm_setup);
config.reverse_port = reverse_port;
config.script_sender_port = script_sender_port;
config.servoj_gain = servoj_gain;
config.servoj_lookahead_time = servoj_lookahead_time;
config.non_blocking_read = non_blocking_read;
config.reverse_ip = reverse_ip;
config.trajectory_port = trajectory_port;
config.script_command_port = script_command_port;
config.force_mode_damping = force_mode_damping;
config.force_mode_gain_scaling = force_mode_gain_scaling;
init(config);
}
/*!
* \brief Constructs a new UrDriver object.
*
* \deprecated Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const
* UrDriverConfiguration& config) instead. This function will be removed in May 2027.
*
* \param robot_ip IP-address under which the robot is reachable.
* \param script_file URScript file that should be sent to the robot.
* \param output_recipe_file Filename where the output recipe is stored in.
Expand All @@ -214,18 +377,36 @@ class UrDriver
* \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1]
* \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
*/
// Called sigD in tests
[[deprecated("Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const "
"UrDriverConfiguration& config) instead. This function will be removed in May 2027.")]]
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)
: UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode,
std::unique_ptr<ToolCommSetup>{}, calibration_checksum, reverse_port, script_sender_port, servoj_gain,
servoj_lookahead_time, non_blocking_read, reverse_ip, trajectory_port, script_command_port,
force_mode_damping, force_mode_gain_scaling)
{
UrDriverConfiguration config;
config.robot_ip = robot_ip;
config.script_file = script_file;
config.output_recipe_file = output_recipe_file;
config.input_recipe_file = input_recipe_file;
config.handle_program_state = handle_program_state;
config.headless_mode = headless_mode;
config.calibration_checksum = calibration_checksum;
config.reverse_port = reverse_port;
config.script_sender_port = script_sender_port;
config.servoj_gain = servoj_gain;
config.servoj_lookahead_time = servoj_lookahead_time;
config.non_blocking_read = non_blocking_read;
config.reverse_ip = reverse_ip;
config.trajectory_port = trajectory_port;
config.script_command_port = script_command_port;
config.force_mode_damping = force_mode_damping;
config.force_mode_gain_scaling = force_mode_gain_scaling;
init(config);
}

virtual ~UrDriver() = default;
Expand Down Expand Up @@ -669,6 +850,7 @@ class UrDriver

private:
static std::string readScriptFile(const std::string& filename);
void init(const UrDriverConfiguration& config);
/*!
* \brief Reconnects the secondary stream used to send program to the robot.
*
Expand Down Expand Up @@ -709,4 +891,4 @@ class UrDriver
VersionInformation robot_version_;
};
} // namespace urcl
#endif // ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
#endif // ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
21 changes: 16 additions & 5 deletions src/example_robot_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,16 +48,27 @@ ExampleRobotWrapper::ExampleRobotWrapper(const std::string& robot_ip, const std:
URCL_LOG_ERROR("Could not connect to dashboard");
}

// In CI we the dashboard client times out for no obvious reason. Hence we increase the timeout
// here.
timeval tv;
tv.tv_sec = 10;
tv.tv_usec = 0;
dashboard_client_->setReceiveTimeout(tv);

if (!initializeRobotWithDashboard())
{
throw UrException("Could not initialize robot with dashboard");
}

std::unique_ptr<ToolCommSetup> tool_comm_setup;
ur_driver_ =
std::make_shared<UrDriver>(robot_ip, script_file, output_recipe_file, input_recipe_file,
std::bind(&ExampleRobotWrapper::handleRobotProgramState, this, std::placeholders::_1),
headless_mode, std::move(tool_comm_setup));
UrDriverConfiguration driver_config;
driver_config.robot_ip = robot_ip;
driver_config.script_file = script_file;
driver_config.output_recipe_file = output_recipe_file;
driver_config.input_recipe_file = input_recipe_file;
driver_config.handle_program_state =
std::bind(&ExampleRobotWrapper::handleRobotProgramState, this, std::placeholders::_1);
driver_config.headless_mode = headless_mode;
ur_driver_ = std::make_shared<UrDriver>(driver_config);

if (!headless_mode && !std::empty(autostart_program))
{
Expand Down
Loading
Loading