44
44
45
45
namespace urcl
46
46
{
47
+ /* !
48
+ * \brief Structure for configuration parameters of a UrDriver object.
49
+ */
47
50
struct UrDriverConfiguration
48
51
{
49
- std::string robot_ip;
50
- std::string script_file;
51
- std::string output_recipe_file;
52
- std::string input_recipe_file;
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
+ */
53
63
std::function<void (bool )> handle_program_state;
54
- bool headless_mode;
64
+ bool headless_mode; // !< Parameter to control if the driver should be started in headless mode.
55
65
56
- std::unique_ptr<ToolCommSetup> tool_comm_setup = nullptr ;
66
+ std::unique_ptr<ToolCommSetup> tool_comm_setup = nullptr ; // !< Configuration for using the tool communication.
57
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
+ */
58
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
+ */
59
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
+ */
60
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
+ */
61
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
+ */
62
98
std::string reverse_ip = " " ;
63
99
100
+ /* !
101
+ * \brief Proportional gain for arm joints following target position, range [100,2000]
102
+ */
64
103
int servoj_gain = 2000 ;
104
+
105
+ /* !
106
+ * \brief Time [S], range [0.03,0.2] smoothens servoj calls with this lookahead time
107
+ */
65
108
double servoj_lookahead_time = 0.03 ;
66
109
67
110
bool non_blocking_read = false ;
68
111
69
112
// TODO: Remove on 2027-05
113
+ // The following parameters are considered deprecated and will be removed in May 2027.
114
+ // / @private
70
115
std::string calibration_checksum = " " ;
116
+ // / @private
71
117
double force_mode_damping = 0.025 ;
118
+ // / @private
72
119
double force_mode_gain_scaling = 0.5 ;
73
120
};
74
121
@@ -82,13 +129,27 @@ struct UrDriverConfiguration
82
129
class UrDriver
83
130
{
84
131
public:
132
+ /* !
133
+ * \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
+ */
85
142
explicit UrDriver (const UrDriverConfiguration& config)
86
143
{
87
144
init (config);
88
145
}
89
146
90
147
/* !
91
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
+ *
92
153
* Upon initialization this class will check the calibration checksum reported from the robot and
93
154
* compare it to a checksum given by the user. If the checksums don't match, the driver will output
94
155
* an error message. This is critical if you want to do forward or inverse kinematics based on the
@@ -158,6 +219,10 @@ class UrDriver
158
219
159
220
/* !
160
221
* \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
+ *
161
226
* \param robot_ip IP-address under which the robot is reachable.
162
227
* \param script_file URScript file that should be sent to the robot.
163
228
* \param output_recipe_file Filename where the output recipe is stored in.
@@ -185,10 +250,8 @@ class UrDriver
185
250
* \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
186
251
*/
187
252
// Called sigB in tests
188
- [[deprecated(" Specifying the force mode damping factor and the force mode gain scaling factor at driver creation has "
189
- " been deprecated. Force mode parameters should be specified with each activiation of force mode, and "
190
- " can be set in the function call to start force mode. This function will be removed in May "
191
- " 2027." )]]
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." )]]
192
255
UrDriver (const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
193
256
const std::string& input_recipe_file, std::function<void (bool )> handle_program_state, bool headless_mode,
194
257
std::unique_ptr<ToolCommSetup> tool_comm_setup, const uint32_t reverse_port,
@@ -219,6 +282,10 @@ class UrDriver
219
282
220
283
/* !
221
284
* \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
+ *
222
289
* \param robot_ip IP-address under which the robot is reachable.
223
290
* \param script_file URScript file that should be sent to the robot.
224
291
* \param output_recipe_file Filename where the output recipe is stored in.
@@ -281,6 +348,9 @@ class UrDriver
281
348
/* !
282
349
* \brief Constructs a new UrDriver object.
283
350
*
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
+ *
284
354
* \param robot_ip IP-address under which the robot is reachable.
285
355
* \param script_file URScript file that should be sent to the robot.
286
356
* \param output_recipe_file Filename where the output recipe is stored in.
0 commit comments