Skip to content

Commit dcb6ea4

Browse files
committed
Add documentation for UrDriverConfiguration struct
1 parent 74b2598 commit dcb6ea4

File tree

1 file changed

+80
-10
lines changed

1 file changed

+80
-10
lines changed

include/ur_client_library/ur/ur_driver.h

Lines changed: 80 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -44,31 +44,78 @@
4444

4545
namespace urcl
4646
{
47+
/*!
48+
* \brief Structure for configuration parameters of a UrDriver object.
49+
*/
4750
struct UrDriverConfiguration
4851
{
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+
*/
5363
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.
5565

56-
std::unique_ptr<ToolCommSetup> tool_comm_setup = nullptr;
66+
std::unique_ptr<ToolCommSetup> tool_comm_setup = nullptr; //!< Configuration for using the tool communication.
5767

68+
/*!
69+
* \brief Port that will be opened by the driver to allow direct communication between the driver
70+
* and the robot controller.
71+
*/
5872
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+
*/
5977
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+
*/
6082
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+
*/
6190
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+
*/
6298
std::string reverse_ip = "";
6399

100+
/*!
101+
* \brief Proportional gain for arm joints following target position, range [100,2000]
102+
*/
64103
int servoj_gain = 2000;
104+
105+
/*!
106+
* \brief Time [S], range [0.03,0.2] smoothens servoj calls with this lookahead time
107+
*/
65108
double servoj_lookahead_time = 0.03;
66109

67110
bool non_blocking_read = false;
68111

69112
// TODO: Remove on 2027-05
113+
// The following parameters are considered deprecated and will be removed in May 2027.
114+
/// @private
70115
std::string calibration_checksum = "";
116+
/// @private
71117
double force_mode_damping = 0.025;
118+
/// @private
72119
double force_mode_gain_scaling = 0.5;
73120
};
74121

@@ -82,13 +129,27 @@ struct UrDriverConfiguration
82129
class UrDriver
83130
{
84131
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+
*/
85142
explicit UrDriver(const UrDriverConfiguration& config)
86143
{
87144
init(config);
88145
}
89146

90147
/*!
91148
* \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+
*
92153
* Upon initialization this class will check the calibration checksum reported from the robot and
93154
* compare it to a checksum given by the user. If the checksums don't match, the driver will output
94155
* an error message. This is critical if you want to do forward or inverse kinematics based on the
@@ -158,6 +219,10 @@ class UrDriver
158219

159220
/*!
160221
* \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+
*
161226
* \param robot_ip IP-address under which the robot is reachable.
162227
* \param script_file URScript file that should be sent to the robot.
163228
* \param output_recipe_file Filename where the output recipe is stored in.
@@ -185,10 +250,8 @@ class UrDriver
185250
* \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series)
186251
*/
187252
// 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.")]]
192255
UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file,
193256
const std::string& input_recipe_file, std::function<void(bool)> handle_program_state, bool headless_mode,
194257
std::unique_ptr<ToolCommSetup> tool_comm_setup, const uint32_t reverse_port,
@@ -219,6 +282,10 @@ class UrDriver
219282

220283
/*!
221284
* \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+
*
222289
* \param robot_ip IP-address under which the robot is reachable.
223290
* \param script_file URScript file that should be sent to the robot.
224291
* \param output_recipe_file Filename where the output recipe is stored in.
@@ -281,6 +348,9 @@ class UrDriver
281348
/*!
282349
* \brief Constructs a new UrDriver object.
283350
*
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+
*
284354
* \param robot_ip IP-address under which the robot is reachable.
285355
* \param script_file URScript file that should be sent to the robot.
286356
* \param output_recipe_file Filename where the output recipe is stored in.

0 commit comments

Comments
 (0)