Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update ci #239

Merged
merged 7 commits into from
Dec 18, 2024
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
7 changes: 6 additions & 1 deletion .github/workflows/ci.yml
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
name: Integration tests
on: [push, pull_request]
on:
workflow_dispatch:
pull_request:
push:
branches:
- main

jobs:
build:
Expand Down
10 changes: 8 additions & 2 deletions .github/workflows/industrial-ci.yml
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
name: ROS industrial ci
on: [push, pull_request]
on:
workflow_dispatch:
pull_request:
push:
branches:
- master

jobs:
industrial_ci:
Expand All @@ -11,7 +16,6 @@ jobs:
ROS_DISTRO:
- {NAME: noetic, DOWNSTREAM_WORKSPACE: "github:UniversalRobots/Universal_Robots_ROS_Driver#master https://raw.githubusercontent.com/UniversalRobots/Universal_Robots_ROS_Driver/master/.noetic.rosinstall"}
- {NAME: humble, DOWNSTREAM_WORKSPACE: "github:UniversalRobots/Universal_Robots_ROS2_Driver#humble"}
- {NAME: iron, DOWNSTREAM_WORKSPACE: "github:UniversalRobots/Universal_Robots_ROS2_Driver#iron"}
- {NAME: jazzy, DOWNSTREAM_WORKSPACE: "github:UniversalRobots/Universal_Robots_ROS2_Driver#main"}
- {NAME: rolling, DOWNSTREAM_WORKSPACE: "github:UniversalRobots/Universal_Robots_ROS2_Driver#main"}
ROS_REPO:
Expand All @@ -22,6 +26,7 @@ jobs:
steps:
- uses: actions/checkout@v4
- run: docker network create --subnet=192.168.56.0/24 ursim_net
if: ${{ !env.ACT }}
- uses: 'ros-industrial/industrial_ci@master'
env:
IMMEDIATE_TEST_OUTPUT: true
Expand All @@ -30,3 +35,4 @@ jobs:
DOWNSTREAM_WORKSPACE: ${{matrix.ROS_DISTRO.DOWNSTREAM_WORKSPACE}}
ROS_DISTRO: ${{matrix.ROS_DISTRO.NAME}}
ROS_REPO: ${{matrix.ROS_REPO}}
CLANG_TIDY: true
4 changes: 1 addition & 3 deletions .github/workflows/pre-commit.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ on:
pull_request:
push:
branches:
- main
- master

jobs:
pre-commit:
Expand All @@ -19,8 +19,6 @@ jobs:
- uses: actions/setup-python@v5
with:
python-version: 3.10.4
- name: Install system hooks
run: sudo apt-get install clang-format-14 cppcheck
- uses: pre-commit/action@v3.0.1
with:
extra_args: --all-files --hook-stage manual
Expand Down
2 changes: 1 addition & 1 deletion .pre-commit-config.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
repos:
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: 'v14.0.6'
rev: 'v19.1.5'
hooks:
- id: clang-format
- repo: https://github.com/DavidAnson/markdownlint-cli2
Expand Down
16 changes: 8 additions & 8 deletions examples/force_mode_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,8 +55,8 @@ 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_;
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.
Expand All @@ -66,9 +66,9 @@ void handleRobotProgramState(bool program_running)
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_);
std::lock_guard<std::mutex> lk(g_program_running_mutex);
g_program_running = program_running;
g_program_running_cv_.notify_one();
g_program_running_cv.notify_one();
}
}

Expand All @@ -84,8 +84,8 @@ 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 ||
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;
Expand Down Expand Up @@ -149,8 +149,8 @@ int main(int argc, char* argv[])

// 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,
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)));

if (!g_my_driver->checkCalibration(CALIBRATION_CHECKSUM))
Expand Down
4 changes: 2 additions & 2 deletions examples/freedrive_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -128,8 +128,8 @@ int main(int argc, char* argv[])

// 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,
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
Expand Down
4 changes: 2 additions & 2 deletions examples/full_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,8 +107,8 @@ int main(int argc, char* argv[])
// 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,
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
Expand Down
12 changes: 6 additions & 6 deletions examples/primary_pipeline_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ using namespace urcl;
class CalibrationConsumer : public urcl::comm::IConsumer<urcl::primary_interface::PrimaryPackage>
{
public:
CalibrationConsumer() : calibrated_(0), have_received_data(false)
CalibrationConsumer() : calibrated_(0), have_received_data_(false)
{
}
virtual ~CalibrationConsumer() = default;
Expand All @@ -38,25 +38,25 @@ class CalibrationConsumer : public urcl::comm::IConsumer<urcl::primary_interface
{
URCL_LOG_INFO("%s", product->toString().c_str());
calibrated_ = kin_info->calibration_status_;
have_received_data = true;
have_received_data_ = true;
}
return true;
}

bool isCalibrated() const
{
const uint32_t LINEARIZED = 2;
return calibrated_ == LINEARIZED;
const uint32_t linearized = 2;
return calibrated_ == linearized;
}

bool calibrationStatusReceived()
{
return have_received_data;
return have_received_data_;
}

private:
uint32_t calibrated_;
bool have_received_data;
bool have_received_data_;
};

// In a real-world example it would be better to get those values from command line parameters / a better configuration
Expand Down
8 changes: 3 additions & 5 deletions examples/rtde_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,8 @@ int main(int argc, char* argv[])
// loop.
my_client.start();

unsigned long startTime = clock();
while (second_to_run < 0 || ((clock() - startTime) / CLOCKS_PER_SEC) < static_cast<unsigned int>(second_to_run))
unsigned long start_time = clock();
while (second_to_run < 0 || ((clock() - start_time) / CLOCKS_PER_SEC) < static_cast<unsigned int>(second_to_run))
{
// Read latest RTDE package. This will block for READ_TIMEOUT, so the
// robot will effectively be in charge of setting the frequency of this loop unless RTDE
Expand All @@ -93,9 +93,7 @@ int main(int argc, char* argv[])
{
// This will happen for example, when the required keys are not configured inside the input
// recipe.
std::cout << "\033[1;31mSending RTDE data failed."
<< "\033[0m\n"
<< std::endl;
std::cout << "\033[1;31mSending RTDE data failed." << "\033[0m\n" << std::endl;
return 1;
}

Expand Down
14 changes: 7 additions & 7 deletions examples/spline_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ std::unique_ptr<UrDriver> g_my_driver;
std::unique_ptr<DashboardClient> g_my_dashboard;
vector6d_t g_joint_positions;

void SendTrajectory(const std::vector<vector6d_t>& p_p, const std::vector<vector6d_t>& p_v,
void sendTrajectory(const std::vector<vector6d_t>& p_p, const std::vector<vector6d_t>& p_v,
const std::vector<vector6d_t>& p_a, const std::vector<double>& time, bool use_spline_interpolation_)
{
assert(p_p.size() == time.size());
Expand Down Expand Up @@ -146,8 +146,8 @@ int main(int argc, char* argv[])
}

// if the robot is not powered on and ready
std::string robotModeRunning("RUNNING");
while (!g_my_dashboard->commandRobotMode(robotModeRunning))
std::string robot_mode_running("RUNNING");
while (!g_my_dashboard->commandRobotMode(robot_mode_running))
{
// Power it off
if (!g_my_dashboard->commandPowerOff())
Expand All @@ -174,8 +174,8 @@ int main(int argc, char* argv[])
// 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,
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));

g_my_driver->registerTrajectoryDoneCallback(&handleTrajectoryState);
Expand Down Expand Up @@ -241,7 +241,7 @@ int main(int argc, char* argv[])
}

// CUBIC
SendTrajectory(p, v, std::vector<vector6d_t>(), time, true);
sendTrajectory(p, v, std::vector<vector6d_t>(), time, true);

g_trajectory_running = true;
while (g_trajectory_running)
Expand Down Expand Up @@ -272,7 +272,7 @@ int main(int argc, char* argv[])
URCL_LOG_INFO("CUBIC Movement done");

// QUINTIC
SendTrajectory(p, v, a, time, true);
sendTrajectory(p, v, a, time, true);

g_trajectory_running = true;
while (g_trajectory_running)
Expand Down
4 changes: 2 additions & 2 deletions examples/tool_contact_example.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -124,8 +124,8 @@ int main(int argc, char* argv[])

// 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,
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));

g_my_driver->registerToolContactResultCallback(&handleToolContactResult);
Expand Down
4 changes: 1 addition & 3 deletions src/ur/ur_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,9 +136,7 @@
}
begin_replace << "set_tool_voltage("
<< static_cast<std::underlying_type<ToolVoltage>::type>(tool_comm_setup->getToolVoltage()) << ")\n";
begin_replace << "set_tool_communication("
<< "True"
<< ", " << tool_comm_setup->getBaudRate() << ", "
begin_replace << "set_tool_communication(" << "True" << ", " << tool_comm_setup->getBaudRate() << ", "

Check warning on line 139 in src/ur/ur_driver.cpp

View check run for this annotation

Codecov / codecov/patch

src/ur/ur_driver.cpp#L139

Added line #L139 was not covered by tests
<< static_cast<std::underlying_type<Parity>::type>(tool_comm_setup->getParity()) << ", "
<< tool_comm_setup->getStopBits() << ", " << tool_comm_setup->getRxIdleChars() << ", "
<< tool_comm_setup->getTxIdleChars() << ")";
Expand Down
6 changes: 3 additions & 3 deletions tests/test_dashboard_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,14 @@

using namespace urcl;

std::string ROBOT_IP = "192.168.56.101";
std::string g_ROBOT_IP = "192.168.56.101";

class DashboardClientTest : public ::testing::Test
{
protected:
void SetUp()
{
dashboard_client_.reset(new DashboardClient(ROBOT_IP));
dashboard_client_.reset(new DashboardClient(g_ROBOT_IP));
}

void TearDown()
Expand Down Expand Up @@ -227,7 +227,7 @@ int main(int argc, char* argv[])
{
if (std::string(argv[i]) == "--robot_ip" && i + 1 < argc)
{
ROBOT_IP = argv[i + 1];
g_ROBOT_IP = argv[i + 1];
break;
}
}
Expand Down
2 changes: 1 addition & 1 deletion tests/test_pipeline.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ class PipelineTest : public ::testing::Test
pipeline_->init();
}

void Teardown()
void teardown()
{
// Clean up
pipeline_->stop();
Expand Down
2 changes: 1 addition & 1 deletion tests/test_producer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class ProducerTest : public ::testing::Test
server_->start();
}

void Teardown()
void teardown()
{
// Clean up
server_.reset();
Expand Down
Loading
Loading