Skip to content

Commit 49196e6

Browse files
Fixed crash on DepthCloudPlugin (#1133) (#1153)
Signed-off-by: Alejandro Hernández Cordero <[email protected]> (cherry picked from commit 85bd663) Co-authored-by: Alejandro Hernández Cordero <[email protected]>
1 parent c3946d0 commit 49196e6

File tree

2 files changed

+24
-1
lines changed

2 files changed

+24
-1
lines changed

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

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -104,6 +104,8 @@ protected Q_SLOTS:
104104
/** @brief Fill list of available and working transport options */
105105
void fillTransportOptionList(rviz_common::properties::EnumProperty * property);
106106

107+
void transformerChangedCallback();
108+
107109
// Property callbacks
108110
virtual void updateTopic();
109111
virtual void updateTopicFilter();

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

Lines changed: 22 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,7 @@ DepthCloudDisplay::DepthCloudDisplay()
7272
: rviz_common::Display()
7373
, messages_received_(0)
7474
, depthmap_sub_()
75+
, depthmap_tf_filter_(nullptr)
7576
, rgb_sub_()
7677
, cam_info_sub_()
7778
, queue_size_(5)
@@ -161,6 +162,11 @@ DepthCloudDisplay::DepthCloudDisplay()
161162
use_occlusion_compensation_property_, SLOT(updateOcclusionTimeOut()), this);
162163
}
163164

165+
void DepthCloudDisplay::transformerChangedCallback()
166+
{
167+
updateTopic();
168+
}
169+
164170
void DepthCloudDisplay::onInitialize()
165171
{
166172
auto rviz_ros_node_ = context_->getRosNodeAbstraction().lock();
@@ -184,6 +190,12 @@ void DepthCloudDisplay::onInitialize()
184190

185191
depth_topic_property_->initialize(rviz_ros_node_);
186192
color_topic_property_->initialize(rviz_ros_node_);
193+
194+
QObject::connect(
195+
reinterpret_cast<QObject *>(context_->getTransformationManager()),
196+
SIGNAL(transformerChanged(std::shared_ptr<rviz_common::transformation::FrameTransformer>)),
197+
this,
198+
SLOT(transformerChangedCallback()));
187199
}
188200

189201
DepthCloudDisplay::~DepthCloudDisplay()
@@ -209,6 +221,9 @@ void DepthCloudDisplay::setTopic(const QString & topic, const QString & datatype
209221

210222
void DepthCloudDisplay::updateQueueSize()
211223
{
224+
if (depthmap_tf_filter_) {
225+
depthmap_tf_filter_->setQueueSize(static_cast<uint32_t>(queue_size_property_->getInt()));
226+
}
212227
queue_size_ = queue_size_property_->getInt();
213228
}
214229

@@ -303,7 +318,7 @@ void DepthCloudDisplay::subscribe()
303318
rviz_common::transformation::FrameTransformer>>(
304319
*context_->getFrameManager()->getTransformer(),
305320
fixed_frame_.toStdString(),
306-
10,
321+
queue_size_,
307322
rviz_ros_node_->get_raw_node());
308323

309324
depthmap_tf_filter_->connectInput(*depthmap_sub_);
@@ -382,6 +397,9 @@ void DepthCloudDisplay::unsubscribe()
382397
void DepthCloudDisplay::clear()
383398
{
384399
pointcloud_common_->reset();
400+
if (depthmap_tf_filter_) {
401+
depthmap_tf_filter_->clear();
402+
}
385403
}
386404

387405
void DepthCloudDisplay::update(float wall_dt, float ros_dt)
@@ -603,6 +621,9 @@ void DepthCloudDisplay::fillTransportOptionList(rviz_common::properties::EnumPro
603621

604622
void DepthCloudDisplay::fixedFrameChanged()
605623
{
624+
if (depthmap_tf_filter_) {
625+
depthmap_tf_filter_->setTargetFrame(fixed_frame_.toStdString());
626+
}
606627
Display::reset();
607628
}
608629

0 commit comments

Comments
 (0)