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
Original file line number Diff line number Diff line change
Expand Up @@ -163,6 +163,10 @@ class AvtVimbaCamera
rcl_interfaces::msg::SetParametersResult parameterCallback(const std::vector<rclcpp::Parameter>& parameters);
void updateCameraInfo();
void getCurrentState(diagnostic_updater::DiagnosticStatusWrapper& stat);

double last_frame_sec = 0.0;
void timerCallback();
rclcpp::TimerBase::SharedPtr timer_;
};
} // namespace avt_vimba_camera
#endif
11 changes: 10 additions & 1 deletion avt_vimba_camera/src/avt_vimba_camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,8 +64,16 @@ AvtVimbaCamera::AvtVimbaCamera(rclcpp::Node::SharedPtr owner_node)

updater_.setHardwareID("unknown");
updater_.add(owner_node->get_name(), this, &AvtVimbaCamera::getCurrentState);
timer_ = nh_->create_wall_timer(std::chrono::milliseconds(1000), std::bind(&AvtVimbaCamera::timerCallback, this));
last_frame_sec = nh_->now().seconds();
}
void AvtVimbaCamera::timerCallback()
{
if ( this->nh_->now().seconds() - last_frame_sec > 2)
{
RCLCPP_ERROR_STREAM(nh_->get_logger(), "Did not get frame after " << this->nh_->now().seconds() - last_frame_sec << " seconds");
}
}

void AvtVimbaCamera::start(const std::string& ip_str, const std::string& guid_str, const std::string& frame_id,
const std::string& camera_info_url)
{
Expand Down Expand Up @@ -277,6 +285,7 @@ CameraPtr AvtVimbaCamera::openCamera(const std::string& id_str)
void AvtVimbaCamera::frameCallback(const FramePtr vimba_frame_ptr)
{
std::unique_lock<std::mutex> lock(config_mutex_);
last_frame_sec = this->nh_->now().seconds();
camera_state_ = OK;
diagnostic_msg_ = "Camera operating normally";

Expand Down