From 71a49085ad2784b06a936e440a3e11a9e11269ae Mon Sep 17 00:00:00 2001 From: Ray Bjorkman Date: Tue, 10 Sep 2024 16:51:57 -0400 Subject: [PATCH 1/2] introduce Makefile and format source code (#4) --- .clang-format | 8 ++ .github/workflows/docker.yml | 1 + Dockerfile | 4 +- Makefile | 75 ++++++++++++++++ compile.sh | 5 -- src/ur5e_arm.cpp | 131 +++++++++++++++------------ src/ur5e_arm.hpp | 168 +++++++++++++++++------------------ 7 files changed, 242 insertions(+), 150 deletions(-) create mode 100644 .clang-format create mode 100644 Makefile delete mode 100755 compile.sh diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000..8d49673 --- /dev/null +++ b/.clang-format @@ -0,0 +1,8 @@ +AllowShortFunctionsOnASingleLine: Empty +AllowShortIfStatementsOnASingleLine: false +AllowShortLoopsOnASingleLine: false +BasedOnStyle: Google +BinPackArguments: false +BinPackParameters: false +ColumnLimit: 140 +IndentWidth: 4 diff --git a/.github/workflows/docker.yml b/.github/workflows/docker.yml index 6af0db8..28665d7 100644 --- a/.github/workflows/docker.yml +++ b/.github/workflows/docker.yml @@ -13,6 +13,7 @@ jobs: docker: name: Build Docker Image permissions: + contents: read packages: write timeout-minutes: 45 runs-on: ${{ matrix.os }} diff --git a/Dockerfile b/Dockerfile index 5cc0fbb..ebcf12b 100644 --- a/Dockerfile +++ b/Dockerfile @@ -39,7 +39,6 @@ RUN bash -c 'wget -O - https://apt.llvm.org/llvm-snapshot.gpg.key|apt-key add -' RUN apt-add-repository -y 'deb http://apt.llvm.org/bookworm/ llvm-toolchain-bookworm-15 main' RUN apt-add-repository -y 'deb http://apt.llvm.org/bookworm/ llvm-toolchain-bookworm-15 main' RUN apt-get update - RUN apt-get -y --no-install-recommends install -t llvm-toolchain-bookworm-15 \ clang-15 \ clang-tidy-15 @@ -86,4 +85,5 @@ RUN apt install -y golang-go RUN apt install -y libgtest-dev # Install Eigen -RUN apt install -y libeigen3-dev \ No newline at end of file +RUN apt install -y libeigen3-dev + diff --git a/Makefile b/Makefile new file mode 100644 index 0000000..33935dd --- /dev/null +++ b/Makefile @@ -0,0 +1,75 @@ +# format the source code +format: src/*.*pp + ls src/*.*pp | xargs clang-format -i --style=file + +SANITIZE ?= OFF +universal-robots: format src/* + rm -rf build/ && \ + mkdir build && \ + cd build && \ + cmake -G Ninja -DENABLE_SANITIZER=$(SANITIZE) .. && \ + ninja all -j 4 + +default: universal-robots + +all: default + +clean: + rm -rf universal-robots + +clean-all: clean + git clean -fxd + +# Docker +BUILD_CMD = docker buildx build --pull $(BUILD_PUSH) --force-rm --build-arg MAIN_TAG=$(MAIN_TAG) \ + --build-arg BASE_TAG=$(BUILD_TAG) --platform linux/$(BUILD_TAG) -f $(BUILD_FILE) -t '$(MAIN_TAG):$(BUILD_TAG)' . +BUILD_PUSH = --load +BUILD_FILE = Dockerfile + +docker: docker-build docker-upload + +docker-build: docker-amd64 + +docker-amd64: MAIN_TAG = ghcr.io/viam-modules/universal-robots +docker-amd64: BUILD_TAG = amd64 +docker-amd64: + $(BUILD_CMD) + +docker-upload: + docker push 'ghcr.io/viam-modules/universal-robots:amd64' + +# CI targets that automatically push, avoid for local test-first-then-push workflows +docker-arm64-ci: MAIN_TAG = ghcr.io/viam-modules/universal-robots +docker-arm64-ci: BUILD_TAG = arm64 +docker-arm64-ci: BUILD_PUSH = --push +docker-arm64-ci: + $(BUILD_CMD) + +docker-amd64-ci: MAIN_TAG = ghcr.io/viam-modules/universal-robots +docker-amd64-ci: BUILD_TAG = amd64 +docker-amd64-ci: BUILD_PUSH = --push +docker-amd64-ci: + $(BUILD_CMD) + +# Define a function for building AppImages +TAG_VERSION?=latest +define BUILD_APPIMAGE + export TAG_NAME=$(TAG_VERSION); \ + cd packaging/appimages && \ + mkdir -p deploy && \ + rm -f deploy/$(1)* && \ + appimage-builder --recipe $(1)-$(2).yml +endef + +# Targets for building AppImages +appimage-arm64: export OUTPUT_NAME = universal-robots +appimage-arm64: export ARCH = aarch64 +appimage-arm64: universal-robots + $(call BUILD_APPIMAGE,$(OUTPUT_NAME),$(ARCH)) + cp ./packaging/appimages/$(OUTPUT_NAME)-*-$(ARCH).AppImage ./packaging/appimages/deploy/ + +appimage-amd64: export OUTPUT_NAME = universal-robots +appimage-amd64: export ARCH = x86_64 +appimage-amd64: universal-robots + $(call BUILD_APPIMAGE,$(OUTPUT_NAME),$(ARCH)) + cp ./packaging/appimages/$(OUTPUT_NAME)-*-$(ARCH).AppImage ./packaging/appimages/deploy/ diff --git a/compile.sh b/compile.sh deleted file mode 100755 index 4fad1f3..0000000 --- a/compile.sh +++ /dev/null @@ -1,5 +0,0 @@ -rm -rf build -mkdir build && cd build -cmake .. -make -cd .. diff --git a/src/ur5e_arm.cpp b/src/ur5e_arm.cpp index 3ddcdc9..c91582c 100644 --- a/src/ur5e_arm.cpp +++ b/src/ur5e_arm.cpp @@ -27,34 +27,51 @@ void reportTrajectoryState(control::TrajectoryResult state) { std::cout << "\033[1;32mtrajectory report: " << report << "\033[0m\n" << std::endl; } -UR5eArm::UR5eArm(Dependencies dep, ResourceConfig cfg) : Arm(cfg.name()) { +UR5eArm::UR5eArm(Dependencies dep, const ResourceConfig& cfg) : Arm(cfg.name()) { // connect to the robot dashboard dashboard.reset(new DashboardClient(DEFAULT_ROBOT_IP)); - if (!dashboard->connect()) throw std::runtime_error("couldn't connect to dashboard"); - + if (!dashboard->connect()) { + throw std::runtime_error("couldn't connect to dashboard"); + } + // stop program, if there is one running - if (!dashboard->commandStop()) throw std::runtime_error("couldn't stop program running on dashboard"); + if (!dashboard->commandStop()) { + throw std::runtime_error("couldn't stop program running on dashboard"); + } // if the robot is not powered on and ready std::string robotModeRunning("RUNNING"); while (!dashboard->commandRobotMode(robotModeRunning)) { // power cycle the arm - if (!dashboard->commandPowerOff()) throw std::runtime_error("couldn't power off arm"); - if (!dashboard->commandPowerOn()) throw std::runtime_error("couldn't power on arm"); + if (!dashboard->commandPowerOff()) { + throw std::runtime_error("couldn't power off arm"); + } + if (!dashboard->commandPowerOn()) { + throw std::runtime_error("couldn't power on arm"); + } } // Release the brakes - if (!dashboard->commandBrakeRelease()) throw std::runtime_error("couldn't release the arm brakes"); + if (!dashboard->commandBrakeRelease()) { + throw std::runtime_error("couldn't release the arm brakes"); + } // Now the robot is ready to receive a program std::unique_ptr tool_comm_setup; const bool HEADLESS = true; - driver.reset(new UrDriver(DEFAULT_ROBOT_IP, SCRIPT_FILE, OUTPUT_RECIPE, INPUT_RECIPE, &reportRobotProgramState, HEADLESS, - std::move(tool_comm_setup), CALIBRATION_CHECKSUM)); + driver.reset(new UrDriver(DEFAULT_ROBOT_IP, + SCRIPT_FILE, + OUTPUT_RECIPE, + INPUT_RECIPE, + &reportRobotProgramState, + HEADLESS, + std::move(tool_comm_setup), + CALIBRATION_CHECKSUM)); driver->registerTrajectoryDoneCallback(&reportTrajectoryState); - - // 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 + + // 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 driver->startRTDECommunication(); read_and_noop(); @@ -68,8 +85,8 @@ std::vector UR5eArm::get_joint_positions(const AttributeMap& extra) { std::unique_ptr data_pkg = driver->getDataPackage(); if (data_pkg && data_pkg->getData("actual_q", joint_state)) { std::vector to_ret; - for(double joint_pos_rad: joint_state){ - double joint_pos_deg = 180.0/M_PI * joint_pos_rad; + for (double joint_pos_rad : joint_state) { + double joint_pos_deg = 180.0 / M_PI * joint_pos_rad; to_ret.push_back(joint_pos_deg); } mu.unlock(); @@ -82,7 +99,7 @@ std::vector UR5eArm::get_joint_positions(const AttributeMap& extra) { void UR5eArm::move_to_joint_positions(const std::vector& positions, const AttributeMap& extra) { std::vector waypoints; Eigen::VectorXd next_waypoint_deg = Eigen::VectorXd::Map(positions.data(), positions.size()); - Eigen::VectorXd next_waypoint_rad = next_waypoint_deg * (M_PI/180.0); // convert from radians to degrees + Eigen::VectorXd next_waypoint_rad = next_waypoint_deg * (M_PI / 180.0); // convert from radians to degrees waypoints.push_back(next_waypoint_rad); move(waypoints); } @@ -115,32 +132,35 @@ UR5eArm::KinematicsData UR5eArm::get_kinematics(const AttributeMap& extra) { } void UR5eArm::stop(const AttributeMap& extra) { - trajectory_running = false; - driver->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_CANCEL, 0, RobotReceiveTimeout::off()); + if (trajectory_running) { + trajectory_running = false; + driver->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_CANCEL, 0, RobotReceiveTimeout::off()); + } } AttributeMap UR5eArm::do_command(const AttributeMap& command) { - if(!command){ + if (!command) { throw std::runtime_error("command is null\n"); } - - // move through a number of waypoints (specified as a 2D array of floats (degrees)) that were sent in a batch - if(command->count(WAYPOINTS_KEY) > 0){ + + // move through a number of waypoints (specified as a 2D array of floats (degrees)) that were + // sent in a batch + if (command->count(WAYPOINTS_KEY) > 0) { std::vector waypoints; std::vector>* vec_protos = (*command)[WAYPOINTS_KEY]->get>>(); - if (vec_protos){ - for(std::shared_ptr& vec_proto: *vec_protos) { + if (vec_protos) { + for (std::shared_ptr& vec_proto : *vec_protos) { std::vector>* vec_joint_pos = vec_proto->get>>(); - if (vec_joint_pos){ + if (vec_joint_pos) { vector6d_t to_add; int counter = 0; - for(std::shared_ptr joint_pos: *vec_joint_pos){ + for (std::shared_ptr joint_pos : *vec_joint_pos) { double* joint_pos_deg = joint_pos->get(); to_add[counter] = *joint_pos_deg; counter += 1; } Eigen::VectorXd waypoint_deg = Eigen::VectorXd::Map(to_add.data(), to_add.size()); - Eigen::VectorXd waypoint_rad = waypoint_deg * (M_PI/180.0); // convert from radians to degrees + Eigen::VectorXd waypoint_rad = waypoint_deg * (M_PI / 180.0); // convert from radians to degrees waypoints.push_back(waypoint_rad); } } @@ -153,7 +173,7 @@ AttributeMap UR5eArm::do_command(const AttributeMap& command) { // Send no-ops and keep socket connection alive void UR5eArm::keep_alive() { - while(true) { + while (true) { mu.lock(); read_and_noop(); mu.unlock(); @@ -165,27 +185,27 @@ void UR5eArm::move(std::vector waypoints) { // get current joint position and add that as starting pose to waypoints std::vector curr_joint_pos = get_joint_positions(NULL); Eigen::VectorXd curr_waypoint_deg = Eigen::VectorXd::Map(curr_joint_pos.data(), curr_joint_pos.size()); - Eigen::VectorXd curr_waypoint_rad = curr_waypoint_deg * (M_PI/180.0); + Eigen::VectorXd curr_waypoint_rad = curr_waypoint_deg * (M_PI / 180.0); waypoints.insert(waypoints.begin(), curr_waypoint_rad); // calculate dot products and identify any consecutive segments with dot product == -1 std::vector segments; segments.push_back(0); - for(int i = 2; i < waypoints.size(); i++){ - Eigen::VectorXd segment_AB = (waypoints[i-1] - waypoints[i-2]); - Eigen::VectorXd segment_BC = (waypoints[i] - waypoints[i-1]); + for (int i = 2; i < waypoints.size(); i++) { + Eigen::VectorXd segment_AB = (waypoints[i - 1] - waypoints[i - 2]); + Eigen::VectorXd segment_BC = (waypoints[i] - waypoints[i - 1]); segment_AB.normalize(); segment_BC.normalize(); double dot = segment_BC.dot(segment_AB); - if(dot == -1){ - segments.push_back(i-1); - } + if (dot == -1) { + segments.push_back(i - 1); + } } - segments.push_back(waypoints.size()-1); + segments.push_back(waypoints.size() - 1); // set velocity/acceleration constraints Eigen::VectorXd maxAcceleration(6); - Eigen::VectorXd maxVelocity(6); + Eigen::VectorXd maxVelocity(6); maxAcceleration << 1.0, 1.0, 1.0, 1.0, 1.0, 1.0; maxVelocity << 3.0, 3.0, 3.0, 3.0, 3.0, 3.0; @@ -194,15 +214,15 @@ void UR5eArm::move(std::vector waypoints) { std::vector a; std::vector time; - for(int i = 0; i < segments.size()-1; i++){ + for (int i = 0; i < segments.size() - 1; i++) { int start = segments[i]; - int end = segments[i+1]+1; + int end = segments[i + 1] + 1; std::list positions_subset(waypoints.begin() + start, waypoints.begin() + end); Trajectory trajectory(Path(positions_subset, 0.1), maxVelocity, maxAcceleration); trajectory.outputPhasePlaneTrajectory(); - if(trajectory.isValid()) { + if (trajectory.isValid()) { double duration = trajectory.getDuration(); - for(double t = 0.0; t < duration; t += TIMESTEP) { + for (double t = 0.0; t < duration; t += TIMESTEP) { Eigen::VectorXd position = trajectory.getPosition(t); Eigen::VectorXd velocity = trajectory.getVelocity(t); p.push_back(vector6d_t{position[0], position[1], position[2], position[3], position[4], position[5]}); @@ -213,7 +233,7 @@ void UR5eArm::move(std::vector waypoints) { throw std::runtime_error("trajectory generation failed\n"); } } - + mu.lock(); send_trajectory(p, v, a, time, true); trajectory_running = true; @@ -224,27 +244,26 @@ void UR5eArm::move(std::vector waypoints) { } // helper function to send time-indexed position, velocity, acceleration setpoints to the UR driver -void UR5eArm::send_trajectory( - const std::vector& p_p, - const std::vector& p_v, - const std::vector& p_a, - const std::vector& time, - bool use_spline_interpolation_ -){ +void UR5eArm::send_trajectory(const std::vector& p_p, + const std::vector& p_v, + const std::vector& p_a, + const std::vector& time, + bool use_spline_interpolation_) { assert(p_p.size() == time.size()); - driver->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, p_p.size(), RobotReceiveTimeout::off()); + driver->writeTrajectoryControlMessage( + urcl::control::TrajectoryControlMessage::TRAJECTORY_START, p_p.size(), RobotReceiveTimeout::off()); for (size_t i = 0; i < p_p.size() && p_p.size() == time.size() && p_p[i].size() == 6; i++) { if (!use_spline_interpolation_) { // movej driver->writeTrajectoryPoint(p_p[i], false, time[i], 0.0); - } else { // use spline interpolation - if (p_v.size() == time.size() && p_a.size() == time.size() && p_v[i].size() == 6 && p_a[i].size() == 6){ + } else { // use spline interpolation + if (p_v.size() == time.size() && p_a.size() == time.size() && p_v[i].size() == 6 && p_a[i].size() == 6) { // quintic driver->writeTrajectorySplinePoint(p_p[i], p_v[i], p_a[i], time[i]); - } else if (p_v.size() == time.size() && p_v[i].size() == 6){ + } else if (p_v.size() == time.size() && p_v[i].size() == 6) { // cubic driver->writeTrajectorySplinePoint(p_p[i], p_v[i], time[i]); - } else{ + } else { // linear driver->writeTrajectorySplinePoint(p_p[i], time[i]); } @@ -258,8 +277,10 @@ void UR5eArm::read_and_noop() { std::unique_ptr data_pkg = driver->getDataPackage(); if (data_pkg) { // read current joint positions from robot data - if (!data_pkg->getData("actual_q", joint_state)) throw std::runtime_error("couldn't get joint positions"); - + if (!data_pkg->getData("actual_q", joint_state)) { + throw std::runtime_error("couldn't get joint positions"); + } + // send a noop to keep the connection alive driver->writeTrajectoryControlMessage(control::TrajectoryControlMessage::TRAJECTORY_NOOP, 0, RobotReceiveTimeout::off()); } diff --git a/src/ur5e_arm.hpp b/src/ur5e_arm.hpp index 2ba9e8f..f7f905e 100644 --- a/src/ur5e_arm.hpp +++ b/src/ur5e_arm.hpp @@ -1,101 +1,93 @@ #pragma once -#include -#include -#include +#include +#include +#include +#include +#include +#include -#include #include -#include -#include #include +#include #include #include #include #include -#include -#include -#include -#include - -#include -#include - -using namespace viam::sdk; +using namespace viam::sdk; using namespace urcl; -class UR5eArm : public Arm{ - public: - UR5eArm(Dependencies dep, ResourceConfig cfg); - - /// @brief Get the joint positions of the arm (in degrees) - /// @param extra Any additional arguments to the method. - /// @return a vector of joint positions of the arm in degrees - std::vector get_joint_positions(const AttributeMap& extra) override; - - /// @brief Move to the the specified joint positions (in degrees) - /// @param positions The joint positions in degrees to move to - /// @param extra Any additional arguments to the method. - void move_to_joint_positions(const std::vector& positions, const AttributeMap& extra) override; - - /// @brief Reports if the arm is in motion. - bool is_moving() override; - - /// @brief Get the kinematics data associated with the arm. - /// @param extra Any additional arguments to the method. - /// @return A variant of kinematics data, with bytes field containing the raw bytes of the file - /// and the object's type indicating the file format. - KinematicsData get_kinematics(const AttributeMap& extra) override; - - /// @brief Stops the Arm. - /// @param extra Extra arguments to pass to the resource's `stop` method. - void stop(const AttributeMap& extra) override; - - /// @brief This is being used as a proxy to move_to_joint_positions except with support for multiple waypoints - /// @param command Will contain a std::vector> called positions that will contain joint waypoints - AttributeMap do_command(const AttributeMap& command) override; - - // --------------- UNIMPLEMENTED FUNCTIONS --------------- - pose get_end_position(const AttributeMap& extra) override{ - throw std::runtime_error("get_end_position unimplemented"); - } - - void move_to_position(const pose& pose, const AttributeMap& extra) override{ - throw std::runtime_error("move_to_position unimplemented"); - } - - std::vector get_geometries(const AttributeMap& extra){ - throw std::runtime_error("get_geometries unimplemented"); - } - - private: - void keep_alive(); - void move(std::vector waypoints); - void send_trajectory( - const std::vector& p_p, - const std::vector& p_v, - const std::vector& p_a, - const std::vector& time, - bool use_spline_interpolation_ - ); - void read_and_noop(); - - std::unique_ptr driver; - std::unique_ptr dashboard; - vector6d_t joint_state; - std::mutex mu; - - const double STOP_VELOCITY_THRESHOLD = 0.005; // rad/s - const int NOOP_DELAY = 100000; // microseconds - const double TIMESTEP = 0.2; // seconds - - const std::string DEFAULT_ROBOT_IP = "10.1.10.84"; - const std::string URDF_FILE = "/host/src/ur5e.urdf"; - const std::string SCRIPT_FILE = "/host/Universal_Robots_Client_Library/resources/external_control.urscript"; - const std::string OUTPUT_RECIPE = "/host/Universal_Robots_Client_Library/examples/resources/rtde_output_recipe.txt"; - const std::string INPUT_RECIPE = "/host/Universal_Robots_Client_Library/examples/resources/rtde_input_recipe.txt"; - const std::string CALIBRATION_CHECKSUM = "calib_12788084448423163542"; - const std::string WAYPOINTS_KEY = "waypoints"; +const double STOP_VELOCITY_THRESHOLD = 0.005; // rad/s +const int NOOP_DELAY = 100000; // microseconds +const double TIMESTEP = 0.2; // seconds + +const std::string DEFAULT_ROBOT_IP = "10.1.10.84"; +const std::string URDF_FILE = "/host/src/ur5e.urdf"; +const std::string SCRIPT_FILE = "/host/Universal_Robots_Client_Library/resources/external_control.urscript"; +const std::string OUTPUT_RECIPE = "/host/Universal_Robots_Client_Library/examples/resources/rtde_output_recipe.txt"; +const std::string INPUT_RECIPE = "/host/Universal_Robots_Client_Library/examples/resources/rtde_input_recipe.txt"; +const std::string CALIBRATION_CHECKSUM = "calib_12788084448423163542"; +const std::string WAYPOINTS_KEY = "waypoints"; + +class UR5eArm : public Arm { + public: + UR5eArm(Dependencies dep, const ResourceConfig& cfg); + + /// @brief Get the joint positions of the arm (in degrees) + /// @param extra Any additional arguments to the method. + /// @return a vector of joint positions of the arm in degrees + std::vector get_joint_positions(const AttributeMap& extra) override; + + /// @brief Move to the the specified joint positions (in degrees) + /// @param positions The joint positions in degrees to move to + /// @param extra Any additional arguments to the method. + void move_to_joint_positions(const std::vector& positions, const AttributeMap& extra) override; + + /// @brief Reports if the arm is in motion. + bool is_moving() override; + + /// @brief Get the kinematics data associated with the arm. + /// @param extra Any additional arguments to the method. + /// @return A variant of kinematics data, with bytes field containing the raw bytes of the file + /// and the object's type indicating the file format. + KinematicsData get_kinematics(const AttributeMap& extra) override; + + /// @brief Stops the Arm. + /// @param extra Extra arguments to pass to the resource's `stop` method. + void stop(const AttributeMap& extra) override; + + /// @brief This is being used as a proxy to move_to_joint_positions except with support for + /// multiple waypoints + /// @param command Will contain a std::vector> called positions that will + /// contain joint waypoints + AttributeMap do_command(const AttributeMap& command) override; + + // --------------- UNIMPLEMENTED FUNCTIONS --------------- + pose get_end_position(const AttributeMap& extra) override { + throw std::runtime_error("get_end_position unimplemented"); + } + + void move_to_position(const pose& pose, const AttributeMap& extra) override { + throw std::runtime_error("move_to_position unimplemented"); + } + + std::vector get_geometries(const AttributeMap& extra) { + throw std::runtime_error("get_geometries unimplemented"); + } + + private: + void keep_alive(); + void move(std::vector waypoints); + void send_trajectory(const std::vector& p_p, + const std::vector& p_v, + const std::vector& p_a, + const std::vector& time, + bool use_spline_interpolation_); + void read_and_noop(); + + std::unique_ptr driver; + std::unique_ptr dashboard; + vector6d_t joint_state; + std::mutex mu; }; - From f60c6533c6a90be0a93368a99680872bc33f549b Mon Sep 17 00:00:00 2001 From: Ray Bjorkman Date: Wed, 11 Sep 2024 12:52:48 -0400 Subject: [PATCH 2/2] add clang-format to dockerfile --- Dockerfile | 1 + Makefile | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/Dockerfile b/Dockerfile index ebcf12b..c928f46 100644 --- a/Dockerfile +++ b/Dockerfile @@ -41,6 +41,7 @@ RUN apt-add-repository -y 'deb http://apt.llvm.org/bookworm/ llvm-toolchain-book RUN apt-get update RUN apt-get -y --no-install-recommends install -t llvm-toolchain-bookworm-15 \ clang-15 \ + clang-format-15 \ clang-tidy-15 RUN mkdir -p /root/opt/src diff --git a/Makefile b/Makefile index 33935dd..5a16932 100644 --- a/Makefile +++ b/Makefile @@ -1,6 +1,6 @@ # format the source code format: src/*.*pp - ls src/*.*pp | xargs clang-format -i --style=file + ls src/*.*pp | xargs clang-format-15 -i --style=file SANITIZE ?= OFF universal-robots: format src/*