Skip to content

Commit bef94bb

Browse files
committed
Enforce suffix-less naming of public members
This changes naming of a lot of public members, as well.
1 parent 0666616 commit bef94bb

20 files changed

+227
-204
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 }

examples/force_mode_example.cpp

Lines changed: 18 additions & 18 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->ur_driver->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->ur_driver->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)
110+
if (g_my_robot->ur_driver->getVersion().major < 5)
111111
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.
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.
118118
else
119119
{
120120
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.
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.
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->ur_driver->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->ur_driver->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->ur_driver->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->ur_driver->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->ur_driver->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->ur_driver->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->ur_driver->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->ur_driver->stopControl();
146146
URCL_LOG_INFO("Movement done");
147147
return 0;
148148
}

examples/instruction_executor.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ int main(int argc, char* argv[])
6161
bool headless_mode = true;
6262
g_my_robot = std::make_unique<urcl::ExampleRobotWrapper>(robot_ip, OUTPUT_RECIPE, INPUT_RECIPE, headless_mode,
6363
"external_control.urp");
64-
if (!g_my_robot->ur_driver_->checkCalibration(CALIBRATION_CHECKSUM))
64+
if (!g_my_robot->ur_driver->checkCalibration(CALIBRATION_CHECKSUM))
6565
{
6666
URCL_LOG_ERROR("Calibration checksum does not match actual robot.");
6767
URCL_LOG_ERROR("Use the ur_calibration tool to extract the correct calibration from the robot and pass that into "
@@ -75,7 +75,7 @@ int main(int argc, char* argv[])
7575
return 1;
7676
}
7777

78-
auto instruction_executor = std::make_shared<urcl::InstructionExecutor>(g_my_robot->ur_driver_);
78+
auto instruction_executor = std::make_shared<urcl::InstructionExecutor>(g_my_robot->ur_driver);
7979
// --------------- INITIALIZATION END -------------------
8080

8181
URCL_LOG_INFO("Running motion");
@@ -105,6 +105,6 @@ int main(int argc, char* argv[])
105105
// goal time parametrization -- acceleration and velocity will be ignored
106106
instruction_executor->moveL({ -0.203, 0.463, 0.559, 0.68, -1.083, -2.076 }, 0.1, 0.1, goal_time_sec);
107107

108-
g_my_robot->ur_driver_->stopControl();
108+
g_my_robot->ur_driver->stopControl();
109109
return 0;
110110
}

examples/spline_example.cpp

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -57,31 +57,31 @@ void sendTrajectory(const std::vector<vector6d_t>& p_p, const std::vector<vector
5757
assert(p_p.size() == time.size());
5858

5959
URCL_LOG_INFO("Starting joint-based trajectory forward");
60-
g_my_robot->ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START,
61-
p_p.size());
60+
g_my_robot->ur_driver->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START,
61+
p_p.size());
6262

6363
for (size_t i = 0; i < p_p.size() && p_p.size() == time.size() && p_p[i].size() == 6; i++)
6464
{
6565
// MoveJ
6666
if (!use_spline_interpolation_)
6767
{
68-
g_my_robot->ur_driver_->writeTrajectoryPoint(p_p[i], false, time[i]);
68+
g_my_robot->ur_driver->writeTrajectoryPoint(p_p[i], false, time[i]);
6969
}
7070
else // Use spline interpolation
7171
{
7272
// QUINTIC
7373
if (p_v.size() == time.size() && p_a.size() == time.size() && p_v[i].size() == 6 && p_a[i].size() == 6)
7474
{
75-
g_my_robot->ur_driver_->writeTrajectorySplinePoint(p_p[i], p_v[i], p_a[i], time[i]);
75+
g_my_robot->ur_driver->writeTrajectorySplinePoint(p_p[i], p_v[i], p_a[i], time[i]);
7676
}
7777
// CUBIC
7878
else if (p_v.size() == time.size() && p_v[i].size() == 6)
7979
{
80-
g_my_robot->ur_driver_->writeTrajectorySplinePoint(p_p[i], p_v[i], time[i]);
80+
g_my_robot->ur_driver->writeTrajectorySplinePoint(p_p[i], p_v[i], time[i]);
8181
}
8282
else
8383
{
84-
g_my_robot->ur_driver_->writeTrajectorySplinePoint(p_p[i], time[i]);
84+
g_my_robot->ur_driver->writeTrajectorySplinePoint(p_p[i], time[i]);
8585
}
8686
}
8787
}
@@ -131,15 +131,15 @@ int main(int argc, char* argv[])
131131
return 1;
132132
}
133133

134-
g_my_robot->ur_driver_->registerTrajectoryDoneCallback(&handleTrajectoryState);
134+
g_my_robot->ur_driver->registerTrajectoryDoneCallback(&handleTrajectoryState);
135135

136136
// Once RTDE communication is started, we have to make sure to read from the interface buffer, as
137137
// otherwise we will get pipeline overflows. Therefore, do this directly before starting your main
138138
// loop.
139139

140-
g_my_robot->ur_driver_->startRTDECommunication();
140+
g_my_robot->ur_driver->startRTDECommunication();
141141

142-
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver_->getDataPackage();
142+
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver->getDataPackage();
143143

144144
if (data_pkg)
145145
{
@@ -162,7 +162,7 @@ int main(int argc, char* argv[])
162162
4.00000000e+00 };
163163

164164
bool ret = false;
165-
ret = g_my_robot->ur_driver_->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
165+
ret = g_my_robot->ur_driver->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
166166
if (!ret)
167167
{
168168
std::stringstream lastq;
@@ -199,7 +199,7 @@ int main(int argc, char* argv[])
199199
g_trajectory_running = true;
200200
while (g_trajectory_running)
201201
{
202-
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver_->getDataPackage();
202+
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver->getDataPackage();
203203
if (data_pkg)
204204
{
205205
// Read current joint positions from robot data
@@ -209,7 +209,7 @@ int main(int argc, char* argv[])
209209
std::string error_msg = "Did not find 'actual_q' in data sent from robot. This should not happen!";
210210
throw std::runtime_error(error_msg);
211211
}
212-
ret = g_my_robot->ur_driver_->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
212+
ret = g_my_robot->ur_driver->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
213213

214214
if (!ret)
215215
{
@@ -230,7 +230,7 @@ int main(int argc, char* argv[])
230230
g_trajectory_running = true;
231231
while (g_trajectory_running)
232232
{
233-
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver_->getDataPackage();
233+
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver->getDataPackage();
234234
if (data_pkg)
235235
{
236236
// Read current joint positions from robot data
@@ -240,7 +240,7 @@ int main(int argc, char* argv[])
240240
std::string error_msg = "Did not find 'actual_q' in data sent from robot. This should not happen!";
241241
throw std::runtime_error(error_msg);
242242
}
243-
ret = g_my_robot->ur_driver_->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
243+
ret = g_my_robot->ur_driver->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
244244

245245
if (!ret)
246246
{
@@ -255,7 +255,7 @@ int main(int argc, char* argv[])
255255

256256
URCL_LOG_INFO("QUINTIC Movement done");
257257

258-
ret = g_my_robot->ur_driver_->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
258+
ret = g_my_robot->ur_driver->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
259259
if (!ret)
260260
{
261261
std::stringstream lastq;
@@ -264,6 +264,6 @@ int main(int argc, char* argv[])
264264
lastq.str().c_str());
265265
return 1;
266266
}
267-
g_my_robot->ur_driver_->stopControl();
267+
g_my_robot->ur_driver->stopControl();
268268
return 0;
269269
}

examples/tool_contact_example.cpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -85,8 +85,8 @@ int main(int argc, char* argv[])
8585
URCL_LOG_ERROR("Something in the robot initialization went wrong. Exiting. Please check the output above.");
8686
return 1;
8787
}
88-
g_my_robot->ur_driver_->registerToolContactResultCallback(&handleToolContactResult);
89-
g_my_robot->ur_driver_->startToolContact();
88+
g_my_robot->ur_driver->registerToolContactResultCallback(&handleToolContactResult);
89+
g_my_robot->ur_driver->startToolContact();
9090

9191
// This will move the robot downward in the z direction of the base until a tool contact is detected or seconds_to_run
9292
// is reached
@@ -96,8 +96,8 @@ int main(int argc, char* argv[])
9696
{
9797
// Setting the RobotReceiveTimeout time is for example purposes only. This will make the example running more
9898
// reliable on non-realtime systems. Use with caution in productive applications.
99-
bool ret = g_my_robot->ur_driver_->writeJointCommand(tcp_speed, comm::ControlMode::MODE_SPEEDL,
100-
RobotReceiveTimeout::millisec(100));
99+
bool ret = g_my_robot->ur_driver->writeJointCommand(tcp_speed, comm::ControlMode::MODE_SPEEDL,
100+
RobotReceiveTimeout::millisec(100));
101101
if (!ret)
102102
{
103103
URCL_LOG_ERROR("Could not send joint command. Is the robot in remote control?");
@@ -111,6 +111,6 @@ int main(int argc, char* argv[])
111111
}
112112
}
113113
URCL_LOG_INFO("Timed out before reaching tool contact.");
114-
g_my_robot->ur_driver_->stopControl();
114+
g_my_robot->ur_driver->stopControl();
115115
return 0;
116116
}

0 commit comments

Comments
 (0)