Skip to content

Commit

Permalink
do not modify parameters unless explicitly set
Browse files Browse the repository at this point in the history
The contrast, saturation, brightness, sharpness and focus parameters
were recently added to usb_cam. This caused a regression
(sigproc/robotic_surgery#17) whereby the default settings for a webcam
are overridden in all cases by the hard-coded defaults in usb_cam.

In the absence of a know good set of "default" values, leave the
parameters unset unless the user has explicitly set them in the launch
file.
  • Loading branch information
rjw57 committed Nov 18, 2014
1 parent 6eec9fb commit 8a1f698
Showing 1 changed file with 36 additions and 19 deletions.
55 changes: 36 additions & 19 deletions nodes/usb_cam_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,10 +68,10 @@ class UsbCamNode

// grab the parameters
node_.param("video_device", video_device_name_, std::string("/dev/video0"));
node_.param("brightness", brightness_, 128); //0-255
node_.param("contrast", contrast_, 32); //0-255
node_.param("saturation", saturation_, 32); //0-255
node_.param("sharpness", sharpness_, 22); //0-255
node_.param("brightness", brightness_, -1); //0-255, -1 "leave alone"
node_.param("contrast", contrast_, -1); //0-255, -1 "leave alone"
node_.param("saturation", saturation_, -1); //0-255, -1 "leave alone"
node_.param("sharpness", sharpness_, -1); //0-255, -1 "leave alone"
// possible values: mmap, read, userptr
node_.param("io_method", io_method_name_, std::string("mmap"));
node_.param("image_width", image_width_, 640);
Expand All @@ -81,7 +81,7 @@ class UsbCamNode
node_.param("pixel_format", pixel_format_name_, std::string("mjpeg"));
// enable/disable autofocus
node_.param("autofocus", autofocus_, false);
node_.param("focus", focus_, 51);
node_.param("focus", focus_, -1); //0-255, -1 "leave alone"
// enable/disable autoexposure
node_.param("autoexposure", autoexposure_, true);
node_.param("exposure", exposure_, 100);
Expand Down Expand Up @@ -138,17 +138,32 @@ class UsbCamNode

// set camera parameters
std::stringstream paramstream;
paramstream << "brightness=" << brightness_;
this->set_v4l_parameters(video_device_name_, paramstream.str());
paramstream.str("");
paramstream << "contrast=" << contrast_;
this->set_v4l_parameters(video_device_name_, paramstream.str());
paramstream.str("");
paramstream << "saturation=" << saturation_;
this->set_v4l_parameters(video_device_name_, paramstream.str());
paramstream.str("");
paramstream << "sharpness=" << sharpness_;
this->set_v4l_parameters(video_device_name_, paramstream.str());
if (brightness_ >= 0)
{
paramstream << "brightness=" << brightness_;
this->set_v4l_parameters(video_device_name_, paramstream.str());
paramstream.str("");
}

if (contrast_ >= 0)
{
paramstream << "contrast=" << contrast_;
this->set_v4l_parameters(video_device_name_, paramstream.str());
paramstream.str("");
}

if (saturation_ >= 0)
{
paramstream << "saturation=" << saturation_;
this->set_v4l_parameters(video_device_name_, paramstream.str());
paramstream.str("");
}

if (sharpness_ >= 0)
{
paramstream << "sharpness=" << sharpness_;
this->set_v4l_parameters(video_device_name_, paramstream.str());
}

// check auto white balance
if (auto_white_balance_)
Expand Down Expand Up @@ -183,9 +198,11 @@ class UsbCamNode
else
{
this->set_v4l_parameters(video_device_name_, "focus_auto=0");
std::stringstream ss;
ss << "focus_absolute=" << focus_;
this->set_v4l_parameters(video_device_name_, ss.str());
if (focus_ >= 0) {
std::stringstream ss;
ss << "focus_absolute=" << focus_;
this->set_v4l_parameters(video_device_name_, ss.str());
}
}
}

Expand Down

0 comments on commit 8a1f698

Please sign in to comment.