Skip to content

Commit

Permalink
Improve error handling in LaserScanDisplay (ros-visualization#1798)
Browse files Browse the repository at this point in the history
* Improve "unknown TF error" message
* LaserScanDisplay: warn about large scan time
  • Loading branch information
rhaschke authored May 25, 2023
1 parent b023cc5 commit 96a76a4
Show file tree
Hide file tree
Showing 3 changed files with 16 additions and 1 deletion.
12 changes: 12 additions & 0 deletions src/rviz/default_plugin/laser_scan_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,16 @@ void LaserScanDisplay::updateQueueSize()
tf_filter_->setQueueSize((uint32_t)queue_size_property_->getInt());
}

void LaserScanDisplay::checkTolerance(int tolerance)
{
if (tolerance > 1)
setStatus(StatusProperty::Warn, "Scan Time",
QString(
"Laser scan time, computed from time_increment * len(ranges), is rather large: %1s.\n"
"The display of any message will be delayed by this amount of time!")
.arg(tolerance));
}

void LaserScanDisplay::processMessage(const sensor_msgs::LaserScanConstPtr& scan)
{
sensor_msgs::PointCloudPtr cloud(new sensor_msgs::PointCloud);
Expand All @@ -89,6 +99,7 @@ void LaserScanDisplay::processMessage(const sensor_msgs::LaserScanConstPtr& scan
{
filter_tolerance_ = tolerance;
tf_filter_->setTolerance(filter_tolerance_);
checkTolerance(filter_tolerance_.toSec());
}

try
Expand Down Expand Up @@ -127,6 +138,7 @@ void LaserScanDisplay::reset()
{
MFDClass::reset();
point_cloud_common_->reset();
checkTolerance(filter_tolerance_.toSec());
}

} // namespace rviz
Expand Down
3 changes: 3 additions & 0 deletions src/rviz/default_plugin/laser_scan_display.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,9 @@ private Q_SLOTS:
/** @brief Process a single message. Overridden from MessageFilterDisplay. */
void processMessage(const sensor_msgs::LaserScanConstPtr& scan) override;

/** create a status warning when tolerance is larger than 1s */
void checkTolerance(int tolerance);

IntProperty* queue_size_property_;

PointCloudCommon* point_cloud_common_;
Expand Down
2 changes: 1 addition & 1 deletion src/rviz/frame_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -392,7 +392,7 @@ std::string FrameManager::discoverFailureReason(const std::string& frame_id,
}
}

return "Unknown reason for transform failure";
return "Unknown reason for transform failure (frame=[" + frame_id + "])";
}

void FrameManager::messageArrived(const std::string& /*frame_id*/,
Expand Down

0 comments on commit 96a76a4

Please sign in to comment.