diff --git a/CMakeLists.txt b/CMakeLists.txt index 192a622..0034ba8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -70,9 +70,12 @@ add_executable(list_devices ) target_link_libraries(list_devices openni2_wrapper) -add_executable(usb_reset src/usb_reset.c) +if (UNIX AND NOT APPLE) + add_executable(usb_reset src/usb_reset.c) + set(ADDITIONAL_EXECUTABLES "usb_reset") +endif() -install(TARGETS openni2_wrapper openni2_camera_nodelet openni2_camera_node list_devices openni2_driver_lib usb_reset +install(TARGETS openni2_wrapper openni2_camera_nodelet openni2_camera_node list_devices openni2_driver_lib ${ADDITIONAL_EXECUTABLES} ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} diff --git a/include/openni2_camera/openni2_frame_listener.h b/include/openni2_camera/openni2_frame_listener.h index 0a09abc..3338042 100644 --- a/include/openni2_camera/openni2_frame_listener.h +++ b/include/openni2_camera/openni2_frame_listener.h @@ -60,7 +60,7 @@ class OpenNI2FrameListener : public openni::VideoStream::NewFrameListener callback_ = callback; } - bool setUseDeviceTimer(bool enable); + void setUseDeviceTimer(bool enable); private: openni::VideoFrameRef m_frame; diff --git a/src/openni2_device.cpp b/src/openni2_device.cpp index 1ef3847..10a1828 100644 --- a/src/openni2_device.cpp +++ b/src/openni2_device.cpp @@ -713,6 +713,7 @@ std::ostream& operator <<(std::ostream& stream, const OpenNI2Device& device) stream << "No Depth sensor available" << std::endl; } + return stream; } } diff --git a/src/openni2_device_manager.cpp b/src/openni2_device_manager.cpp index e6daf46..c2a0416 100644 --- a/src/openni2_device_manager.cpp +++ b/src/openni2_device_manager.cpp @@ -268,6 +268,8 @@ std::ostream& operator << (std::ostream& stream, const OpenNI2DeviceManager& dev ", Product ID: " << it->product_id_ << ")" << std::endl; } + + return stream; } diff --git a/src/openni2_driver.cpp b/src/openni2_driver.cpp index 4b8fdc3..6e1d62c 100644 --- a/src/openni2_driver.cpp +++ b/src/openni2_driver.cpp @@ -68,7 +68,7 @@ OpenNI2Driver::OpenNI2Driver(ros::NodeHandle& n, ros::NodeHandle& pnh) : while (!config_init_) { ROS_DEBUG("Waiting for dynamic reconfigure configuration."); - boost::this_thread::sleep(boost::posix_time::seconds(0.1)); + boost::this_thread::sleep(boost::posix_time::milliseconds(100)); } ROS_DEBUG("Dynamic reconfigure configuration received."); @@ -718,6 +718,8 @@ std::string OpenNI2Driver::resolveDeviceURI(const std::string& device_id) throw( } return matched_uri; } + + return "INVALID"; } void OpenNI2Driver::initDevice() @@ -748,7 +750,7 @@ void OpenNI2Driver::initDevice() while (ros::ok() && !device_->isValid()) { ROS_DEBUG("Waiting for device initialization.."); - boost::this_thread::sleep(boost::posix_time::seconds(0.1)); + boost::this_thread::sleep(boost::posix_time::milliseconds(100)); } } diff --git a/src/openni2_frame_listener.cpp b/src/openni2_frame_listener.cpp index 18579fb..40cd627 100644 --- a/src/openni2_frame_listener.cpp +++ b/src/openni2_frame_listener.cpp @@ -51,7 +51,7 @@ OpenNI2FrameListener::OpenNI2FrameListener() : ros::Time::init(); } -bool OpenNI2FrameListener::setUseDeviceTimer(bool enable) +void OpenNI2FrameListener::setUseDeviceTimer(bool enable) { user_device_timer_ = enable;