Skip to content

Commit

Permalink
patch update
Browse files Browse the repository at this point in the history
Signed-off-by: wep21 <[email protected]>
  • Loading branch information
wep21 committed Jan 31, 2025
1 parent f0be491 commit 1cf7711
Showing 1 changed file with 15 additions and 146 deletions.
161 changes: 15 additions & 146 deletions patch/ros-humble-ur-client-library.patch
Original file line number Diff line number Diff line change
@@ -1,133 +1,8 @@
diff --git a/include/ur_client_library/portable_endian.h b/include/ur_client_library/portable_endian.h
new file mode 100644
index 0000000..2b43378
--- /dev/null
+++ b/include/ur_client_library/portable_endian.h
@@ -0,0 +1,118 @@
+// "License": Public Domain
+// 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__
+
+#if (defined(_WIN16) || defined(_WIN32) || defined(_WIN64)) && !defined(__WINDOWS__)
+
+# define __WINDOWS__
+
+#endif
+
+#if defined(__linux__) || defined(__CYGWIN__)
+
+# include <endian.h>
+
+#elif defined(__APPLE__)
+
+# include <libkern/OSByteOrder.h>
+
+# 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 <sys/endian.h>
+
+#elif defined(__NetBSD__) || defined(__FreeBSD__) || defined(__DragonFly__)
+
+# include <sys/endian.h>
+
+# 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(__WINDOWS__)
+
+# include <winsock2.h>
+# include <sys/param.h>
+
+# if BYTE_ORDER == LITTLE_ENDIAN
+
+# define htobe16(x) htons(x)
+# define htole16(x) (x)
+# define be16toh(x) ntohs(x)
+# define le16toh(x) (x)
+
+# define htobe32(x) htonl(x)
+# define htole32(x) (x)
+# define be32toh(x) ntohl(x)
+# define le32toh(x) (x)
+
+# define htobe64(x) htonll(x)
+# define htole64(x) (x)
+# define be64toh(x) ntohll(x)
+# define le64toh(x) (x)
+
+# elif BYTE_ORDER == BIG_ENDIAN
+
+ /* that would be xbox 360 */
+# define htobe16(x) (x)
+# define htole16(x) __builtin_bswap16(x)
+# define be16toh(x) (x)
+# define le16toh(x) __builtin_bswap16(x)
+
+# define htobe32(x) (x)
+# define htole32(x) __builtin_bswap32(x)
+# define be32toh(x) (x)
+# define le32toh(x) __builtin_bswap32(x)
+
+# define htobe64(x) (x)
+# define htole64(x) __builtin_bswap64(x)
+# define be64toh(x) (x)
+# define le64toh(x) __builtin_bswap64(x)
+
+# else
+
+# error byte order 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 not supported
+
+#endif
+
+#endif

diff --git a/CMakeLists.txt b/CMakeLists.txt
index e95db8f..2620abd 100644
index 3c41f99..04ecc7b 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -63,6 +63,9 @@ endif()
@@ -61,6 +61,9 @@ endif()
if(CMAKE_THREAD_LIBS_INIT)
target_link_libraries(urcl PUBLIC "${CMAKE_THREAD_LIBS_INIT}")
endif()
Expand All @@ -137,17 +12,8 @@ index e95db8f..2620abd 100644

##
## Build testing if enabled by option
@@ -75,7 +78,7 @@ else()
endif()


-target_link_libraries(urcl INTERFACE ${Boost_Libraries})
+target_link_libraries(urcl INTERFACE ${Boost_LIBRARIES})

add_subdirectory(examples)

diff --git a/include/ur_client_library/comm/bin_parser.h b/include/ur_client_library/comm/bin_parser.h
index cad7c63..91af811 100644
index e13aba6..83f8e6c 100644
--- a/include/ur_client_library/comm/bin_parser.h
+++ b/include/ur_client_library/comm/bin_parser.h
@@ -21,7 +21,6 @@
Expand Down Expand Up @@ -181,12 +47,12 @@ index 7745da9..ded500a 100644
namespace urcl
{
diff --git a/include/ur_client_library/control/reverse_interface.h b/include/ur_client_library/control/reverse_interface.h
index d1e5707..e06e723 100644
index 9919dbd..275bba3 100644
--- a/include/ur_client_library/control/reverse_interface.h
+++ b/include/ur_client_library/control/reverse_interface.h
@@ -34,8 +34,8 @@
#include "ur_client_library/types.h"
@@ -35,8 +35,8 @@
#include "ur_client_library/log.h"
#include "ur_client_library/ur/robot_receive_timeout.h"
#include <cstring>
-#include <endian.h>
#include <condition_variable>
Expand Down Expand Up @@ -221,28 +87,31 @@ index f910a08..eb509ea 100644
#include "ur_client_library/comm/package_serializer.h"

diff --git a/src/comm/tcp_socket.cpp b/src/comm/tcp_socket.cpp
index 586cb72..cee3961 100644
index 8803664..1d92880 100644
--- a/src/comm/tcp_socket.cpp
+++ b/src/comm/tcp_socket.cpp
@@ -21,11 +21,11 @@
@@ -21,7 +21,6 @@
*/

#include <arpa/inet.h>
-#include <endian.h>
#include <netinet/tcp.h>
#include <unistd.h>
#include <cstring>
#include <chrono>
@@ -29,6 +28,7 @@
#include <sstream>
#include <thread>

+#include "ur_client_library/portable_endian.h"
#include "ur_client_library/log.h"
#include "ur_client_library/comm/tcp_socket.h"

@@ -45,7 +45,9 @@ void TCPSocket::setOptions(int socket_fd)
@@ -48,7 +48,9 @@ void TCPSocket::setupOptions()
{
int flag = 1;
setsockopt(socket_fd, IPPROTO_TCP, TCP_NODELAY, &flag, sizeof(int));
setsockopt(socket_fd_, IPPROTO_TCP, TCP_NODELAY, &flag, sizeof(int));
+#ifndef __APPLE__
setsockopt(socket_fd, IPPROTO_TCP, TCP_QUICKACK, &flag, sizeof(int));
setsockopt(socket_fd_, IPPROTO_TCP, TCP_QUICKACK, &flag, sizeof(int));
+#endif

if (recv_timeout_ != nullptr)
Expand Down

0 comments on commit 1cf7711

Please sign in to comment.