Skip to content

Commit

Permalink
enhance: changed message of acquisition start/stop to info-level
Browse files Browse the repository at this point in the history
  • Loading branch information
boitumeloruf committed Dec 5, 2024
1 parent b561639 commit 872968a
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 13 deletions.
28 changes: 15 additions & 13 deletions camera_aravis2/src/camera_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1064,7 +1064,7 @@ void CameraDriver::handleMessageSubscriptionChange(rclcpp::MatchedInfo& iEventIn
//--- no subscriber so far, start acquisition
if (iEventInfo.current_count > 0 && current_num_subscribers_ == 0)
{
RCLCPP_DEBUG(logger_, "-> Acquisition started.");
RCLCPP_INFO(logger_, "-> Acquisition start.");

arv_device_execute_command(p_device_, "AcquisitionStart", err.ref());
CHECK_GERROR_MSG(err, logger_, "In executing 'AcquisitionStart'.");
Expand All @@ -1073,15 +1073,17 @@ void CameraDriver::handleMessageSubscriptionChange(rclcpp::MatchedInfo& iEventIn
//--- subscribers until now, stop acquisition
else if (iEventInfo.current_count == 0 && current_num_subscribers_ > 0)
{
RCLCPP_DEBUG(logger_, "-> Acquisition stopped.");
RCLCPP_INFO(logger_, "-> Acquisition stop.");

arv_device_execute_command(p_device_, "AcquisitionStop", err.ref());
CHECK_GERROR_MSG(err, logger_, "In executing 'AcquisitionStop'.");
}
}
else
{
RCLCPP_DEBUG(logger_, "p_device_ is NULL or node is not initialized.");
RCLCPP_WARN(logger_, "Subscription change detected but no action taken. "
"Reason: p_device_ is NULL or node is not initialized.");
return;
}

//--- get the maximum number of subscribers over all streams and assign to the member variable
Expand Down Expand Up @@ -1686,6 +1688,15 @@ void CameraDriver::spawnCameraStreams()
arv_stream_set_emit_signals(STREAM.p_arv_stream, TRUE);
}

//--- print final output message
std::string camera_guid_str = CameraAravisNodeBase::constructCameraGuidStr(p_camera_);
RCLCPP_INFO(logger_, "Done initializing.");
RCLCPP_INFO(logger_, " Camera: %s", camera_guid_str.c_str());
if (arv_camera_is_gv_device(p_camera_) && CameraAravisNodeBase::isIpAddress(guid_))
RCLCPP_INFO(logger_, " IP: %s", guid_.c_str());
RCLCPP_INFO(logger_, " Num. Streams: (%i / %i)",
num_opened_streams, static_cast<int>(streams_.size()));

#ifndef WITH_MATCHED_EVENTS
//--- If matched events are not available, the number of subscribers are not dynamically
//--- changed. Thus, set number of subscribers to 1 in order for the acquisition to be started
Expand All @@ -1696,21 +1707,12 @@ void CameraDriver::spawnCameraStreams()
//--- When there are already subscribers to the image topic, start acquisition.
if (current_num_subscribers_ > 0)
{
RCLCPP_DEBUG(logger_, "'AcquisitionStart' at initialization.");
RCLCPP_INFO(logger_, "-> Acquisition start at initialization.");

arv_device_execute_command(p_device_, "AcquisitionStart", err.ref());
CHECK_GERROR_MSG(err, logger_, "In executing 'AcquisitionStart'.");
}

//--- print final output message
std::string camera_guid_str = CameraAravisNodeBase::constructCameraGuidStr(p_camera_);
RCLCPP_INFO(logger_, "Done initializing.");
RCLCPP_INFO(logger_, " Camera: %s", camera_guid_str.c_str());
if (arv_camera_is_gv_device(p_camera_) && CameraAravisNodeBase::isIpAddress(guid_))
RCLCPP_INFO(logger_, " IP: %s", guid_.c_str());
RCLCPP_INFO(logger_, " Num. Streams: (%i / %i)",
num_opened_streams, static_cast<int>(streams_.size()));

this->is_initialized_ = true;
}

Expand Down
2 changes: 2 additions & 0 deletions camera_aravis2/src/camera_driver_gv.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,8 @@ CameraDriverGv::~CameraDriverGv()
//--- stop acquisition
if (p_device_)
{
RCLCPP_INFO(logger_, "-> Acquisition stop.");

arv_device_execute_command(p_device_, "AcquisitionStop", err.ref());
CHECK_GERROR_MSG(err, logger_, "In executing 'AcquisitionStop'.");
}
Expand Down
2 changes: 2 additions & 0 deletions camera_aravis2/src/camera_driver_uv.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,8 @@ CameraDriverUv::~CameraDriverUv()
//--- stop acquisition
if (p_device_)
{
RCLCPP_INFO(logger_, "-> Acquisition stop.");

arv_device_execute_command(p_device_, "AcquisitionStop", err.ref());
CHECK_GERROR_MSG(err, logger_, "In executing 'AcquisitionStop'.");
}
Expand Down

0 comments on commit 872968a

Please sign in to comment.