Skip to content

Commit

Permalink
Update display if empty pointcloud2 is published (#1073)
Browse files Browse the repository at this point in the history
Do not show last point cloud any more, if published point cloud message does not contain any points
  • Loading branch information
axelschroth authored and wjwwood committed Jun 5, 2017
1 parent f1f7f2a commit 60cb183
Showing 1 changed file with 33 additions and 32 deletions.
65 changes: 33 additions & 32 deletions src/rviz/default_plugin/point_cloud2_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,50 +106,51 @@ void PointCloud2Display::processMessage( const sensor_msgs::PointCloud2ConstPtr&
}

filtered->data.resize(cloud->data.size());
uint32_t output_count;
if (point_count == 0)
{
return;
}

uint8_t* output_ptr = &filtered->data.front();
const uint8_t* ptr = &cloud->data.front(), *ptr_end = &cloud->data.back(), *ptr_init;
size_t points_to_copy = 0;
for (; ptr < ptr_end; ptr += point_step)
{
float x = *reinterpret_cast<const float*>(ptr + xoff);
float y = *reinterpret_cast<const float*>(ptr + yoff);
float z = *reinterpret_cast<const float*>(ptr + zoff);
if (validateFloats(x) && validateFloats(y) && validateFloats(z))
output_count = 0;
} else {
uint8_t* output_ptr = &filtered->data.front();
const uint8_t* ptr = &cloud->data.front(), *ptr_end = &cloud->data.back(), *ptr_init;
size_t points_to_copy = 0;
for (; ptr < ptr_end; ptr += point_step)
{
if (points_to_copy == 0)
float x = *reinterpret_cast<const float*>(ptr + xoff);
float y = *reinterpret_cast<const float*>(ptr + yoff);
float z = *reinterpret_cast<const float*>(ptr + zoff);
if (validateFloats(x) && validateFloats(y) && validateFloats(z))
{
// Only memorize where to start copying from
ptr_init = ptr;
points_to_copy = 1;
if (points_to_copy == 0)
{
// Only memorize where to start copying from
ptr_init = ptr;
points_to_copy = 1;
}
else
{
++points_to_copy;
}
}
else
{
++points_to_copy;
if (points_to_copy)
{
// Copy all the points that need to be copied
memcpy(output_ptr, ptr_init, point_step*points_to_copy);
output_ptr += point_step*points_to_copy;
points_to_copy = 0;
}
}
}
else
// Don't forget to flush what needs to be copied
if (points_to_copy)
{
if (points_to_copy)
{
// Copy all the points that need to be copied
memcpy(output_ptr, ptr_init, point_step*points_to_copy);
output_ptr += point_step*points_to_copy;
points_to_copy = 0;
}
memcpy(output_ptr, ptr_init, point_step*points_to_copy);
output_ptr += point_step*points_to_copy;
}
output_count = (output_ptr - &filtered->data.front()) / point_step;
}
// Don't forget to flush what needs to be copied
if (points_to_copy)
{
memcpy(output_ptr, ptr_init, point_step*points_to_copy);
output_ptr += point_step*points_to_copy;
}
uint32_t output_count = (output_ptr - &filtered->data.front()) / point_step;

filtered->header = cloud->header;
filtered->fields = cloud->fields;
Expand Down

0 comments on commit 60cb183

Please sign in to comment.