Skip to content

Commit

Permalink
Merge pull request #58 from MisoRobotics/release/1.0.0
Browse files Browse the repository at this point in the history
Release 1.0.0 for flippy
  • Loading branch information
zzv2 authored Jun 20, 2024
2 parents 6891d70 + 2020b8f commit 45fa98c
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 4 deletions.
11 changes: 11 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,17 @@ Changelog for package usb_cam
* fix bug for byte count in a pixel (3 bytes not 24 bytes) (`#40 <https://github.com/ros-drivers/usb_cam/issues/40>`_ )
* Contributors: Daniel Seifert, Eric Zavesky, Kei Okada, Ludovico Russo, Russell Toris, honeytrap15

1.0.0 (2024-06-20)
------------------
* Merge pull request `#56 <https://github.com/MisoRobotics/usb_cam/issues/56>`_ from MisoRobotics/user/hjoe72/feature/make-auto-exposure-reset-optional
F3-2048: Make periodic auto exposure reset optional
* Make periodic auto exposure reset optional
Make periodic auto exposure reset optional since
it stops streaming images when resetting.
* Merge pull request `#53 <https://github.com/MisoRobotics/usb_cam/issues/53>`_ from MisoRobotics/master
Backmerge master into develop for flippy-0.8.4
* Contributors: Hendry Joe, Zach Zweig Vinegar

0.8.4 (2022-10-31)
------------------
* Merge pull request `#51 <https://github.com/MisoRobotics/usb_cam/issues/51>`_ from MisoRobotics/user/hungrh/fix/autobin-auto-reset-exposure-setting
Expand Down
12 changes: 9 additions & 3 deletions nodes/usb_cam_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,9 @@ const int WAIT_CHANGING_AUTO_EXPOSURE_SEC = 2;
//! \brief Timer period in seconds between calls to reset camera exposure setting
const double AUTO_RESET_EXPOSURE_PERIOD = 60.0;

//! \brief Timer period in seconds between calls to reset camera exposure setting
const double ONE_SHOT_RESET_EXPOSURE_WAIT = 5.0;

class UsbCamNode
{
misocpp::DiagnosticHeartbeat heartbeat_;
Expand Down Expand Up @@ -141,7 +144,7 @@ class UsbCamNode
node_.param("focus", focus_, -1); //0-255, -1 "leave alone"
// enable/disable autoexposure
node_.param("autoexposure", autoexposure_, true);
node_.param("auto_reset_exposure_period", auto_reset_exposure_period_, AUTO_RESET_EXPOSURE_PERIOD);
node_.param("auto_reset_exposure_period", auto_reset_exposure_period_, AUTO_RESET_EXPOSURE_PERIOD); // No reset if < 0
node_.param("exposure", exposure_, 100);
node_.param("gain", gain_, -1); //0-100?, -1 "leave alone"
// enable/disable auto white balance temperature
Expand Down Expand Up @@ -326,9 +329,12 @@ class UsbCamNode
ROS_ASSERT(diag_freq_camera_info_);

enable_auto_reset_exposure_ = true;
bool timer_oneshot = auto_reset_exposure_period_ <= 0;
double timer_period = timer_oneshot ? ONE_SHOT_RESET_EXPOSURE_WAIT : auto_reset_exposure_period_;
auto_reset_exposure_timer_ = node_.createTimer(
ros::Duration(auto_reset_exposure_period_),
boost::bind(&UsbCamNode::checkAutoResetExposure, this, _1)
ros::Duration(timer_period),
boost::bind(&UsbCamNode::checkAutoResetExposure, this, _1),
timer_oneshot
);
}

Expand Down
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>usb_cam</name>
<version>0.8.4</version>
<version>1.0.0</version>
<description>A ROS Driver for V4L USB Cameras</description>

<maintainer email="rctoris@wpi.edu">Russell Toris</maintainer>
Expand Down

0 comments on commit 45fa98c

Please sign in to comment.