Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -49,3 +49,6 @@ qtcreator-*

# Catkin custom files
CATKIN_IGNORE

.clang-format
.clang-tidy
2 changes: 2 additions & 0 deletions cfg/camera.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -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"))
1 change: 1 addition & 0 deletions include/galaxy_camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down
6 changes: 6 additions & 0 deletions src/galaxy_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_);
Expand Down Expand Up @@ -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)
{
Expand Down