Skip to content

Commit

Permalink
Merge pull request #30 from hgaiser/indigo-devel
Browse files Browse the repository at this point in the history
Compile fix for OSX
  • Loading branch information
mikeferguson committed Dec 2, 2015
2 parents f546a37 + c53722e commit 2dc246f
Show file tree
Hide file tree
Showing 6 changed files with 14 additions and 6 deletions.
7 changes: 5 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}
Expand Down
2 changes: 1 addition & 1 deletion include/openni2_camera/openni2_frame_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
1 change: 1 addition & 0 deletions src/openni2_device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -713,6 +713,7 @@ std::ostream& operator <<(std::ostream& stream, const OpenNI2Device& device)
stream << "No Depth sensor available" << std::endl;
}

return stream;
}

}
2 changes: 2 additions & 0 deletions src/openni2_device_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -268,6 +268,8 @@ std::ostream& operator << (std::ostream& stream, const OpenNI2DeviceManager& dev
", Product ID: " << it->product_id_ <<
")" << std::endl;
}

return stream;
}


Expand Down
6 changes: 4 additions & 2 deletions src/openni2_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.");

Expand Down Expand Up @@ -718,6 +718,8 @@ std::string OpenNI2Driver::resolveDeviceURI(const std::string& device_id) throw(
}
return matched_uri;
}

return "INVALID";
}

void OpenNI2Driver::initDevice()
Expand Down Expand Up @@ -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));
}

}
Expand Down
2 changes: 1 addition & 1 deletion src/openni2_frame_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ OpenNI2FrameListener::OpenNI2FrameListener() :
ros::Time::init();
}

bool OpenNI2FrameListener::setUseDeviceTimer(bool enable)
void OpenNI2FrameListener::setUseDeviceTimer(bool enable)
{
user_device_timer_ = enable;

Expand Down

0 comments on commit 2dc246f

Please sign in to comment.