Skip to content

Commit d497014

Browse files
DepthCloud plugin: Append measured subscription frequency to topic status (#1137) (#1146)
Signed-off-by: Alejandro Hernández Cordero <[email protected]> (cherry picked from commit ad1990b) Co-authored-by: Alejandro Hernández Cordero <[email protected]>
1 parent a75eedc commit d497014

File tree

2 files changed

+17
-5
lines changed

2 files changed

+17
-5
lines changed

rviz_default_plugins/include/rviz_default_plugins/displays/depth_cloud/depth_cloud_display.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -155,6 +155,7 @@ protected Q_SLOTS:
155155
typedef message_filters::Synchronizer<SyncPolicyDepthColor> SynchronizerDepthColor;
156156

157157
std::shared_ptr<SynchronizerDepthColor> sync_depth_color_;
158+
rclcpp::Time subscription_start_time_;
158159

159160
// RVIZ properties
160161
rviz_common::properties::Property * topic_filter_property_;

rviz_default_plugins/src/rviz_default_plugins/displays/depth_cloud/depth_cloud_display.cpp

Lines changed: 16 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -412,11 +412,22 @@ void DepthCloudDisplay::processMessage(
412412

413413
std::ostringstream s;
414414

415-
++messages_received_;
416-
setStatus(
417-
rviz_common::properties::StatusProperty::Ok, "Depth Map",
418-
QString::number(messages_received_) + " depth maps received");
419-
setStatus(rviz_common::properties::StatusProperty::Ok, "Message", "Ok");
415+
{
416+
++messages_received_;
417+
auto rviz_ros_node_ = context_->getRosNodeAbstraction().lock();
418+
QString topic_str = QString::number(messages_received_) + " messages received";
419+
// Append topic subscription frequency if we can lock rviz_ros_node_.
420+
if (rviz_ros_node_ != nullptr) {
421+
const double duration =
422+
(rviz_ros_node_->get_raw_node()->now() - subscription_start_time_).seconds();
423+
const double subscription_frequency =
424+
static_cast<double>(messages_received_) / duration;
425+
topic_str += " at " + QString::number(subscription_frequency, 'f', 1) + " hz.";
426+
}
427+
setStatus(
428+
rviz_common::properties::StatusProperty::Ok, "Depth Map", topic_str);
429+
setStatus(rviz_common::properties::StatusProperty::Ok, "Message", "Ok");
430+
}
420431

421432
sensor_msgs::msg::CameraInfo::ConstSharedPtr cam_info;
422433
{

0 commit comments

Comments
 (0)