Skip to content

Commit

Permalink
Merge pull request #262 from gavanderhoorn/rebased_export_compiler_flags
Browse files Browse the repository at this point in the history
Rebased 190: export compiler flags
  • Loading branch information
gavanderhoorn authored Jun 22, 2021
2 parents ce04cae + 22bcc1c commit 3fe10f1
Show file tree
Hide file tree
Showing 13 changed files with 92 additions and 46 deletions.
27 changes: 20 additions & 7 deletions industrial_robot_client/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,6 @@ find_package(catkin REQUIRED COMPONENTS roscpp std_msgs sensor_msgs

find_package(Boost REQUIRED COMPONENTS system thread)

# The definition is copied from the CMakeList for the simple_message package.
add_definitions(-DROS=1) #build using ROS libraries
add_definitions(-DLINUXSOCKETS=1) #build using LINUX SOCKETS libraries

set(SRC_FILES src/joint_relay_handler.cpp
src/robot_status_relay_handler.cpp
src/joint_trajectory_downloader.cpp
Expand All @@ -31,11 +27,12 @@ catkin_package(
industrial_utils
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}_dummy
CFG_EXTRAS issue46_workaround.cmake
CFG_EXTRAS
issue46_workaround.cmake
platform_build_flags.cmake
)



include_directories(include
${catkin_INCLUDE_DIRS}
)
Expand Down Expand Up @@ -70,9 +67,13 @@ install(TARGETS ${PROJECT_NAME}_dummy DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATI

add_library(industrial_robot_client ${SRC_FILES})
target_link_libraries(industrial_robot_client simple_message)
target_compile_definitions(industrial_robot_client PUBLIC
${simple_message_DEFINITIONS})

add_library(industrial_robot_client_bswap ${SRC_FILES})
target_link_libraries(industrial_robot_client_bswap simple_message_bswap)
target_compile_definitions(industrial_robot_client_bswap PUBLIC
${simple_message_bswap_DEFINITIONS})

# The following executables(nodes) are for applications where the robot
# controller and pc have the same byte order (i.e. byte swapping NOT
Expand All @@ -84,20 +85,26 @@ target_link_libraries(robot_state
industrial_robot_client
simple_message
${catkin_LIBRARIES})
target_compile_definitions(robot_state PRIVATE
${simple_message_DEFINITIONS})

add_executable(motion_streaming_interface
src/generic_joint_streamer_node.cpp)
target_link_libraries(motion_streaming_interface
industrial_robot_client
simple_message
${catkin_LIBRARIES})
target_compile_definitions(motion_streaming_interface PRIVATE
${simple_message_DEFINITIONS})

add_executable(motion_download_interface
src/generic_joint_downloader_node.cpp)
target_link_libraries(motion_download_interface
industrial_robot_client
simple_message
${catkin_LIBRARIES})
target_compile_definitions(motion_download_interface PRIVATE
${simple_message_DEFINITIONS})

# The following executables(nodes) are for applications where the robot
# controller and pc have different same byte order (i.e. byte swapping IS
Expand All @@ -109,20 +116,26 @@ target_link_libraries(robot_state_bswap
industrial_robot_client_bswap
simple_message_bswap
${catkin_LIBRARIES})
target_compile_definitions(robot_state_bswap PRIVATE
${simple_message_bswap_DEFINITIONS})

add_executable(motion_streaming_interface_bswap
src/generic_joint_streamer_node.cpp)
target_link_libraries(motion_streaming_interface_bswap
industrial_robot_client_bswap
simple_message_bswap
${catkin_LIBRARIES})
target_compile_definitions(motion_streaming_interface_bswap PRIVATE
${simple_message_bswap_DEFINITIONS})

add_executable(motion_download_interface_bswap
src/generic_joint_downloader_node.cpp)
target_link_libraries(motion_download_interface_bswap
industrial_robot_client_bswap
simple_message_bswap
${catkin_LIBRARIES})
target_compile_definitions(motion_download_interface_bswap PRIVATE
${simple_message_bswap_DEFINITIONS})

# The following executables(nodes) interface with the robot controller
# at a higher level so there is no need to create two versions (one with
Expand All @@ -131,7 +144,7 @@ target_link_libraries(motion_download_interface_bswap
add_executable(joint_trajectory_action
src/generic_joint_trajectory_action_node.cpp
src/joint_trajectory_action.cpp)
target_link_libraries(joint_trajectory_action
target_link_libraries(joint_trajectory_action PRIVATE
industrial_robot_client ${catkin_LIBRARIES})

##########
Expand Down
7 changes: 7 additions & 0 deletions industrial_robot_client/cmake/platform_build_flags.cmake.in
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@

# industrial_robot_client doesn't have anything to add, but we must re-export
# the definitions from simple_message, so consumers of industrial_robot_client
# also get them.

set(industrial_robot_client_DEFINITIONS @simple_message_DEFINITIONS@)
set(industrial_robot_client_bswap_DEFINITIONS @simple_message_bswap_DEFINITIONS@)
49 changes: 29 additions & 20 deletions simple_message/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,6 @@ find_package(catkin REQUIRED COMPONENTS roscpp industrial_msgs)
set(ROS_BUILD_STATIC_LIBS true)
set(ROS_BUILD_SHARED_LIBS false)

# The simple_message library is designed to cross compile on Ubuntu
# and various robot controllers. This requires conditionally compiling
# certain functions and headers. The definition below enables compiling
# for a ROS node.
add_definitions(-DROS=1) #build using ROS libraries
add_definitions(-DLINUXSOCKETS=1) #use linux sockets for communication

set(SRC_FILES src/byte_array.cpp
src/simple_message.cpp
src/smpl_msg_connection.cpp
Expand Down Expand Up @@ -48,30 +41,36 @@ set(SRC_FILES src/byte_array.cpp

set(UTEST_SRC_FILES test/utest.cpp test/utest_message.cpp)

# The simple message make file builds two libraries: simple_message and
# simple_message_byte_swapping.
# The simple message make file builds three libraries: simple_message,
# simple_message_bswap and simple_message_float64.
#
# simple_message - is the default library. This library should be used
# when the target for the simple message is the same endian (i.e. both
# big-endian or little-endian). Intel based machines are little endian
#
# simple_message_byte_swapping - is an alternative library that can be used
# simple_message_bswap - is an alternative library that can be used
# when the target for simple message is a DIFFERENT endian AND when the target
# target cannot perform byte swapping (as is the case for some industrial
# controllers). This library performs byte swapping at the lowest load/unload
# levels.

#
# simple_message_float64 - another alternative which uses 8 byte floats instead
# of 4 byte floats (ie: double precision vs single precision).
# This variant changes the shared_float typedef everywhere to be 8 byte floats.
#
# NOTE: The libraries generated this package are not included in the catkin_package
# macro because libraries must be explicitly linked in projects that depend on this
# package. If this is not done (and these libraries were exported), then multiple
# library definitions (normal - simple_message and byteswapped - simple_message_bswap)
# are both included (this is bad).
# library definitions (normal - simple_message, byteswapped - simple_message_bswap
# and simple_message_float64) are all included (this is bad).

catkin_package(
CATKIN_DEPENDS roscpp industrial_msgs
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}_dummy
CFG_EXTRAS issue46_workaround.cmake
CFG_EXTRAS
issue46_workaround.cmake
platform_build_flags.cmake
)


Expand All @@ -98,37 +97,47 @@ install(TARGETS ${PROJECT_NAME}_dummy DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATI

# DEFAULT LIBRARY (SAME ENDIAN)
add_library(simple_message ${SRC_FILES})
# NOTE: keep these in-sync with the lists in 'cmake/platform_build_flags.cmake'.
# Yes, we could have used get_target_property(..) and then configure_file(..)
# (or Catkin's equivalent), but there is a low probably these will ever change
# again, so for now, manually managing it all is an OK trade-off
target_compile_definitions(simple_message PUBLIC
SIMPLE_MESSAGE_USE_ROS SIMPLE_MESSAGE_LINUX)
target_link_libraries(simple_message ${catkin_LIBRARIES})
add_dependencies(simple_message ${industrial_msgs_EXPORTED_TARGETS})

# ALTERNATIVE LIBRARY (DIFFERENT ENDIAN)
add_library(simple_message_bswap ${SRC_FILES})
set_target_properties(simple_message_bswap PROPERTIES COMPILE_DEFINITIONS "BYTE_SWAPPING")
# NOTE: keep these in-sync with the lists in 'cmake/platform_build_flags.cmake'
target_compile_definitions(simple_message_bswap PUBLIC
SIMPLE_MESSAGE_USE_ROS SIMPLE_MESSAGE_LINUX BYTE_SWAPPING)
target_link_libraries(simple_message_bswap ${catkin_LIBRARIES})
add_dependencies(simple_message_bswap ${industrial_msgs_EXPORTED_TARGETS})

# ALTERNATIVE LIBRARY (64-bit floats)
add_library(simple_message_float64 ${SRC_FILES})
set_target_properties(simple_message_float64 PROPERTIES COMPILE_DEFINITIONS "FLOAT64")
# NOTE: keep these in-sync with the lists in 'cmake/platform_build_flags.cmake'
target_compile_definitions(simple_message_float64 PUBLIC
SIMPLE_MESSAGE_USE_ROS SIMPLE_MESSAGE_LINUX FLOAT64)
target_link_libraries(simple_message_float64 ${catkin_LIBRARIES})
add_dependencies(simple_message_float64 ${industrial_msgs_EXPORTED_TARGETS})

if(CATKIN_ENABLE_TESTING)

catkin_add_gtest(utest ${UTEST_SRC_FILES})
set_target_properties(utest PROPERTIES COMPILE_DEFINITIONS "TEST_PORT_BASE=11000")
target_compile_definitions(utest PRIVATE TEST_PORT_BASE=11000)
target_link_libraries(utest simple_message)

catkin_add_gtest(utest_byte_swapping ${UTEST_SRC_FILES})
set_target_properties(utest_byte_swapping PROPERTIES COMPILE_DEFINITIONS "TEST_PORT_BASE=12000")
target_compile_definitions(utest_byte_swapping PRIVATE TEST_PORT_BASE=12000)
target_link_libraries(utest_byte_swapping simple_message_bswap)

catkin_add_gtest(utest_float64 ${UTEST_SRC_FILES})
set_target_properties(utest_float64 PROPERTIES COMPILE_DEFINITIONS "TEST_PORT_BASE=13000;FLOAT64")
target_compile_definitions(utest_float64 PRIVATE TEST_PORT_BASE=13000 FLOAT64)
target_link_libraries(utest_float64 simple_message_float64)

catkin_add_gtest(utest_udp ${UTEST_SRC_FILES})
set_target_properties(utest_udp PROPERTIES COMPILE_DEFINITIONS "TEST_PORT_BASE=15000;UDP_TEST")
target_compile_definitions(utest_udp PRIVATE TEST_PORT_BASE=15000 UDP_TEST)
target_link_libraries(utest_udp simple_message)

endif()
Expand Down
17 changes: 17 additions & 0 deletions simple_message/cmake/platform_build_flags.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# The simple_message library is designed to cross compile on Ubuntu
# and various robot controllers. This requires conditionally compiling
# certain functions and headers. The default flags in this file enable
# compiling for a ROS node. This file is also exported to dependent packages
# via the catkin_package(..) commmand.

# Note: these are the same set of defines passed to target_compile_definitions(..)
# in the simple_message/CMakeLists.txt. In order to keep things simple and
# deterministic, they are replicated here.

# with plain CMake, we'd use target_compile_definitions(..) and then
# target_link_libraries(..) with EXPORT(..)-ed targets, but that's not possible
# right now with Catkin, so we use this work-around.

set(simple_message_DEFINITIONS SIMPLE_MESSAGE_USE_ROS;SIMPLE_MESSAGE_LINUX)
set(simple_message_bswap_DEFINITIONS SIMPLE_MESSAGE_USE_ROS;SIMPLE_MESSAGE_LINUX;BYTE_SWAPPING)
set(simple_message_float64_DEFINITIONS SIMPLE_MESSAGE_USE_ROS;SIMPLE_MESSAGE_LINUX;FLOAT64)
6 changes: 3 additions & 3 deletions simple_message/include/simple_message/log_wrapper.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,11 @@
#ifndef LOG_WRAPPER_H_
#define LOG_WRAPPER_H_

#ifdef ROS
#ifdef SIMPLE_MESSAGE_USE_ROS
#include "ros/ros.h"
#endif

#ifdef MOTOPLUS
#ifdef SIMPLE_MESSAGE_MOTOPLUS
#include "motoPlus.h"
#endif

Expand All @@ -55,7 +55,7 @@ namespace log_wrapper


// Define ROS if this library will execute under ROS
#ifdef ROS
#ifdef SIMPLE_MESSAGE_USE_ROS

// The LOG_COMM redirects to debug in ROS because ROS has
// debug filtering tools that allow the communications messages
Expand Down
4 changes: 2 additions & 2 deletions simple_message/include/simple_message/robot_status.h
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ enum RobotMode
MANUAL = 1, AUTO = 2,
};

#ifdef ROS
#ifdef SIMPLE_MESSAGE_USE_ROS
int toROSMsgEnum(RobotModes::RobotMode mode);
#endif

Expand All @@ -85,7 +85,7 @@ enum TriState
TS_FALSE = 0, TS_OFF = 0, TS_DISABLED = 0, TS_LOW = 0
};

#ifdef ROS
#ifdef SIMPLE_MESSAGE_USE_ROS
int toROSMsgEnum(TriStates::TriState state);
#endif

Expand Down
4 changes: 2 additions & 2 deletions simple_message/include/simple_message/socket/simple_socket.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@
#include "smpl_msg_connection.h"
#endif

#ifdef LINUXSOCKETS
#ifdef SIMPLE_MESSAGE_LINUX

#include "sys/socket.h"
#include "arpa/inet.h"
Expand Down Expand Up @@ -73,7 +73,7 @@

#endif

#ifdef MOTOPLUS
#ifdef SIMPLE_MESSAGE_MOTOPLUS

#include "motoPlus.h"

Expand Down
4 changes: 2 additions & 2 deletions simple_message/include/simple_message/socket/tcp_socket.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,15 +40,15 @@
#include "shared_types.h"
#endif

#ifdef LINUXSOCKETS
#ifdef SIMPLE_MESSAGE_LINUX
#include "sys/socket.h"
#include "netdb.h"
#include "arpa/inet.h"
#include "string.h"
#include "unistd.h"
#endif

#ifdef MOTOPLUS
#ifdef SIMPLE_MESSAGE_MOTOPLUS
#include "motoPlus.h"
#endif

Expand Down
4 changes: 2 additions & 2 deletions simple_message/include/simple_message/socket/udp_socket.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,15 +42,15 @@
#include "smpl_msg_connection.h"
#endif

#ifdef LINUXSOCKETS
#ifdef SIMPLE_MESSAGE_LINUX
#include "sys/socket.h"
#include "arpa/inet.h"
#include "string.h"
#include "netdb.h"
#include "unistd.h"
#endif

#ifdef MOTOPLUS
#ifdef SIMPLE_MESSAGE_MOTOPLUS
#include "motoPlus.h"
#endif

Expand Down
6 changes: 3 additions & 3 deletions simple_message/src/message_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#include "simple_message.h"
#endif

#ifdef ROS
#ifdef SIMPLE_MESSAGE_USE_ROS
#include "ros/ros.h"
#else
#include "unistd.h"
Expand Down Expand Up @@ -171,7 +171,7 @@ void MessageManager::spinOnce()
int ms_per_clock;
void mySleep(int sec)
{
#ifdef MOTOPLUS
#ifdef SIMPLE_MESSAGE_MOTOPLUS
if (ms_per_clock <= 0)
ms_per_clock = mpGetRtc();

Expand All @@ -184,7 +184,7 @@ void mySleep(int sec)
void MessageManager::spin()
{
LOG_INFO("Entering message manager spin loop");
#ifdef ROS
#ifdef SIMPLE_MESSAGE_USE_ROS
while (ros::ok())
#else
while (true)
Expand Down
6 changes: 3 additions & 3 deletions simple_message/src/robot_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@
#include "log_wrapper.h"
#endif

#ifdef ROS
#ifdef SIMPLE_MESSAGE_USE_ROS
// Files below used to translate between ROS messages enums and
// enums defined in this file
#include "industrial_msgs/RobotMode.h"
Expand All @@ -55,7 +55,7 @@ namespace robot_status
namespace RobotModes
{

#ifdef ROS
#ifdef SIMPLE_MESSAGE_USE_ROS

int toROSMsgEnum(RobotModes::RobotMode mode)
{
Expand Down Expand Up @@ -83,7 +83,7 @@ int toROSMsgEnum(RobotModes::RobotMode mode)
namespace TriStates
{

#ifdef ROS
#ifdef SIMPLE_MESSAGE_USE_ROS

int toROSMsgEnum(TriStates::TriState state)
{
Expand Down
2 changes: 1 addition & 1 deletion simple_message/src/simple_message.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@
#include "log_wrapper.h"
#endif

#ifdef MOTOPLUS
#ifdef SIMPLE_MESSAGE_MOTOPLUS
#include "motoPlus.h"
#endif

Expand Down
Loading

0 comments on commit 3fe10f1

Please sign in to comment.