diff --git a/spinnaker_camera_driver/include/spinnaker_camera_driver/camera.hpp b/spinnaker_camera_driver/include/spinnaker_camera_driver/camera.hpp index e3398f88..b4d4e34e 100644 --- a/spinnaker_camera_driver/include/spinnaker_camera_driver/camera.hpp +++ b/spinnaker_camera_driver/include/spinnaker_camera_driver/camera.hpp @@ -143,6 +143,7 @@ class Camera double acquisitionTimeout_{3.0}; bool adjustTimeStamp_{false}; bool connectWhileSubscribed_{false}; // if true, connects to SDK when subscription happens + bool enableExternalControl_{false}; uint32_t currentExposureTime_{0}; double averageTimeDifference_{std::numeric_limits::quiet_NaN()}; int64_t baseTimeOffset_{0}; diff --git a/spinnaker_camera_driver/src/camera.cpp b/spinnaker_camera_driver/src/camera.cpp index b371d9c4..05831c79 100644 --- a/spinnaker_camera_driver/src/camera.cpp +++ b/spinnaker_camera_driver/src/camera.cpp @@ -216,6 +216,7 @@ void Camera::readParameters() acquisitionTimeout_ = safe_declare(prefix_ + "acquisition_timeout", 3.0); parameterFile_ = safe_declare(prefix_ + "parameter_file", "parameters.yaml"); connectWhileSubscribed_ = safe_declare(prefix_ + "connect_while_subscribed", false); + enableExternalControl_ = safe_declare(prefix_ + "enable_external_control", false); callbackHandle_ = node_->add_on_set_parameters_callback( std::bind(&Camera::parameterChanged, this, std::placeholders::_1)); } @@ -667,9 +668,11 @@ bool Camera::start() infoManager_ = std::make_shared( node_, name_.empty() ? node_->get_name() : name_, cameraInfoURL_); - controlSub_ = node_->create_subscription( - "~/" + topicPrefix_ + "control", 10, - std::bind(&Camera::controlCallback, this, std::placeholders::_1)); + if (enableExternalControl_) { + controlSub_ = node_->create_subscription( + "~/" + topicPrefix_ + "control", 10, + std::bind(&Camera::controlCallback, this, std::placeholders::_1)); + } metaPub_ = node_->create_publisher("~/" + topicPrefix_ + "meta", 1);