File tree 6 files changed +20
-14
lines changed
include/simple_message/socket
6 files changed +20
-14
lines changed Original file line number Diff line number Diff line change @@ -8,10 +8,6 @@ find_package(catkin REQUIRED COMPONENTS roscpp std_msgs sensor_msgs
8
8
9
9
find_package (Boost REQUIRED COMPONENTS system thread)
10
10
11
- # The definition is copied from the CMakeList for the simple_message package.
12
- add_definitions (-DROS=1) #build using ROS libraries
13
- add_definitions (-DLINUXSOCKETS=1) #build using LINUX SOCKETS libraries
14
-
15
11
set (SRC_FILES src/joint_relay_handler.cpp
16
12
src/robot_status_relay_handler.cpp
17
13
src/joint_trajectory_downloader.cpp
@@ -31,7 +27,6 @@ catkin_package(
31
27
industrial_utils
32
28
INCLUDE_DIRS include
33
29
LIBRARIES ${PROJECT_NAME} _dummy
34
- CFG_EXTRAS issue46_workaround.cmake
35
30
)
36
31
37
32
Original file line number Diff line number Diff line change @@ -9,11 +9,11 @@ set(ROS_BUILD_STATIC_LIBS true)
9
9
set (ROS_BUILD_SHARED_LIBS false )
10
10
11
11
# The simple_message library is designed to cross compile on Ubuntu
12
- # and various robot controllers. This requires conditionally compiling
13
- # certain functions and headers. The definition below enables compiling
14
- # for a ROS node.
15
- add_definitions (-DROS=1) #build using ROS libraries
16
- add_definitions (-DLINUXSOCKETS=1) #use linux sockets for communication
12
+ # and various robot controllers. This requires conditionally compiling
13
+ # certain functions and headers. The default flags in the file included
14
+ # here enable compiling for a ROS node. This file is also exported to
15
+ # dependent packages via the `catkin_package` commmand.
16
+ include (cmake/platform_build_flags.cmake)
17
17
18
18
set (SRC_FILES src/byte_array.cpp
19
19
src/simple_message.cpp
@@ -71,7 +71,7 @@ catkin_package(
71
71
CATKIN_DEPENDS roscpp industrial_msgs
72
72
INCLUDE_DIRS include
73
73
LIBRARIES ${PROJECT_NAME} _dummy
74
- CFG_EXTRAS issue46_workaround.cmake
74
+ CFG_EXTRAS platform_build_flags.cmake issue46_workaround.cmake
75
75
)
76
76
77
77
Original file line number Diff line number Diff line change
1
+ # Flags that control the conditional compilation of this library for use on different platforms. The
2
+ # defaults set here will be exported to dependent projects via catkin. Dependent projects can use
3
+ # cmake's `remove_definitions` command to change these defaults if desired.
4
+
5
+ #Include code that interfaces with ROS
6
+ add_definitions (-DROS)
7
+
8
+ #Control which platform's underlying networking library is used by this package.
9
+ #The package will not build unless one (and only one) of these definitions is set.
10
+ add_definitions (-DLINUX_SOCKETS)
11
+ #add_definitions(-DMOTOPLUS)
Original file line number Diff line number Diff line change 42
42
#include " smpl_msg_connection.h"
43
43
#endif
44
44
45
- #ifdef LINUXSOCKETS
45
+ #ifdef LINUX_SOCKETS
46
46
47
47
#include " sys/socket.h"
48
48
#include " arpa/inet.h"
Original file line number Diff line number Diff line change 40
40
#include " shared_types.h"
41
41
#endif
42
42
43
- #ifdef LINUXSOCKETS
43
+ #ifdef LINUX_SOCKETS
44
44
#include " sys/socket.h"
45
45
#include " netdb.h"
46
46
#include " arpa/inet.h"
Original file line number Diff line number Diff line change 42
42
#include " smpl_msg_connection.h"
43
43
#endif
44
44
45
- #ifdef LINUXSOCKETS
45
+ #ifdef LINUX_SOCKETS
46
46
#include " sys/socket.h"
47
47
#include " arpa/inet.h"
48
48
#include " string.h"
You can’t perform that action at this time.
0 commit comments