Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Improve error handling in LaserScanDisplay #1798

Merged
merged 2 commits into from
May 25, 2023
Merged
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
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