Skip to content

Commit

Permalink
Merge pull request #52 from MisoRobotics/release/0.8.4
Browse files Browse the repository at this point in the history
Release 0.8.4 for flippy
  • Loading branch information
zzv2 authored Nov 1, 2022
2 parents ebe80dd + 9628bfa commit 6891d70
Show file tree
Hide file tree
Showing 6 changed files with 66 additions and 29 deletions.
15 changes: 15 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,21 @@ 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

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
FSIT-3680: Fix autobin auto reset exposure setting
* Fix autobin auto reset exposure setting
This commit fixes to reset the exposure setting
without stopping the capture of the V4L2 buffer.
* Merge pull request `#45 <https://github.com/MisoRobotics/usb_cam/issues/45>`_ from MisoRobotics/user/jhong/feature/add_freq_monitoring
SFS-8564, SFS-10034: Add new freq monitoring and diagnostic launch files
* SFS-8564: Diag 4 - Add frequency monitoring
Add frequency monitoring.
* Merge pull request `#50 <https://github.com/MisoRobotics/usb_cam/issues/50>`_ from MisoRobotics/master
Backmerge master into develop for flippy-0.8.3
* Contributors: Hung Ruo Han, Junpyo Hong, Zach Zweig Vinegar

0.8.3 (2022-10-17)
------------------
* Merge pull request `#46 <https://github.com/MisoRobotics/usb_cam/issues/46>`_ from MisoRobotics/user/hungrh/feature/auto-reset-exposure-setting
Expand Down
11 changes: 9 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ project(usb_cam)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS image_transport roscpp std_msgs std_srvs sensor_msgs camera_info_manager)
find_package(catkin REQUIRED COMPONENTS image_transport roscpp std_msgs std_srvs sensor_msgs camera_info_manager misocpp)

## pkg-config libraries
find_package(PkgConfig REQUIRED)
Expand All @@ -20,14 +20,20 @@ pkg_check_modules(udev libudev REQUIRED)
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
INCLUDE_DIRS include ${MISO_INCLUDE_DIRS}
LIBRARIES ${PROJECT_NAME}
CATKIN_DEPENDS
misocpp
)

###########
## Build ##
###########

set(CMAKE_CXX_STANDARD 17)

set(GCC_COVERAGE_LINK_FLAGS "-lstdc++fs")

include_directories(include
${catkin_INCLUDE_DIRS}
${avcodec_INCLUDE_DIRS}
Expand All @@ -44,6 +50,7 @@ target_link_libraries(${PROJECT_NAME}
${avcodec_LIBRARIES}
${swscale_LIBRARIES}
${catkin_LIBRARIES}
${GCC_COVERAGE_LINK_FLAGS}
)

## Declare a cpp executable
Expand Down
4 changes: 4 additions & 0 deletions include/usb_cam/usb_cam.h
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,9 @@ class UsbCam {
void start_capturing(void);
bool is_capturing();

bool is_changing_config();
void is_changing_config(bool is_changing);

private:
typedef struct
{
Expand Down Expand Up @@ -132,6 +135,7 @@ class UsbCam {
void open_device(void);
bool grab_image();
bool is_capturing_;
bool is_changing_config_;


std::string camera_dev_;
Expand Down
50 changes: 25 additions & 25 deletions nodes/usb_cam_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,18 +34,19 @@
*
*********************************************************************/

#include <filesystem>

#include <ros/ros.h>
#include <usb_cam/usb_cam.h>
#include <image_transport/image_transport.h>
#include <camera_info_manager/camera_info_manager.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include <diagnostic_updater/update_functions.h>
#include <memory>
#include <sstream>
#include <std_srvs/Empty.h>
#include <std_srvs/SetBool.h>
#include <thread>
#include <usb_cam/device_utils.h>
#include <misocpp/diagnostic_updater_wrapper.h>

namespace usb_cam {

Expand All @@ -63,13 +64,10 @@ const double AUTO_RESET_EXPOSURE_PERIOD = 60.0;

class UsbCamNode
{
// ROS diagnostic updater object.
diagnostic_updater::Updater diagnostic_updater_;
diagnostic_updater::Heartbeat heartbeat_;
std::unique_ptr<diagnostic_updater::FrequencyStatusParam> frequency_status_param_;
std::unique_ptr<diagnostic_updater::FrequencyStatus> frequency_status_;
misocpp::DiagnosticHeartbeat heartbeat_;
std::unique_ptr<misocpp::DiagnosticFrequency> diag_freq_image_raw_{ nullptr };
std::unique_ptr<misocpp::DiagnosticFrequency> diag_freq_camera_info_{ nullptr };
double expected_freq_, auto_reset_exposure_period_;

ros::Timer auto_reset_exposure_timer_;
bool enable_auto_reset_exposure_;

Expand Down Expand Up @@ -312,19 +310,20 @@ class UsbCamNode
}
}

// Set hardware ID for diagnostic updater.
diagnostic_updater_.setHardwareID("none");

// Heartbeat
diagnostic_updater_.add(heartbeat_);

// Frequency Status
std::string ns = ros::this_node::getNamespace();
expected_freq_ = static_cast<double>(framerate_);
frequency_status_param_ = std::make_unique<diagnostic_updater::FrequencyStatusParam>(&expected_freq_, &expected_freq_);
ROS_ASSERT(frequency_status_param_);
frequency_status_ = std::make_unique<diagnostic_updater::FrequencyStatus>(*frequency_status_param_, "FrequencyStatus");
ROS_ASSERT(frequency_status_);
diagnostic_updater_.add(*frequency_status_);
std::filesystem::path topic = ns;
topic /= image_pub_.getTopic();
diag_freq_image_raw_ =
std::make_unique<misocpp::DiagnosticFrequency>(topic.c_str(), expected_freq_, expected_freq_);
ROS_ASSERT(diag_freq_image_raw_);
std::string s(topic);
s = s.erase(s.rfind('/'), std::string::npos);
topic = s;
topic /= "camera_info";
diag_freq_camera_info_ =
std::make_unique<misocpp::DiagnosticFrequency>(topic.c_str(), expected_freq_, expected_freq_);
ROS_ASSERT(diag_freq_camera_info_);

enable_auto_reset_exposure_ = true;
auto_reset_exposure_timer_ = node_.createTimer(
Expand All @@ -349,14 +348,15 @@ class UsbCamNode

// publish the image
image_pub_.publish(img_, *ci);
frequency_status_->tick();
diag_freq_camera_info_->tick();
diag_freq_image_raw_->tick();

return true;
}

void resetExposureSettings()
{
cam_.stop_capturing();
cam_.is_changing_config(true);
cam_.set_v4l_parameter(
"exposure_auto",
AUTO_EXPOSURE_APERTURE_PRIORITY_MODE
Expand All @@ -366,7 +366,7 @@ class UsbCamNode
);
cam_.set_v4l_parameter("exposure_auto", AUTO_EXPOSURE_MANUAL_MODE);
cam_.set_v4l_parameter("exposure_absolute", exposure_);
cam_.start_capturing();
cam_.is_changing_config(false);
}

void checkAutoResetExposure(const ros::TimerEvent&)
Expand All @@ -382,11 +382,11 @@ class UsbCamNode
ros::Rate loop_rate(this->framerate_);
while (node_.ok())
{
if (cam_.is_capturing()) {
if (cam_.is_capturing() && !cam_.is_changing_config()) {
if (!take_and_send_image()) ROS_WARN("USB camera did not respond in time.");
}
ros::spinOnce();
diagnostic_updater_.update();
heartbeat_.update();
loop_rate.sleep();

}
Expand Down
4 changes: 3 additions & 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.3</version>
<version>0.8.4</version>
<description>A ROS Driver for V4L USB Cameras</description>

<maintainer email="rctoris@wpi.edu">Russell Toris</maintainer>
Expand All @@ -17,6 +17,8 @@

<buildtool_depend>catkin</buildtool_depend>

<depend>misocpp</depend>

<build_depend>image_transport</build_depend>
<build_depend>libudev-dev</build_depend>
<build_depend>udev</build_depend>
Expand Down
11 changes: 10 additions & 1 deletion src/usb_cam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -356,7 +356,8 @@ void rgb242rgb(char *YUV, char *RGB, int NumPixels)
UsbCam::UsbCam()
: io_(IO_METHOD_MMAP), fd_(-1), buffers_(NULL), n_buffers_(0), avframe_camera_(NULL),
avframe_rgb_(NULL), avcodec_(NULL), avoptions_(NULL), avcodec_context_(NULL),
avframe_camera_size_(0), avframe_rgb_size_(0), video_sws_(NULL), image_(NULL), is_capturing_(false) {
avframe_camera_size_(0), avframe_rgb_size_(0), video_sws_(NULL), image_(NULL),
is_capturing_(false), is_changing_config_(false) {
}
UsbCam::~UsbCam()
{
Expand Down Expand Up @@ -597,6 +598,14 @@ bool UsbCam::is_capturing() {
return is_capturing_;
}

bool UsbCam::is_changing_config() {
return is_changing_config_;
}

void UsbCam::is_changing_config(bool is_changing) {
is_changing_config_ = is_changing;
}

void UsbCam::stop_capturing(void)
{
if(!is_capturing_) return;
Expand Down

0 comments on commit 6891d70

Please sign in to comment.