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 #1035

Merged
merged 5 commits into from
Sep 5, 2023
Merged
Show file tree
Hide file tree
Changes from 4 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 @@ -47,6 +47,8 @@
#include "rviz_default_plugins/transformation/tf_frame_transformer.hpp"
#include "rviz_default_plugins/visibility_control.hpp"

#include <rclcpp/duration.hpp>

namespace rviz_common
{
class QueueSizeProperty;
Expand Down Expand Up @@ -81,6 +83,9 @@ class RVIZ_DEFAULT_PLUGINS_PUBLIC LaserScanDisplay : public
/** @brief Process a single message. Overridden from MessageFilterDisplay. */
void processMessage(sensor_msgs::msg::LaserScan::ConstSharedPtr scan) override;

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

std::unique_ptr<PointCloudCommon> point_cloud_common_;
std::unique_ptr<laser_geometry::LaserProjection> projector_;
rclcpp::Duration filter_tolerance_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,11 +35,14 @@
#include "tf2_ros/buffer.h"

#include "rviz_common/properties/int_property.hpp"
#include "rviz_common/properties/status_property.hpp"
#include "rviz_common/transformation/transformation_manager.hpp"
#include "rviz_common/validate_floats.hpp"
#include "rviz_default_plugins/displays/pointcloud/point_cloud_common.hpp"
#include "rviz_default_plugins/transformation/tf_wrapper.hpp"

#include <rclcpp/duration.hpp>

namespace rviz_default_plugins
{
namespace displays
Expand All @@ -61,6 +64,19 @@ void LaserScanDisplay::onInitialize()
transformer_guard_->initialize(context_);
}

void LaserScanDisplay::checkTolerance(rclcpp::Duration tolerance)
{
auto tolerance_seg = RCL_NS_TO_S(filter_tolerance_.nanoseconds());
if (tolerance_seg > 1) {
setStatus(
rviz_common::properties::StatusProperty::Warn, "Scan Time",
QString(
"Laser scan time, computed from time_increment * len(ranges), is rather large: "
" %1s.\nThe display of any message will be delayed by this amount of time!")
.arg(tolerance_seg));
}
}

void LaserScanDisplay::processMessage(sensor_msgs::msg::LaserScan::ConstSharedPtr scan)
{
// Compute tolerance necessary for this scan
Expand All @@ -72,6 +88,7 @@ void LaserScanDisplay::processMessage(sensor_msgs::msg::LaserScan::ConstSharedPt
if (tolerance > filter_tolerance_) {
filter_tolerance_ = tolerance;
tf_filter_->setTolerance(filter_tolerance_);
checkTolerance(filter_tolerance_);
}
auto cloud = std::make_shared<sensor_msgs::msg::PointCloud2>();
auto tf_wrapper = std::dynamic_pointer_cast<transformation::TFWrapper>(
Expand Down Expand Up @@ -108,6 +125,7 @@ void LaserScanDisplay::reset()
{
MFDClass::reset();
point_cloud_common_->reset();
checkTolerance(filter_tolerance_);
}

void LaserScanDisplay::onDisable()
Expand Down