Skip to content

Commit

Permalink
Rebase from 'upstream'
Browse files Browse the repository at this point in the history
  • Loading branch information
urfeex committed Dec 16, 2024
1 parent b4fb90b commit 1597666
Show file tree
Hide file tree
Showing 29 changed files with 1,233 additions and 190 deletions.
46 changes: 43 additions & 3 deletions .github/helpers/check_urls.sh
Original file line number Diff line number Diff line change
Expand Up @@ -2,14 +2,54 @@

set -e

IGNORE_FILES=""
IGNORE_PATTERNS=""

while getopts ":f:d:p:" opt; do
case "${opt}" in
f)
IGNORE_FILES="${OPTARG}";;
d)
IGNORE_DIRS="${OPTARG}";;
p)
IGNORE_PATTERNS="${OPTARG}";;
\?)
echo "Invalid option -$OPTARG"
exit;;
esac
done

read -r -a ignore_files <<<"$IGNORE_FILES"
read -r -a ignore_dirs <<<"$IGNORE_DIRS"
read -r -a ignore_patterns <<<"$IGNORE_PATTERNS"

IGNORE_FILES_ARG=""
for item in "${ignore_files[@]}"; do
IGNORE_FILES_ARG="$IGNORE_FILES_ARG --exclude=$item"
done
IGNORE_DIRS_ARG=""
for item in "${ignore_dirs[@]}"; do
IGNORE_DIRS_ARG="$IGNORE_DIRS_ARG --exclude-dir=$item"
done

#Find URLs in code:
urls=$(grep -oP "(http|ftp|https):\/\/([a-zA-Z0-9_-]+(?:(?:\.[a-zA-Z0-9_-]+)+))([a-zA-Z0-9_.,@?^=%&:\/~+#-]*[a-zA-Z0-9_@?^=%&\/~+#-])?" "$@")
urls=$(grep -oP '(http|ftp|https):\/\/([a-zA-Z0-9_-]+(?:(?:\.[a-zA-Z0-9_-]+)+))([a-zA-Z0-9_.,@?^=%&:\/~+#-]*[a-zA-Z0-9_@?^=%&\/~+#-])?' -rI $IGNORE_FILES_ARG $IGNORE_DIRS_ARG)

fail_counter=0

FAILED_LINKS=()
for item in $urls; do
# echo $item
# echo $item
skip=0
for pattern in "${ignore_patterns[@]}"; do
[[ "$item" =~ $pattern ]] && skip=1
done

if [[ $skip == 1 ]]; then
echo "SKIPPING $item"
continue
fi

filename=$(echo "$item" | cut -d':' -f1)
url=$(echo "$item" | cut -d':' -f2-)
echo -n "Checking $url from file $filename"
Expand All @@ -24,4 +64,4 @@ done

echo "Failed files:"
printf '%s\n' "${FAILED_LINKS[@]}"
exit $fail_counter
exit $fail_counter
21 changes: 11 additions & 10 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ jobs:
runs-on: ubuntu-latest
name: build (${{matrix.env.URSIM_VERSION}}-${{matrix.env.ROBOT_MODEL}})
strategy:
fail-fast: false
matrix:
env:
- DOCKER_RUN_OPTS: --network ursim_net
Expand All @@ -21,6 +22,12 @@ jobs:
ROBOT_MODEL: 'ur5e'
URSIM_VERSION: '5.9.4'
PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/e-series'
- DOCKER_RUN_OPTS: --network ursim_net
BEFORE_INIT: 'apt-get update -qq && apt-get install -y iproute2 iputils-ping && ip addr && ping -c5 192.168.56.101'
CTEST_OUTPUT_ON_FAILURE: 1
ROBOT_MODEL: 'ur20'
URSIM_VERSION: 'latest'
PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/e-series'

steps:
- uses: actions/checkout@v1
Expand Down Expand Up @@ -92,16 +99,10 @@ jobs:
- uses: actions/checkout@v2
- name: Check URLs
run: |
.github/helpers/check_urls.sh -rI \
--exclude-dir=.git \
--exclude-dir=build/ \
--exclude-dir=tests \
--exclude=package.xml \
--exclude-dir=CMakeModules \
--exclude=tcp_socket.cpp \
--exclude-dir=debian \
--exclude=dataflow.graphml \
--exclude=start_ursim.sh
.github/helpers/check_urls.sh \
-d ".git build CMakeModules debian" \
-f "package.xml architecture_coarse.svg dataflow.graphml start_ursim.sh" \
-p "vnc\.html opensource\.org\/licenses\/BSD-3-Clause kernel\.org\/pub\/linux\/kernel"
rosdoc_lite_check:
runs-on: ubuntu-latest
Expand Down
12 changes: 12 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,18 @@
Changelog for package ur_client_library
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.5.0 (2024-11-25)
------------------
* Adapt RTDE output recipe based on robot response (`#221 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/221>`_)
* CI: Fix flaky example runs (`#223 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/223>`_)
* Giving force mode parameters as arguments when calling startForceMode (`#208 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/208>`_)
* Add more arguments to start_ursim.sh (`#220 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/220>`_)
* Tcp socket improvements (`#222 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/222>`_)
* Added family photo to readme (`#219 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/219>`_)
* Add missing algorithm include (`#214 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/214>`_)
* Added missing RTDE data packages and fixed incorrect names (`#213 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/213>`_)
* Contributors: Felix Exner, Remi Siffert, URJala

1.4.0 (2024-09-10)
------------------
* Ensure that the targets are reachable within the robots limits (`#184 <https://github.com/UniversalRobots/Universal_Robots_Client_Library/issues/184>`_)
Expand Down
5 changes: 5 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,11 @@ A C++ library for accessing Universal Robots interfaces. With this library C++-b
implemented in order to create external applications leveraging the versatility of Universal Robots
robotic manipulators.

<!-- markdownlint-disable MD033 -->
<div align="center">
<img src="doc/resources/family_photo.png" alt="Universal Robot family" style="width: 90%;"/>
</div>

## Requirements

* **Polyscope** (The software running on the robot controller) version **3.14.3** (for CB3-Series),
Expand Down
5 changes: 5 additions & 0 deletions doc/architecture.rst
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,11 @@ sure to
* run it from the package's main folder, as for simplicity reasons it doesn't use any sophisticated
method to locate the required files.

.. note::
The ``URDriver`` class creates a ``RTDEClient`` during initialization using the provided
recipes and utilizing the robot model's maximum frequency. If you would like to use a different
frequency, please use the ``resetRTDEClient()`` method after the ``UrDriver`` object has been
created.

RTDEWriter
^^^^^^^^^^
Expand Down
2 changes: 1 addition & 1 deletion doc/conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@
# -- Project information -----------------------------------------------------

project = "ur_client_library"
copyright = "2022, Felix Exner"
copyright = "2022, Universal Robots A/S"
author = "Felix Exner"

# The short X.Y version
Expand Down
Binary file added doc/resources/family_photo.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
3 changes: 3 additions & 0 deletions examples/dashboard_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include <iostream>
#include <memory>
#include <thread>
#include <unistd.h>

using namespace urcl;

Expand Down Expand Up @@ -96,6 +97,8 @@ int main(int argc, char* argv[])
return 1;
}

sleep(1);

// Play loaded program
if (!my_dashboard->commandPlay())
{
Expand Down
68 changes: 60 additions & 8 deletions examples/force_mode_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,11 +55,21 @@ const std::string CALIBRATION_CHECKSUM = "calib_12788084448423163542";
std::unique_ptr<UrDriver> g_my_driver;
std::unique_ptr<DashboardClient> g_my_dashboard;

std::condition_variable g_program_running_cv_;
std::mutex g_program_running_mutex_;
bool g_program_running;

// We need a callback function to register. See UrDriver's parameters for details.
void handleRobotProgramState(bool program_running)
{
// Print the text in green so we see it better
std::cout << "\033[1;32mProgram running: " << std::boolalpha << program_running << "\033[0m\n" << std::endl;
if (program_running)
{
std::lock_guard<std::mutex> lk(g_program_running_mutex_);
g_program_running = program_running;
g_program_running_cv_.notify_one();
}
}

void sendFreedriveMessageOrDie(const control::FreedriveControlMessage freedrive_action)
Expand All @@ -72,6 +82,17 @@ void sendFreedriveMessageOrDie(const control::FreedriveControlMessage freedrive_
}
}

bool waitForProgramRunning(int milliseconds = 100)
{
std::unique_lock<std::mutex> lk(g_program_running_mutex_);
if (g_program_running_cv_.wait_for(lk, std::chrono::milliseconds(milliseconds)) == std::cv_status::no_timeout ||
g_program_running == true)
{
return true;
}
return false;
}

int main(int argc, char* argv[])
{
urcl::setLogLevel(urcl::LogLevel::INFO);
Expand Down Expand Up @@ -130,7 +151,16 @@ int main(int argc, char* argv[])
std::unique_ptr<ToolCommSetup> tool_comm_setup;
const bool HEADLESS = true;
g_my_driver.reset(new UrDriver(robot_ip, SCRIPT_FILE, OUTPUT_RECIPE, INPUT_RECIPE, &handleRobotProgramState, HEADLESS,
std::move(tool_comm_setup), CALIBRATION_CHECKSUM));
std::move(tool_comm_setup)));

if (!g_my_driver->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 "
"the description. See "
"[https://github.com/UniversalRobots/Universal_Robots_ROS_Driver#extract-calibration-information] "
"for details.");
}

// 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
Expand All @@ -141,15 +171,37 @@ int main(int argc, char* argv[])
std::chrono::duration<double> timeout(second_to_run);
auto stopwatch_last = std::chrono::steady_clock::now();
auto stopwatch_now = stopwatch_last;
g_my_driver->writeKeepalive();
// Make sure that external control script is running
if (!waitForProgramRunning())
{
URCL_LOG_ERROR("External Control script not running.");
return 1;
}
// 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
g_my_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, 0, 0, 0, 0 }, // do not apply any active wrench
2, // do not transform the force frame at all
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }); // limits. See ScriptManual for
// details.
bool success;
if (g_my_driver->getVersion().major < 5)
success = g_my_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, 0, 0, 0, 0 }, // do not apply any active wrench
2, // do not transform the force frame at all
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
0.025); // damping_factor. See ScriptManual for details.
else
{
success = g_my_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, 0, 0, 0, 0 }, // do not apply any active wrench
2, // do not transform the force frame at all
{ 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits
0.025, // damping_factor
0.8); // gain_scaling. See ScriptManual for details.
}
if (!success)
{
URCL_LOG_ERROR("Failed to start force mode.");
return 1;
}

while (true)
{
Expand Down
4 changes: 4 additions & 0 deletions include/ur_client_library/comm/pipeline.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ template <typename T>
class IConsumer
{
public:
virtual ~IConsumer() = default;

/*!
* \brief Set-up functionality of the consumer.
*/
Expand Down Expand Up @@ -170,6 +172,8 @@ template <typename T>
class IProducer
{
public:
virtual ~IProducer() = default;

/*!
* \brief Set-up functionality of the producers.
*
Expand Down
15 changes: 12 additions & 3 deletions include/ur_client_library/control/script_command_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -105,14 +105,23 @@ class ScriptCommandInterface : public ReverseInterface
* 2: The force frame is not transformed.
* 3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp velocity vector
* onto the x-y plane of the force frame
* \param limits (Float) 6d vector. For compliant axes, these values are the maximum allowed tcp speed along/about the
* \param limits 6d vector. For compliant axes, these values are the maximum allowed tcp speed along/about the
* axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis between the actual
* tcp position and the one set by the program
*
* \param damping_factor Sets the damping parameter in force mode. In range [0,1], default value is 0.025
* A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0
* is no damping, here the robot will maintain the speed.
*
* \param gain_scaling_factor Scales the gain in force mode. scaling parameter is in range [0,2], default
* is 0.5. A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard
* surfaces.
*
* \returns True, if the write was performed successfully, false otherwise.
*/
bool startForceMode(const vector6d_t* task_frame, const vector6uint32_t* selection_vector, const vector6d_t* wrench,
const unsigned int type, const vector6d_t* limits);
const unsigned int type, const vector6d_t* limits, double damping_factor,
double gain_scaling_factor);

/*!
* \brief Stop force mode and put the robot into normal operation mode.
Expand Down Expand Up @@ -178,7 +187,7 @@ class ScriptCommandInterface : public ReverseInterface
};

bool client_connected_;
static const int MAX_MESSAGE_LENGTH = 26;
static const int MAX_MESSAGE_LENGTH = 28;

std::function<void(ToolContactResult)> handle_tool_contact_result_;
};
Expand Down
Loading

0 comments on commit 1597666

Please sign in to comment.