Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions .clang-tidy
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ CheckOptions:
- { key: readability-identifier-naming.NamespaceCase, value: lower_case }
- { key: readability-identifier-naming.ClassCase, value: CamelCase }
- { key: readability-identifier-naming.PrivateMemberSuffix, value: _ }
- { key: readability-identifier-naming.PublicMemberSuffix, value: "" }
- { key: readability-identifier-naming.StructCase, value: CamelCase }
- { key: readability-identifier-naming.FunctionCase, value: camelBack }
- { key: readability-identifier-naming.VariableCase, value: lower_case }
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/industrial-ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -35,5 +35,5 @@ jobs:
DOWNSTREAM_WORKSPACE: ${{matrix.ROS_DISTRO.DOWNSTREAM_WORKSPACE}}
ROS_DISTRO: ${{matrix.ROS_DISTRO.NAME}}
ROS_REPO: ${{matrix.ROS_REPO}}
CLANG_TIDY: true
CLANG_TIDY: pedantic
CLANG_TIDY_ARGS: '--extra-arg=-std=c++17' # needed for Humble
4 changes: 2 additions & 2 deletions doc/examples/instruction_executor.rst
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ The `instruction_executor.cpp <https://github.com/UniversalRobots/Universal_Robo
:linenos:
:lineno-match:
:start-at: bool headless_mode = true;
:end-at: auto instruction_executor = std::make_shared<urcl::InstructionExecutor>(g_my_robot->ur_driver_);
:end-at: auto instruction_executor = std::make_shared<urcl::InstructionExecutor>(g_my_robot->getUrDriver());

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

Again, time parametrization has priority over acceleration / velocity parameters.
6 changes: 3 additions & 3 deletions doc/examples/tool_contact_example.rst
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ At first, we create a initialize a driver as usual:
:linenos:
:lineno-match:
:start-at: bool headless_mode = true;
:end-before: g_my_robot->ur_driver_->registerToolContactResultCallback
:end-before: g_my_robot->getUrDriver()->registerToolContactResultCallback

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

Once everything is initialized, we can start a control loop commanding the robot to move in the
negative z direction until the program timeout is hit or a tool contact is detected:
Expand Down
8 changes: 4 additions & 4 deletions doc/examples/trajectory_point_interface.rst
Original file line number Diff line number Diff line change
Expand Up @@ -45,8 +45,8 @@ That callback can be registered at the ``UrDriver`` object:
:caption: examples/trajectory_point_interface.cpp
:linenos:
:lineno-match:
:start-at: g_my_robot->ur_driver_->registerTrajectoryDoneCallback(&trajDoneCallback);
:end-at: g_my_robot->ur_driver_->registerTrajectoryDoneCallback(&trajDoneCallback);
:start-at: g_my_robot->getUrDriver()->registerTrajectoryDoneCallback(&trajDoneCallback);
:end-at: g_my_robot->getUrDriver()->registerTrajectoryDoneCallback(&trajDoneCallback);


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

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

MoveL Trajectory
Expand Down
1 change: 1 addition & 0 deletions doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -15,3 +15,4 @@ can be found on `GitHub <https://github.com/UniversalRobots/Universal_Robots_Cli
architecture
examples
real_time
migration_notes
26 changes: 26 additions & 0 deletions doc/migration_notes.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
Migration notes
===============

This document contains notes on the migration of the ur_client_library between major versions.

It contains only breaking changes.

Migrating from 1.x.x to 2.x.x
-----------------------------

- In the ``urcl::ExampleRobotWrapper`` class the ``ur_driver_``, ``dashboard_client`` and
``primary_client`` members are now private. Use ``getUrDriver()``, ``getDashboardClient()`` and
``getPrimaryClient()`` to access them.

- In ``urcl::comm::ControlModeTypes`` two member functions have been renamed:

- ``is_control_mode_realtime`` -> ``isControlModeRealtime``
- ``is_control_mode_non_realtime`` -> ``isControlModeNonRealtime``

- In ``urcl::RobotReceiveTimeout`` the ``timeout_`` member is now private. Use
``getAsMilliseconds()`` to access it.

- In ``urcl::UrDriverConfiguration`` two members have been renamed:

- ``rtde_initialization_attempts_`` -> ``rtde_initialization_attempts``
- ``rtde_initialization_timeout_`` -> ``rtde_initialization_timeout``
40 changes: 20 additions & 20 deletions examples/force_mode_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ std::unique_ptr<ExampleRobotWrapper> g_my_robot;

void sendFreedriveMessageOrDie(const control::FreedriveControlMessage freedrive_action)
{
bool ret = g_my_robot->ur_driver_->writeFreedriveControlMessage(freedrive_action);
bool ret = g_my_robot->getUrDriver()->writeFreedriveControlMessage(freedrive_action);
if (!ret)
{
URCL_LOG_ERROR("Could not send joint command. Is the robot in remote control?");
Expand Down Expand Up @@ -91,7 +91,7 @@ int main(int argc, char* argv[])
URCL_LOG_ERROR("Something in the robot initialization went wrong. Exiting. Please check the output above.");
return 1;
}
if (!g_my_robot->ur_driver_->checkCalibration(CALIBRATION_CHECKSUM))
if (!g_my_robot->getUrDriver()->checkCalibration(CALIBRATION_CHECKSUM))
{
URCL_LOG_ERROR("Calibration checksum does not match actual robot.");
URCL_LOG_ERROR("Use the ur_calibration tool to extract the correct calibration from the robot and pass that into "
Expand All @@ -107,24 +107,24 @@ int main(int argc, char* argv[])
// Task frame at the robot's base with limits being large enough to cover the whole workspace
// Compliance in z axis and rotation around z axis
bool success;
if (g_my_robot->ur_driver_->getVersion().major < 5)
success =
g_my_robot->ur_driver_->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base
{ 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis
{ 0, 0, -2, 0, 0, 0 }, // Press in -z direction
2, // do not transform the force frame at all
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
0.005); // damping_factor. See ScriptManual for details.
if (g_my_robot->getUrDriver()->getVersion().major < 5)
success = g_my_robot->getUrDriver()->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base
{ 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation
// around z axis
{ 0, 0, -2, 0, 0, 0 }, // Press in -z direction
2, // do not transform the force frame at all
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
0.005); // damping_factor. See ScriptManual for details.
else
{
success =
g_my_robot->ur_driver_->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base
{ 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis
{ 0, 0, -2, 0, 0, 0 }, // Press in -z direction
2, // do not transform the force frame at all
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
0.005, // damping_factor
1.0); // gain_scaling. See ScriptManual for details.
success = g_my_robot->getUrDriver()->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base
{ 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation
// around z axis
{ 0, 0, -2, 0, 0, 0 }, // Press in -z direction
2, // do not transform the force frame at all
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
0.005, // damping_factor
1.0); // gain_scaling. See ScriptManual for details.
}
if (!success)
{
Expand All @@ -138,13 +138,13 @@ int main(int argc, char* argv[])
auto stopwatch_now = stopwatch_last;
while (time_done < timeout || second_to_run.count() == 0)
{
g_my_robot->ur_driver_->writeKeepalive();
g_my_robot->getUrDriver()->writeKeepalive();

stopwatch_now = std::chrono::steady_clock::now();
time_done += stopwatch_now - stopwatch_last;
stopwatch_last = stopwatch_now;
std::this_thread::sleep_for(std::chrono::milliseconds(2));
}
URCL_LOG_INFO("Timeout reached.");
g_my_robot->ur_driver_->endForceMode();
g_my_robot->getUrDriver()->endForceMode();
}
2 changes: 1 addition & 1 deletion examples/freedrive_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ std::unique_ptr<ExampleRobotWrapper> g_my_robot;

void sendFreedriveMessageOrDie(const control::FreedriveControlMessage freedrive_action)
{
bool ret = g_my_robot->ur_driver_->writeFreedriveControlMessage(freedrive_action);
bool ret = g_my_robot->getUrDriver()->writeFreedriveControlMessage(freedrive_action);
if (!ret)
{
URCL_LOG_ERROR("Could not send joint command. Is there an external_control program running on the robot?");
Expand Down
12 changes: 6 additions & 6 deletions examples/full_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ int main(int argc, char* argv[])

// Increment depends on robot version
double increment_constant = 0.0005;
if (g_my_robot->ur_driver_->getVersion().major < 5)
if (g_my_robot->getUrDriver()->getVersion().major < 5)
{
increment_constant = 0.002;
}
Expand All @@ -86,14 +86,14 @@ int main(int argc, char* argv[])
// Once RTDE communication is started, we have to make sure to read from the interface buffer, as
// otherwise we will get pipeline overflows. Therefor, do this directly before starting your main
// loop.
g_my_robot->ur_driver_->startRTDECommunication();
g_my_robot->getUrDriver()->startRTDECommunication();
while (!(passed_positive_part && passed_negative_part))
{
// Read latest RTDE package. This will block for a hard-coded timeout (see UrDriver), so the
// robot will effectively be in charge of setting the frequency of this loop.
// In a real-world application this thread should be scheduled with real-time priority in order
// to ensure that this is called in time.
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver_->getDataPackage();
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->getUrDriver()->getDataPackage();
if (!data_pkg)
{
URCL_LOG_WARN("Could not get fresh data package from robot");
Expand Down Expand Up @@ -133,16 +133,16 @@ int main(int argc, char* argv[])
joint_target[5] += increment;
// Setting the RobotReceiveTimeout time is for example purposes only. This will make the example running more
// reliable on non-realtime systems. Use with caution in productive applications.
bool ret = g_my_robot->ur_driver_->writeJointCommand(joint_target, comm::ControlMode::MODE_SERVOJ,
RobotReceiveTimeout::millisec(100));
bool ret = g_my_robot->getUrDriver()->writeJointCommand(joint_target, comm::ControlMode::MODE_SERVOJ,
RobotReceiveTimeout::millisec(100));
if (!ret)
{
URCL_LOG_ERROR("Could not send joint command. Is the robot in remote control?");
return 1;
}
URCL_LOG_DEBUG("data_pkg:\n%s", data_pkg->toString().c_str());
}
g_my_robot->ur_driver_->stopControl();
g_my_robot->getUrDriver()->stopControl();
URCL_LOG_INFO("Movement done");
return 0;
}
6 changes: 3 additions & 3 deletions examples/instruction_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ int main(int argc, char* argv[])
bool headless_mode = true;
g_my_robot = std::make_unique<urcl::ExampleRobotWrapper>(robot_ip, OUTPUT_RECIPE, INPUT_RECIPE, headless_mode,
"external_control.urp");
if (!g_my_robot->ur_driver_->checkCalibration(CALIBRATION_CHECKSUM))
if (!g_my_robot->getUrDriver()->checkCalibration(CALIBRATION_CHECKSUM))
{
URCL_LOG_ERROR("Calibration checksum does not match actual robot.");
URCL_LOG_ERROR("Use the ur_calibration tool to extract the correct calibration from the robot and pass that into "
Expand All @@ -75,7 +75,7 @@ int main(int argc, char* argv[])
return 1;
}

auto instruction_executor = std::make_shared<urcl::InstructionExecutor>(g_my_robot->ur_driver_);
auto instruction_executor = std::make_shared<urcl::InstructionExecutor>(g_my_robot->getUrDriver());
// --------------- INITIALIZATION END -------------------

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

g_my_robot->ur_driver_->stopControl();
g_my_robot->getUrDriver()->stopControl();
return 0;
}
34 changes: 18 additions & 16 deletions examples/spline_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,31 +57,31 @@ void sendTrajectory(const std::vector<vector6d_t>& p_p, const std::vector<vector
assert(p_p.size() == time.size());

URCL_LOG_INFO("Starting joint-based trajectory forward");
g_my_robot->ur_driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START,
p_p.size());
g_my_robot->getUrDriver()->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START,
p_p.size());

for (size_t i = 0; i < p_p.size() && p_p.size() == time.size() && p_p[i].size() == 6; i++)
{
// MoveJ
if (!use_spline_interpolation_)
{
g_my_robot->ur_driver_->writeTrajectoryPoint(p_p[i], false, time[i]);
g_my_robot->getUrDriver()->writeTrajectoryPoint(p_p[i], false, time[i]);
}
else // Use spline interpolation
{
// QUINTIC
if (p_v.size() == time.size() && p_a.size() == time.size() && p_v[i].size() == 6 && p_a[i].size() == 6)
{
g_my_robot->ur_driver_->writeTrajectorySplinePoint(p_p[i], p_v[i], p_a[i], time[i]);
g_my_robot->getUrDriver()->writeTrajectorySplinePoint(p_p[i], p_v[i], p_a[i], time[i]);
}
// CUBIC
else if (p_v.size() == time.size() && p_v[i].size() == 6)
{
g_my_robot->ur_driver_->writeTrajectorySplinePoint(p_p[i], p_v[i], time[i]);
g_my_robot->getUrDriver()->writeTrajectorySplinePoint(p_p[i], p_v[i], time[i]);
}
else
{
g_my_robot->ur_driver_->writeTrajectorySplinePoint(p_p[i], time[i]);
g_my_robot->getUrDriver()->writeTrajectorySplinePoint(p_p[i], time[i]);
}
}
}
Expand Down Expand Up @@ -131,15 +131,15 @@ int main(int argc, char* argv[])
return 1;
}

g_my_robot->ur_driver_->registerTrajectoryDoneCallback(&handleTrajectoryState);
g_my_robot->getUrDriver()->registerTrajectoryDoneCallback(&handleTrajectoryState);

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

g_my_robot->ur_driver_->startRTDECommunication();
g_my_robot->getUrDriver()->startRTDECommunication();

std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver_->getDataPackage();
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->getUrDriver()->getDataPackage();

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

bool ret = false;
ret = g_my_robot->ur_driver_->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
ret = g_my_robot->getUrDriver()->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
if (!ret)
{
std::stringstream lastq;
Expand Down Expand Up @@ -199,7 +199,7 @@ int main(int argc, char* argv[])
g_trajectory_running = true;
while (g_trajectory_running)
{
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver_->getDataPackage();
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->getUrDriver()->getDataPackage();
if (data_pkg)
{
// Read current joint positions from robot data
Expand All @@ -209,7 +209,8 @@ int main(int argc, char* argv[])
std::string error_msg = "Did not find 'actual_q' in data sent from robot. This should not happen!";
throw std::runtime_error(error_msg);
}
ret = g_my_robot->ur_driver_->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
ret =
g_my_robot->getUrDriver()->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);

if (!ret)
{
Expand All @@ -230,7 +231,7 @@ int main(int argc, char* argv[])
g_trajectory_running = true;
while (g_trajectory_running)
{
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->ur_driver_->getDataPackage();
std::unique_ptr<rtde_interface::DataPackage> data_pkg = g_my_robot->getUrDriver()->getDataPackage();
if (data_pkg)
{
// Read current joint positions from robot data
Expand All @@ -240,7 +241,8 @@ int main(int argc, char* argv[])
std::string error_msg = "Did not find 'actual_q' in data sent from robot. This should not happen!";
throw std::runtime_error(error_msg);
}
ret = g_my_robot->ur_driver_->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
ret =
g_my_robot->getUrDriver()->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);

if (!ret)
{
Expand All @@ -255,7 +257,7 @@ int main(int argc, char* argv[])

URCL_LOG_INFO("QUINTIC Movement done");

ret = g_my_robot->ur_driver_->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
ret = g_my_robot->getUrDriver()->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP);
if (!ret)
{
std::stringstream lastq;
Expand All @@ -264,6 +266,6 @@ int main(int argc, char* argv[])
lastq.str().c_str());
return 1;
}
g_my_robot->ur_driver_->stopControl();
g_my_robot->getUrDriver()->stopControl();
return 0;
}
Loading
Loading