diff --git a/patch/ros-jazzy-moveit-planners-stomp.win.patch b/patch/ros-jazzy-moveit-planners-stomp.win.patch deleted file mode 100644 index 42de8099..00000000 --- a/patch/ros-jazzy-moveit-planners-stomp.win.patch +++ /dev/null @@ -1,13 +0,0 @@ -diff --git a/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp b/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp -index b910cd3393..97350bec21 100644 ---- a/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp -+++ b/moveit_planners/stomp/include/stomp_moveit/cost_functions.hpp -@@ -168,7 +168,7 @@ CostFn getCostFunctionFromStateValidator(const StateValidatorFn& state_validator - const long kernel_start = mu - static_cast(sigma) * 4; - const long kernel_end = mu + static_cast(sigma) * 4; - const long bounded_kernel_start = std::max(0l, kernel_start); -- const long bounded_kernel_end = std::min(values.cols() - 1, kernel_end); -+ const long bounded_kernel_end = std::min(static_cast(values.cols()) - 1, kernel_end); - for (auto j = bounded_kernel_start; j <= bounded_kernel_end; ++j) - { - costs(j) = std::exp(-std::pow(j - mu, 2) / (2 * std::pow(sigma, 2))) / (sigma * std::sqrt(2 * M_PI)); diff --git a/patch/ros-jazzy-moveit-ros-benchmarks.win.patch b/patch/ros-jazzy-moveit-ros-benchmarks.win.patch index ac75eeb8..f1c22a16 100644 --- a/patch/ros-jazzy-moveit-ros-benchmarks.win.patch +++ b/patch/ros-jazzy-moveit-ros-benchmarks.win.patch @@ -1,7 +1,7 @@ diff --git a/moveit_ros/benchmarks/CMakeLists.txt b/moveit_ros/benchmarks/CMakeLists.txt index 58538a70b9..7b60f0a220 100644 ---- a/moveit_ros/benchmarks/CMakeLists.txt -+++ b/moveit_ros/benchmarks/CMakeLists.txt +--- a/CMakeLists.txt ++++ b/CMakeLists.txt @@ -34,6 +34,7 @@ set_target_properties(moveit_ros_benchmarks if(WIN32) set(EXTRA_LIB ws2_32.lib) diff --git a/patch/ros-jazzy-moveit-ros-warehouse.win.patch b/patch/ros-jazzy-moveit-ros-warehouse.win.patch index d515f792..c321805f 100644 --- a/patch/ros-jazzy-moveit-ros-warehouse.win.patch +++ b/patch/ros-jazzy-moveit-ros-warehouse.win.patch @@ -1,7 +1,7 @@ -diff --git a/moveit_ros/warehouse/CMakeLists.txt b/moveit_ros/warehouse/CMakeLists.txt +diff --git a/warehouse/CMakeLists.txt b/CMakeLists.txt index 825f6b11c7..e68e1d866b 100644 ---- a/moveit_ros/warehouse/CMakeLists.txt -+++ b/moveit_ros/warehouse/CMakeLists.txt +--- a/CMakeLists.txt ++++ b/CMakeLists.txt @@ -56,7 +56,7 @@ target_link_libraries(moveit_warehouse_broadcast moveit_warehouse) add_executable(moveit_save_to_warehouse src/save_to_warehouse.cpp) ament_target_dependencies(moveit_save_to_warehouse diff --git a/patch/ros-jazzy-moveit-servo.win.patch b/patch/ros-jazzy-moveit-servo.win.patch deleted file mode 100644 index 31101065..00000000 --- a/patch/ros-jazzy-moveit-servo.win.patch +++ /dev/null @@ -1,59 +0,0 @@ - -diff --git a/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp b/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp -index 8a6507c569..9c5d0805a6 100644 ---- a/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp -+++ b/moveit_ros/moveit_servo/demos/servo_keyboard_input.cpp -@@ -45,8 +45,12 @@ - #include - #include - #include -+#ifndef WIN32 - #include - #include -+#else -+#include -+#endif - - // Define used keys - namespace -@@ -88,6 +92,7 @@ class KeyboardReader - public: - KeyboardReader() : file_descriptor_(0) - { -+#ifndef WIN32 - // get the console in raw mode - tcgetattr(file_descriptor_, &cooked_); - struct termios raw; -@@ -97,23 +102,32 @@ class KeyboardReader - raw.c_cc[VEOL] = 1; - raw.c_cc[VEOF] = 2; - tcsetattr(file_descriptor_, TCSANOW, &raw); -+#endif - } - void readOne(char* c) - { -+#ifndef WIN32 - int rc = read(file_descriptor_, c, 1); - if (rc < 0) - { - throw std::runtime_error("read failed"); - } -+#else -+ *c = static_cast(_getch()); -+#endif - } - void shutdown() - { -+#ifndef WIN32 - tcsetattr(file_descriptor_, TCSANOW, &cooked_); -+#endif - } - - private: - int file_descriptor_; -+#ifndef WIN32 - struct termios cooked_; -+#endif - }; - - // Converts key-presses to Twist or Jog commands for Servo, in lieu of a controller diff --git a/patch/ros-jazzy-moveit-setup-core-plugins.win.patch b/patch/ros-jazzy-moveit-setup-core-plugins.win.patch new file mode 100644 index 00000000..b7ac58b4 --- /dev/null +++ b/patch/ros-jazzy-moveit-setup-core-plugins.win.patch @@ -0,0 +1,13 @@ +diff --git a/src/start_screen_widget.cpp b/src/start_screen_widget.cpp +index edd73eb3c..d88a90eaa 100644 +--- a/src/start_screen_widget.cpp ++++ b/src/start_screen_widget.cpp +@@ -79,7 +79,7 @@ void StartScreenWidget::onInit() + right_image_label_ = new QLabel(this); + auto image_path = getSharePath("moveit_setup_assistant") / "resources/MoveIt_Setup_Assistant2.png"; + +- if (right_image_->load(image_path.c_str())) ++ if (right_image_->load(QString::fromStdString(image_path.string()))) + { + right_image_label_->setPixmap(QPixmap::fromImage(*right_image_)); + right_image_label_->setMinimumHeight(384); // size of right_image_label_ diff --git a/patch/ros-jazzy-pilz-industrial-motion-planner.win.patch b/patch/ros-jazzy-pilz-industrial-motion-planner.win.patch deleted file mode 100644 index 791a162e..00000000 --- a/patch/ros-jazzy-pilz-industrial-motion-planner.win.patch +++ /dev/null @@ -1,36 +0,0 @@ -diff --git a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.hpp b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.hpp -index 89bd99f1da..b135d1c3d3 100644 ---- a/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.hpp -+++ b/moveit_planners/pilz_industrial_motion_planner/include/joint_limits_copy/joint_limits_rosparam.hpp -@@ -32,7 +32,7 @@ namespace - template - void declareParameterTemplate(const rclcpp::Node::SharedPtr& node, const std::string& name, T default_value) - { -- if (not node->has_parameter(name)) -+ if (!node->has_parameter(name)) - { - node->declare_parameter(name, default_value); - } - -diff --git a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp -index c1fccdf3bd..01a7f11b59 100644 ---- a/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp -+++ b/moveit_planners/pilz_industrial_motion_planner/src/trajectory_functions.cpp -@@ -117,7 +117,7 @@ bool pilz_industrial_motion_planner::computePoseIK(const planning_scene::Plannin - const double timeout) - { - Eigen::Isometry3d pose_eigen; -- tf2::convert(pose, pose_eigen); -+ tf2::fromMsg(pose, pose_eigen); - return computePoseIK(scene, group_name, link_name, pose_eigen, frame_id, seed, solution, check_self_collision, - timeout); - } -@@ -591,7 +591,7 @@ bool pilz_industrial_motion_planner::isStateColliding(const planning_scene::Plan - void normalizeQuaternion(geometry_msgs::msg::Quaternion& quat) - { - tf2::Quaternion q; -- tf2::convert(quat, q); -+ tf2::fromMsg(quat, q); - quat = tf2::toMsg(q.normalized()); - } - diff --git a/patch/ros-jazzy-ur-calibration.win.patch b/patch/ros-jazzy-ur-calibration.win.patch index 59340b8b..0c7dd43e 100644 --- a/patch/ros-jazzy-ur-calibration.win.patch +++ b/patch/ros-jazzy-ur-calibration.win.patch @@ -1,7 +1,7 @@ -diff --git a/ur_calibration/CMakeLists.txt b/ur_calibration/CMakeLists.txt -index 0b17e4d5f..31c63864f 100644 ---- a/ur_calibration/CMakeLists.txt -+++ b/ur_calibration/CMakeLists.txt +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 0b17e4d5..9ace1736 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt @@ -2,10 +2,9 @@ cmake_minimum_required(VERSION 3.5) project(ur_calibration) @@ -15,12 +15,7 @@ index 0b17e4d5f..31c63864f 100644 if(NOT CMAKE_CONFIGURATION_TYPES AND NOT CMAKE_BUILD_TYPE) message("${PROJECT_NAME}: You did not request a specific build type: selecting 'RelWithDebInfo'.") - -diff --git a/ur_calibration/CMakeLists.txt b/ur_calibration/CMakeLists.txt -index 0b17e4d5f..8b8bbf871 100644 ---- a/ur_calibration/CMakeLists.txt -+++ b/ur_calibration/CMakeLists.txt -@@ -37,7 +37,7 @@ target_include_directories(calibration +@@ -37,7 +36,7 @@ target_include_directories(calibration ${YAML_CPP_INCLUDE_DIRS} ) target_link_libraries(calibration diff --git a/patch/ros-jazzy-ur-client-library.win.patch b/patch/ros-jazzy-ur-client-library.win.patch new file mode 100644 index 00000000..0e9389c2 --- /dev/null +++ b/patch/ros-jazzy-ur-client-library.win.patch @@ -0,0 +1,207 @@ +diff --git a/include/ur_client_library/comm/bin_parser.h b/include/ur_client_library/comm/bin_parser.h +index e13aba6..6de673e 100644 +--- a/include/ur_client_library/comm/bin_parser.h ++++ b/include/ur_client_library/comm/bin_parser.h +@@ -21,7 +21,6 @@ + #pragma once + + #include +-#include + #include + #include + #include +@@ -29,6 +28,7 @@ + #include + #include + #include ++#include "ur_client_library/endian.h" + #include "ur_client_library/log.h" + #include "ur_client_library/types.h" + #include "ur_client_library/exceptions.h" +diff --git a/include/ur_client_library/comm/package_serializer.h b/include/ur_client_library/comm/package_serializer.h +index 7745da9..ebf128e 100644 +--- a/include/ur_client_library/comm/package_serializer.h ++++ b/include/ur_client_library/comm/package_serializer.h +@@ -29,7 +29,7 @@ + #ifndef UR_CLIENT_LIBRARY_PACKAGE_SERIALIZER_H_INCLUDED + #define UR_CLIENT_LIBRARY_PACKAGE_SERIALIZER_H_INCLUDED + +-#include ++#include "ur_client_library/endian.h" + #include + + namespace urcl +diff --git a/include/ur_client_library/control/reverse_interface.h b/include/ur_client_library/control/reverse_interface.h +index e68acd9..aa9d1c1 100644 +--- a/include/ur_client_library/control/reverse_interface.h ++++ b/include/ur_client_library/control/reverse_interface.h +@@ -29,13 +29,13 @@ + #ifndef UR_CLIENT_LIBRARY_REVERSE_INTERFACE_H_INCLUDED + #define UR_CLIENT_LIBRARY_REVERSE_INTERFACE_H_INCLUDED + ++#include "ur_client_library/endian.h" + #include "ur_client_library/comm/tcp_server.h" + #include "ur_client_library/comm/control_mode.h" + #include "ur_client_library/types.h" + #include "ur_client_library/log.h" + #include "ur_client_library/ur/robot_receive_timeout.h" + #include +-#include + #include + + namespace urcl +diff --git a/include/ur_client_library/endian.h b/include/ur_client_library/endian.h +new file mode 100644 +index 0000000..9c5500b +--- /dev/null ++++ b/include/ur_client_library/endian.h +@@ -0,0 +1,103 @@ ++// ++// endian.h ++// ++// https://gist.github.com/panzi/6856583 ++// ++// I, Mathias Panzenböck, place this file hereby into the public domain. Use ++// it at your own risk for whatever you like. In case there are ++// jurisdictions that don't support putting things in the public domain you ++// can also consider it to be "dual licensed" under the BSD, MIT and Apache ++// licenses, if you want to. This code is trivial anyway. Consider it an ++// example on how to get the endian conversion functions on different ++// platforms. ++ ++#ifndef PORTABLE_ENDIAN_H__ ++#define PORTABLE_ENDIAN_H__ ++ ++// Byte order ++#if defined(linux) || defined(__linux) || defined(__linux__) || defined(__CYGWIN__) ++# include ++#elif defined(__APPLE__) ++# include ++ ++# define htobe16(x) OSSwapHostToBigInt16(x) ++# define htole16(x) OSSwapHostToLittleInt16(x) ++# define be16toh(x) OSSwapBigToHostInt16(x) ++# define le16toh(x) OSSwapLittleToHostInt16(x) ++ ++# define htobe32(x) OSSwapHostToBigInt32(x) ++# define htole32(x) OSSwapHostToLittleInt32(x) ++# define be32toh(x) OSSwapBigToHostInt32(x) ++# define le32toh(x) OSSwapLittleToHostInt32(x) ++ ++# define htobe64(x) OSSwapHostToBigInt64(x) ++# define htole64(x) OSSwapHostToLittleInt64(x) ++# define be64toh(x) OSSwapBigToHostInt64(x) ++# define le64toh(x) OSSwapLittleToHostInt64(x) ++ ++# define __BYTE_ORDER BYTE_ORDER ++# define __BIG_ENDIAN BIG_ENDIAN ++# define __LITTLE_ENDIAN LITTLE_ENDIAN ++# define __PDP_ENDIAN PDP_ENDIAN ++#elif defined(__OpenBSD__) ++# include ++#elif defined(__NetBSD__) || defined(__FreeBSD__) || defined(__DragonFly__) ++# include ++ ++# define be16toh(x) betoh16(x) ++# define le16toh(x) letoh16(x) ++ ++# define be32toh(x) betoh32(x) ++# define le32toh(x) letoh32(x) ++ ++# define be64toh(x) betoh64(x) ++# define le64toh(x) letoh64(x) ++#elif defined(_WIN32) ++# include ++# if BYTE_ORDER == LITTLE_ENDIAN ++# if defined(_MSC_VER) ++# define htobe16(x) _byteswap_ushort(x) ++# define htole16(x) (x) ++# define be16toh(x) _byteswap_ushort(x) ++# define le16toh(x) (x) ++ ++# define htobe32(x) _byteswap_ulong(x) ++# define htole32(x) (x) ++# define be32toh(x) _byteswap_ulong(x) ++# define le32toh(x) (x) ++ ++# define htobe64(x) _byteswap_uint64(x) ++# define htole64(x) (x) ++# define be64toh(x) _byteswap_uint64(x) ++# define le64toh(x) (x) ++# elif defined(__GNUC__) || defined(__clang__) ++# define htobe16(x) __builtin_bswap16(x) ++# define htole16(x) (x) ++# define be16toh(x) __builtin_bswap16(x) ++# define le16toh(x) (x) ++ ++# define htobe32(x) __builtin_bswap32(x) ++# define htole32(x) (x) ++# define be32toh(x) __builtin_bswap32(x) ++# define le32toh(x) (x) ++ ++# define htobe64(x) __builtin_bswap64(x) ++# define htole64(x) (x) ++# define be64toh(x) __builtin_bswap64(x) ++# define le64toh(x) (x) ++# else ++# error Compiler is not supported ++# endif ++# else ++# error Byte order is not supported ++# endif ++ ++# define __BYTE_ORDER BYTE_ORDER ++# define __BIG_ENDIAN BIG_ENDIAN ++# define __LITTLE_ENDIAN LITTLE_ENDIAN ++# define __PDP_ENDIAN PDP_ENDIAN ++#else ++# error Platform is not supported ++#endif ++ ++#endif // PORTABLE_ENDIAN_H__ +diff --git a/include/ur_client_library/primary/package_header.h b/include/ur_client_library/primary/package_header.h +index cd64bda..b5c2754 100644 +--- a/include/ur_client_library/primary/package_header.h ++++ b/include/ur_client_library/primary/package_header.h +@@ -32,7 +32,7 @@ + + #include + #include +-#include ++#include "ur_client_library/endian.h" + #include "ur_client_library/types.h" + + namespace urcl +diff --git a/include/ur_client_library/rtde/package_header.h b/include/ur_client_library/rtde/package_header.h +index f910a08..066e004 100644 +--- a/include/ur_client_library/rtde/package_header.h ++++ b/include/ur_client_library/rtde/package_header.h +@@ -31,7 +31,7 @@ + #define UR_CLIENT_LIBRARY_RTDE__HEADER_H_INCLUDED + + #include +-#include ++#include "ur_client_library/endian.h" + #include "ur_client_library/types.h" + #include "ur_client_library/comm/package_serializer.h" + +diff --git a/src/comm/tcp_socket.cpp b/src/comm/tcp_socket.cpp +index 778e5f1..55f60c8 100644 +--- a/src/comm/tcp_socket.cpp ++++ b/src/comm/tcp_socket.cpp +@@ -20,7 +20,6 @@ + * limitations under the License. + */ + +-#include + #include + #include + #include +@@ -31,6 +30,7 @@ + # include + #endif + ++#include "ur_client_library/endian.h" + #include "ur_client_library/log.h" + #include "ur_client_library/comm/tcp_socket.h" + diff --git a/patch/ros-jazzy-ur-controllers.win.patch b/patch/ros-jazzy-ur-controllers.win.patch index 3fefcac0..0a57f3bd 100644 --- a/patch/ros-jazzy-ur-controllers.win.patch +++ b/patch/ros-jazzy-ur-controllers.win.patch @@ -1,7 +1,7 @@ -diff --git a/ur_controllers/CMakeLists.txt b/ur_controllers/CMakeLists.txt -index 79a89acbd..9e4584419 100644 ---- a/ur_controllers/CMakeLists.txt -+++ b/ur_controllers/CMakeLists.txt +diff --git a/CMakeLists.txt b/CMakeLists.txt +index 3db6e822..52fb849b 100644 +--- a/CMakeLists.txt ++++ b/CMakeLists.txt @@ -4,6 +4,7 @@ project(ur_controllers) if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra) @@ -14,9 +14,9 @@ index 79a89acbd..9e4584419 100644 ${THIS_PACKAGE_INCLUDE_DEPENDS} ) --target_compile_options(${PROJECT_NAME} PRIVATE -Wpedantic -Werror=return-type) +-target_compile_options(${PROJECT_NAME} PRIVATE -Wpedantic -Werror) +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") -+ target_compile_options(${PROJECT_NAME} PRIVATE -Wpedantic -Werror=return-type) ++ target_compile_options(${PROJECT_NAME} PRIVATE -Wpedantic -Werror) +endif() # prevent pluginlib from using boost diff --git a/pkg_additional_info.yaml b/pkg_additional_info.yaml new file mode 100644 index 00000000..d8850172 --- /dev/null +++ b/pkg_additional_info.yaml @@ -0,0 +1,2 @@ +ur_client_library: + build_number: 6