Skip to content

Commit

Permalink
Add threadid to a few of the log statements
Browse files Browse the repository at this point in the history
  • Loading branch information
apartridge committed Feb 20, 2025
1 parent 8d12fcd commit c204ecf
Showing 1 changed file with 10 additions and 8 deletions.
18 changes: 10 additions & 8 deletions zivid_camera/src/zivid_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,9 +107,9 @@ ZividCamera::ZividCamera(ros::NodeHandle& nh, ros::NodeHandle& priv)
, zivid_(makeZividApplication())
, header_seq_(0)
{
ROS_INFO("Zivid ROS driver version %s", ZIVID_ROS_DRIVER_VERSION);

ROS_INFO_STREAM("Zivid ROS driver version" << ZIVID_ROS_DRIVER_VERSION << " Threadid=" std::this_thread::get_id());
ROS_INFO("Node's namespace is '%s'", nh_.getNamespace().c_str());

if (nh_.getNamespace() == "")
{
// Require the user to specify the namespace that this node will run in.
Expand Down Expand Up @@ -264,7 +264,7 @@ ZividCamera::ZividCamera(ros::NodeHandle& nh, ros::NodeHandle& priv)

void ZividCamera::onCameraConnectionKeepAliveTimeout(const ros::TimerEvent&)
{
ROS_INFO_STREAM(__func__);
ROS_INFO_STREAM(__func__ << " threadid=" << std::this_thread::get_id());
try
{
reconnectToCameraIfNecessary();
Expand All @@ -277,7 +277,7 @@ void ZividCamera::onCameraConnectionKeepAliveTimeout(const ros::TimerEvent&)

void ZividCamera::reconnectToCameraIfNecessary()
{
ROS_INFO_STREAM(__func__);
ROS_INFO_STREAM(__func__ << " threadid=" << std::this_thread::get_id());

const auto state = camera_.state();
if (state.isConnected().value())
Expand Down Expand Up @@ -348,7 +348,7 @@ bool ZividCamera::cameraInfoSerialNumberServiceHandler(zivid_camera::CameraInfoS

bool ZividCamera::captureServiceHandler(Capture::Request&, Capture::Response&)
{
ROS_INFO_STREAM(__func__);
ROS_INFO_STREAM(__func__ << " threadid=" << std::this_thread::get_id());

invokeCaptureAndPublishFrame();

Expand All @@ -357,7 +357,7 @@ bool ZividCamera::captureServiceHandler(Capture::Request&, Capture::Response&)

bool ZividCamera::captureAndSaveServiceHandler(CaptureAndSave::Request& req, CaptureAndSave::Response&)
{
ROS_INFO_STREAM(__func__);
ROS_INFO_STREAM(__func__ << " threadid=" << std::this_thread::get_id());

const auto frame = invokeCaptureAndPublishFrame();
ROS_INFO("Saving frame to '%s'", req.file_path.c_str());
Expand All @@ -368,7 +368,7 @@ bool ZividCamera::captureAndSaveServiceHandler(CaptureAndSave::Request& req, Cap

bool ZividCamera::capture2DServiceHandler(Capture2D::Request&, Capture2D::Response&)
{
ROS_INFO_STREAM(__func__);
ROS_INFO_STREAM(__func__ << " threadid=" << std::this_thread::get_id());

serviceHandlerHandleCameraConnectionLoss();

Expand Down Expand Up @@ -452,6 +452,7 @@ bool ZividCamera::loadSettings2DFromFileServiceHandler(LoadSettings2DFromFile::R

void ZividCamera::serviceHandlerHandleCameraConnectionLoss()
{
ROS_INFO_STREAM(__func__ << " threadid=" << std::this_thread::get_id());
reconnectToCameraIfNecessary();
if (camera_status_ != CameraStatus::Connected)
{
Expand All @@ -468,6 +469,7 @@ bool ZividCamera::isConnectedServiceHandler(IsConnected::Request&, IsConnected::

void ZividCamera::publishFrame(const Zivid::Frame& frame)
{
ROS_INFO_STREAM(__func__ << " threadid=" << std::this_thread::get_id());
const bool publish_points_xyz = shouldPublishPointsXYZ();
const bool publish_points_xyzrgba = shouldPublishPointsXYZRGBA();
const bool publish_color_img = shouldPublishColorImg();
Expand Down Expand Up @@ -708,7 +710,7 @@ sensor_msgs::CameraInfoConstPtr ZividCamera::makeCameraInfo(const std_msgs::Head

Zivid::Frame ZividCamera::invokeCaptureAndPublishFrame()
{
ROS_INFO_STREAM(__func__);
ROS_INFO_STREAM(__func__ << " threadid=" << std::this_thread::get_id());

serviceHandlerHandleCameraConnectionLoss();

Expand Down

0 comments on commit c204ecf

Please sign in to comment.