From 5cdce126a56fc8d22affed8f1f41e53c35e1a71b Mon Sep 17 00:00:00 2001 From: urrsk <41109954+urrsk@users.noreply.github.com> Date: Mon, 2 Mar 2026 16:25:14 +0100 Subject: [PATCH 1/3] Fix windows compile warnings From now all warning is treat as errors --- CMakeLists.txt | 16 ++- examples/CMakeLists.txt | 5 + examples/external_fts_through_rtde.cpp | 2 +- examples/spline_example.cpp | 10 +- examples/trajectory_point_interface.cpp | 25 +++-- include/ur_client_library/comm/pipeline.h | 9 +- include/ur_client_library/log.h | 17 +++ .../primary/primary_consumer.h | 4 +- .../primary/primary_parser.h | 12 +-- .../ur/dashboard_client_implementation.h | 2 +- .../ur/dashboard_client_implementation_x.h | 2 +- include/ur_client_library/ur/ur_driver.h | 2 +- src/comm/tcp_server.cpp | 4 +- src/control/reverse_interface.cpp | 12 ++- src/control/script_command_interface.cpp | 5 +- src/control/trajectory_point_interface.cpp | 10 +- src/helpers.cpp | 5 +- src/primary/primary_client.cpp | 4 +- src/rtde/control_package_setup_inputs.cpp | 2 +- src/rtde/control_package_setup_outputs.cpp | 4 +- src/rtde/rtde_client.cpp | 9 +- src/rtde/rtde_writer.cpp | 3 +- src/ur/dashboard_client.cpp | 3 +- src/ur/dashboard_client_implementation_g5.cpp | 11 +- src/ur/dashboard_client_implementation_x.cpp | 60 ++++++----- src/ur/instruction_executor.cpp | 4 +- src/ur/robot_receive_timeout.cpp | 10 +- src/ur/ur_driver.cpp | 30 ++++-- tests/CMakeLists.txt | 6 ++ tests/fake_rtde_server.cpp | 100 +++++++++--------- tests/test_bin_parser.cpp | 2 +- tests/test_control_mode.cpp | 6 +- tests/test_dashboard_client.cpp | 20 ++-- tests/test_pipeline.cpp | 8 +- tests/test_producer.cpp | 2 +- tests/test_reverse_interface.cpp | 15 ++- tests/test_robot_receive_timeout.cpp | 4 +- tests/test_rtde_parser.cpp | 19 +++- tests/test_rtde_writer.cpp | 2 +- tests/test_stream.cpp | 2 +- tests/test_tcp_server.cpp | 10 +- tests/test_tcp_socket.cpp | 14 +-- tests/test_trajectory_point_interface.cpp | 8 +- 43 files changed, 301 insertions(+), 199 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1553f62c1..40eae1eab 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -71,7 +71,21 @@ if(MSVC) target_link_libraries(urcl ws2_32) else() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -pedantic") - target_compile_options(urcl PRIVATE -Wall -Wextra -Wno-unused-parameter) + target_compile_options(urcl PRIVATE -Wall -Wextra -Werror) + + # GCC 13-15 have a false positive -Wmaybe-uninitialized in headers + # (https://gcc.gnu.org/bugzilla/show_bug.cgi?id=105562). + # Bump the upper bound if the bug persists in newer GCC versions. + if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU" + AND CMAKE_CXX_COMPILER_VERSION VERSION_GREATER_EQUAL 13 + AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 16) + set_source_files_properties( + src/control/script_reader.cpp + src/ur/dashboard_client.cpp + src/ur/dashboard_client_implementation_g5.cpp + src/ur/dashboard_client_implementation_x.cpp + PROPERTIES COMPILE_OPTIONS "-Wno-maybe-uninitialized") + endif() if(WITH_ASAN) target_compile_options(urcl PUBLIC -fsanitize=address) diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 2d52ae3dc..f61f48d65 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -3,6 +3,11 @@ project(ur_driver_examples) # find_package(ur_client_library REQUIRED) +if(MSVC) + add_compile_options(/W4 /WX) # High warning level, treat warnings as errors +else() + add_compile_options(-Wall -Wextra -Werror) +endif() add_executable(driver_example full_driver.cpp) diff --git a/examples/external_fts_through_rtde.cpp b/examples/external_fts_through_rtde.cpp index dfd22cbb2..a3c9173cc 100644 --- a/examples/external_fts_through_rtde.cpp +++ b/examples/external_fts_through_rtde.cpp @@ -46,7 +46,7 @@ char getChar() { if (_kbhit()) { - ch = _getch(); + ch = static_cast(_getch()); } } return ch; diff --git a/examples/spline_example.cpp b/examples/spline_example.cpp index c9303ffde..d6e3a0865 100644 --- a/examples/spline_example.cpp +++ b/examples/spline_example.cpp @@ -58,30 +58,30 @@ void sendTrajectory(const std::vector& p_p, const std::vectorgetUrDriver()->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, - p_p.size()); + static_cast(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->getUrDriver()->writeTrajectoryPoint(p_p[i], false, time[i]); + g_my_robot->getUrDriver()->writeTrajectoryPoint(p_p[i], false, static_cast(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->getUrDriver()->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], static_cast(time[i])); } // CUBIC else if (p_v.size() == time.size() && p_v[i].size() == 6) { - g_my_robot->getUrDriver()->writeTrajectorySplinePoint(p_p[i], p_v[i], time[i]); + g_my_robot->getUrDriver()->writeTrajectorySplinePoint(p_p[i], p_v[i], static_cast(time[i])); } else { - g_my_robot->getUrDriver()->writeTrajectorySplinePoint(p_p[i], time[i]); + g_my_robot->getUrDriver()->writeTrajectorySplinePoint(p_p[i], static_cast(time[i])); } } } diff --git a/examples/trajectory_point_interface.cpp b/examples/trajectory_point_interface.cpp index 7e2efe18b..c4bce60b4 100644 --- a/examples/trajectory_point_interface.cpp +++ b/examples/trajectory_point_interface.cpp @@ -88,18 +88,20 @@ int main(int argc, char* argv[]) // Trajectory execution g_my_robot->getUrDriver()->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, - points.size() * 2); + static_cast(points.size() * 2)); for (size_t i = 0; i < points.size(); i++) { - g_my_robot->getUrDriver()->writeTrajectoryPoint(points[i], false, motion_durations[i], blend_radii[i]); + g_my_robot->getUrDriver()->writeTrajectoryPoint(points[i], false, static_cast(motion_durations[i]), + static_cast(blend_radii[i])); } // Same motion, but parametrized with acceleration and velocity motion_durations = { 0.0, 0.0 }; for (size_t i = 0; i < points.size(); i++) { - g_my_robot->getUrDriver()->writeTrajectoryPoint(points[i], accelerations[i], velocities[i], false, - motion_durations[i], blend_radii[i]); + g_my_robot->getUrDriver()->writeTrajectoryPoint( + points[i], static_cast(accelerations[i]), static_cast(velocities[i]), false, + static_cast(motion_durations[i]), static_cast(blend_radii[i])); } while (!g_trajectory_done) @@ -125,19 +127,21 @@ int main(int argc, char* argv[]) // Trajectory execution of the path that goes through the points twice. g_my_robot->getUrDriver()->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, - points.size() * 2); + static_cast(points.size() * 2)); for (size_t i = 0; i < points.size(); i++) { // setting the cartesian parameter makes it interpret the 6d vector as a pose and use movel - g_my_robot->getUrDriver()->writeTrajectoryPoint(points[i], true, motion_durations[i], blend_radii[i]); + g_my_robot->getUrDriver()->writeTrajectoryPoint(points[i], true, static_cast(motion_durations[i]), + static_cast(blend_radii[i])); } // Same motion, but parametrized with acceleration and velocity motion_durations = { 0.0, 0.0 }; for (size_t i = 0; i < points.size(); i++) { - g_my_robot->getUrDriver()->writeTrajectoryPoint(points[i], accelerations[i], velocities[i], true, - motion_durations[i], blend_radii[i]); + g_my_robot->getUrDriver()->writeTrajectoryPoint( + points[i], static_cast(accelerations[i]), static_cast(velocities[i]), true, + static_cast(motion_durations[i]), static_cast(blend_radii[i])); } while (!g_trajectory_done) @@ -165,10 +169,11 @@ int main(int argc, char* argv[]) // Trajectory execution g_my_robot->getUrDriver()->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, - positions.size()); + static_cast(positions.size())); for (size_t i = 0; i < positions.size(); i++) { - g_my_robot->getUrDriver()->writeTrajectorySplinePoint(positions[i], velocities[i], motion_durations[i]); + g_my_robot->getUrDriver()->writeTrajectorySplinePoint(positions[i], velocities[i], + static_cast(motion_durations[i])); } while (!g_trajectory_done) diff --git a/include/ur_client_library/comm/pipeline.h b/include/ur_client_library/comm/pipeline.h index 3b55faab0..dbd7b0e04 100644 --- a/include/ur_client_library/comm/pipeline.h +++ b/include/ur_client_library/comm/pipeline.h @@ -215,8 +215,9 @@ class IProducer * failed. Unlimited number of attempts when set to 0. * \param reconnection_time time in between connection attempts to the server */ - virtual void setupProducer(const size_t max_num_tries = 0, - const std::chrono::milliseconds reconnection_time = std::chrono::seconds(10)) + virtual void + setupProducer([[maybe_unused]] const size_t max_num_tries = 0, + [[maybe_unused]] const std::chrono::milliseconds reconnection_time = std::chrono::seconds(10)) { } /*! @@ -267,13 +268,13 @@ class INotifier /*! * \brief Start notification. */ - virtual void started(std::string name) + virtual void started([[maybe_unused]] std::string name) { } /*! * \brief Stop notification. */ - virtual void stopped(std::string name) + virtual void stopped([[maybe_unused]] std::string name) { } }; diff --git a/include/ur_client_library/log.h b/include/ur_client_library/log.h index 87de90e3c..72f33a708 100644 --- a/include/ur_client_library/log.h +++ b/include/ur_client_library/log.h @@ -19,6 +19,8 @@ #pragma once #include #include +#include +#include #define URCL_LOG_DEBUG(...) urcl::log(__FILE__, __LINE__, urcl::LogLevel::DEBUG, __VA_ARGS__) #define URCL_LOG_WARN(...) urcl::log(__FILE__, __LINE__, urcl::LogLevel::WARN, __VA_ARGS__) @@ -88,4 +90,19 @@ void setLogLevel(LogLevel level); * \param fmt Format string */ void log(const char* file, int line, LogLevel level, const char* fmt, ...); + +/*! + * \brief Cross-platform replacement for strerror. + * + * On MSVC, strerror triggers C4996 (deprecated). This function uses std::error_code instead, + * which is portable and thread-safe. + * + * \param errnum Error number (typically errno) + * \returns Human-readable error message + */ +inline std::string strerror_portable(int errnum) +{ + return std::error_code(errnum, std::generic_category()).message(); +} + } // namespace urcl diff --git a/include/ur_client_library/primary/primary_consumer.h b/include/ur_client_library/primary/primary_consumer.h index b167c6535..4dc142059 100644 --- a/include/ur_client_library/primary/primary_consumer.h +++ b/include/ur_client_library/primary/primary_consumer.h @@ -62,7 +62,7 @@ class PrimaryConsumer : public AbstractPrimaryConsumer * * \returns True */ - virtual bool consume(RobotMessage& msg) override + virtual bool consume([[maybe_unused]] RobotMessage& msg) override { return true; } @@ -74,7 +74,7 @@ class PrimaryConsumer : public AbstractPrimaryConsumer * * \returns True */ - virtual bool consume(RobotState& msg) override + virtual bool consume([[maybe_unused]] RobotState& msg) override { return true; } diff --git a/include/ur_client_library/primary/primary_parser.h b/include/ur_client_library/primary/primary_parser.h index 80db3adb3..c65837533 100644 --- a/include/ur_client_library/primary/primary_parser.h +++ b/include/ur_client_library/primary/primary_parser.h @@ -102,10 +102,10 @@ class PrimaryParser : public comm::Parser // deconstruction of a sub parser will increment the position of the parent parser comm::BinParser sbp(bp, sub_size); sbp.consume(sizeof(sub_size)); - RobotStateType type; - sbp.parse(type); + RobotStateType sub_type; + sbp.parse(sub_type); - std::unique_ptr packet(stateFromType(type)); + std::unique_ptr packet(stateFromType(sub_type)); if (packet == nullptr) { @@ -117,7 +117,7 @@ class PrimaryParser : public comm::Parser if (!packet->parseWith(sbp)) { - URCL_LOG_ERROR("Sub-package parsing of type %d failed!", static_cast(type)); + URCL_LOG_ERROR("Sub-package parsing of type %d failed!", static_cast(sub_type)); return false; } @@ -128,10 +128,10 @@ class PrimaryParser : public comm::Parser sbp.debug(); if (strict_mode_) { - throw UrException("Sub-package of type " + std::string(robotStateString(type)) + + throw UrException("Sub-package of type " + std::string(robotStateString(sub_type)) + " was not parsed completely, and strict mode is enabled, so aborting parsing!"); } - URCL_LOG_WARN("Sub-package of type %s was not parsed completely!", robotStateString(type)); + URCL_LOG_WARN("Sub-package of type %s was not parsed completely!", robotStateString(sub_type)); sbp.consume(); } } diff --git a/include/ur_client_library/ur/dashboard_client_implementation.h b/include/ur_client_library/ur/dashboard_client_implementation.h index bbc98f311..9979f529a 100644 --- a/include/ur_client_library/ur/dashboard_client_implementation.h +++ b/include/ur_client_library/ur/dashboard_client_implementation.h @@ -133,7 +133,7 @@ class DashboardClientImpl * * \param timeout The timeout to be set */ - virtual void setReceiveTimeout(const timeval& timeout) {}; + virtual void setReceiveTimeout([[maybe_unused]] const timeval& timeout) {}; /*! * \brief Sends command and verifies that a valid answer is received. diff --git a/include/ur_client_library/ur/dashboard_client_implementation_x.h b/include/ur_client_library/ur/dashboard_client_implementation_x.h index fd325c8ab..26e23bdf2 100644 --- a/include/ur_client_library/ur/dashboard_client_implementation_x.h +++ b/include/ur_client_library/ur/dashboard_client_implementation_x.h @@ -162,7 +162,7 @@ class DashboardClientImplX : public DashboardClientImpl DashboardResponse commandUpdateProgram(const std::string& file_path) override; DashboardResponse commandDownloadProgram(const std::string& filename, const std::string& save_path) override; - void setReceiveTimeout(const timeval& timeout) override + void setReceiveTimeout([[maybe_unused]] const timeval& timeout) override { } diff --git a/include/ur_client_library/ur/ur_driver.h b/include/ur_client_library/ur/ur_driver.h index 64d2e442b..4e93e7814 100644 --- a/include/ur_client_library/ur/ur_driver.h +++ b/include/ur_client_library/ur/ur_driver.h @@ -486,7 +486,7 @@ class UrDriver uint32_t getControlFrequency() const { - return rtde_client_->getTargetFrequency(); + return static_cast(rtde_client_->getTargetFrequency()); } /*! diff --git a/src/comm/tcp_server.cpp b/src/comm/tcp_server.cpp index 90f5d65b9..a211f359f 100644 --- a/src/comm/tcp_server.cpp +++ b/src/comm/tcp_server.cpp @@ -121,7 +121,7 @@ void TCPServer::shutdown() memset(&address, 0, sizeof(address)); address.sin_family = AF_INET; address.sin_addr.s_addr = htonl(INADDR_LOOPBACK); - address.sin_port = htons(port_); + address.sin_port = htons(static_cast(port_)); ::connect(shutdown_socket, reinterpret_cast(&address), sizeof(address)); @@ -152,7 +152,7 @@ void TCPServer::bind(const size_t max_num_tries, const std::chrono::milliseconds // INADDR_ANY is a special constant that signalizes "ANY IFACE", server_addr.sin_addr.s_addr = htonl(INADDR_ANY); - server_addr.sin_port = htons(port_); + server_addr.sin_port = htons(static_cast(port_)); int err = -1; size_t connection_counter = 0; do diff --git a/src/control/reverse_interface.cpp b/src/control/reverse_interface.cpp index efd39ef4b..5606dc5a8 100644 --- a/src/control/reverse_interface.cpp +++ b/src/control/reverse_interface.cpp @@ -95,9 +95,9 @@ bool ReverseInterface::write(const vector6d_t* positions, const comm::ControlMod { for (auto const& pos : *positions) { - int32_t val = static_cast(round(pos * MULT_JOINTSTATE)); - val = htobe32(val); - b_pos += append(b_pos, val); + int32_t joint_val = static_cast(round(pos * MULT_JOINTSTATE)); + joint_val = htobe32(joint_val); + b_pos += append(b_pos, joint_val); } } else @@ -250,11 +250,13 @@ void ReverseInterface::disconnectionCallback(const socket_t filedescriptor) } for (auto handler : disconnect_callbacks_) { - handler.function(filedescriptor); + // socket_t is UINT_PTR on Windows, so a narrowing cast is needed to match the callback signature + handler.function(static_cast(filedescriptor)); } } -void ReverseInterface::messageCallback(const socket_t filedescriptor, char* buffer, int nbytesrecv) +void ReverseInterface::messageCallback([[maybe_unused]] const socket_t filedescriptor, [[maybe_unused]] char* buffer, + [[maybe_unused]] int nbytesrecv) { URCL_LOG_WARN("Message on ReverseInterface received. The reverse interface currently does not support any message " "handling. This message will be ignored."); diff --git a/src/control/script_command_interface.cpp b/src/control/script_command_interface.cpp index 2ae7ad0e3..88f68aa7d 100644 --- a/src/control/script_command_interface.cpp +++ b/src/control/script_command_interface.cpp @@ -372,11 +372,12 @@ void ScriptCommandInterface::disconnectionCallback(const socket_t filedescriptor client_connected_ = false; } -void ScriptCommandInterface::messageCallback(const socket_t filedescriptor, char* buffer, int nbytesrecv) +void ScriptCommandInterface::messageCallback([[maybe_unused]] const socket_t filedescriptor, char* buffer, + int nbytesrecv) { if (nbytesrecv == 4) { - int32_t* status = reinterpret_cast(buffer); + int32_t* status = reinterpret_cast(buffer); URCL_LOG_DEBUG("Received message %d on Script command interface", be32toh(*status)); if (handle_tool_contact_result_) diff --git a/src/control/trajectory_point_interface.cpp b/src/control/trajectory_point_interface.cpp index fa6d2df7c..ff1b1f8e5 100644 --- a/src/control/trajectory_point_interface.cpp +++ b/src/control/trajectory_point_interface.cpp @@ -230,7 +230,7 @@ bool TrajectoryPointInterface::writeTrajectoryPoint(const vector6d_t* positions, bool TrajectoryPointInterface::writeTrajectoryPoint(const vector6d_t* positions, const float goal_time, const float blend_radius, const bool cartesian) { - return writeTrajectoryPoint(positions, 1.4, 1.05, goal_time, blend_radius, cartesian); + return writeTrajectoryPoint(positions, 1.4f, 1.05f, goal_time, blend_radius, cartesian); } bool TrajectoryPointInterface::writeTrajectorySplinePoint(const vector6d_t* positions, const vector6d_t* velocities, @@ -277,16 +277,18 @@ void TrajectoryPointInterface::disconnectionCallback(const socket_t filedescript URCL_LOG_DEBUG("Connection to trajectory interface dropped."); for (auto handler : disconnect_callbacks_) { - handler.function(filedescriptor); + // socket_t is UINT_PTR on Windows, so a narrowing cast is needed to match the callback signature + handler.function(static_cast(filedescriptor)); } client_fd_ = INVALID_SOCKET; } -void TrajectoryPointInterface::messageCallback(const socket_t filedescriptor, char* buffer, int nbytesrecv) +void TrajectoryPointInterface::messageCallback([[maybe_unused]] const socket_t filedescriptor, char* buffer, + int nbytesrecv) { if (nbytesrecv == 4) { - int32_t* status = reinterpret_cast(buffer); + int32_t* status = reinterpret_cast(buffer); URCL_LOG_DEBUG("Received message %d on TrajectoryPointInterface", be32toh(*status)); if (!trajectory_end_callbacks_.empty()) diff --git a/src/helpers.cpp b/src/helpers.cpp index 9e3e23eec..5ff776733 100644 --- a/src/helpers.cpp +++ b/src/helpers.cpp @@ -69,7 +69,7 @@ bool setFiFoScheduling(pthread_t& thread, const int priority) { URCL_LOG_ERROR("Unsuccessful in setting thread to FIFO scheduling with priority %i. %s", priority, - strerror(ret)); + strerror_portable(ret).c_str()); } } @@ -123,7 +123,8 @@ void waitFor(std::function condition, const std::chrono::milliseconds ti bool parseBoolean(const std::string& str) { std::string lower = str; - std::transform(lower.begin(), lower.end(), lower.begin(), [](unsigned char c) { return std::tolower(c); }); + std::transform(lower.begin(), lower.end(), lower.begin(), + [](unsigned char c) { return static_cast(std::tolower(c)); }); if (lower == "true" || lower == "1" || lower == "yes" || lower == "on") { diff --git a/src/primary/primary_client.cpp b/src/primary/primary_client.cpp index c90ac46a7..ca18ae546 100644 --- a/src/primary/primary_client.cpp +++ b/src/primary/primary_client.cpp @@ -40,7 +40,7 @@ namespace urcl { namespace primary_interface { -PrimaryClient::PrimaryClient(const std::string& robot_ip, comm::INotifier& notifier) +PrimaryClient::PrimaryClient(const std::string& robot_ip, [[maybe_unused]] comm::INotifier& notifier) : stream_(robot_ip, UR_PRIMARY_PORT) { parser_.setStrictMode(COMPILE_OPTIONS.PRIMARY_CLIENT_STRICT_PARSING); @@ -178,7 +178,7 @@ void PrimaryClient::commandPowerOn(const bool validate, const std::chrono::milli { waitFor([this]() { return getRobotMode() == RobotMode::IDLE; }, timeout); } - catch (const TimeoutException& ex) + catch (const TimeoutException&) { throw TimeoutException("Robot did not power on within the given timeout", timeout); } diff --git a/src/rtde/control_package_setup_inputs.cpp b/src/rtde/control_package_setup_inputs.cpp index deb5b1490..900af5f9f 100644 --- a/src/rtde/control_package_setup_inputs.cpp +++ b/src/rtde/control_package_setup_inputs.cpp @@ -59,7 +59,7 @@ size_t ControlPackageSetupInputsRequest::generateSerializedRequest(uint8_t* buff for (const auto& piece : variable_names) variables += (piece + ","); variables.pop_back(); - uint16_t payload_size = variables.size(); + uint16_t payload_size = static_cast(variables.size()); size_t size = 0; size += PackageHeader::serializeHeader(buffer, PACKAGE_TYPE, payload_size); diff --git a/src/rtde/control_package_setup_outputs.cpp b/src/rtde/control_package_setup_outputs.cpp index 6e527db50..5d81a9492 100644 --- a/src/rtde/control_package_setup_outputs.cpp +++ b/src/rtde/control_package_setup_outputs.cpp @@ -84,7 +84,7 @@ size_t ControlPackageSetupOutputsRequest::generateSerializedRequest(uint8_t* buf for (const auto& piece : variable_names) variables += (piece + ","); variables.pop_back(); - uint16_t payload_size = sizeof(double) + variables.size(); + uint16_t payload_size = static_cast(sizeof(double) + variables.size()); size_t size = 0; size += PackageHeader::serializeHeader(buffer, PACKAGE_TYPE, payload_size); @@ -105,7 +105,7 @@ size_t ControlPackageSetupOutputsRequest::generateSerializedRequest(uint8_t* buf for (const auto& piece : variable_names) variables += (piece + ","); variables.pop_back(); - uint16_t payload_size = variables.size(); + uint16_t payload_size = static_cast(variables.size()); size_t size = 0; size += PackageHeader::serializeHeader(buffer, PACKAGE_TYPE, payload_size); diff --git a/src/rtde/rtde_client.cpp b/src/rtde/rtde_client.cpp index 9adeccd38..f18238720 100644 --- a/src/rtde/rtde_client.cpp +++ b/src/rtde/rtde_client.cpp @@ -33,6 +33,7 @@ #include #include #include +#include namespace urcl { @@ -643,12 +644,12 @@ bool RTDEClient::sendStart() { return tmp->accepted_; } - else if (rtde_interface::DataPackage* tmp = dynamic_cast(package.get())) + else if (rtde_interface::DataPackage* data_tmp = dynamic_cast(package.get())) { // There is a race condition whether the last received packet was the start confirmation or // is already a data package. In that case consider the start as successful. double timestamp; - return tmp->getData("timestamp", timestamp); + return data_tmp->getData("timestamp", timestamp); } else { @@ -706,7 +707,7 @@ std::vector RTDEClient::readRecipe(const std::string& recipe_file) if (file.fail()) { std::stringstream msg; - msg << "Opening file '" << recipe_file << "' failed with error: " << strerror(errno); + msg << "Opening file '" << recipe_file << "' failed with error: " << strerror_portable(errno); URCL_LOG_ERROR("%s", msg.str().c_str()); throw UrException(msg.str()); } @@ -984,7 +985,7 @@ void RTDEClient::backgroundReadThreadFunc() if (data_pkg != nullptr) { { - std::scoped_lock lock(read_mutex_, write_mutex_); + std::scoped_lock rw_lock(read_mutex_, write_mutex_); std::swap(data_buffer0_, data_buffer1_); } diff --git a/src/rtde/rtde_writer.cpp b/src/rtde/rtde_writer.cpp index 425ec0912..c0c48ccdb 100644 --- a/src/rtde/rtde_writer.cpp +++ b/src/rtde/rtde_writer.cpp @@ -303,8 +303,7 @@ bool RTDEWriter::sendStandardAnalogOutput(uint8_t output_pin, double value, cons if (type != AnalogOutputType::SET_ON_TEACH_PENDANT) { static const std::string key_type = "standard_analog_output_type"; - auto output_type_bits = [](const uint8_t pin, const uint8_t type) { return type << pin; }; - uint8_t output_type = output_type_bits(output_pin, toUnderlying(type)); + uint8_t output_type = static_cast(toUnderlying(type) << output_pin); success = success && current_store_buffer_->setData(key_type, output_type); } static const std::string key_output_0 = "standard_analog_output_0"; diff --git a/src/ur/dashboard_client.cpp b/src/ur/dashboard_client.cpp index 381ddd07b..6065f8cdd 100644 --- a/src/ur/dashboard_client.cpp +++ b/src/ur/dashboard_client.cpp @@ -117,7 +117,8 @@ bool DashboardClient::waitForReply(const std::string& command, const std::string return false; } -bool DashboardClient::retryCommand(const std::string& requestCommand, const std::string& requestExpectedResponse, +bool DashboardClient::retryCommand(const std::string& requestCommand, + [[maybe_unused]] const std::string& requestExpectedResponse, const std::string& waitRequest, const std::string& waitExpectedResponse, const std::chrono::duration timeout, const std::chrono::duration retry_period) diff --git a/src/ur/dashboard_client_implementation_g5.cpp b/src/ur/dashboard_client_implementation_g5.cpp index e462ac280..6f2d65bb2 100644 --- a/src/ur/dashboard_client_implementation_g5.cpp +++ b/src/ur/dashboard_client_implementation_g5.cpp @@ -400,7 +400,8 @@ std::string DashboardClientImplG5::retryCommandString(const std::string& request "' within the timeout. Last response was: " + response); } -bool DashboardClientImplG5::retryCommand(const std::string& requestCommand, const std::string& requestExpectedResponse, +bool DashboardClientImplG5::retryCommand(const std::string& requestCommand, + [[maybe_unused]] const std::string& requestExpectedResponse, const std::string& waitRequest, const std::string& waitExpectedResponse, const std::chrono::duration timeout, const std::chrono::duration retry_period) @@ -1192,20 +1193,20 @@ DashboardResponse DashboardClientImplG5::commandGetProgramList() polyscope_version_.toString() + ". It is supported from PolyScope 10.12.0 onwards."); } -DashboardResponse DashboardClientImplG5::commandUploadProgram(const std::string& program_file_name) +DashboardResponse DashboardClientImplG5::commandUploadProgram([[maybe_unused]] const std::string& program_file_name) { throw NotImplementedException("commandUploadProgram is not available for PolyScope " + polyscope_version_.toString() + ". It is supported from PolyScope 10.12.0 onwards."); } -DashboardResponse DashboardClientImplG5::commandUpdateProgram(const std::string& program_file_name) +DashboardResponse DashboardClientImplG5::commandUpdateProgram([[maybe_unused]] const std::string& program_file_name) { throw NotImplementedException("commandUpdateProgram is not available for PolyScope " + polyscope_version_.toString() + ". It is supported from PolyScope 10.12.0 onwards."); } -DashboardResponse DashboardClientImplG5::commandDownloadProgram(const std::string& program_file_name, - const std::string& destination_path) +DashboardResponse DashboardClientImplG5::commandDownloadProgram([[maybe_unused]] const std::string& program_file_name, + [[maybe_unused]] const std::string& destination_path) { throw NotImplementedException("commandDownloadProgram is not available for PolyScope " + polyscope_version_.toString() + ". It is supported from PolyScope 10.12.0 onwards."); diff --git a/src/ur/dashboard_client_implementation_x.cpp b/src/ur/dashboard_client_implementation_x.cpp index c5c9a8cc3..46e9e2ec8 100644 --- a/src/ur/dashboard_client_implementation_x.cpp +++ b/src/ur/dashboard_client_implementation_x.cpp @@ -51,12 +51,13 @@ DashboardClientImplX::DashboardClientImplX(const std::string& host) : DashboardC cli_->set_follow_location(true); } -std::string DashboardClientImplX::sendAndReceive(const std::string& text) +std::string DashboardClientImplX::sendAndReceive([[maybe_unused]] const std::string& text) { throw NotImplementedException("sendAndReceive is not implemented for DashboardClientImplX."); } -bool DashboardClientImplX::connect(const size_t max_num_tries, const std::chrono::milliseconds reconnection_time) +bool DashboardClientImplX::connect([[maybe_unused]] const size_t max_num_tries, + [[maybe_unused]] const std::chrono::milliseconds reconnection_time) { std::string endpoint = base_url_ + "/openapi.json"; // The PolyScope X Robot API doesn't require any connection prior to making calls. However, this @@ -101,36 +102,40 @@ VersionInformation DashboardClientImplX::queryPolyScopeVersion() throw NotImplementedException("queryPolyScopeVersion is not implemented for DashboardClientImplX."); } -void DashboardClientImplX::assertHasCommand(const std::string& command) const +void DashboardClientImplX::assertHasCommand([[maybe_unused]] const std::string& command) const { // Currently, there is only one set of implemented commands. Once the first software release has // been made with a Dashboard Server, following versions will support more commands, which is // when we might have to deal with that here. } -bool DashboardClientImplX::sendRequest(const std::string& command_str, const std::string& expected_response_pattern, - const std::string& payload) +bool DashboardClientImplX::sendRequest([[maybe_unused]] const std::string& command_str, + [[maybe_unused]] const std::string& expected_response_pattern, + [[maybe_unused]] const std::string& payload) { throw NotImplementedException("sendRequestis not implemented for DashboardClientImplX."); } -std::string DashboardClientImplX::sendRequestString(const std::string& command_str, - const std::string& expected_response_pattern, - const std::string& payload) +std::string DashboardClientImplX::sendRequestString([[maybe_unused]] const std::string& command_str, + [[maybe_unused]] const std::string& expected_response_pattern, + [[maybe_unused]] const std::string& payload) { throw NotImplementedException("sendRequestString is not implemented for DashboardClientImplX."); } -bool DashboardClientImplX::waitForReply(const std::string& command, const std::string& expected, - const std::chrono::duration timeout) +bool DashboardClientImplX::waitForReply([[maybe_unused]] const std::string& command, + [[maybe_unused]] const std::string& expected, + [[maybe_unused]] const std::chrono::duration timeout) { throw NotImplementedException("waitForReply is not implemented for DashboardClientImplX."); } -bool DashboardClientImplX::retryCommand(const std::string& requestCommand, const std::string& requestExpectedResponse, - const std::string& waitRequest, const std::string& waitExpectedResponse, - const std::chrono::duration timeout, - const std::chrono::duration retry_period) +bool DashboardClientImplX::retryCommand([[maybe_unused]] const std::string& requestCommand, + [[maybe_unused]] const std::string& requestExpectedResponse, + [[maybe_unused]] const std::string& waitRequest, + [[maybe_unused]] const std::string& waitExpectedResponse, + [[maybe_unused]] const std::chrono::duration timeout, + [[maybe_unused]] const std::chrono::duration retry_period) { throw NotImplementedException("retryCommand is not implemented for DashboardClientImplX."); } @@ -140,7 +145,7 @@ DashboardResponse DashboardClientImplX::commandPowerOff() return put("/robotstate/v1/state", R"({"action": "POWER_OFF"})"); } -DashboardResponse DashboardClientImplX::commandPowerOn(const std::chrono::duration timeout) +DashboardResponse DashboardClientImplX::commandPowerOn([[maybe_unused]] const std::chrono::duration timeout) { return put("/robotstate/v1/state", R"({"action": "POWER_ON"})"); } @@ -162,7 +167,8 @@ DashboardResponse DashboardClientImplX::commandLoadProgram(const std::string& pr return put(endpoint, R"({")" + program_key + R"(": ")" + program_file_name + R"("})"); } -DashboardResponse DashboardClientImplX::commandLoadInstallation(const std::string& installation_file_name) +DashboardResponse +DashboardClientImplX::commandLoadInstallation([[maybe_unused]] const std::string& installation_file_name) { throw NotImplementedException("commandLoadInstallation is not implemented for DashboardClientImplX."); } @@ -252,12 +258,12 @@ DashboardResponse DashboardClientImplX::commandIsInRemoteControl() return response; } -DashboardResponse DashboardClientImplX::commandPopup(const std::string& popup_text) +DashboardResponse DashboardClientImplX::commandPopup([[maybe_unused]] const std::string& popup_text) { throw NotImplementedException("commandPopup is not implemented for DashboardClientImplX."); } -DashboardResponse DashboardClientImplX::commandAddToLog(const std::string& log_text) +DashboardResponse DashboardClientImplX::commandAddToLog([[maybe_unused]] const std::string& log_text) { throw NotImplementedException("commandAddToLog is not implemented for DashboardClientImplX."); } @@ -357,7 +363,7 @@ DashboardResponse DashboardClientImplX::commandGetOperationalMode() return response; } -DashboardResponse DashboardClientImplX::commandSetOperationalMode(const std::string& operational_mode) +DashboardResponse DashboardClientImplX::commandSetOperationalMode([[maybe_unused]] const std::string& operational_mode) { throw NotImplementedException("commandSetOperationalMode is not implemented for DashboardClientImplX."); } @@ -367,7 +373,7 @@ DashboardResponse DashboardClientImplX::commandClearOperationalMode() throw NotImplementedException("commandClearOperationalMode is not implemented for DashboardClientImplX."); } -DashboardResponse DashboardClientImplX::commandSetUserRole(const std::string& user_role) +DashboardResponse DashboardClientImplX::commandSetUserRole([[maybe_unused]] const std::string& user_role) { throw NotImplementedException("commandSetUserRole is not implemented for DashboardClientImplX."); } @@ -377,12 +383,12 @@ DashboardResponse DashboardClientImplX::commandGetUserRole() throw NotImplementedException("commandGetUserRole is not implemented for DashboardClientImplX."); } -DashboardResponse DashboardClientImplX::commandGenerateFlightReport(const std::string& report_type) +DashboardResponse DashboardClientImplX::commandGenerateFlightReport([[maybe_unused]] const std::string& report_type) { throw NotImplementedException("commandGenerateFlightReport is not implemented for DashboardClientImplX."); } -DashboardResponse DashboardClientImplX::commandGenerateSupportFile(const std::string& dir_path) +DashboardResponse DashboardClientImplX::commandGenerateSupportFile([[maybe_unused]] const std::string& dir_path) { throw NotImplementedException("commandGenerateSupportFile is not implemented for DashboardClientImplX."); } @@ -494,11 +500,11 @@ DashboardResponse DashboardClientImplX::commandDownloadProgram(const std::string std::ofstream save_file(save_path, std::ios_base::out); if (!save_file.is_open()) { - DashboardResponse response; - response.ok = false; - response.message = "Failed to open file for saving: " + save_path; - URCL_LOG_ERROR(response.message.c_str()); - return response; + DashboardResponse error_response; + error_response.ok = false; + error_response.message = "Failed to open file for saving: " + save_path; + URCL_LOG_ERROR(error_response.message.c_str()); + return error_response; } save_file << response.message; diff --git a/src/ur/instruction_executor.cpp b/src/ur/instruction_executor.cpp index e989c866c..c18e4670d 100644 --- a/src/ur/instruction_executor.cpp +++ b/src/ur/instruction_executor.cpp @@ -44,7 +44,7 @@ void urcl::InstructionExecutor::trajDoneCallback(const urcl::control::Trajectory trajectory_running_ = false; } } -void urcl::InstructionExecutor::trajDisconnectCallback(const int filedescriptor) +void urcl::InstructionExecutor::trajDisconnectCallback([[maybe_unused]] const int filedescriptor) { URCL_LOG_INFO("Trajectory disconnect"); std::unique_lock lock(trajectory_result_mutex_); @@ -59,7 +59,7 @@ bool urcl::InstructionExecutor::executeMotion( const std::vector>& motion_sequence) { if (!driver_->writeTrajectoryControlMessage(urcl::control::TrajectoryControlMessage::TRAJECTORY_START, - motion_sequence.size())) + static_cast(motion_sequence.size()))) { URCL_LOG_ERROR("Cannot send trajectory control command. No client connected?"); std::unique_lock lock(trajectory_result_mutex_); diff --git a/src/ur/robot_receive_timeout.cpp b/src/ur/robot_receive_timeout.cpp index 1ce10d139..acb5d7050 100644 --- a/src/ur/robot_receive_timeout.cpp +++ b/src/ur/robot_receive_timeout.cpp @@ -72,11 +72,11 @@ int RobotReceiveTimeout::verifyRobotReceiveTimeout(const comm::ControlMode contr ss << "Robot receive timeout " << timeout_.count() << "ms is below the step time " << step_time.count() << "ms. It will be reset to the step time."; URCL_LOG_ERROR(ss.str().c_str()); - return step_time.count(); + return static_cast(step_time.count()); } else { - return timeout_.count(); + return static_cast(timeout_.count()); } } else if (comm::ControlModeTypes::isControlModeRealtime(control_mode)) @@ -87,7 +87,7 @@ int RobotReceiveTimeout::verifyRobotReceiveTimeout(const comm::ControlMode contr ss << "Realtime read timeout " << timeout_.count() << "ms is below the step time " << step_time.count() << ". It will be reset to the step time."; URCL_LOG_ERROR(ss.str().c_str()); - return step_time.count(); + return static_cast(step_time.count()); } else if (timeout_ > MAX_RT_RECEIVE_TIMEOUT_MS) { @@ -96,11 +96,11 @@ int RobotReceiveTimeout::verifyRobotReceiveTimeout(const comm::ControlMode contr << "ms is above the maximum allowed timeout for realtime commands " << MAX_RT_RECEIVE_TIMEOUT_MS.count() << ". It will be reset to the maximum allowed timeout."; URCL_LOG_ERROR(ss.str().c_str()); - return MAX_RT_RECEIVE_TIMEOUT_MS.count(); + return static_cast(MAX_RT_RECEIVE_TIMEOUT_MS.count()); } else { - return timeout_.count(); + return static_cast(timeout_.count()); } } else diff --git a/src/ur/ur_driver.cpp b/src/ur/ur_driver.cpp index 2c2ec764f..e7c7105b9 100644 --- a/src/ur/ur_driver.cpp +++ b/src/ur/ur_driver.cpp @@ -188,8 +188,13 @@ void UrDriver::init(const UrDriverConfiguration& config) URCL_LOG_DEBUG("Initialization done"); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#ifdef __GNUC__ +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#elif defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable : 4996) +#endif std::unique_ptr urcl::UrDriver::getDataPackage() { // This can take one of two values, 0ms or 100ms. The large timeout is for when the robot is commanding the control @@ -199,7 +204,11 @@ std::unique_ptr urcl::UrDriver::getDataPackage() return rtde_client_->getDataPackage(timeout); } -#pragma GCC diagnostic pop +#ifdef __GNUC__ +# pragma GCC diagnostic pop +#elif defined(_MSC_VER) +# pragma warning(pop) +#endif bool UrDriver::getDataPackage(rtde_interface::DataPackage& data_package) { @@ -687,10 +696,19 @@ void UrDriver::setKeepaliveCount(const uint32_t count) "read timeout in the write commands directly. This keepalive count will overwrite the timeout passed " "to the write functions."); // TODO: Remove 2027-05 -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#ifdef _MSC_VER +# pragma warning(push) +# pragma warning(disable : 4996) +#else +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif reverse_interface_->setKeepaliveCount(count); -#pragma GCC diagnostic pop +#ifdef _MSC_VER +# pragma warning(pop) +#else +# pragma GCC diagnostic pop +#endif } void UrDriver::resetRTDEClient(const std::vector& output_recipe, diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 99db15ba2..582d8e3da 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -14,6 +14,12 @@ FetchContent_Declare( set(gtest_force_shared_crt ON CACHE BOOL "" FORCE) FetchContent_MakeAvailable(googletest) +if(MSVC) + add_compile_options(/W4 /WX) # High warning level, treat warnings as errors +else() + add_compile_options(-Wall -Wextra -Werror) +endif() + add_executable(fake_rtde_server fake_rtde_server.cpp fake_rtde_server_main.cpp) target_link_libraries(fake_rtde_server PRIVATE ur_client_library::urcl) diff --git a/tests/fake_rtde_server.cpp b/tests/fake_rtde_server.cpp index 5985b92e0..c0219029c 100644 --- a/tests/fake_rtde_server.cpp +++ b/tests/fake_rtde_server.cpp @@ -32,7 +32,7 @@ void RTDEServer::disconnectionCallback(const socket_t filedescriptor) URCL_LOG_INFO("Client disconnected from RTDE server on FD %d", filedescriptor); stopSendingDataPackages(); } -void RTDEServer::messageCallback(const socket_t filedescriptor, char* buffer, int nbytesrecv) +void RTDEServer::messageCallback([[maybe_unused]] const socket_t filedescriptor, char* buffer, int nbytesrecv) { comm::BinParser bp(reinterpret_cast(buffer), nbytesrecv); rtde_interface::PackageHeader::_package_size_type size; @@ -46,31 +46,31 @@ void RTDEServer::messageCallback(const socket_t filedescriptor, char* buffer, in { bool accepted = true; comm::PackageSerializer serializer; - uint8_t buffer[4096]; - size_t size = 0; - size += rtde_interface::PackageHeader::serializeHeader( - buffer, rtde_interface::PackageType::RTDE_REQUEST_PROTOCOL_VERSION, sizeof(uint8_t)); - size += serializer.serialize(buffer + size, accepted); + uint8_t send_buffer[4096]; + size_t send_size = 0; + send_size += rtde_interface::PackageHeader::serializeHeader( + send_buffer, rtde_interface::PackageType::RTDE_REQUEST_PROTOCOL_VERSION, sizeof(uint8_t)); + send_size += serializer.serialize(send_buffer + send_size, accepted); size_t written; - server_.writeUnchecked(filedescriptor, buffer, size, written); + server_.writeUnchecked(filedescriptor, send_buffer, send_size, written); break; } case rtde_interface::PackageType::RTDE_GET_URCONTROL_VERSION: { comm::PackageSerializer serializer; - uint8_t buffer[4096]; - size_t size = 0; - size += rtde_interface::PackageHeader::serializeHeader( - buffer, rtde_interface::PackageType::RTDE_GET_URCONTROL_VERSION, 4 * sizeof(uint32_t)); + uint8_t send_buffer[4096]; + size_t send_size = 0; + send_size += rtde_interface::PackageHeader::serializeHeader( + send_buffer, rtde_interface::PackageType::RTDE_GET_URCONTROL_VERSION, 4 * sizeof(uint32_t)); uint32_t version = 10; - size += serializer.serialize(buffer + size, version); // major - size += serializer.serialize(buffer + size, version); // minor - size += serializer.serialize(buffer + size, version); // bugfix - size += serializer.serialize(buffer + size, version); // build + send_size += serializer.serialize(send_buffer + send_size, version); // major + send_size += serializer.serialize(send_buffer + send_size, version); // minor + send_size += serializer.serialize(send_buffer + send_size, version); // bugfix + send_size += serializer.serialize(send_buffer + send_size, version); // build size_t written; - server_.writeUnchecked(filedescriptor, buffer, size, written); + server_.writeUnchecked(filedescriptor, send_buffer, send_size, written); break; } case rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_SETUP_OUTPUTS: @@ -85,20 +85,20 @@ void RTDEServer::messageCallback(const socket_t filedescriptor, char* buffer, in output_data_package_->initEmpty(); comm::PackageSerializer serializer; - uint8_t buffer[4096]; - size_t size = 0; - size += rtde_interface::PackageHeader::serializeHeader( - buffer, rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_SETUP_OUTPUTS, - variable_names_str.length() + sizeof(uint8_t)); + uint8_t send_buffer[4096]; + size_t send_size = 0; + send_size += rtde_interface::PackageHeader::serializeHeader( + send_buffer, rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_SETUP_OUTPUTS, + static_cast(variable_names_str.length() + sizeof(uint8_t))); uint8_t recipe_id = 1; - size += serializer.serialize(buffer + size, recipe_id); - size += serializer.serialize(buffer + size, - variable_names_str); // We return the variable - // names list directly. For the initialization process, it is - // only important, that no field is "NOT_FOUND". + send_size += serializer.serialize(send_buffer + send_size, recipe_id); + send_size += serializer.serialize(send_buffer + send_size, + variable_names_str); // We return the variable + // names list directly. For the initialization process, it + // is only important, that no field is "NOT_FOUND". size_t written; - server_.writeUnchecked(filedescriptor, buffer, size, written); + server_.writeUnchecked(filedescriptor, send_buffer, send_size, written); URCL_LOG_INFO("Output recipe set"); break; } @@ -111,20 +111,20 @@ void RTDEServer::messageCallback(const socket_t filedescriptor, char* buffer, in input_data_package_ = std::make_unique(input_recipe_); comm::PackageSerializer serializer; - uint8_t buffer[4096]; - size_t size = 0; - size += rtde_interface::PackageHeader::serializeHeader( - buffer, rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_SETUP_INPUTS, - variable_names_str.length() + sizeof(uint8_t)); + uint8_t send_buffer[4096]; + size_t send_size = 0; + send_size += rtde_interface::PackageHeader::serializeHeader( + send_buffer, rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_SETUP_INPUTS, + static_cast(variable_names_str.length() + sizeof(uint8_t))); uint8_t recipe_id = 1; - size += serializer.serialize(buffer + size, recipe_id); - size += serializer.serialize(buffer + size, - variable_names_str); // We return the variable - // names list directly. For the initialization process, it is - // only important, that no field is "NOT_FOUND". + send_size += serializer.serialize(send_buffer + send_size, recipe_id); + send_size += serializer.serialize(send_buffer + send_size, + variable_names_str); // We return the variable + // names list directly. For the initialization process, it + // is only important, that no field is "NOT_FOUND". size_t written; - server_.writeUnchecked(filedescriptor, buffer, size, written); + server_.writeUnchecked(filedescriptor, send_buffer, send_size, written); URCL_LOG_INFO("Input recipe set with %zu variables.", input_recipe_.size()); break; @@ -132,30 +132,30 @@ void RTDEServer::messageCallback(const socket_t filedescriptor, char* buffer, in case rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_START: { comm::PackageSerializer serializer; - uint8_t buffer[4096]; - size_t size = 0; - size += rtde_interface::PackageHeader::serializeHeader( - buffer, rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_START, sizeof(uint8_t)); + uint8_t send_buffer[4096]; + size_t send_size = 0; + send_size += rtde_interface::PackageHeader::serializeHeader( + send_buffer, rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_START, sizeof(uint8_t)); bool accepted = true; - size += serializer.serialize(buffer + size, accepted); + send_size += serializer.serialize(send_buffer + send_size, accepted); size_t written; - server_.writeUnchecked(filedescriptor, buffer, size, written); + server_.writeUnchecked(filedescriptor, send_buffer, send_size, written); startSendingDataPackages(); break; } case rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_PAUSE: { comm::PackageSerializer serializer; - uint8_t buffer[4096]; - size_t size = 0; - size += rtde_interface::PackageHeader::serializeHeader( - buffer, rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_PAUSE, sizeof(uint8_t)); + uint8_t send_buffer[4096]; + size_t send_size = 0; + send_size += rtde_interface::PackageHeader::serializeHeader( + send_buffer, rtde_interface::PackageType::RTDE_CONTROL_PACKAGE_PAUSE, sizeof(uint8_t)); bool accepted = true; - size += serializer.serialize(buffer + size, accepted); + send_size += serializer.serialize(send_buffer + send_size, accepted); size_t written; - server_.writeUnchecked(filedescriptor, buffer, size, written); + server_.writeUnchecked(filedescriptor, send_buffer, send_size, written); stopSendingDataPackages(); break; } diff --git a/tests/test_bin_parser.cpp b/tests/test_bin_parser.cpp index 290d0d3cf..45beda4b8 100644 --- a/tests/test_bin_parser.cpp +++ b/tests/test_bin_parser.cpp @@ -178,7 +178,7 @@ TEST(bin_parser, parse_data_types) uint8_t buffer_float[] = { 0x41, 0xb2, 0xb8, 0x52 }; comm::BinParser bp_float(buffer_float, sizeof(buffer_float)); - float expected_float = 22.34; + float expected_float = 22.34f; float parsed_float; bp_float.parse(parsed_float); diff --git a/tests/test_control_mode.cpp b/tests/test_control_mode.cpp index 287311bf4..e1f436f2a 100644 --- a/tests/test_control_mode.cpp +++ b/tests/test_control_mode.cpp @@ -84,9 +84,9 @@ TEST(control_mode, control_mode_types_size_equals_number_off_control_modes) { number_of_control_modes++; } - int number_of_control_mode_types = comm::ControlModeTypes::REALTIME_CONTROL_MODES.size() + - comm::ControlModeTypes::NON_REALTIME_CONTROL_MODES.size() + - comm::ControlModeTypes::STATIONARY_CONTROL_MODES.size(); + int number_of_control_mode_types = static_cast(comm::ControlModeTypes::REALTIME_CONTROL_MODES.size() + + comm::ControlModeTypes::NON_REALTIME_CONTROL_MODES.size() + + comm::ControlModeTypes::STATIONARY_CONTROL_MODES.size()); EXPECT_EQ(number_of_control_mode_types, number_of_control_modes); } diff --git a/tests/test_dashboard_client.cpp b/tests/test_dashboard_client.cpp index 2ab9cef68..c449c140c 100644 --- a/tests/test_dashboard_client.cpp +++ b/tests/test_dashboard_client.cpp @@ -52,7 +52,8 @@ class MockDashboardClientImpl : public DashboardClientImplG5 { } - bool connect(const size_t max_num_tries, const std::chrono::milliseconds reconnection_time) override + bool connect([[maybe_unused]] const size_t max_num_tries, + [[maybe_unused]] const std::chrono::milliseconds reconnection_time) override { return true; // Simulate a successful connection } @@ -215,12 +216,13 @@ TEST_F(DashboardClientTest, log_and_getters) EXPECT_TRUE(dashboard_client_->connect()); const auto impl = dashboard_client_->getImplPtr(); EXPECT_CALL(*impl, commandAddToLog("Testing Log:")).WillOnce(testing::Return(SUCCESS_RESPONSE)); - EXPECT_CALL(*impl, commandPolyscopeVersion()).WillOnce(testing::Return(DashboardResponse{ true, "5.6.0" })); - EXPECT_CALL(*impl, commandRobotMode()).WillOnce(testing::Return(DashboardResponse{ true, "Robotmode: POWER_OFF" })); + EXPECT_CALL(*impl, commandPolyscopeVersion()).WillOnce(testing::Return(DashboardResponse{ true, "5.6.0", {} })); + EXPECT_CALL(*impl, commandRobotMode()) + .WillOnce(testing::Return(DashboardResponse{ true, "Robotmode: POWER_OFF", {} })); EXPECT_CALL(*impl, commandGetLoadedProgram()) - .WillOnce(testing::Return(DashboardResponse{ true, "Loaded program: wait_program.urp" })); + .WillOnce(testing::Return(DashboardResponse{ true, "Loaded program: wait_program.urp", {} })); EXPECT_CALL(*impl, commandProgramState()) - .WillOnce(testing::Return(DashboardResponse{ true, "STOPPED wait_program.urp" })); + .WillOnce(testing::Return(DashboardResponse{ true, "STOPPED wait_program.urp", {} })); EXPECT_CALL(*impl, commandSaveLog()).WillOnce(testing::Return(SUCCESS_RESPONSE)); EXPECT_TRUE(dashboard_client_->commandAddToLog("Testing Log:")); @@ -247,9 +249,9 @@ TEST_F(DashboardClientTest, version_specific_calls) EXPECT_TRUE(dashboard_client_->connect()); const auto impl = dashboard_client_->getImplPtr(); EXPECT_CALL(*impl, commandSafetyStatus()) - .WillOnce(testing::Return(DashboardResponse{ true, "Safety status: NORMAL" })); + .WillOnce(testing::Return(DashboardResponse{ true, "Safety status: NORMAL", {} })); EXPECT_CALL(*impl, commandSetUserRole("PROGRAMMER")).WillOnce(testing::Return(SUCCESS_RESPONSE)); - EXPECT_CALL(*impl, commandGetUserRole()).WillOnce(testing::Return(DashboardResponse{ true, "PROGRAMMER" })); + EXPECT_CALL(*impl, commandGetUserRole()).WillOnce(testing::Return(DashboardResponse{ true, "PROGRAMMER", {} })); std::string msg, user_role; EXPECT_TRUE(dashboard_client_->commandSafetyStatus(msg)); @@ -287,7 +289,7 @@ TEST_F(DashboardClientTest, operational_mode) const auto impl = dashboard_client_->getImplPtr(); EXPECT_CALL(*impl, commandSetOperationalMode("AUTOMATIC")).WillOnce(testing::Return(SUCCESS_RESPONSE)); - EXPECT_CALL(*impl, commandGetOperationalMode()).WillOnce(testing::Return(DashboardResponse{ true, "AUTOMATIC" })); + EXPECT_CALL(*impl, commandGetOperationalMode()).WillOnce(testing::Return(DashboardResponse{ true, "AUTOMATIC", {} })); EXPECT_CALL(*impl, commandClearOperationalMode()).WillOnce(testing::Return(SUCCESS_RESPONSE)); EXPECT_CALL(*impl, commandIsInRemoteControl()) .WillOnce(testing::Return(DashboardResponse{ true, "false", { { "remote_control", false } } })); @@ -337,7 +339,7 @@ TEST_F(DashboardClientTest, set_receive_timeout) { timeval expected_tv; expected_tv.tv_sec = 30; - expected_tv.tv_usec = 0.0; + expected_tv.tv_usec = 0; dashboard_client_->setReceiveTimeout(expected_tv); EXPECT_TRUE(dashboard_client_->connect()); diff --git a/tests/test_pipeline.cpp b/tests/test_pipeline.cpp index ca2368d6d..8f85c8f85 100644 --- a/tests/test_pipeline.cpp +++ b/tests/test_pipeline.cpp @@ -165,9 +165,9 @@ TEST_F(PipelineTest, get_product_from_running_pipeline) if (rtde_interface::DataPackage* data = dynamic_cast(urpackage.get())) { double timestamp; - double expected_timestamp = 7103.8579; + double expected_timestamp = 7103.858; data->getData("timestamp", timestamp); - EXPECT_FLOAT_EQ(timestamp, expected_timestamp); + EXPECT_DOUBLE_EQ(timestamp, expected_timestamp); } else { @@ -229,8 +229,8 @@ TEST_F(PipelineTest, consumer_pipeline) EXPECT_LT(count, max_retries); // Test that the package was consumed - double expected_timestamp = 7103.8579; - EXPECT_FLOAT_EQ(consumer.timestamp, expected_timestamp); + double expected_timestamp = 7103.858; + EXPECT_DOUBLE_EQ(consumer.timestamp, expected_timestamp); pipeline_->stop(); } diff --git a/tests/test_producer.cpp b/tests/test_producer.cpp index 9d9a398f4..55741bdcc 100644 --- a/tests/test_producer.cpp +++ b/tests/test_producer.cpp @@ -109,7 +109,7 @@ TEST_F(ProducerTest, get_data_package) { double timestamp; data->getData("timestamp", timestamp); - EXPECT_FLOAT_EQ(timestamp, 7103.86); + EXPECT_DOUBLE_EQ(timestamp, 7103.858); } else { diff --git a/tests/test_reverse_interface.cpp b/tests/test_reverse_interface.cpp index 7e1e42baf..33a72e327 100644 --- a/tests/test_reverse_interface.cpp +++ b/tests/test_reverse_interface.cpp @@ -484,10 +484,19 @@ TEST_F(ReverseInterfaceTest, deprecated_set_keep_alive_count) // Test that it works to set the keepalive count using the deprecated function int keep_alive_count = 10; -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#ifdef _MSC_VER +# pragma warning(push) +# pragma warning(disable : 4996) +#else +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif reverse_interface_->setKeepaliveCount(keep_alive_count); -#pragma GCC diagnostic pop +#ifdef _MSC_VER +# pragma warning(pop) +#else +# pragma GCC diagnostic pop +#endif int32_t expected_read_timeout = 20 * keep_alive_count; urcl::vector6d_t pos = { 0, 0, 0, 0, 0, 0 }; diff --git a/tests/test_robot_receive_timeout.cpp b/tests/test_robot_receive_timeout.cpp index 4bf574e00..31edd8381 100644 --- a/tests/test_robot_receive_timeout.cpp +++ b/tests/test_robot_receive_timeout.cpp @@ -53,9 +53,9 @@ TEST(RobotReceiveTimeout, empty_milliseconds_configuration) TEST(RobotReceiveTimeout, seconds_configuration) { - float timeout = 0.1; + float timeout = 0.1f; RobotReceiveTimeout robot_receive_timeout = RobotReceiveTimeout::sec(timeout); - const int expected_timeout = timeout * 1000; // Convert to milliseconds + const int expected_timeout = static_cast(timeout * 1000); // Convert to milliseconds EXPECT_EQ(robot_receive_timeout.getAsMilliseconds().count(), expected_timeout); } diff --git a/tests/test_rtde_parser.cpp b/tests/test_rtde_parser.cpp index 44e1f18a4..3c11b96d4 100644 --- a/tests/test_rtde_parser.cpp +++ b/tests/test_rtde_parser.cpp @@ -210,7 +210,7 @@ TEST(rtde_parser, data_package) data->getData("timestamp", timestamp); data->getData("target_speed_fraction", target_speed_fraction); - EXPECT_FLOAT_EQ(timestamp, 16412.2); + EXPECT_DOUBLE_EQ(timestamp, 16412.206); EXPECT_EQ(target_speed_fraction, 1); } else @@ -271,10 +271,19 @@ TEST(rtde_parser, test_deprecated_parse_method) std::vector> products; { comm::BinParser bp(raw_data, sizeof(raw_data)); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#ifdef __GNUC__ +# pragma GCC diagnostic push +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#elif defined(_MSC_VER) +# pragma warning(push) +# pragma warning(disable : 4996) +#endif parser.parse(bp, products); -#pragma GCC diagnostic pop +#ifdef __GNUC__ +# pragma GCC diagnostic pop +#elif defined(_MSC_VER) +# pragma warning(pop) +#endif } EXPECT_EQ(products.size(), 1); @@ -285,7 +294,7 @@ TEST(rtde_parser, test_deprecated_parse_method) data->getData("timestamp", timestamp); data->getData("target_speed_fraction", target_speed_fraction); - EXPECT_FLOAT_EQ(timestamp, 16412.2); + EXPECT_DOUBLE_EQ(timestamp, 16412.206); EXPECT_EQ(target_speed_fraction, 1); } else diff --git a/tests/test_rtde_writer.cpp b/tests/test_rtde_writer.cpp index 37d450828..b95e9f088 100644 --- a/tests/test_rtde_writer.cpp +++ b/tests/test_rtde_writer.cpp @@ -65,7 +65,7 @@ class RTDEWriterTest : public ::testing::Test server_.reset(); } - void messageCallback(const socket_t filedescriptor, char* buffer, int nbytesrecv) + void messageCallback([[maybe_unused]] const socket_t filedescriptor, char* buffer, int nbytesrecv) { std::lock_guard lk(message_mutex_); uint8_t* buf = reinterpret_cast(buffer); diff --git a/tests/test_stream.cpp b/tests/test_stream.cpp index 853228bb6..1cc735005 100644 --- a/tests/test_stream.cpp +++ b/tests/test_stream.cpp @@ -58,7 +58,7 @@ class StreamTest : public ::testing::Test } // callback functions for the tcp server - void messageCallback(const socket_t filedescriptor, char* buffer, size_t nbytesrecv) + void messageCallback([[maybe_unused]] const socket_t filedescriptor, char* buffer, size_t nbytesrecv) { std::lock_guard lk(message_mutex_); read_ = nbytesrecv; diff --git a/tests/test_tcp_server.cpp b/tests/test_tcp_server.cpp index 5e28e032b..d85994216 100644 --- a/tests/test_tcp_server.cpp +++ b/tests/test_tcp_server.cpp @@ -91,7 +91,7 @@ class TCPServerTest : public ::testing::Test connection_callback_ = true; } - void disconnectionCallback(const socket_t filedescriptor) + void disconnectionCallback([[maybe_unused]] const socket_t filedescriptor) { std::lock_guard lk(disconnect_mutex_); client_fd_ = INVALID_SOCKET; @@ -99,7 +99,7 @@ class TCPServerTest : public ::testing::Test disconnection_callback_ = true; } - void messageCallback(const socket_t filedescriptor, char* buffer) + void messageCallback([[maybe_unused]] const socket_t filedescriptor, char* buffer) { std::lock_guard lk(message_mutex_); message_ = std::string(buffer); @@ -310,15 +310,15 @@ TEST_F(TCPServerTest, client_connections) // Test that we can connect multiple clients Client client1(port_); EXPECT_TRUE(waitForConnectionCallback()); - int client1_fd = client_fd_; + socket_t client1_fd = client_fd_; Client client2(port_); EXPECT_TRUE(waitForConnectionCallback()); - int client2_fd = client_fd_; + socket_t client2_fd = client_fd_; Client client3(port_); EXPECT_TRUE(waitForConnectionCallback()); - int client3_fd = client_fd_; + socket_t client3_fd = client_fd_; // Test that the correct clients are disconnected on the server side. client1.close(); diff --git a/tests/test_tcp_socket.cpp b/tests/test_tcp_socket.cpp index 5e71b885c..f3a6fe9bf 100644 --- a/tests/test_tcp_socket.cpp +++ b/tests/test_tcp_socket.cpp @@ -35,7 +35,11 @@ // This file adds a test for a deprecated function. To avoid a compiler warning in CI (where we want // to treat warnings as errors) we suppress the warning inside this file. -#pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#ifdef _MSC_VER +# pragma warning(disable : 4996) +#else +# pragma GCC diagnostic ignored "-Wdeprecated-declarations" +#endif #include #include #include "ur_client_library/types.h" @@ -63,7 +67,7 @@ class TCPSocketTest : public ::testing::Test } // callback functions for the tcp server - void messageCallback(const socket_t filedescriptor, char* buffer) + void messageCallback([[maybe_unused]] const socket_t filedescriptor, char* buffer) { std::lock_guard lk(message_mutex_); received_message_ = std::string(buffer); @@ -302,16 +306,14 @@ TEST_F(TCPSocketTest, read_on_connected_socket) TEST_F(TCPSocketTest, get_socket_fd) { - // When the client is not connected to any socket the fd should be -1 - int expected_fd = -1; - int actual_fd = client_->getSocketFD(); + socket_t expected_fd = INVALID_SOCKET; + socket_t actual_fd = client_->getSocketFD(); EXPECT_EQ(expected_fd, actual_fd); client_->setup(); actual_fd = client_->getSocketFD(); - // When the client has connected to the socket the file descriptor should be different from -1 EXPECT_NE(expected_fd, actual_fd); client_->close(); diff --git a/tests/test_trajectory_point_interface.cpp b/tests/test_trajectory_point_interface.cpp index 1cdf05ffb..72e1db5fa 100644 --- a/tests/test_trajectory_point_interface.cpp +++ b/tests/test_trajectory_point_interface.cpp @@ -277,7 +277,7 @@ class TrajectoryPointInterfaceTest : public ::testing::Test (double)spl.blend_radius_or_spline_type / control::TrajectoryPointInterface::MULT_TIME, (double)spl.acc[1] / control::TrajectoryPointInterface::MULT_JOINTSTATE, (double)spl.acc[0] / control::TrajectoryPointInterface::MULT_JOINTSTATE, - round((double)spl.acc[2] / control::TrajectoryPointInterface::MULT_JOINTSTATE)); + static_cast(round((double)spl.acc[2] / control::TrajectoryPointInterface::MULT_JOINTSTATE))); } else { @@ -485,8 +485,8 @@ TEST_F(TrajectoryPointInterfaceTest, write_goal_time) TEST_F(TrajectoryPointInterfaceTest, write_acceleration_velocity) { urcl::vector6d_t send_positions = { 0, 0, 0, 0, 0, 0 }; - float send_move_acceleration = 0.123; - float send_move_velocity = 0.456; + float send_move_acceleration = 0.123f; + float send_move_velocity = 0.456f; float send_goal_time = 0.5; traj_point_interface_->writeTrajectoryPoint(&send_positions, send_move_acceleration, send_move_velocity, send_goal_time, 0, 0); @@ -611,7 +611,7 @@ TEST_F(TrajectoryPointInterfaceTest, send_movec) double blend_radius = 0.5; double acceleration = 0.7; double velocity = 0.7; - double mode = 1; + int32_t mode = 1; auto primitive = std::make_shared(send_via, send_target, blend_radius, acceleration, velocity, mode); From cf8c7b764c6cca465f47186efa019f7d678325e2 Mon Sep 17 00:00:00 2001 From: urrsk <41109954+urrsk@users.noreply.github.com> Date: Mon, 16 Mar 2026 12:08:09 +0100 Subject: [PATCH 2/3] Apply pr feedback --- .github/workflows/alpine-build.yml | 2 +- .github/workflows/ci.yml | 3 ++- .github/workflows/win-build.yml | 3 +-- CMakeLists.txt | 10 +++++++++- examples/CMakeLists.txt | 6 ------ include/ur_client_library/control/reverse_interface.h | 6 +++--- include/ur_client_library/ur/instruction_executor.h | 2 +- include/ur_client_library/ur/ur_driver.h | 2 +- src/control/reverse_interface.cpp | 3 +-- src/control/trajectory_point_interface.cpp | 3 +-- src/ur/dashboard_client.cpp | 5 ++--- src/ur/dashboard_client_implementation_g5.cpp | 5 ++--- src/ur/instruction_executor.cpp | 2 +- tests/CMakeLists.txt | 6 ------ tests/test_reverse_interface.cpp | 4 ++-- tests/test_trajectory_point_interface.cpp | 4 ++-- 16 files changed, 29 insertions(+), 37 deletions(-) diff --git a/.github/workflows/alpine-build.yml b/.github/workflows/alpine-build.yml index 165da77a8..6317d4309 100644 --- a/.github/workflows/alpine-build.yml +++ b/.github/workflows/alpine-build.yml @@ -19,7 +19,7 @@ jobs: run: apk add --no-cache build-base cmake linux-headers git - uses: actions/checkout@v6 - name: configure - run: mkdir build && cd build && cmake .. -DBUILDING_TESTS=1 + run: mkdir build && cd build && cmake .. -DBUILDING_TESTS=1 -DCMAKE_COMPILE_WARNING_AS_ERROR=ON - name: build run: cmake --build build --config Debug - name: test diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 1f03e8d50..3d6486cee 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -66,8 +66,9 @@ jobs: -DINTEGRATION_TESTS=1 -DWITH_ASAN=ON -DPRIMARY_CLIENT_STRICT_PARSING=ON + -DCMAKE_COMPILE_WARNING_AS_ERROR=ON env: - CXXFLAGS: -g -O2 -fprofile-arcs -ftest-coverage + CXXFLAGS: -g -O2 -fprofile-arcs -ftest-coverage CFLAGS: -g -O2 -fprofile-arcs -ftest-coverage LDFLAGS: -fprofile-arcs -ftest-coverage - name: build diff --git a/.github/workflows/win-build.yml b/.github/workflows/win-build.yml index 1896dd953..077420613 100644 --- a/.github/workflows/win-build.yml +++ b/.github/workflows/win-build.yml @@ -16,8 +16,7 @@ jobs: steps: - uses: actions/checkout@v6 - name: configure - run: mkdir build && cd build && cmake .. -DBUILDING_TESTS=1 - #run: mkdir build && cd build && cmake .. -DBUILDING_TESTS=1 -DINTEGRATION_TESTS=1 + run: mkdir build && cd build && cmake .. -DBUILDING_TESTS=1 -DCMAKE_COMPILE_WARNING_AS_ERROR=ON - name: build run: cmake --build build --config Debug - name: test diff --git a/CMakeLists.txt b/CMakeLists.txt index 40eae1eab..ab7a83a9d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -71,7 +71,6 @@ if(MSVC) target_link_libraries(urcl ws2_32) else() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -pedantic") - target_compile_options(urcl PRIVATE -Wall -Wextra -Werror) # GCC 13-15 have a false positive -Wmaybe-uninitialized in headers # (https://gcc.gnu.org/bugzilla/show_bug.cgi?id=105562). @@ -115,6 +114,15 @@ if(CMAKE_THREAD_LIBS_INIT) target_link_libraries(urcl PUBLIC "${CMAKE_THREAD_LIBS_INIT}") endif() +# When warnings are treated as errors, also enable high warning level for all targets +if(CMAKE_COMPILE_WARNING_AS_ERROR) + if(MSVC) + add_compile_options(/W4) + else() + add_compile_options(-Wall -Wextra) + endif() +endif() + ## ## Build testing if enabled by option ## diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index f61f48d65..b7da3567d 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -3,12 +3,6 @@ project(ur_driver_examples) # find_package(ur_client_library REQUIRED) -if(MSVC) - add_compile_options(/W4 /WX) # High warning level, treat warnings as errors -else() - add_compile_options(-Wall -Wextra -Werror) -endif() - add_executable(driver_example full_driver.cpp) target_link_libraries(driver_example ur_client_library::urcl) diff --git a/include/ur_client_library/control/reverse_interface.h b/include/ur_client_library/control/reverse_interface.h index 994521ca6..c0bef8e34 100644 --- a/include/ur_client_library/control/reverse_interface.h +++ b/include/ur_client_library/control/reverse_interface.h @@ -166,7 +166,7 @@ class ReverseInterface * \returns A unique handler ID for the registered callback. This can be used to unregister the * callback later. */ - uint32_t registerDisconnectionCallback(std::function disconnection_fun) + uint32_t registerDisconnectionCallback(std::function disconnection_fun) { disconnect_callbacks_.push_back({ next_disconnect_callback_id_, disconnection_fun }); return next_disconnect_callback_id_++; @@ -180,7 +180,7 @@ class ReverseInterface void unregisterDisconnectionCallback(const uint32_t handler_id) { disconnect_callbacks_.remove_if( - [handler_id](const HandlerFunction& h) { return h.id == handler_id; }); + [handler_id](const HandlerFunction& h) { return h.id == handler_id; }); } /*! @@ -213,7 +213,7 @@ class ReverseInterface virtual void messageCallback(const socket_t filedescriptor, char* buffer, int nbytesrecv); - std::list> disconnect_callbacks_; + std::list> disconnect_callbacks_; uint32_t next_disconnect_callback_id_ = 0; socket_t client_fd_; comm::TCPServer server_; diff --git a/include/ur_client_library/ur/instruction_executor.h b/include/ur_client_library/ur/instruction_executor.h index ecec111d8..f5fd28956 100644 --- a/include/ur_client_library/ur/instruction_executor.h +++ b/include/ur_client_library/ur/instruction_executor.h @@ -189,7 +189,7 @@ class InstructionExecutor protected: void trajDoneCallback(const urcl::control::TrajectoryResult& result); - void trajDisconnectCallback(const int filedescriptor); + void trajDisconnectCallback(const socket_t filedescriptor); uint32_t traj_done_callback_handler_id_; uint32_t disconnected_handler_id_; diff --git a/include/ur_client_library/ur/ur_driver.h b/include/ur_client_library/ur/ur_driver.h index 4e93e7814..157a50375 100644 --- a/include/ur_client_library/ur/ur_driver.h +++ b/include/ur_client_library/ur/ur_driver.h @@ -1000,7 +1000,7 @@ class UrDriver * * \returns The ID of the callback that can be used to unregister the callback later. */ - uint32_t registerTrajectoryInterfaceDisconnectedCallback(std::function fun) + uint32_t registerTrajectoryInterfaceDisconnectedCallback(std::function fun) { return trajectory_interface_->registerDisconnectionCallback(fun); } diff --git a/src/control/reverse_interface.cpp b/src/control/reverse_interface.cpp index 5606dc5a8..0cd8ad928 100644 --- a/src/control/reverse_interface.cpp +++ b/src/control/reverse_interface.cpp @@ -250,8 +250,7 @@ void ReverseInterface::disconnectionCallback(const socket_t filedescriptor) } for (auto handler : disconnect_callbacks_) { - // socket_t is UINT_PTR on Windows, so a narrowing cast is needed to match the callback signature - handler.function(static_cast(filedescriptor)); + handler.function(filedescriptor); } } diff --git a/src/control/trajectory_point_interface.cpp b/src/control/trajectory_point_interface.cpp index ff1b1f8e5..75484af17 100644 --- a/src/control/trajectory_point_interface.cpp +++ b/src/control/trajectory_point_interface.cpp @@ -277,8 +277,7 @@ void TrajectoryPointInterface::disconnectionCallback(const socket_t filedescript URCL_LOG_DEBUG("Connection to trajectory interface dropped."); for (auto handler : disconnect_callbacks_) { - // socket_t is UINT_PTR on Windows, so a narrowing cast is needed to match the callback signature - handler.function(static_cast(filedescriptor)); + handler.function(filedescriptor); } client_fd_ = INVALID_SOCKET; } diff --git a/src/ur/dashboard_client.cpp b/src/ur/dashboard_client.cpp index 6065f8cdd..e40530d56 100644 --- a/src/ur/dashboard_client.cpp +++ b/src/ur/dashboard_client.cpp @@ -117,8 +117,7 @@ bool DashboardClient::waitForReply(const std::string& command, const std::string return false; } -bool DashboardClient::retryCommand(const std::string& requestCommand, - [[maybe_unused]] const std::string& requestExpectedResponse, +bool DashboardClient::retryCommand(const std::string& requestCommand, const std::string& requestExpectedResponse, const std::string& waitRequest, const std::string& waitExpectedResponse, const std::chrono::duration timeout, const std::chrono::duration retry_period) @@ -126,7 +125,7 @@ bool DashboardClient::retryCommand(const std::string& requestCommand, std::chrono::duration time_done(0); do { - impl_->sendRequest(requestCommand); + impl_->sendRequest(requestCommand, requestExpectedResponse); time_done += retry_period; if (waitForReply(waitRequest, waitExpectedResponse, retry_period)) diff --git a/src/ur/dashboard_client_implementation_g5.cpp b/src/ur/dashboard_client_implementation_g5.cpp index 6f2d65bb2..9b853b495 100644 --- a/src/ur/dashboard_client_implementation_g5.cpp +++ b/src/ur/dashboard_client_implementation_g5.cpp @@ -400,8 +400,7 @@ std::string DashboardClientImplG5::retryCommandString(const std::string& request "' within the timeout. Last response was: " + response); } -bool DashboardClientImplG5::retryCommand(const std::string& requestCommand, - [[maybe_unused]] const std::string& requestExpectedResponse, +bool DashboardClientImplG5::retryCommand(const std::string& requestCommand, const std::string& requestExpectedResponse, const std::string& waitRequest, const std::string& waitExpectedResponse, const std::chrono::duration timeout, const std::chrono::duration retry_period) @@ -409,7 +408,7 @@ bool DashboardClientImplG5::retryCommand(const std::string& requestCommand, std::chrono::duration time_done(0); do { - sendRequest(requestCommand); + sendRequest(requestCommand, requestExpectedResponse); time_done += retry_period; if (waitForReply(waitRequest, waitExpectedResponse, retry_period)) diff --git a/src/ur/instruction_executor.cpp b/src/ur/instruction_executor.cpp index c18e4670d..ab6243e31 100644 --- a/src/ur/instruction_executor.cpp +++ b/src/ur/instruction_executor.cpp @@ -44,7 +44,7 @@ void urcl::InstructionExecutor::trajDoneCallback(const urcl::control::Trajectory trajectory_running_ = false; } } -void urcl::InstructionExecutor::trajDisconnectCallback([[maybe_unused]] const int filedescriptor) +void urcl::InstructionExecutor::trajDisconnectCallback([[maybe_unused]] const socket_t filedescriptor) { URCL_LOG_INFO("Trajectory disconnect"); std::unique_lock lock(trajectory_result_mutex_); diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 582d8e3da..99db15ba2 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -14,12 +14,6 @@ FetchContent_Declare( set(gtest_force_shared_crt ON CACHE BOOL "" FORCE) FetchContent_MakeAvailable(googletest) -if(MSVC) - add_compile_options(/W4 /WX) # High warning level, treat warnings as errors -else() - add_compile_options(-Wall -Wextra -Werror) -endif() - add_executable(fake_rtde_server fake_rtde_server.cpp fake_rtde_server_main.cpp) target_link_libraries(fake_rtde_server PRIVATE ur_client_library::urcl) diff --git a/tests/test_reverse_interface.cpp b/tests/test_reverse_interface.cpp index 33a72e327..80595db5d 100644 --- a/tests/test_reverse_interface.cpp +++ b/tests/test_reverse_interface.cpp @@ -523,12 +523,12 @@ TEST_F(ReverseInterfaceTest, disconnected_callbacks_are_called) // Register disconnection callbacks int disconnection_callback_id_1 = - reverse_interface_->registerDisconnectionCallback([&disconnect_called_1](const int fd) { + reverse_interface_->registerDisconnectionCallback([&disconnect_called_1](const socket_t fd) { std::cout << "Disconnection 1 callback called with fd: " << fd << std::endl; disconnect_called_1 = true; }); int disconnection_callback_id_2 = - reverse_interface_->registerDisconnectionCallback([&disconnect_called_2](const int fd) { + reverse_interface_->registerDisconnectionCallback([&disconnect_called_2](const socket_t fd) { std::cout << "Disconnection 2 callback called with fd: " << fd << std::endl; disconnect_called_2 = true; }); diff --git a/tests/test_trajectory_point_interface.cpp b/tests/test_trajectory_point_interface.cpp index 72e1db5fa..292018a0b 100644 --- a/tests/test_trajectory_point_interface.cpp +++ b/tests/test_trajectory_point_interface.cpp @@ -639,12 +639,12 @@ TEST_F(TrajectoryPointInterfaceTest, disconnected_callbacks_are_called_correctly // Register disconnection callbacks int disconnection_callback_id_1 = - traj_point_interface_->registerDisconnectionCallback([&disconnect_called_1](const int fd) { + traj_point_interface_->registerDisconnectionCallback([&disconnect_called_1](const socket_t fd) { std::cout << "Disconnection 1 callback called with fd: " << fd << std::endl; disconnect_called_1 = true; }); int disconnection_callback_id_2 = - traj_point_interface_->registerDisconnectionCallback([&disconnect_called_2](const int fd) { + traj_point_interface_->registerDisconnectionCallback([&disconnect_called_2](const socket_t fd) { std::cout << "Disconnection 2 callback called with fd: " << fd << std::endl; disconnect_called_2 = true; }); From 475cea29636a68edf7bfde6e9ff8268a2d7dc5a1 Mon Sep 17 00:00:00 2001 From: urrsk <41109954+urrsk@users.noreply.github.com> Date: Wed, 18 Mar 2026 09:31:39 +0100 Subject: [PATCH 3/3] Add CMake option --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index ab7a83a9d..40bc80396 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,6 +9,7 @@ endif() option(WITH_ASAN "Compile with address sanitizer support" OFF) option(BUILD_SHARED_LIBS "Build using shared libraries" ON) option(PRIMARY_CLIENT_STRICT_PARSING_ "Enable strict parsing of primary client messages" OFF) +option(CMAKE_COMPILE_WARNING_AS_ERROR "Treat even small warnings as errors" OFF) if(MSVC) set(BUILD_SHARED_LIBS OFF)