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
21 changes: 8 additions & 13 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
Expand Up @@ -15,22 +15,13 @@ jobs:
fail-fast: false
matrix:
env:
- 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: 'ur5'
- ROBOT_MODEL: 'ur5'
URSIM_VERSION: '3.14.3'
PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/cb3'
- 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: 'ur5e'
- 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'
- ROBOT_MODEL: 'ur20'
URSIM_VERSION: 'latest'
PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/e-series'

Expand All @@ -39,7 +30,11 @@ jobs:
- name: start ursim
run: |
scripts/start_ursim.sh -m $ROBOT_MODEL -v $URSIM_VERSION -p $PROGRAM_FOLDER -d
env: ${{matrix.env}}
env:
DOCKER_RUN_OPTS: --network ursim_net
ROBOT_MODEL: ${{matrix.env.ROBOT_MODEL}}
URSIM_VERSION: ${{matrix.env.URSIM_VERSION}}
PROGRAM_FOLDER: ${{matrix.env.PROGRAM_FOLDER}}
- name: configure
run: mkdir build && cd build && cmake .. -DBUILDING_TESTS=1 -DINTEGRATION_TESTS=1 -DWITH_ASAN=ON
env:
Expand Down
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ add_library(urcl SHARED
src/ur/version_information.cpp
src/rtde/rtde_writer.cpp
src/default_log_handler.cpp
src/example_robot_wrapper.cpp
src/log.cpp
src/helpers.cpp
)
Expand Down
91 changes: 15 additions & 76 deletions examples/freedrive_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include <ur_client_library/ur/dashboard_client.h>
#include <ur_client_library/ur/ur_driver.h>
#include <ur_client_library/types.h>
#include <ur_client_library/example_robot_wrapper.h>

#include <chrono>
#include <cstdlib>
Expand All @@ -47,27 +48,17 @@
using namespace urcl;

const std::string DEFAULT_ROBOT_IP = "192.168.56.101";
const std::string SCRIPT_FILE = "resources/external_control.urscript";
const std::string OUTPUT_RECIPE = "examples/resources/rtde_output_recipe.txt";
const std::string INPUT_RECIPE = "examples/resources/rtde_input_recipe.txt";
const std::string CALIBRATION_CHECKSUM = "calib_12788084448423163542";

std::unique_ptr<UrDriver> g_my_driver;
std::unique_ptr<DashboardClient> g_my_dashboard;

// 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;
}
std::unique_ptr<ExampleRobotWrapper> g_my_robot;

void sendFreedriveMessageOrDie(const control::FreedriveControlMessage freedrive_action)
{
bool ret = g_my_driver->writeFreedriveControlMessage(freedrive_action);
bool ret = g_my_robot->ur_driver_->writeFreedriveControlMessage(freedrive_action);
if (!ret)
{
URCL_LOG_ERROR("Could not send joint command. Is the robot in remote control?");
URCL_LOG_ERROR("Could not send freedrive command. Is the robot in remote control?");
exit(1);
}
}
Expand All @@ -89,86 +80,34 @@ int main(int argc, char* argv[])
second_to_run = std::chrono::seconds(std::stoi(argv[2]));
}

// Making the robot ready for the program by:
// Connect the robot Dashboard
g_my_dashboard.reset(new DashboardClient(robot_ip));
if (!g_my_dashboard->connect())
{
URCL_LOG_ERROR("Could not connect to dashboard");
return 1;
}
bool headless_mode = true;

// // Stop program, if there is one running
if (!g_my_dashboard->commandStop())
{
URCL_LOG_ERROR("Could not send stop program command");
return 1;
}
g_my_robot = std::make_unique<ExampleRobotWrapper>(robot_ip, OUTPUT_RECIPE, INPUT_RECIPE, headless_mode,
"external_control.urp");

// Power it off
if (!g_my_dashboard->commandPowerOff())
if (!g_my_robot->waitForProgramRunning())
{
URCL_LOG_ERROR("Could not send Power off command");
URCL_LOG_ERROR("External Control script not running.");
return 1;
}

// Power it on
if (!g_my_dashboard->commandPowerOn())
{
URCL_LOG_ERROR("Could not send Power on command");
return 1;
}

// Release the brakes
if (!g_my_dashboard->commandBrakeRelease())
{
URCL_LOG_ERROR("Could not send BrakeRelease command");
return 1;
}

// Now the robot is ready to receive a program
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));

// 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_driver->startRTDECommunication();
URCL_LOG_INFO("Starting freedrive mode");
sendFreedriveMessageOrDie(control::FreedriveControlMessage::FREEDRIVE_START);

std::chrono::duration<double> time_done(0);
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();
sendFreedriveMessageOrDie(control::FreedriveControlMessage::FREEDRIVE_START);

while (true)
while (time_done < timeout || second_to_run.count() == 0)
{
// 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_driver->getDataPackage();
if (data_pkg)
{
sendFreedriveMessageOrDie(control::FreedriveControlMessage::FREEDRIVE_NOOP);

if (time_done > timeout && second_to_run.count() != 0)
{
URCL_LOG_INFO("Timeout reached.");
break;
}
}
else
{
URCL_LOG_WARN("Could not get fresh data package from robot");
}
sendFreedriveMessageOrDie(control::FreedriveControlMessage::FREEDRIVE_NOOP);

stopwatch_now = std::chrono::steady_clock::now();
time_done += stopwatch_now - stopwatch_last;
stopwatch_last = stopwatch_now;
}

URCL_LOG_INFO("Stopping freedrive mode");
sendFreedriveMessageOrDie(control::FreedriveControlMessage::FREEDRIVE_STOP);
}
184 changes: 184 additions & 0 deletions include/ur_client_library/example_robot_wrapper.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,184 @@
// -- BEGIN LICENSE BLOCK ----------------------------------------------
// Copyright 2025 Universal Robots A/S
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the {copyright_holder} nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
// -- END LICENSE BLOCK ------------------------------------------------

#ifndef UR_CLIENT_LIBRARY_EXAMPLE_ROBOT_WRAPPER_H_INCLUDED
#define UR_CLIENT_LIBRARY_EXAMPLE_ROBOT_WRAPPER_H_INCLUDED

#include <ur_client_library/ur/dashboard_client.h>
#include <ur_client_library/ur/ur_driver.h>
#include <ur_client_library/log.h>

namespace urcl
{
/*!
* \class ExampleRobotWrapper
* \brief This class is a high-level abstraction around UrDriver and DashboardClient. It's main
* purpose is to help us avoiding repetitive robot initialization code in our examples and tests.
*
* It is therefore not intended to be used in production code, but rather as a helper class for
* developers. If you want to use this wrapper in your own code, please make sure to understand the
* logic behind it and adjust it to your needs.
*
* Since this is mainly intended for internal use, don't count on the API being stable for this
* class!
*/
class ExampleRobotWrapper
{
public:
inline static const std::string DEFAULT_ROBOT_IP = "192.168.56.101";
inline static const std::string SCRIPT_FILE = "resources/external_control.urscript";

ExampleRobotWrapper() = delete;
/*!
* \brief Construct a new Example Robot Wrapper object
*
* This will connect to a robot and initialize it. In headless mode the program will be running
* instantly, in teach pendant mode the from \p autostart_program will be started.
*
* Note: RTDE communication has to be started separately.
*
* \param robot_ip IP address of the robot to connect to
* \param output_recipe_file Output recipe file for RTDE communication
* \param input_recipe_file Input recipe file for RTDE communication
* \param headless_mode Should the driver be started in headless mode or not?
* \param autostart_program Program to start automatically after initialization when not in
* headless mode. This flag is ignored in headless mode.
* \param script_file URScript file to send to the robot. That should be script code
* communicating to the driver's reverse interface and trajectory interface.
*/
ExampleRobotWrapper(const std::string& robot_ip, const std::string& output_recipe_file,
const std::string& input_recipe_file, const bool headless_mode = true,
const std::string& autostart_program = "", const std::string& script_file = SCRIPT_FILE);
~ExampleRobotWrapper();

/**
* @brief Initializes the robot in order to be able to start a program.
*
* The robot will be power-cycled once and end up switched on, breaks released.
*/
void initializeRobotWithDashboard();

/**
* @brief Starts RTDE communication with the robot.
*
* @param consume_data Once the RTDE client is started, it's data has to be consumed. If you
* don't actually care about that data, this class can silently consume RTDE data when `true` is
* passed. This can be stopped and started at any time using the startConsumingRTDEData() and
* stopConsumingRTDEData() methods.
*/
void startRTDECommununication(const bool consume_data = false);

/**
* @brief Start consuming RTDE data in the background.
*/
void startConsumingRTDEData();

/**
* @brief Stop consuming RTDE data in the background. Note that data has to be consumed manually
* using readDataPackage().
*/
void stopConsumingRTDEData();

/**
* @brief Get the latest RTDE package.
*
* Do not call this, while RTDE data is being consumed in the background. In doubt, call
* stopConsumingRTDEData() before calling this function.
*
* @param[out] data_pkg The data package will be stored in that object
* @return true on a successful read, false if no package can be read or when RTDE data is
* already being consumed in the background.
*/
bool readDataPackage(std::unique_ptr<rtde_interface::DataPackage>& data_pkg);

/**
* @brief Blocks until there is a robot program connected to the driver's reverse interface or
* until the timeout is hit.
*
* @param milliseconds How long to wait for a successful connection.
* @return True on a successful connection, false if not connection could be detected before the
* timeout.
*/
bool waitForProgramRunning(int milliseconds = 100);

/**
* @brief Blocks until there is a disconnection event from the driver's reverse interface
* detected or until the timeout is hit.
*
* @param milliseconds How long to wait for a disconnection.
* @return True on a disconnection event has been detected, false if no event could be detected before the
* timeout.
*/
bool waitForProgramNotRunning(int milliseconds = 100);

/**
* @brief Depending on whether it is headless or not start autostart_program or call driver's resendRobotProgram
* function.
*
* @return True on successful program start, false otherwise.
*/
bool resendRobotProgram();

/**
* @brief Start the program \p program_file_name on the robot.
*
* The program has be be present on the robot, otherwise this call does not succeed. The robot
* needs to be in remote_control mode for this to work properly.
*
* @param program_file_name Filename on the robot including the ".urp" extension.
* @return True on successful program start, false otherwise.
*/
bool startRobotProgram(const std::string& program_file_name);

std::shared_ptr<urcl::DashboardClient> dashboard_client_; /*!< Dashboard client to interact with the robot */
std::shared_ptr<urcl::UrDriver> ur_driver_; /*!< UR driver to interact with the robot */

private:
void handleRobotProgramState(bool program_running);

std::atomic<bool> rtde_communication_started_ = false;
std::atomic<bool> consume_rtde_packages_ = false;
std::mutex read_package_mutex_;
std::unique_ptr<rtde_interface::DataPackage> data_pkg_;

bool program_running_;
std::condition_variable program_running_cv_;
std::condition_variable program_not_running_cv_;
std::mutex program_running_mutex_;
std::mutex program_not_running_mutex_;

std::thread rtde_consumer_thread_;

bool headless_mode_;
std::string autostart_program_;
};
} // namespace urcl

#endif
2 changes: 1 addition & 1 deletion scripts/start_ursim.sh
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ help()
If not specified, will fallback to ${PERSISTENT_BASE}/${ROBOT_SERIES}/urcaps"
echo " -n Name of the docker container. Defaults to '$CONTAINER_NAME'"
echo " -i IP address the container should get. Defaults to $IP_ADDRESS"
echo " -d Detached mode - start in backgound"
echo " -d Detached mode - start in background"
echo " -f Specify port forwarding to use. Defaults to '$PORT_FORWARDING'. Set to empty string to disable port forwarding."
echo " -h Print this Help."
echo
Expand Down
Loading
Loading