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

RGBD camera noise model

asked 2015-10-08 05:55:51 -0500

DISCLAIMER: I know this question should go on Gazebo Answers, but I am having problems logging in (or the site is fallen).

I saw there are many sensor models and plugins in order to simulate an RGB camera (either Asus, Kinect, etc). However, I do not see any way to include noise in both RGB and Depth, neither in Gazebo nor in the available plugins. I tried the <noise> tag in the sensor but it seems to have no effect.

Is there any gazebo_ros plugin (or Gazebo plugin) somewhere to simulate the RGB camera more accurately?

Thank you!

For completeness, I include the part of the sensor of my model:

        <sensor type="depth" name="rgbd_camera">
            <camera>
                <horizontal_fov>1.047</horizontal_fov>
                <image>
                    <width>640</width>
                    <height>480</height>
                    <format>R8G8B8</format>
                </image>
                <clip>
                    <near>0.05</near>
                    <far>30</far>
                </clip>
                <noise>   <!-- This does apparently nothing neither RGB nor depth-->
                    <type>gaussian</type>
                    <mean>0.0</mean>
                    <stddev>5.0</stddev>
                </noise>
            </camera>
            <update_rate>30.0</update_rate>
            <always_on>1</always_on>
            <plugin name="multirotor_rgbd_plugin" filename="libgazebo_ros_openni_kinect.so">
                <imageTopicName>rgb/image_raw</imageTopicName>
                <cameraInfoTopicName>rgb/camera_info</cameraInfoTopicName>
                <pointCloudTopicName>depth/points</pointCloudTopicName>
                <depthImageTopicName>depth/image_raw</depthImageTopicName>
                <depthImageCameraInfoTopicName>depth/camera_info</depthImageCameraInfoTopicName>
                <pointCloudCutoff>0.4</pointCloudCutoff>
                <pointCloudCutoffMax>5.0</pointCloudCutoffMax>
                <frameName>rgbd_camera_link</frameName>
                <cameraName>rgbd_camera</cameraName>
                <updateRate>30.0</updateRate>
            </plugin>
        </sensor>
edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
1

answered 2019-10-29 02:06:22 -0500

The question has been asked years ago but to people who might need this in future; Gazebo does not provide a noise model for the depth part of RGBD, most probably your depth data will be inside a ROS node in sensor_msgs::Pointcloud2, I used PCL to add gaussian noise to cloud as follow;

//Gaussian noise to pcl
#include <boost/random.hpp>
#include <boost/random/normal_distribution.hpp>
#include <boost/thread/thread.hpp>
#include <boost/lexical_cast.hpp>
#include <boost/make_shared.hpp>
#include <boost/date_time/gregorian/gregorian_types.hpp>
#include <boost/date_time/posix_time/posix_time.hpp>
#include <boost/date_time/posix_time/posix_time_types.hpp>
#include <boost/thread/thread.hpp>
#include <pcl/console/print.h>
#include <pcl/console/parse.h>
#include <pcl/console/time.h>

using namespace pcl;
using namespace pcl::io;
using namespace pcl::console;

void addGaussiaNoise(const sensor_msgs::PointCloud2::ConstPtr &input, sensor_msgs::PointCloud2 &output,
                     double standard_deviation)
{
    TicToc tt;
    tt.tic();

    print_highlight("Adding Gaussian noise with mean 0.0 and standard deviation %f\n", standard_deviation);

    PointCloud<PointXYZ>::Ptr xyz_cloud(new pcl::PointCloud<PointXYZ>());
    PointCloud<PointXYZ>::Ptr output_cloud_pcl(new pcl::PointCloud<PointXYZ>());

    fromROSMsg(*input, *xyz_cloud);

    PointCloud<PointXYZ>::Ptr xyz_cloud_filtered(new PointCloud<PointXYZ>());
    xyz_cloud_filtered->points.resize(xyz_cloud->points.size());
    xyz_cloud_filtered->header = xyz_cloud->header;
    xyz_cloud_filtered->width = xyz_cloud->width;
    xyz_cloud_filtered->height = xyz_cloud->height;

    boost::mt19937 rng;
    rng.seed(static_cast<unsigned int>(time(0)));
    boost::normal_distribution<> nd(0, standard_deviation);
    boost::variate_generator<boost::mt19937 &, boost::normal_distribution<>> var_nor(rng, nd);

    for (size_t point_i = 0; point_i < xyz_cloud->points.size(); ++point_i)
    {
        xyz_cloud_filtered->points[point_i].x = xyz_cloud->points[point_i].x + static_cast<float>(var_nor());
        xyz_cloud_filtered->points[point_i].y = xyz_cloud->points[point_i].y + static_cast<float>(var_nor());
        xyz_cloud_filtered->points[point_i].z = xyz_cloud->points[point_i].z + static_cast<float>(var_nor());
    }

    sensor_msgs::PointCloud2 input_xyz_filtered;

    concatenateFields(*xyz_cloud, *xyz_cloud_filtered, *output_cloud_pcl);

    toROSMsg(*output_cloud_pcl, output);

    print_info("[done, ");
    print_value("%g", tt.toc());
    print_info(" ms: ");
    print_value("%d", output.width * output.height);
    print_info(" points]\n");
}
edit flag offensive delete link more
1

answered 2015-10-09 02:57:56 -0500

I asked the same question 3 years ago (see here), but I'm not aware of a plugin available that implements a (somewhat) realistic error model. It however appears doable to take the "perfect" depth image provided by Gazebo inside a plugin and then apply a error model to it to generate more realistic data.

edit flag offensive delete link more

Comments

Thanks for the info. That is what I was planning to do if there are not implementations out there. Actually, I saw your question but I expected to be some more information 3 years later :)

Javier V. Gómez gravatar image Javier V. Gómez  ( 2015-10-09 05:31:20 -0500 )edit

4 years later and still nothing

Fetullah Atas gravatar image Fetullah Atas  ( 2019-10-29 01:09:37 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-10-08 05:55:51 -0500

Seen: 1,615 times

Last updated: Oct 29 '19