Skip to content
Snippets Groups Projects
Commit 874ab1ea authored by Ken Tossell's avatar Ken Tossell
Browse files

Removed dependency on the deprecated driver_base package.

parent 30b3cfd1
No related branches found
No related tags found
No related merge requests found
...@@ -2,7 +2,7 @@ ...@@ -2,7 +2,7 @@
cmake_minimum_required(VERSION 2.8.3) cmake_minimum_required(VERSION 2.8.3)
project(libuvc_camera) project(libuvc_camera)
# Load catkin and all dependencies required for this package # Load catkin and all dependencies required for this package
find_package(catkin REQUIRED COMPONENTS roscpp camera_info_manager driver_base dynamic_reconfigure image_transport nodelet sensor_msgs) find_package(catkin REQUIRED COMPONENTS roscpp camera_info_manager dynamic_reconfigure image_transport nodelet sensor_msgs)
generate_dynamic_reconfigure_options(cfg/UVCCamera.cfg) generate_dynamic_reconfigure_options(cfg/UVCCamera.cfg)
...@@ -12,7 +12,6 @@ catkin_package( ...@@ -12,7 +12,6 @@ catkin_package(
CATKIN_DEPENDS CATKIN_DEPENDS
roscpp roscpp
camera_info_manager camera_info_manager
driver_base
dynamic_reconfigure dynamic_reconfigure
image_transport image_transport
nodelet nodelet
......
...@@ -2,32 +2,35 @@ ...@@ -2,32 +2,35 @@
# Derived from camera1394 cfg # Derived from camera1394 cfg
from dynamic_reconfigure.parameter_generator_catkin import * from dynamic_reconfigure.parameter_generator_catkin import *
from driver_base.msg import SensorLevels
RECONFIGURE_CLOSE = 3 # Parameters that need a sensor to be stopped completely when changed
RECONFIGURE_STOP = 1 # Parameters that need a sensor to stop streaming when changed
RECONFIGURE_RUNNING = 0 # Parameters that can be changed while a sensor is streaming
gen = ParameterGenerator() gen = ParameterGenerator()
# Name, Type, Reconfiguration level, Description, Default, Min, Max # Name, Type, Reconfiguration level, Description, Default, Min, Max
gen.add("vendor", str_t, SensorLevels.RECONFIGURE_CLOSE, gen.add("vendor", str_t, RECONFIGURE_CLOSE,
"Vendor ID, hex digits (use camera of any vendor if null).", "Vendor ID, hex digits (use camera of any vendor if null).",
"") "")
gen.add("product", str_t, SensorLevels.RECONFIGURE_CLOSE, gen.add("product", str_t, RECONFIGURE_CLOSE,
"Product ID, hex digits (use camera of any model if null).", "Product ID, hex digits (use camera of any model if null).",
"") "")
gen.add("serial", str_t, SensorLevels.RECONFIGURE_CLOSE, gen.add("serial", str_t, RECONFIGURE_CLOSE,
"Serial number, arbitrary string (use camera of any serial number if null).", "Serial number, arbitrary string (use camera of any serial number if null).",
"") "")
gen.add("index", int_t, SensorLevels.RECONFIGURE_CLOSE, gen.add("index", int_t, RECONFIGURE_CLOSE,
"Index into the list of cameras that match the above parameters.", "Index into the list of cameras that match the above parameters.",
0, 0) 0, 0)
gen.add("width", int_t, SensorLevels.RECONFIGURE_CLOSE, gen.add("width", int_t, RECONFIGURE_CLOSE,
"Image width.", 640, 0) "Image width.", 640, 0)
gen.add("height", int_t, SensorLevels.RECONFIGURE_CLOSE, gen.add("height", int_t, RECONFIGURE_CLOSE,
"Image height.", 480, 0) "Image height.", 480, 0)
video_modes = gen.enum([gen.const("uncompressed", str_t, "uncompressed", "Use any uncompressed format"), video_modes = gen.enum([gen.const("uncompressed", str_t, "uncompressed", "Use any uncompressed format"),
...@@ -37,11 +40,11 @@ video_modes = gen.enum([gen.const("uncompressed", str_t, "uncompressed", "Use an ...@@ -37,11 +40,11 @@ video_modes = gen.enum([gen.const("uncompressed", str_t, "uncompressed", "Use an
gen.const("jpeg", str_t, "jpeg", "JPEG/MJPEG")], gen.const("jpeg", str_t, "jpeg", "JPEG/MJPEG")],
"Video stream format") "Video stream format")
gen.add("video_mode", str_t, SensorLevels.RECONFIGURE_CLOSE, gen.add("video_mode", str_t, RECONFIGURE_CLOSE,
"Format of video stream from camera.", "uncompressed", "Format of video stream from camera.", "uncompressed",
edit_method = video_modes) edit_method = video_modes)
gen.add("frame_rate", double_t, SensorLevels.RECONFIGURE_CLOSE, gen.add("frame_rate", double_t, RECONFIGURE_CLOSE,
"Camera speed, frames per second.", 15.0, 0.1, 1000.0) "Camera speed, frames per second.", 15.0, 0.1, 1000.0)
timestamp_methods = gen.enum([gen.const("PubTime", str_t, "pub", "Time of publication"), timestamp_methods = gen.enum([gen.const("PubTime", str_t, "pub", "Time of publication"),
...@@ -50,15 +53,15 @@ timestamp_methods = gen.enum([gen.const("PubTime", str_t, "pub", "Time of public ...@@ -50,15 +53,15 @@ timestamp_methods = gen.enum([gen.const("PubTime", str_t, "pub", "Time of public
gen.const("HostReceiptTime", str_t, "hostrcpt", "Time when camera-to-host transfer completed")], gen.const("HostReceiptTime", str_t, "hostrcpt", "Time when camera-to-host transfer completed")],
"Methods for determining the timestamp") "Methods for determining the timestamp")
gen.add("timestamp_method", str_t, SensorLevels.RECONFIGURE_CLOSE, gen.add("timestamp_method", str_t, RECONFIGURE_CLOSE,
"Method for determining the timestamp.", "start", "Method for determining the timestamp.", "start",
edit_method = timestamp_methods) edit_method = timestamp_methods)
gen.add("frame_id", str_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("frame_id", str_t, RECONFIGURE_RUNNING,
"ROS tf frame of reference, resolved with tf_prefix unless absolute.", "ROS tf frame of reference, resolved with tf_prefix unless absolute.",
"camera") "camera")
gen.add("camera_info_url", str_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("camera_info_url", str_t, RECONFIGURE_RUNNING,
"Path to camera calibration file.", "") "Path to camera calibration file.", "")
# Camera Terminal controls # Camera Terminal controls
...@@ -67,7 +70,7 @@ scanning_modes = gen.enum([gen.const("Interlaced", int_t, 0, ""), ...@@ -67,7 +70,7 @@ scanning_modes = gen.enum([gen.const("Interlaced", int_t, 0, ""),
gen.const("Progressive", int_t, 1, "")], gen.const("Progressive", int_t, 1, "")],
"Scanning modes") "Scanning modes")
gen.add("scanning_mode", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("scanning_mode", int_t, RECONFIGURE_RUNNING,
"Scanning mode.", 0, 0, 1, "Scanning mode.", 0, 0, 1,
edit_method = scanning_modes) edit_method = scanning_modes)
...@@ -77,64 +80,64 @@ auto_exposure_modes = gen.enum([gen.const("Manual", int_t, 0, "Manual exposure, ...@@ -77,64 +80,64 @@ auto_exposure_modes = gen.enum([gen.const("Manual", int_t, 0, "Manual exposure,
gen.const("Aperture_Priority", int_t, 3, "auto exposure, manual iris")], gen.const("Aperture_Priority", int_t, 3, "auto exposure, manual iris")],
"Auto-exposure modes") "Auto-exposure modes")
gen.add("auto_exposure", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("auto_exposure", int_t, RECONFIGURE_RUNNING,
"Auto exposure mode.", "Auto exposure mode.",
1, 0, 3, edit_method = auto_exposure_modes) 1, 0, 3, edit_method = auto_exposure_modes)
gen.add("auto_exposure_priority", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("auto_exposure_priority", int_t, RECONFIGURE_RUNNING,
"In auto mode or shutter priority mode, allow the device to vary frame rate.", "In auto mode or shutter priority mode, allow the device to vary frame rate.",
0, 0, 1) 0, 0, 1)
gen.add("exposure_absolute", double_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("exposure_absolute", double_t, RECONFIGURE_RUNNING,
"Length of exposure, seconds.", 0., 0.0001, 10.0) "Length of exposure, seconds.", 0., 0.0001, 10.0)
# TODO: relative exposure time # TODO: relative exposure time
gen.add("iris_absolute", double_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("iris_absolute", double_t, RECONFIGURE_RUNNING,
"Aperture, f.", 0., 0., 655.35) "Aperture, f.", 0., 0., 655.35)
# TODO: relative iris # TODO: relative iris
gen.add("auto_focus", bool_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("auto_focus", bool_t, RECONFIGURE_RUNNING,
"Maintain focus automatically.", False) "Maintain focus automatically.", False)
gen.add("focus_absolute", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("focus_absolute", int_t, RECONFIGURE_RUNNING,
"Absolute focal distance, millimeters.", 0, 0, 65536) "Absolute focal distance, millimeters.", 0, 0, 65536)
# TODO: relative focus # TODO: relative focus
# TODO: zoom # TODO: zoom
gen.add("pan_absolute", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("pan_absolute", int_t, RECONFIGURE_RUNNING,
"Pan (clockwise), arc seconds.", 0, -180*3600, 180*3600) "Pan (clockwise), arc seconds.", 0, -180*3600, 180*3600)
gen.add("tilt_absolute", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("tilt_absolute", int_t, RECONFIGURE_RUNNING,
"Tilt (up), arc seconds.", 0, -180*3600, 180*3600) "Tilt (up), arc seconds.", 0, -180*3600, 180*3600)
# TODO: relative pan/tilt # TODO: relative pan/tilt
gen.add("roll_absolute", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("roll_absolute", int_t, RECONFIGURE_RUNNING,
"Roll (clockwise), degrees.", 0, -180, 180) "Roll (clockwise), degrees.", 0, -180, 180)
# TODO: relative roll # TODO: relative roll
gen.add("privacy", bool_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("privacy", bool_t, RECONFIGURE_RUNNING,
"Image capture disabled.", False) "Image capture disabled.", False)
# Processing Unit controls # Processing Unit controls
gen.add("backlight_compensation", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("backlight_compensation", int_t, RECONFIGURE_RUNNING,
"Backlight compensation, device-dependent (zero for none, increasing compensation above zero).", "Backlight compensation, device-dependent (zero for none, increasing compensation above zero).",
0, 0, 65536) 0, 0, 65536)
gen.add("brightness", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("brightness", int_t, RECONFIGURE_RUNNING,
"Brightness, device dependent.", 0, -32768, 32767) "Brightness, device dependent.", 0, -32768, 32767)
gen.add("contrast", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("contrast", int_t, RECONFIGURE_RUNNING,
"Contrast, device dependent.", 0, -32768, 32767) "Contrast, device dependent.", 0, -32768, 32767)
gen.add("gain", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("gain", int_t, RECONFIGURE_RUNNING,
"Gain, device dependent.", 0, 0, 65536) "Gain, device dependent.", 0, 0, 65536)
power_line_frequency_modes = gen.enum([gen.const("Disabled", int_t, 0, "Disabled"), power_line_frequency_modes = gen.enum([gen.const("Disabled", int_t, 0, "Disabled"),
...@@ -142,39 +145,39 @@ power_line_frequency_modes = gen.enum([gen.const("Disabled", int_t, 0, "Disabled ...@@ -142,39 +145,39 @@ power_line_frequency_modes = gen.enum([gen.const("Disabled", int_t, 0, "Disabled
gen.const("Freq_60", int_t, 1, "60 Hz")], gen.const("Freq_60", int_t, 1, "60 Hz")],
"Power line frequency modes") "Power line frequency modes")
gen.add("power_line_frequency", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("power_line_frequency", int_t, RECONFIGURE_RUNNING,
"Power line frequency anti-flicker processing.", "Power line frequency anti-flicker processing.",
0, 0, 2, 0, 0, 2,
edit_method = power_line_frequency_modes) edit_method = power_line_frequency_modes)
gen.add("auto_hue", bool_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("auto_hue", bool_t, RECONFIGURE_RUNNING,
"Automatic hue control.", False) "Automatic hue control.", False)
gen.add("hue", double_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("hue", double_t, RECONFIGURE_RUNNING,
"Hue, degrees.", 0., -180., 180.) "Hue, degrees.", 0., -180., 180.)
gen.add("saturation", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("saturation", int_t, RECONFIGURE_RUNNING,
"Saturation, device dependent (zero for grayscale).", 0, 0, 65536) "Saturation, device dependent (zero for grayscale).", 0, 0, 65536)
gen.add("sharpness", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("sharpness", int_t, RECONFIGURE_RUNNING,
"Image sharpness, device dependent.", "Image sharpness, device dependent.",
0, 0, 65536) 0, 0, 65536)
# TODO: check range definition # TODO: check range definition
gen.add("gamma", double_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("gamma", double_t, RECONFIGURE_RUNNING,
"Gamma.", 1.0, 0.01, 5.0) "Gamma.", 1.0, 0.01, 5.0)
gen.add("auto_white_balance", bool_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("auto_white_balance", bool_t, RECONFIGURE_RUNNING,
"Automatic white balance.", False) "Automatic white balance.", False)
gen.add("white_balance_temperature", int_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("white_balance_temperature", int_t, RECONFIGURE_RUNNING,
"White balance temperature, degrees.", 0, 0, 65536) "White balance temperature, degrees.", 0, 0, 65536)
gen.add("white_balance_BU", double_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("white_balance_BU", double_t, RECONFIGURE_RUNNING,
"Blue or U component of white balance, device-dependent.", "Blue or U component of white balance, device-dependent.",
0, 0, 65536) 0, 0, 65536)
gen.add("white_balance_RV", double_t, SensorLevels.RECONFIGURE_RUNNING, gen.add("white_balance_RV", double_t, RECONFIGURE_RUNNING,
"Red or V component of white balance, device-dependent.", "Red or V component of white balance, device-dependent.",
0, 0, 65536) 0, 0, 65536)
......
...@@ -28,6 +28,11 @@ private: ...@@ -28,6 +28,11 @@ private:
kRunning = 2, kRunning = 2,
}; };
// Flags controlling whether the sensor needs to be stopped (or reopened) when changing settings
static const int kReconfigureClose = 3; // Need to close and reopen sensor to change this setting
static const int kReconfigureStop = 1; // Need to stop the stream before changing this setting
static const int kReconfigureRunning = 0; // We can change this setting without stopping the stream
void OpenCamera(UVCCameraConfig &new_config); void OpenCamera(UVCCameraConfig &new_config);
void CloseCamera(); void CloseCamera();
......
...@@ -35,7 +35,6 @@ ...@@ -35,7 +35,6 @@
<!-- <build_depend>message_generation</build_depend> --> <!-- <build_depend>message_generation</build_depend> -->
<build_depend>roscpp</build_depend> <build_depend>roscpp</build_depend>
<build_depend>camera_info_manager</build_depend> <build_depend>camera_info_manager</build_depend>
<build_depend>driver_base</build_depend>
<build_depend>dynamic_reconfigure</build_depend> <build_depend>dynamic_reconfigure</build_depend>
<build_depend>image_transport</build_depend> <build_depend>image_transport</build_depend>
<build_depend>libuvc</build_depend> <build_depend>libuvc</build_depend>
...@@ -48,7 +47,6 @@ ...@@ -48,7 +47,6 @@
<!-- <run_depend>message_runtime</run_depend> --> <!-- <run_depend>message_runtime</run_depend> -->
<run_depend>roscpp</run_depend> <run_depend>roscpp</run_depend>
<run_depend>camera_info_manager</run_depend> <run_depend>camera_info_manager</run_depend>
<run_depend>driver_base</run_depend>
<run_depend>dynamic_reconfigure</run_depend> <run_depend>dynamic_reconfigure</run_depend>
<run_depend>image_transport</run_depend> <run_depend>image_transport</run_depend>
<run_depend>libuvc</run_depend> <run_depend>libuvc</run_depend>
......
...@@ -38,7 +38,6 @@ ...@@ -38,7 +38,6 @@
#include <std_msgs/Header.h> #include <std_msgs/Header.h>
#include <image_transport/camera_publisher.h> #include <image_transport/camera_publisher.h>
#include <dynamic_reconfigure/server.h> #include <dynamic_reconfigure/server.h>
#include <dynamic_reconfigure/SensorLevels.h>
#include <libuvc/libuvc.h> #include <libuvc/libuvc.h>
namespace libuvc_camera { namespace libuvc_camera {
...@@ -100,7 +99,7 @@ void CameraDriver::Stop() { ...@@ -100,7 +99,7 @@ void CameraDriver::Stop() {
void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t level) { void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t level) {
boost::recursive_mutex::scoped_lock(mutex_); boost::recursive_mutex::scoped_lock(mutex_);
if (level & dynamic_reconfigure::SensorLevels::RECONFIGURE_CLOSE) { if ((level & kReconfigureClose) == kReconfigureClose) {
if (state_ == kRunning) if (state_ == kRunning)
CloseCamera(); CloseCamera();
} }
......
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