4444
4545namespace urcl
4646{
47+ /* !
48+ * \brief Structure for configuration parameters of a UrDriver object.
49+ */
50+ struct UrDriverConfiguration
51+ {
52+ std::string robot_ip; // !< IP-address under which the robot is reachable.
53+ std::string script_file; // !< URScript file that should be sent to the robot.
54+ std::string output_recipe_file; // !< Filename where the output recipe is stored in.
55+ std::string input_recipe_file; // !< Filename where the input recipe is stored in.
56+
57+ /* !
58+ * \brief Function handle to a callback on program state changes.
59+ *
60+ * For this to work, the URScript program will have to send keepalive signals to the \p
61+ * reverse_port.
62+ */
63+ std::function<void (bool )> handle_program_state;
64+ bool headless_mode; // !< Parameter to control if the driver should be started in headless mode.
65+
66+ std::unique_ptr<ToolCommSetup> tool_comm_setup = nullptr ; // !< Configuration for using the tool communication.
67+
68+ /* !
69+ * \brief Port that will be opened by the driver to allow direct communication between the driver
70+ * and the robot controller.
71+ */
72+ uint32_t reverse_port = 50001 ;
73+
74+ /* ! \brief The driver will offer an interface to receive the program's URScript on this port. If
75+ * the robot cannot connect to this port, `External Control` will stop immediately.
76+ */
77+ uint32_t script_sender_port = 50002 ;
78+
79+ /* !
80+ * \brief Port used for sending trajectory points to the robot in case of trajectory forwarding.
81+ */
82+ uint32_t trajectory_port = 50003 ;
83+
84+ /* !
85+ * \brief Port used for forwarding script commands to the robot.
86+ *
87+ * This interface supports a set of predefined commands.
88+ * The script commands will be executed locally on the robot.
89+ */
90+ uint32_t script_command_port = 50004 ;
91+
92+ /* !
93+ * \brief IP address that the reverse_port will get bound to.
94+ *
95+ * If not specified, the IP address of the interface that is used for connecting to the robot's RTDE port will be
96+ * used.
97+ */
98+ std::string reverse_ip = " " ;
99+
100+ /* !
101+ * \brief Proportional gain for arm joints following target position, range [100,2000]
102+ */
103+ int servoj_gain = 2000 ;
104+
105+ /* !
106+ * \brief Time [S], range [0.03,0.2] smoothens servoj calls with this lookahead time
107+ */
108+ double servoj_lookahead_time = 0.03 ;
109+
110+ bool non_blocking_read = false ;
111+
112+ // TODO: Remove on 2027-05
113+ // The following parameters are considered deprecated and will be removed in May 2027.
114+ // / @private
115+ std::string calibration_checksum = " " ;
116+ // / @private
117+ double force_mode_damping = 0.025 ;
118+ // / @private
119+ double force_mode_gain_scaling = 0.5 ;
120+ };
121+
47122/* !
48123 * \brief This is the main class for interfacing the driver.
49124 *
@@ -56,6 +131,25 @@ class UrDriver
56131public:
57132 /* !
58133 * \brief Constructs a new UrDriver object.
134+ *
135+ * An RTDE connection to the robot will be established using the given recipe files. However, RTDE
136+ * communication will not be started automatically, as this requires an external structure to read
137+ * data from the RTDE client using the getDataPackage() method periodically. Once this is setup,
138+ * please use the startRTDECommunication() method to actually start RTDE communication.
139+ *
140+ * \param config Configuration struct for the UrDriver. See it's documentation for details.
141+ */
142+ explicit UrDriver (const UrDriverConfiguration& config)
143+ {
144+ init (config);
145+ }
146+
147+ /* !
148+ * \brief Constructs a new UrDriver object.
149+ *
150+ * \deprecated Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const
151+ * UrDriverConfiguration& config) instead. This function will be removed in May 2027.
152+ *
59153 * Upon initialization this class will check the calibration checksum reported from the robot and
60154 * compare it to a checksum given by the user. If the checksums don't match, the driver will output
61155 * an error message. This is critical if you want to do forward or inverse kinematics based on the
@@ -94,15 +188,41 @@ class UrDriver
94188 * \param script_command_port Port used for forwarding script commands to the robot. The script commands will be
95189 * executed locally on the robot.
96190 */
191+ // Called sigA in tests
192+ [[deprecated(" Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const "
193+ " UrDriverConfiguration& config) instead. This function will be removed in May 2027." )]]
97194 UrDriver (const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
98195 const std::string& input_recipe_file, std::function<void (bool )> handle_program_state, bool headless_mode,
99196 std::unique_ptr<ToolCommSetup> tool_comm_setup, const uint32_t reverse_port = 50001 ,
100197 const uint32_t script_sender_port = 50002 , int servoj_gain = 2000 , double servoj_lookahead_time = 0.03 ,
101198 bool non_blocking_read = false , const std::string& reverse_ip = " " , const uint32_t trajectory_port = 50003 ,
102- const uint32_t script_command_port = 50004 );
199+ const uint32_t script_command_port = 50004 )
200+ {
201+ UrDriverConfiguration config;
202+ config.robot_ip = robot_ip;
203+ config.script_file = script_file;
204+ config.output_recipe_file = output_recipe_file;
205+ config.input_recipe_file = input_recipe_file;
206+ config.handle_program_state = handle_program_state;
207+ config.headless_mode = headless_mode;
208+ config.tool_comm_setup = std::move (tool_comm_setup);
209+ config.reverse_port = reverse_port;
210+ config.script_sender_port = script_sender_port;
211+ config.servoj_gain = servoj_gain;
212+ config.servoj_lookahead_time = servoj_lookahead_time;
213+ config.non_blocking_read = non_blocking_read;
214+ config.reverse_ip = reverse_ip;
215+ config.trajectory_port = trajectory_port;
216+ config.script_command_port = script_command_port;
217+ init (config);
218+ }
103219
104220 /* !
105221 * \brief Constructs a new UrDriver object.
222+ *
223+ * \deprecated Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const
224+ * UrDriverConfiguration& config) instead. This function will be removed in May 2027.
225+ *
106226 * \param robot_ip IP-address under which the robot is reachable.
107227 * \param script_file URScript file that should be sent to the robot.
108228 * \param output_recipe_file Filename where the output recipe is stored in.
@@ -129,28 +249,43 @@ class UrDriver
129249 * \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1]
130250 * \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
131251 */
132- [[deprecated(
133- " Specifying the force mode damping factor and the force mode gain scaling factor at driver creation has "
134- " been deprecated. Force mode parameters should be specified with each activiation of force mode, and "
135- " can be set in the function call to start force mode." )]] UrDriver(const std::string& robot_ip,
136- const std::string& script_file,
137- const std::string& output_recipe_file,
138- const std::string& input_recipe_file,
139- std::function<void (bool )> handle_program_state,
140- bool headless_mode,
141- std::unique_ptr<ToolCommSetup> tool_comm_setup,
142- const uint32_t reverse_port,
143- const uint32_t script_sender_port,
144- int servoj_gain, double servoj_lookahead_time,
145- bool non_blocking_read,
146- const std::string& reverse_ip,
147- const uint32_t trajectory_port,
148- const uint32_t script_command_port,
149- double force_mode_damping,
150- double force_mode_gain_scaling = 0.5 );
252+ // Called sigB in tests
253+ [[deprecated(" Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const "
254+ " UrDriverConfiguration& config) instead. This function will be removed in May 2027." )]]
255+ UrDriver (const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
256+ const std::string& input_recipe_file, std::function<void (bool )> handle_program_state, bool headless_mode,
257+ std::unique_ptr<ToolCommSetup> tool_comm_setup, const uint32_t reverse_port,
258+ const uint32_t script_sender_port, int servoj_gain, double servoj_lookahead_time, bool non_blocking_read,
259+ const std::string& reverse_ip, const uint32_t trajectory_port, const uint32_t script_command_port,
260+ double force_mode_damping, double force_mode_gain_scaling = 0.5 )
261+ {
262+ UrDriverConfiguration config;
263+ config.robot_ip = robot_ip;
264+ config.script_file = script_file;
265+ config.output_recipe_file = output_recipe_file;
266+ config.input_recipe_file = input_recipe_file;
267+ config.handle_program_state = handle_program_state;
268+ config.headless_mode = headless_mode;
269+ config.tool_comm_setup = std::move (tool_comm_setup);
270+ config.reverse_port = reverse_port;
271+ config.script_sender_port = script_sender_port;
272+ config.servoj_gain = servoj_gain;
273+ config.servoj_lookahead_time = servoj_lookahead_time;
274+ config.non_blocking_read = non_blocking_read;
275+ config.reverse_ip = reverse_ip;
276+ config.trajectory_port = trajectory_port;
277+ config.script_command_port = script_command_port;
278+ config.force_mode_damping = force_mode_damping;
279+ config.force_mode_gain_scaling = force_mode_gain_scaling;
280+ init (config);
281+ }
151282
152283 /* !
153284 * \brief Constructs a new UrDriver object.
285+ *
286+ * \deprecated Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const
287+ * UrDriverConfiguration& config) instead. This function will be removed in May 2027.
288+ *
154289 * \param robot_ip IP-address under which the robot is reachable.
155290 * \param script_file URScript file that should be sent to the robot.
156291 * \param output_recipe_file Filename where the output recipe is stored in.
@@ -178,16 +313,44 @@ class UrDriver
178313 * \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1]
179314 * \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
180315 */
316+ // Called sigC in tests
317+ [[deprecated(" Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const "
318+ " UrDriverConfiguration& config) instead. This function will be removed in May 2027." )]]
181319 UrDriver (const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
182320 const std::string& input_recipe_file, std::function<void (bool )> handle_program_state, bool headless_mode,
183321 std::unique_ptr<ToolCommSetup> tool_comm_setup, const std::string& calibration_checksum,
184322 const uint32_t reverse_port = 50001 , const uint32_t script_sender_port = 50002 , int servoj_gain = 2000 ,
185323 double servoj_lookahead_time = 0.03 , bool non_blocking_read = false , const std::string& reverse_ip = " " ,
186324 const uint32_t trajectory_port = 50003 , const uint32_t script_command_port = 50004 ,
187- double force_mode_damping = 0.025 , double force_mode_gain_scaling = 0.5 );
325+ double force_mode_damping = 0.025 , double force_mode_gain_scaling = 0.5 )
326+ {
327+ UrDriverConfiguration config;
328+ config.robot_ip = robot_ip;
329+ config.script_file = script_file;
330+ config.output_recipe_file = output_recipe_file;
331+ config.input_recipe_file = input_recipe_file;
332+ config.handle_program_state = handle_program_state;
333+ config.headless_mode = headless_mode;
334+ config.calibration_checksum = calibration_checksum;
335+ config.tool_comm_setup = std::move (tool_comm_setup);
336+ config.reverse_port = reverse_port;
337+ config.script_sender_port = script_sender_port;
338+ config.servoj_gain = servoj_gain;
339+ config.servoj_lookahead_time = servoj_lookahead_time;
340+ config.non_blocking_read = non_blocking_read;
341+ config.reverse_ip = reverse_ip;
342+ config.trajectory_port = trajectory_port;
343+ config.script_command_port = script_command_port;
344+ config.force_mode_damping = force_mode_damping;
345+ config.force_mode_gain_scaling = force_mode_gain_scaling;
346+ init (config);
347+ }
188348 /* !
189349 * \brief Constructs a new UrDriver object.
190350 *
351+ * \deprecated Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const
352+ * UrDriverConfiguration& config) instead. This function will be removed in May 2027.
353+ *
191354 * \param robot_ip IP-address under which the robot is reachable.
192355 * \param script_file URScript file that should be sent to the robot.
193356 * \param output_recipe_file Filename where the output recipe is stored in.
@@ -214,18 +377,36 @@ class UrDriver
214377 * \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1]
215378 * \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
216379 */
380+ // Called sigD in tests
381+ [[deprecated(" Initializing a UrDriver object with an argument list is deprecated. Please use UrDriver(const "
382+ " UrDriverConfiguration& config) instead. This function will be removed in May 2027." )]]
217383 UrDriver (const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
218384 const std::string& input_recipe_file, std::function<void (bool )> handle_program_state, bool headless_mode,
219385 const std::string& calibration_checksum = " " , const uint32_t reverse_port = 50001 ,
220386 const uint32_t script_sender_port = 50002 , int servoj_gain = 2000 , double servoj_lookahead_time = 0.03 ,
221387 bool non_blocking_read = false , const std::string& reverse_ip = " " , const uint32_t trajectory_port = 50003 ,
222388 const uint32_t script_command_port = 50004 , double force_mode_damping = 0.025 ,
223389 double force_mode_gain_scaling = 0.5 )
224- : UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode,
225- std::unique_ptr<ToolCommSetup>{}, calibration_checksum, reverse_port, script_sender_port, servoj_gain,
226- servoj_lookahead_time, non_blocking_read, reverse_ip, trajectory_port, script_command_port,
227- force_mode_damping, force_mode_gain_scaling)
228390 {
391+ UrDriverConfiguration config;
392+ config.robot_ip = robot_ip;
393+ config.script_file = script_file;
394+ config.output_recipe_file = output_recipe_file;
395+ config.input_recipe_file = input_recipe_file;
396+ config.handle_program_state = handle_program_state;
397+ config.headless_mode = headless_mode;
398+ config.calibration_checksum = calibration_checksum;
399+ config.reverse_port = reverse_port;
400+ config.script_sender_port = script_sender_port;
401+ config.servoj_gain = servoj_gain;
402+ config.servoj_lookahead_time = servoj_lookahead_time;
403+ config.non_blocking_read = non_blocking_read;
404+ config.reverse_ip = reverse_ip;
405+ config.trajectory_port = trajectory_port;
406+ config.script_command_port = script_command_port;
407+ config.force_mode_damping = force_mode_damping;
408+ config.force_mode_gain_scaling = force_mode_gain_scaling;
409+ init (config);
229410 }
230411
231412 virtual ~UrDriver () = default ;
@@ -669,6 +850,7 @@ class UrDriver
669850
670851private:
671852 static std::string readScriptFile (const std::string& filename);
853+ void init (const UrDriverConfiguration& config);
672854 /* !
673855 * \brief Reconnects the secondary stream used to send program to the robot.
674856 *
@@ -709,4 +891,4 @@ class UrDriver
709891 VersionInformation robot_version_;
710892};
711893} // namespace urcl
712- #endif // ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
894+ #endif // ifndef UR_CLIENT_LIBRARY_UR_UR_DRIVER_H_INCLUDED
0 commit comments