Skip to content

Commit 1632f6d

Browse files
authored
Fix naming issues (#307)
We have been a bit inconsistent in the past when it comes to naming public members. While the changes in 71bab65 and 42cf147 would probably not impact many people, the changes from bef94bb would be more impactful. Potentially there would be many more changes in the message structures for the primary and RTDE interfaces which I have disabled for now.
1 parent 3ca3774 commit 1632f6d

29 files changed

+267
-198
lines changed

.clang-tidy

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@ CheckOptions:
33
- { key: readability-identifier-naming.NamespaceCase, value: lower_case }
44
- { key: readability-identifier-naming.ClassCase, value: CamelCase }
55
- { key: readability-identifier-naming.PrivateMemberSuffix, value: _ }
6+
- { key: readability-identifier-naming.PublicMemberSuffix, value: "" }
67
- { key: readability-identifier-naming.StructCase, value: CamelCase }
78
- { key: readability-identifier-naming.FunctionCase, value: camelBack }
89
- { key: readability-identifier-naming.VariableCase, value: lower_case }

.github/workflows/industrial-ci.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,5 +35,5 @@ jobs:
3535
DOWNSTREAM_WORKSPACE: ${{matrix.ROS_DISTRO.DOWNSTREAM_WORKSPACE}}
3636
ROS_DISTRO: ${{matrix.ROS_DISTRO.NAME}}
3737
ROS_REPO: ${{matrix.ROS_REPO}}
38-
CLANG_TIDY: true
38+
CLANG_TIDY: pedantic
3939
CLANG_TIDY_ARGS: '--extra-arg=-std=c++17' # needed for Humble

doc/examples/instruction_executor.rst

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@ The `instruction_executor.cpp <https://github.com/UniversalRobots/Universal_Robo
2121
:linenos:
2222
:lineno-match:
2323
:start-at: bool headless_mode = true;
24-
:end-at: auto instruction_executor = std::make_shared<urcl::InstructionExecutor>(g_my_robot->ur_driver_);
24+
:end-at: auto instruction_executor = std::make_shared<urcl::InstructionExecutor>(g_my_robot->getUrDriver());
2525

2626
At first, a ``InstructionExecutor`` object is created with the URDriver object as it needs that
2727
for communication with the robot.
@@ -61,6 +61,6 @@ To run a single motion, the ``InstructionExecutor`` provides the methods ``moveJ
6161
:linenos:
6262
:lineno-match:
6363
:start-at: double goal_time_sec = 2.0;
64-
:end-before: g_my_robot->ur_driver_->stopControl();
64+
:end-before: g_my_robot->getUrDriver()->stopControl();
6565

6666
Again, time parametrization has priority over acceleration / velocity parameters.

doc/examples/tool_contact_example.rst

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ At first, we create a initialize a driver as usual:
2020
:linenos:
2121
:lineno-match:
2222
:start-at: bool headless_mode = true;
23-
:end-before: g_my_robot->ur_driver_->registerToolContactResultCallback
23+
:end-before: g_my_robot->getUrDriver()->registerToolContactResultCallback
2424

2525
We use a small helper function to make sure that the reverse interface is active and connected
2626
before proceeding.
@@ -45,8 +45,8 @@ This function is registered as a callback to the driver and then tool_contact mo
4545
:caption: examples/tool_contact_example.cpp
4646
:linenos:
4747
:lineno-match:
48-
:start-at: g_my_robot->ur_driver_->registerToolContactResultCallback(&handleToolContactResult);
49-
:end-at: g_my_robot->ur_driver_->startToolContact()
48+
:start-at: g_my_robot->getUrDriver()->registerToolContactResultCallback(&handleToolContactResult);
49+
:end-at: g_my_robot->getUrDriver()->startToolContact()
5050

5151
Once everything is initialized, we can start a control loop commanding the robot to move in the
5252
negative z direction until the program timeout is hit or a tool contact is detected:

doc/examples/trajectory_point_interface.rst

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -45,8 +45,8 @@ That callback can be registered at the ``UrDriver`` object:
4545
:caption: examples/trajectory_point_interface.cpp
4646
:linenos:
4747
:lineno-match:
48-
:start-at: g_my_robot->ur_driver_->registerTrajectoryDoneCallback(&trajDoneCallback);
49-
:end-at: g_my_robot->ur_driver_->registerTrajectoryDoneCallback(&trajDoneCallback);
48+
:start-at: g_my_robot->getUrDriver()->registerTrajectoryDoneCallback(&trajDoneCallback);
49+
:end-at: g_my_robot->getUrDriver()->registerTrajectoryDoneCallback(&trajDoneCallback);
5050

5151

5252
MoveJ Trajectory
@@ -67,12 +67,12 @@ parameters. The following example shows execution of a 2-point trajectory using
6767
In fact, the path is followed twice, once parametrized by a segment duration and once using maximum
6868
velocity / acceleration settings. If a duration > 0 is given for a segment, the velocity and
6969
acceleration settings will be ignored as in the underlying URScript functions. In the example
70-
above, each of the ``g_my_robot->ur_driver_->writeTrajectoryPoint()`` calls will be translated into a
70+
above, each of the ``g_my_robot->getUrDriver()->writeTrajectoryPoint()`` calls will be translated into a
7171
``movej`` command in URScript.
7272

7373
While the trajectory is running, we need to tell the robot program that connection is still active
7474
and we expect the trajectory to be running. This is being done by the
75-
``g_my_robot->ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_NOOP);``
75+
``g_my_robot->getUrDriver()->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_NOOP);``
7676
call.
7777

7878
MoveL Trajectory

doc/index.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,3 +15,4 @@ can be found on `GitHub <https://github.com/UniversalRobots/Universal_Robots_Cli
1515
architecture
1616
examples
1717
real_time
18+
migration_notes

doc/migration_notes.rst

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
Migration notes
2+
===============
3+
4+
This document contains notes on the migration of the ur_client_library between major versions.
5+
6+
It contains only breaking changes.
7+
8+
Migrating from 1.x.x to 2.x.x
9+
-----------------------------
10+
11+
- In the ``urcl::ExampleRobotWrapper`` class the ``ur_driver_``, ``dashboard_client`` and
12+
``primary_client`` members are now private. Use ``getUrDriver()``, ``getDashboardClient()`` and
13+
``getPrimaryClient()`` to access them.
14+
15+
- In ``urcl::comm::ControlModeTypes`` two member functions have been renamed:
16+
17+
- ``is_control_mode_realtime`` -> ``isControlModeRealtime``
18+
- ``is_control_mode_non_realtime`` -> ``isControlModeNonRealtime``
19+
20+
- In ``urcl::RobotReceiveTimeout`` the ``timeout_`` member is now private. Use
21+
``getAsMilliseconds()`` to access it.
22+
23+
- In ``urcl::UrDriverConfiguration`` two members have been renamed:
24+
25+
- ``rtde_initialization_attempts_`` -> ``rtde_initialization_attempts``
26+
- ``rtde_initialization_timeout_`` -> ``rtde_initialization_timeout``

examples/force_mode_example.cpp

Lines changed: 20 additions & 20 deletions
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ std::unique_ptr<ExampleRobotWrapper> g_my_robot;
5757

5858
void sendFreedriveMessageOrDie(const control::FreedriveControlMessage freedrive_action)
5959
{
60-
bool ret = g_my_robot->ur_driver_->writeFreedriveControlMessage(freedrive_action);
60+
bool ret = g_my_robot->getUrDriver()->writeFreedriveControlMessage(freedrive_action);
6161
if (!ret)
6262
{
6363
URCL_LOG_ERROR("Could not send joint command. Is the robot in remote control?");
@@ -91,7 +91,7 @@ int main(int argc, char* argv[])
9191
URCL_LOG_ERROR("Something in the robot initialization went wrong. Exiting. Please check the output above.");
9292
return 1;
9393
}
94-
if (!g_my_robot->ur_driver_->checkCalibration(CALIBRATION_CHECKSUM))
94+
if (!g_my_robot->getUrDriver()->checkCalibration(CALIBRATION_CHECKSUM))
9595
{
9696
URCL_LOG_ERROR("Calibration checksum does not match actual robot.");
9797
URCL_LOG_ERROR("Use the ur_calibration tool to extract the correct calibration from the robot and pass that into "
@@ -107,24 +107,24 @@ int main(int argc, char* argv[])
107107
// Task frame at the robot's base with limits being large enough to cover the whole workspace
108108
// Compliance in z axis and rotation around z axis
109109
bool success;
110-
if (g_my_robot->ur_driver_->getVersion().major < 5)
111-
success =
112-
g_my_robot->ur_driver_->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base
113-
{ 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis
114-
{ 0, 0, -2, 0, 0, 0 }, // Press in -z direction
115-
2, // do not transform the force frame at all
116-
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
117-
0.005); // damping_factor. See ScriptManual for details.
110+
if (g_my_robot->getUrDriver()->getVersion().major < 5)
111+
success = g_my_robot->getUrDriver()->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base
112+
{ 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation
113+
// around z axis
114+
{ 0, 0, -2, 0, 0, 0 }, // Press in -z direction
115+
2, // do not transform the force frame at all
116+
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
117+
0.005); // damping_factor. See ScriptManual for details.
118118
else
119119
{
120-
success =
121-
g_my_robot->ur_driver_->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base
122-
{ 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis
123-
{ 0, 0, -2, 0, 0, 0 }, // Press in -z direction
124-
2, // do not transform the force frame at all
125-
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
126-
0.005, // damping_factor
127-
1.0); // gain_scaling. See ScriptManual for details.
120+
success = g_my_robot->getUrDriver()->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base
121+
{ 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation
122+
// around z axis
123+
{ 0, 0, -2, 0, 0, 0 }, // Press in -z direction
124+
2, // do not transform the force frame at all
125+
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
126+
0.005, // damping_factor
127+
1.0); // gain_scaling. See ScriptManual for details.
128128
}
129129
if (!success)
130130
{
@@ -138,13 +138,13 @@ int main(int argc, char* argv[])
138138
auto stopwatch_now = stopwatch_last;
139139
while (time_done < timeout || second_to_run.count() == 0)
140140
{
141-
g_my_robot->ur_driver_->writeKeepalive();
141+
g_my_robot->getUrDriver()->writeKeepalive();
142142

143143
stopwatch_now = std::chrono::steady_clock::now();
144144
time_done += stopwatch_now - stopwatch_last;
145145
stopwatch_last = stopwatch_now;
146146
std::this_thread::sleep_for(std::chrono::milliseconds(2));
147147
}
148148
URCL_LOG_INFO("Timeout reached.");
149-
g_my_robot->ur_driver_->endForceMode();
149+
g_my_robot->getUrDriver()->endForceMode();
150150
}

examples/freedrive_example.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ std::unique_ptr<ExampleRobotWrapper> g_my_robot;
5555

5656
void sendFreedriveMessageOrDie(const control::FreedriveControlMessage freedrive_action)
5757
{
58-
bool ret = g_my_robot->ur_driver_->writeFreedriveControlMessage(freedrive_action);
58+
bool ret = g_my_robot->getUrDriver()->writeFreedriveControlMessage(freedrive_action);
5959
if (!ret)
6060
{
6161
URCL_LOG_ERROR("Could not send joint command. Is there an external_control program running on the robot?");

examples/full_driver.cpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -71,7 +71,7 @@ int main(int argc, char* argv[])
7171

7272
// Increment depends on robot version
7373
double increment_constant = 0.0005;
74-
if (g_my_robot->ur_driver_->getVersion().major < 5)
74+
if (g_my_robot->getUrDriver()->getVersion().major < 5)
7575
{
7676
increment_constant = 0.002;
7777
}
@@ -86,14 +86,14 @@ int main(int argc, char* argv[])
8686
// Once RTDE communication is started, we have to make sure to read from the interface buffer, as
8787
// otherwise we will get pipeline overflows. Therefor, do this directly before starting your main
8888
// loop.
89-
g_my_robot->ur_driver_->startRTDECommunication();
89+
g_my_robot->getUrDriver()->startRTDECommunication();
9090
while (!(passed_positive_part && passed_negative_part))
9191
{
9292
// Read latest RTDE package. This will block for a hard-coded timeout (see UrDriver), so the
9393
// robot will effectively be in charge of setting the frequency of this loop.
9494
// In a real-world application this thread should be scheduled with real-time priority in order
9595
// to ensure that this is called in time.
96-
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver_->getDataPackage();
96+
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->getUrDriver()->getDataPackage();
9797
if (!data_pkg)
9898
{
9999
URCL_LOG_WARN("Could not get fresh data package from robot");
@@ -133,16 +133,16 @@ int main(int argc, char* argv[])
133133
joint_target[5] += increment;
134134
// Setting the RobotReceiveTimeout time is for example purposes only. This will make the example running more
135135
// reliable on non-realtime systems. Use with caution in productive applications.
136-
bool ret = g_my_robot->ur_driver_->writeJointCommand(joint_target, comm::ControlMode::MODE_SERVOJ,
137-
RobotReceiveTimeout::millisec(100));
136+
bool ret = g_my_robot->getUrDriver()->writeJointCommand(joint_target, comm::ControlMode::MODE_SERVOJ,
137+
RobotReceiveTimeout::millisec(100));
138138
if (!ret)
139139
{
140140
URCL_LOG_ERROR("Could not send joint command. Is the robot in remote control?");
141141
return 1;
142142
}
143143
URCL_LOG_DEBUG("data_pkg:\n%s", data_pkg->toString().c_str());
144144
}
145-
g_my_robot->ur_driver_->stopControl();
145+
g_my_robot->getUrDriver()->stopControl();
146146
URCL_LOG_INFO("Movement done");
147147
return 0;
148148
}

0 commit comments

Comments
 (0)