-
-
Notifications
You must be signed in to change notification settings - Fork 74
/
Copy pathros-noetic-microstrain-inertial-driver.patch
40 lines (35 loc) · 2.22 KB
/
ros-noetic-microstrain-inertial-driver.patch
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
diff --git a/CMakeLists.txt b/CMakeLists.txt
index d8338e7..21160f7 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -71,7 +71,8 @@ else()
endif()
# Set some general CMake flags
-set(CMAKE_C_FLAGS "-Wno-implicit-function-declaration -Wno-incompatible-pointer-types -Wno-unused-variable -Wno-format -fno-builtin-memcpy")
+set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -Wno-implicit-function-declaration -Wno-incompatible-pointer-types -Wno-unused-variable -Wno-format -Wno-missing-template-arg-list-after-template-kw -fno-builtin-memcpy")
+set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wno-implicit-function-declaration -Wno-incompatible-pointer-types -Wno-unused-variable -Wno-format -Wno-missing-template-arg-list-after-template-kw -fno-builtin-memcpy")
# Include the MIP SDK source
add_subdirectory("${MIP_SDK_DIR}" EXCLUDE_FROM_ALL)
@@ -207,11 +208,7 @@ set_source_files_properties(${COMMON_SRC_DIR}/services.cpp PROPERTIES COMPILE_OP
add_definitions(-DMICROSTRAIN_DRIVER_VERSION="${DRIVER_GIT_VERSION}")
# Let the code know if it is being compiled with ROS1 or ROS2
-if(DEFINED ENV{ROS_VERSION})
- add_definitions(-DMICROSTRAIN_ROS_VERSION=$ENV{ROS_VERSION})
-else()
- message(FATAL_ERROR "ROS_VERSION environment variable is not set.")
-endif()
+add_definitions(-DMICROSTRAIN_ROS_VERSION=1)
# Allow the MSCL include directory to be accessed
include_directories(${MSCL_INC_PATH} ${BOOST_INC_PATH})
diff --git a/microstrain_inertial_driver_common/include/microstrain_inertial_driver_common/utils/ros_compat.h b/microstrain_inertial_driver_common/include/microstrain_inertial_driver_common/utils/ros_compat.h
index b6fe468..dca949e 100644
--- a/microstrain_inertial_driver_common/include/microstrain_inertial_driver_common/utils/ros_compat.h
+++ b/microstrain_inertial_driver_common/include/microstrain_inertial_driver_common/utils/ros_compat.h
@@ -501,7 +501,7 @@ template <class ClassType>
RosTimerType createTimer(RosNodeType* node, double hz, void (ClassType::*fp)(), ClassType* obj)
{
return std::make_shared<::ros::Timer>(
- node->template createTimer(ros::Duration(1.0 / hz), [=](const ros::TimerEvent& event) { (obj->*fp)(); }));
+ node->createTimer(::ros::Duration(1.0 / hz), [obj, fp](const ::ros::TimerEvent&) { (obj->*fp)(); }));
}
/**