Skip to content

Commit

Permalink
Add some more extended logging
Browse files Browse the repository at this point in the history
  • Loading branch information
apartridge committed Feb 28, 2025
1 parent 8cf8e57 commit 99739e4
Showing 1 changed file with 7 additions and 2 deletions.
9 changes: 7 additions & 2 deletions zivid_camera/src/zivid_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,10 @@ class ScopeExit final

#define ZIVIDROS_LOG_ENTRY() \
const auto current_time = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); \
ROS_INFO_STREAM("ENTER:" << __func__ << " threadid=" << std::this_thread::get_id() << " time=" << std::put_time(std::gmtime(&current_time), "%c %Z")); \
ROS_INFO_STREAM("ENTER:" << __func__ << " threadid=" << std::this_thread::get_id() << " time=" << std::put_time(std::localtime(&current_time), "%c %Z")); \
auto logOnExitAlso = ScopeExit([funname=std::string{__func__}]() { \
const auto exit_time = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); \
ROS_INFO_STREAM("EXIT:" << funname << " threadid=" << std::this_thread::get_id() << " time=" << std::put_time(std::gmtime(&exit_time), "%c %Z")); \
ROS_INFO_STREAM("EXIT:" << funname << " threadid=" << std::this_thread::get_id() << " time=" << std::put_time(std::localtime(&exit_time), "%c %Z")); \
});


Expand Down Expand Up @@ -160,6 +160,9 @@ ZividCamera::ZividCamera(ros::NodeHandle& nh, ros::NodeHandle& priv)
ROS_INFO_STREAM("Zivid ROS driver version" << ZIVID_ROS_DRIVER_VERSION);
ROS_INFO("Node's namespace is '%s'", nh_.getNamespace().c_str());

boost::process::pid_t pid = boost::this_process::get_id();
ROS_INFO_STREAM("This node's process id is " << pid);

if (nh_.getNamespace() == "")
{
// Require the user to specify the namespace that this node will run in.
Expand Down Expand Up @@ -513,7 +516,9 @@ void ZividCamera::serviceHandlerHandleCameraConnectionLoss()

bool ZividCamera::isConnectedServiceHandler(IsConnected::Request&, IsConnected::Response& res)
{
ZIVIDROS_LOG_ENTRY();
res.is_connected = camera_status_ == CameraStatus::Connected;
ROS_INFO_STREAM(__func__ << " res.is_connected=" << res.is_connected);
return true;
}

Expand Down

0 comments on commit 99739e4

Please sign in to comment.