From f8aae6c22497a9ac646c4f22370bf0df643f17b4 Mon Sep 17 00:00:00 2001 From: lovod <743648056@qq.com> Date: Sun, 20 Jul 2025 11:01:17 +0800 Subject: [PATCH] Add the stop_grub_ function. --- .gitignore | 3 +++ cfg/camera.cfg | 2 ++ include/galaxy_camera.h | 1 + src/galaxy_camera.cpp | 6 ++++++ 4 files changed, 12 insertions(+) diff --git a/.gitignore b/.gitignore index 35d74bb..a2c2192 100644 --- a/.gitignore +++ b/.gitignore @@ -49,3 +49,6 @@ qtcreator-* # Catkin custom files CATKIN_IGNORE + +.clang-format +.clang-tidy diff --git a/cfg/camera.cfg b/cfg/camera.cfg index 9f61a09..2c2051f 100755 --- a/cfg/camera.cfg +++ b/cfg/camera.cfg @@ -43,4 +43,6 @@ mode = gen.enum([gen.const("Both", int_t, 0, "Both open"), "mode") gen.add("improve_mode", int_t, 0, "Image improve mode selector", 3, 0, 3, edit_method=mode) +gen.add("stop_grab", bool_t, 0, "Stop camera grabbing", False) + exit(gen.generate(PACKAGE, "galaxy_camera", "Camera")) diff --git a/include/galaxy_camera.h b/include/galaxy_camera.h index 6a863e0..5d13c8d 100644 --- a/include/galaxy_camera.h +++ b/include/galaxy_camera.h @@ -73,6 +73,7 @@ class GalaxyCameraNodelet : public nodelet::Nodelet static int64_t contrast_param_; static int improve_mode_; ros::Subscriber camera_change_sub; + bool stop_grab_{}; }; } // namespace galaxy_camera diff --git a/src/galaxy_camera.cpp b/src/galaxy_camera.cpp index 82b3ad2..bf4edfc 100644 --- a/src/galaxy_camera.cpp +++ b/src/galaxy_camera.cpp @@ -35,6 +35,7 @@ void GalaxyCameraNodelet::onInit() nh_.param("frame_rate", frame_rate_, 210.0); nh_.param("exposure_auto", exposure_auto_, true); nh_.param("exposure_value", exposure_value_, std::float_t(2000.)); + nh_.param("stop_grab", stop_grab_, false); info_manager_.reset(new camera_info_manager::CameraInfoManager(nh_, camera_name_, camera_info_url_)); image_transport::ImageTransport it(nh_); @@ -334,8 +335,13 @@ void GalaxyCameraNodelet::reconfigCB(CameraConfig& config, uint32_t level) { config.exposure_value = exposure_value_; config.exposure_auto = exposure_auto_; + config.stop_grab = stop_grab_; exposure_initialized_flag_ = true; } + if (!config.stop_grab) + GXStreamOn(dev_handle_); + else + GXStreamOff(dev_handle_); // Exposure if (config.exposure_auto) {