File tree Expand file tree Collapse file tree 2 files changed +17
-5
lines changed
include/rviz_default_plugins/displays/depth_cloud
src/rviz_default_plugins/displays/depth_cloud Expand file tree Collapse file tree 2 files changed +17
-5
lines changed Original file line number Diff line number Diff line change @@ -155,6 +155,7 @@ protected Q_SLOTS:
155
155
typedef message_filters::Synchronizer<SyncPolicyDepthColor> SynchronizerDepthColor;
156
156
157
157
std::shared_ptr<SynchronizerDepthColor> sync_depth_color_;
158
+ rclcpp::Time subscription_start_time_;
158
159
159
160
// RVIZ properties
160
161
rviz_common::properties::Property * topic_filter_property_;
Original file line number Diff line number Diff line change @@ -412,11 +412,22 @@ void DepthCloudDisplay::processMessage(
412
412
413
413
std::ostringstream s;
414
414
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
+ }
420
431
421
432
sensor_msgs::msg::CameraInfo::ConstSharedPtr cam_info;
422
433
{
You can’t perform that action at this time.
0 commit comments