Skip to content
Snippets Groups Projects
Commit 196ca42a authored by Kei Okada's avatar Kei Okada Committed by GitHub
Browse files

Merge pull request #41 from ros-drivers/fix_l

enable to compile with libuvc <= v0.0.5
parents 20a88b0c f23bd63f
No related branches found
No related tags found
No related merge requests found
...@@ -7,6 +7,7 @@ find_package(catkin REQUIRED COMPONENTS roscpp camera_info_manager dynamic_recon ...@@ -7,6 +7,7 @@ find_package(catkin REQUIRED COMPONENTS roscpp camera_info_manager dynamic_recon
generate_dynamic_reconfigure_options(cfg/UVCCamera.cfg) generate_dynamic_reconfigure_options(cfg/UVCCamera.cfg)
find_package(libuvc REQUIRED) find_package(libuvc REQUIRED)
message(STATUS "libuvc ${libuvc_VERSION_MAJOR}.${libuvc_VERSION_MINOR}.${libuvc_VERSION_PATCH}")
catkin_package( catkin_package(
CATKIN_DEPENDS CATKIN_DEPENDS
...@@ -19,6 +20,9 @@ catkin_package( ...@@ -19,6 +20,9 @@ catkin_package(
LIBRARIES libuvc_camera_nodelet LIBRARIES libuvc_camera_nodelet
) )
add_definitions(-Dlibuvc_VERSION_MAJOR=${libuvc_VERSION_MAJOR})
add_definitions(-Dlibuvc_VERSION_MINOR=${libuvc_VERSION_MINOR})
add_definitions(-Dlibuvc_VERSION_PATCH=${libuvc_VERSION_PATCH})
include_directories(include ${libuvc_INCLUDE_DIRS} ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS}) include_directories(include ${libuvc_INCLUDE_DIRS} ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS})
link_directories(${catkin_LINK_DIRS}) link_directories(${catkin_LINK_DIRS})
......
...@@ -39,6 +39,9 @@ ...@@ -39,6 +39,9 @@
#include <image_transport/camera_publisher.h> #include <image_transport/camera_publisher.h>
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include <libuvc/libuvc.h> #include <libuvc/libuvc.h>
#define libuvc_VERSION (libuvc_VERSION_MAJOR * 10000 \
+ libuvc_VERSION_MINOR * 100 \
+ libuvc_VERSION_PATCH)
namespace libuvc_camera { namespace libuvc_camera {
...@@ -126,9 +129,11 @@ void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t lev ...@@ -126,9 +129,11 @@ void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t lev
PARAM_INT(exposure_absolute, exposure_abs, new_config.exposure_absolute * 10000); PARAM_INT(exposure_absolute, exposure_abs, new_config.exposure_absolute * 10000);
PARAM_INT(auto_focus, focus_auto, new_config.auto_focus ? 1 : 0); PARAM_INT(auto_focus, focus_auto, new_config.auto_focus ? 1 : 0);
PARAM_INT(focus_absolute, focus_abs, new_config.focus_absolute); PARAM_INT(focus_absolute, focus_abs, new_config.focus_absolute);
#if libuvc_VERSION > 00005 /* version > 0.0.5 */
PARAM_INT(gain, gain, new_config.gain); PARAM_INT(gain, gain, new_config.gain);
PARAM_INT(iris_absolute, iris_abs, new_config.iris_absolute); PARAM_INT(iris_absolute, iris_abs, new_config.iris_absolute);
PARAM_INT(brightness, brightness, new_config.brightness); PARAM_INT(brightness, brightness, new_config.brightness);
#endif
if (new_config.pan_absolute != config_.pan_absolute || new_config.tilt_absolute != config_.tilt_absolute) { if (new_config.pan_absolute != config_.pan_absolute || new_config.tilt_absolute != config_.tilt_absolute) {
...@@ -188,8 +193,10 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) { ...@@ -188,8 +193,10 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) {
} }
image->encoding = "bgr8"; image->encoding = "bgr8";
memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes); memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
#if libuvc_VERSION > 00005 /* version > 0.0.5 */
} else if (frame->frame_format == UVC_FRAME_FORMAT_MJPEG) { } else if (frame->frame_format == UVC_FRAME_FORMAT_MJPEG) {
// FIXME: uvc_any2bgr does not work on "mjpeg" format, so use uvc_mjpeg2rgb directly. // Enable mjpeg support despite uvs_any2bgr shortcoming
// https://github.com/ros-drivers/libuvc_ros/commit/7508a09f
uvc_error_t conv_ret = uvc_mjpeg2rgb(frame, rgb_frame_); uvc_error_t conv_ret = uvc_mjpeg2rgb(frame, rgb_frame_);
if (conv_ret != UVC_SUCCESS) { if (conv_ret != UVC_SUCCESS) {
uvc_perror(conv_ret, "Couldn't convert frame to RGB"); uvc_perror(conv_ret, "Couldn't convert frame to RGB");
...@@ -197,6 +204,7 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) { ...@@ -197,6 +204,7 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) {
} }
image->encoding = "rgb8"; image->encoding = "rgb8";
memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes); memcpy(&(image->data[0]), rgb_frame_->data, rgb_frame_->data_bytes);
#endif
} else { } else {
uvc_error_t conv_ret = uvc_any2bgr(frame, rgb_frame_); uvc_error_t conv_ret = uvc_any2bgr(frame, rgb_frame_);
if (conv_ret != UVC_SUCCESS) { if (conv_ret != UVC_SUCCESS) {
...@@ -320,6 +328,9 @@ void CameraDriver::OpenCamera(UVCCameraConfig &new_config) { ...@@ -320,6 +328,9 @@ void CameraDriver::OpenCamera(UVCCameraConfig &new_config) {
uvc_device_t **devs; uvc_device_t **devs;
// Implement missing index select behavior
// https://github.com/ros-drivers/libuvc_ros/commit/4f30e9a0
#if libuvc_VERSION > 00005 /* version > 0.0.5 */
uvc_error_t find_err = uvc_find_devices( uvc_error_t find_err = uvc_find_devices(
ctx_, &devs, ctx_, &devs,
vendor_id, vendor_id,
...@@ -349,7 +360,19 @@ void CameraDriver::OpenCamera(UVCCameraConfig &new_config) { ...@@ -349,7 +360,19 @@ void CameraDriver::OpenCamera(UVCCameraConfig &new_config) {
ROS_ERROR("Unable to find device at index %d", new_config.index); ROS_ERROR("Unable to find device at index %d", new_config.index);
return; return;
} }
#else
uvc_error_t find_err = uvc_find_device(
ctx_, &dev_,
vendor_id,
product_id,
new_config.serial.empty() ? NULL : new_config.serial.c_str());
if (find_err != UVC_SUCCESS) {
uvc_perror(find_err, "uvc_find_device");
return;
}
#endif
uvc_error_t open_err = uvc_open(dev_, &devh_); uvc_error_t open_err = uvc_open(dev_, &devh_);
if (open_err != UVC_SUCCESS) { if (open_err != UVC_SUCCESS) {
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment