diff --git a/imu_monitor/CMakeLists.txt b/imu_monitor/CMakeLists.txt
index fcdc8c1..61b014c 100644
--- a/imu_monitor/CMakeLists.txt
+++ b/imu_monitor/CMakeLists.txt
@@ -1,5 +1,7 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 2.8.12)
+if(POLICY CMP0048)
+ cmake_policy(SET CMP0048 NEW)
+endif()
project(imu_monitor)
find_package(catkin REQUIRED)
diff --git a/imu_monitor/scripts/imu_monitor.py b/imu_monitor/scripts/imu_monitor.py
index 58e63fc..b55dd28 100755
--- a/imu_monitor/scripts/imu_monitor.py
+++ b/imu_monitor/scripts/imu_monitor.py
@@ -26,7 +26,9 @@ def __init__(self):
self.odom_sub = rospy.Subscriber('base_odometry/odometer', Odometer, self.odom_cb)
# diagnostics
- self.pub_diag = rospy.Publisher('/diagnostics', DiagnosticArray)
+ self.pub_diag = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size= 1)
+
+ self.diag_timer = rospy.Timer(rospy.Duration(1), self.publish_diagnostics)
def imu_cb(self, msg):
@@ -44,14 +46,16 @@ def odom_cb(self, msg):
self.start_time = rospy.Time.now()
self.start_angle = self.last_angle
self.dist = dist
-
+
# do imu test if possible
if rospy.Time.now() > self.start_time + rospy.Duration(10.0):
self.drift = fabs(self.start_angle - self.last_angle)*180/(pi*10)
self.start_time = rospy.Time.now()
self.start_angle = self.last_angle
self.last_measured = rospy.Time.now()
-
+
+ def publish_diagnostics(self, event):
+ with self.lock:
# publish diagnostics
d = DiagnosticArray()
d.header.stamp = rospy.Time.now()
@@ -77,7 +81,7 @@ def odom_cb(self, msg):
elif age < 3600:
last_measured = '%f minutes ago'%(age/60)
else:
- last_measured = '%f hours ago'%(age/3600)
+ last_measured = '%f hours ago'%(age/3600)
ds.values = [
KeyValue('Last measured', last_measured),
KeyValue('Drift (deg/sec)', str(drift)) ]
diff --git a/pr2_bringup/CMakeLists.txt b/pr2_bringup/CMakeLists.txt
index 694f110..95fbd64 100644
--- a/pr2_bringup/CMakeLists.txt
+++ b/pr2_bringup/CMakeLists.txt
@@ -1,5 +1,7 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 2.8.12)
+if(POLICY CMP0048)
+ cmake_policy(SET CMP0048 NEW)
+endif()
project(pr2_bringup)
# Load catkin and all dependencies required for this package
diff --git a/pr2_bringup/config/dualstereo_camera.launch b/pr2_bringup/config/dualstereo_camera.launch
index 356fecb..2ffc542 100644
--- a/pr2_bringup/config/dualstereo_camera.launch
+++ b/pr2_bringup/config/dualstereo_camera.launch
@@ -31,6 +31,7 @@
+
diff --git a/pr2_bringup/config/kinect2_bridge.launch b/pr2_bringup/config/kinect2_bridge.launch
index e71bdf6..80c0f30 100644
--- a/pr2_bringup/config/kinect2_bridge.launch
+++ b/pr2_bringup/config/kinect2_bridge.launch
@@ -22,7 +22,7 @@
+ if="$(arg start_manager)" machine="pr2-head" output="screen" respawn="true"/>
error_offset):
st.level = DiagnosticStatus.ERROR
st.message = "NTP Offset Too High"
-
else:
- st.level = DiagnosticStatus.ERROR
+ st.level = DiagnosticStatus.WARN
st.message = "Error Running ntpdate. Returned %d" % res
st.values = [ KeyValue("Offset (us)", "N/A"),
KeyValue("Offset tolerance (us)", str(off)),
diff --git a/pr2_controller_configuration/CMakeLists.txt b/pr2_controller_configuration/CMakeLists.txt
index a870041..2bd77bc 100644
--- a/pr2_controller_configuration/CMakeLists.txt
+++ b/pr2_controller_configuration/CMakeLists.txt
@@ -1,5 +1,7 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 2.8.12)
+if(POLICY CMP0048)
+ cmake_policy(SET CMP0048 NEW)
+endif()
project(pr2_controller_configuration)
# Load catkin and all dependencies required for this package
diff --git a/pr2_ethercat/CMakeLists.txt b/pr2_ethercat/CMakeLists.txt
index cb68c9a..0bc101b 100644
--- a/pr2_ethercat/CMakeLists.txt
+++ b/pr2_ethercat/CMakeLists.txt
@@ -1,5 +1,7 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 2.8.12)
+if(POLICY CMP0048)
+ cmake_policy(SET CMP0048 NEW)
+endif()
project(pr2_ethercat)
# Load catkin and all dependencies required for this package
@@ -10,15 +12,21 @@ find_package(catkin REQUIRED COMPONENTS
pr2_controller_manager
ethercat_hardware
realtime_tools
- diagnostic_updater)
+ diagnostic_updater
+ cpp_common)
find_package(Boost REQUIRED COMPONENTS system thread)
include_directories(include ${Boost_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS})
-catkin_package()
+catkin_package(DEPENDS CATKIN_DEPENDS cpp_common)
add_definitions(-O3)
+# needed to circumvent LD_LIBRARY_PATH being emptied through ethercat_grant
+# in addition to not propagating ros_ethercat_loop RUNPATH to dependencies, in contrast to RPATH
+SET(GCC_NEWDTAGS_LINK_FLAGS "-Wl,--disable-new-dtags")
+SET(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} ${GCC_NEWDTAGS_LINK_FLAGS}")
+
add_executable(pr2_ethercat src/main.cpp)
target_link_libraries(pr2_ethercat rt ${catkin_LIBRARIES} ${Boost_LIBRARIES})
add_dependencies(pr2_ethercat ${catkin_EXPORTED_TARGETS})
diff --git a/pr2_ethercat/package.xml b/pr2_ethercat/package.xml
index ee4c9ab..fc57833 100644
--- a/pr2_ethercat/package.xml
+++ b/pr2_ethercat/package.xml
@@ -20,6 +20,7 @@
realtime_tools
diagnostic_msgs
diagnostic_updater
+ cpp_common
pr2_controller_manager
roscpp
@@ -28,4 +29,5 @@
realtime_tools
diagnostic_msgs
diagnostic_updater
+ cpp_common
diff --git a/pr2_robot/CMakeLists.txt b/pr2_robot/CMakeLists.txt
index f4a5b2a..41ea0f5 100644
--- a/pr2_robot/CMakeLists.txt
+++ b/pr2_robot/CMakeLists.txt
@@ -1,4 +1,7 @@
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 2.8.12)
+if(POLICY CMP0048)
+ cmake_policy(SET CMP0048 NEW)
+endif()
project(pr2_robot)
find_package(catkin REQUIRED)
catkin_metapackage()
diff --git a/pr2_run_stop_auto_restart/CMakeLists.txt b/pr2_run_stop_auto_restart/CMakeLists.txt
index b449b0a..d8a56c6 100644
--- a/pr2_run_stop_auto_restart/CMakeLists.txt
+++ b/pr2_run_stop_auto_restart/CMakeLists.txt
@@ -1,5 +1,7 @@
-# http://ros.org/doc/groovy/api/catkin/html/user_guide/supposed.html
-cmake_minimum_required(VERSION 2.8.3)
+cmake_minimum_required(VERSION 2.8.12)
+if(POLICY CMP0048)
+ cmake_policy(SET CMP0048 NEW)
+endif()
project(pr2_run_stop_auto_restart)
# Load catkin and all dependencies required for this package