Skip to content

Commit e879f68

Browse files
committed
Export platform build flags to dependent catkin projects
1 parent 2cdbbe6 commit e879f68

File tree

6 files changed

+20
-14
lines changed

6 files changed

+20
-14
lines changed

industrial_robot_client/CMakeLists.txt

-5
Original file line numberDiff line numberDiff line change
@@ -8,10 +8,6 @@ find_package(catkin REQUIRED COMPONENTS roscpp std_msgs sensor_msgs
88

99
find_package(Boost REQUIRED COMPONENTS system thread)
1010

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-
1511
set(SRC_FILES src/joint_relay_handler.cpp
1612
src/robot_status_relay_handler.cpp
1713
src/joint_trajectory_downloader.cpp
@@ -31,7 +27,6 @@ catkin_package(
3127
industrial_utils
3228
INCLUDE_DIRS include
3329
LIBRARIES ${PROJECT_NAME}_dummy
34-
CFG_EXTRAS issue46_workaround.cmake
3530
)
3631

3732

simple_message/CMakeLists.txt

+6-6
Original file line numberDiff line numberDiff line change
@@ -9,11 +9,11 @@ set(ROS_BUILD_STATIC_LIBS true)
99
set(ROS_BUILD_SHARED_LIBS false)
1010

1111
# 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)
1717

1818
set(SRC_FILES src/byte_array.cpp
1919
src/simple_message.cpp
@@ -71,7 +71,7 @@ catkin_package(
7171
CATKIN_DEPENDS roscpp industrial_msgs
7272
INCLUDE_DIRS include
7373
LIBRARIES ${PROJECT_NAME}_dummy
74-
CFG_EXTRAS issue46_workaround.cmake
74+
CFG_EXTRAS platform_build_flags.cmake issue46_workaround.cmake
7575
)
7676

7777

Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
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)

simple_message/include/simple_message/socket/simple_socket.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@
4242
#include "smpl_msg_connection.h"
4343
#endif
4444

45-
#ifdef LINUXSOCKETS
45+
#ifdef LINUX_SOCKETS
4646

4747
#include "sys/socket.h"
4848
#include "arpa/inet.h"

simple_message/include/simple_message/socket/tcp_socket.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@
4040
#include "shared_types.h"
4141
#endif
4242

43-
#ifdef LINUXSOCKETS
43+
#ifdef LINUX_SOCKETS
4444
#include "sys/socket.h"
4545
#include "netdb.h"
4646
#include "arpa/inet.h"

simple_message/include/simple_message/socket/udp_socket.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@
4242
#include "smpl_msg_connection.h"
4343
#endif
4444

45-
#ifdef LINUXSOCKETS
45+
#ifdef LINUX_SOCKETS
4646
#include "sys/socket.h"
4747
#include "arpa/inet.h"
4848
#include "string.h"

0 commit comments

Comments
 (0)