-
-
Notifications
You must be signed in to change notification settings - Fork 74
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
cfe65c1
commit ea5ee05
Showing
4 changed files
with
105 additions
and
1 deletion.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,54 @@ | ||
diff --git a/tf/CMakeLists.txt b/tf/CMakeLists.txt | ||
index c418afce..483bbb75 100644 | ||
--- a/CMakeLists.txt | ||
+++ b/CMakeLists.txt | ||
@@ -1,16 +1,9 @@ | ||
cmake_minimum_required(VERSION 3.0.2) | ||
project(tf) | ||
|
||
-include(CheckCXXCompilerFlag) | ||
-unset(COMPILER_SUPPORTS_CXX11 CACHE) | ||
-if(MSVC) | ||
- # https://docs.microsoft.com/en-us/cpp/build/reference/std-specify-language-standard-version | ||
- # MSVC has c++14 enabled by default, no need to specify c++11 | ||
-else() | ||
- check_cxx_compiler_flag(-std=c++11 COMPILER_SUPPORTS_CXX11) | ||
- if(COMPILER_SUPPORTS_CXX11) | ||
- add_compile_options(-std=c++11) | ||
- endif() | ||
+# Melodic default to C++14 | ||
+if(NOT CMAKE_CXX_STANDARD) | ||
+ set(CMAKE_CXX_STANDARD 14) | ||
endif() | ||
|
||
find_package(catkin REQUIRED COMPONENTS | ||
diff --git a/tf/include/tf/tf.h b/tf/include/tf/tf.h | ||
index 934aabf6..ecc43349 100644 | ||
--- a/include/tf/tf.h | ||
+++ b/include/tf/tf.h | ||
@@ -49,6 +49,12 @@ | ||
#include <tf2_ros/buffer.h> | ||
#include <ros/macros.h> | ||
|
||
+// Boost winapi.h includes winerror.h. Subsequently NO_ERROR gets defined | ||
+// and which conflicts with tf::NO_ERROR. | ||
+#if defined(_WIN32) && defined(NO_ERROR) | ||
+ #undef NO_ERROR | ||
+#endif | ||
+ | ||
// Import/export for windows dll's and visibility for gcc shared libraries. | ||
#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries | ||
#ifdef tf_EXPORTS // we are building a shared lib/dll | ||
diff --git a/tf/src/tf.cpp b/tf/src/tf.cpp | ||
index ac9ad0da..13f027c4 100644 | ||
--- a/src/tf.cpp | ||
+++ b/src/tf.cpp | ||
@@ -30,7 +30,6 @@ | ||
/** \author Tully Foote */ | ||
|
||
#include "tf/tf.h" | ||
-#include <sys/time.h> | ||
#include "ros/assert.h" | ||
#include "ros/ros.h" | ||
#include <angles/angles.h> | ||
|
File renamed without changes.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,48 @@ | ||
diff --git a/CMakeLists.txt b/CMakeLists.txt | ||
index cb01537..69c8aac 100644 | ||
--- a/CMakeLists.txt | ||
+++ b/CMakeLists.txt | ||
@@ -19,6 +19,8 @@ find_package(catkin REQUIRED COMPONENTS | ||
) | ||
find_package(Boost REQUIRED COMPONENTS thread) | ||
|
||
+find_package(Threads) | ||
+ | ||
catkin_python_setup() | ||
|
||
catkin_package( | ||
@@ -49,6 +51,9 @@ add_library(${PROJECT_NAME} | ||
) | ||
add_dependencies(${PROJECT_NAME} ${catkin_EXPORTED_TARGETS}) | ||
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES}) | ||
+if(UNIX AND NOT APPLE) | ||
+ target_link_libraries(${PROJECT_NAME} rt) | ||
+endif() | ||
|
||
# buffer_server executable | ||
add_executable(${PROJECT_NAME}_buffer_server src/buffer_server_main.cpp) | ||
@@ -57,6 +62,7 @@ target_link_libraries(${PROJECT_NAME}_buffer_server | ||
${PROJECT_NAME} | ||
${catkin_LIBRARIES} | ||
${Boost_LIBRARIES} | ||
+ ${CMAKE_THREAD_LIBS_INIT} | ||
) | ||
set_target_properties(${PROJECT_NAME}_buffer_server | ||
PROPERTIES OUTPUT_NAME buffer_server | ||
@@ -70,6 +76,7 @@ add_dependencies(${PROJECT_NAME}_static_transform_publisher ${catkin_EXPORTED_TA | ||
target_link_libraries(${PROJECT_NAME}_static_transform_publisher | ||
${PROJECT_NAME} | ||
${catkin_LIBRARIES} | ||
+ ${CMAKE_THREAD_LIBS_INIT} | ||
) | ||
set_target_properties(${PROJECT_NAME}_static_transform_publisher | ||
PROPERTIES OUTPUT_NAME static_transform_publisher | ||
@@ -88,7 +91,7 @@ install(TARGETS | ||
${PROJECT_NAME}_buffer_server ${PROJECT_NAME}_static_transform_publisher | ||
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} | ||
- RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} | ||
+ RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION} | ||
) | ||
|
||
install(DIRECTORY include/${PROJECT_NAME}/ |