ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Very slow visualization of a huge point cloud inside RViz

asked 2018-11-12 04:50:30 -0500

ravijoshi gravatar image

Hi, I am trying to visualize a huge point cloud inside RViz. I noticed that the visualization is very slow (less than 1 FPS as shown in the bottom right side RViz). Please see below a table showing the FPS and other details-

|-----------------|-----|-----------|--------------|
| Publishing Freq | FPS | CPU Usage | Memory Usage |
|-----------------|-----|-----------|--------------|
|      10 Hz      |  0  |    4%     |     30%      |
|-----------------|-----|-----------|--------------|
|       5 Hz      |  0  |    4%     |     28%      |
|-----------------|-----|-----------|--------------|
|       None      |  0  |    4%     |     25%      |
|-----------------|-----|-----------|--------------|

Below are the details of the environment-

  • Intel® Xeon(R) CPU E5-2640 v2 @ 2.00GHz × 17
  • GeForce GTX 1050 Ti/PCIe/SSE2
  • 32 GB Memory
  • Ubuntu 14.04 LTS 64 Bit OS

During the experiment, nvidia-smi shows less than 20% GPU usage. Below is the minimal code to reproduce the issue-

#include <ros/ros.h>
#include <sensor_msgs/PointCloud2.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/conversions.h>

int main(int argc, char** argv)
{
    ros::init(argc, argv, "pcl_tutorial");
    ros::NodeHandle nh;
    ros::Publisher pub_output = nh.advertise<sensor_msgs::PointCloud2>("points", 1);

    // number of points in point cloud
    int n = 8000000;

    // create a point cloud with random data
    pcl::PointCloud<pcl::PointXYZRGB> cloud;
    cloud.width = n;
    cloud.height = 1;
    cloud.is_dense = false;
    cloud.points.resize(cloud.width * cloud.height);

    for (size_t i = 0; i < cloud.points.size(); ++i) {
        cloud.points[i].x = 1024 * rand() / (RAND_MAX + 1.0f);
        cloud.points[i].y = 1024 * rand() / (RAND_MAX + 1.0f);
        cloud.points[i].z = 1024 * rand() / (RAND_MAX + 1.0f);
        cloud.points[i].r = 255.0 * rand();
        cloud.points[i].g = 255.0 * rand();
        cloud.points[i].b = 255.0 * rand();
    }

    // convert to PointCloud2
    sensor_msgs::PointCloud2 temp_cloud;
    pcl::toROSMsg(cloud, temp_cloud);
    // attach a frame
    temp_cloud.header.frame_id = "base";

    boost::shared_ptr<sensor_msgs::PointCloud2> cloud2 = boost::make_shared<sensor_msgs::PointCloud2>(temp_cloud);

    ros::Rate loop_rate(5);
    while (ros::ok()) {
        // update the timestamp
        cloud2->header.stamp = ros::Time::now();
        pub_output.publish(cloud2);

        ros::spinOnce();
        loop_rate.sleep();
    }
    return 0;
}

Following command was used for calculating CPU Usage-

grep 'cpu ' /proc/stat | awk '{usage=($2+$4)*100/($2+$4+$5)} END {print usage "%"}'

Memory Used-

free | grep Mem | awk '{print $3/$2 * 100.0}'

Following are my questions-

  1. How to know the FPS of the followings-
    • Point cloud publisher and receiver?
    • Point cloud visualization inside RViz?
  2. Why RViz is showing so slow visualization?
  3. How to increase the FPS of visualization inside RViz?
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2018-11-12 05:58:05 -0500

You can use rostopic hz <topic name=""> to find out the rate that messages are being published, it's possible that publishing a 160MB point cloud cannot be done at 5 hz. This will tell you if the speed is being limited by the message passing system or the rendering in RVIZ.

Regarding RVIZ what visualisation style have you got selected for the point cloud? Anything other than points will be slowing things down considerably, spheres for example will be trying to render many triangles for each of the 8 million points. Even the flat squares option will be rendering 16 million triangles.

Another thing you can try is to adjust the number of points you're publishing an visualising, start lower and increase it to find out if there is a cliff edge in the performance where the speed suddenly drops off above a certain size. This will give you some clues as to what's slowing this down.

Hope this helps.

edit flag offensive delete link more

Comments

Thank you very much. After debugging for hours, I realized that ROS publisher is not able to handle a huge amount of data efficiently. Any suggestions? I started a new post to make my post much clear. Please have a look here.

ravijoshi gravatar image ravijoshi  ( 2018-11-13 04:26:35 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-11-12 04:50:30 -0500

Seen: 2,550 times

Last updated: Nov 12 '18