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

Intel Realsense D400 in Gazebo simulation

asked 2020-03-02 06:46:28 -0500

q8wwe gravatar image

updated 2020-03-04 03:44:40 -0500

fvd gravatar image

Im trying to use intel D400 with gazebo simulation on ROS Kinetic / Ubuntu 16.04. So far I have been using the OpenNI Kinect plugin (libgazebo_ros_openni_kinect.so).

I found there is a Realsense plugin for Gazebo (librealsense_gazebo_plugin.so). I am not sure how to replace the openni_kinect plugin with it in my URDF file, considering that the Realsense has two infrared cameras and an RGB camera.

I want to experiment with the Realsense in simulation before shifting to the real camera. I would like to work with depth images and point clouds for my application. First by using the depthimage_to_laserscan package and later the point clouds for obstacle avoidance. Thanks in advance.

Here is how I currently use the OpenNI Kinect plugin in URDF:

            <link name="camera_link">
          <visual>
            <origin xyz="0.0 0.0 0.004" rpy="0 0 0"/>
            <geometry>
              <mesh filename="package://evarobotmodel_description/meshes/kinect.dae" scale="0.9 0.9 0.9"/>
            </geometry>
          </visual>
          <collision>
            <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
            <geometry>
                <box size="0.0730 0.2760 0.0720"/>
            </geometry>
          </collision>
          <inertial>
            <mass value="0.170" />
            <origin xyz="0 0 0" />
            <inertia ixx="0.001152600" ixy="0.0" ixz="0.0"
                     iyy="0.000148934" iyz="0.0"
                     izz="0.001154654" />
          </inertial>
        </link>
        <joint name="camera_rgb_joint" type="fixed">
          <origin xyz="0.0 -0.02 0.0" rpy="0.0 0.0 0.0"/>
          <parent link="camera_link"/>
          <child link="camera_rgb_frame" />
        </joint>
        <gazebo reference="camera_link">
            <material>Gazebo/FlatBlack</material>
        </gazebo>
        <link name="camera_rgb_frame"/>
        <joint name="camera_rgb_optical_joint" type="fixed">
          <origin xyz="0 0 0" rpy="-1.57079632679 0 -1.57079632679" />
          <parent link="camera_rgb_frame" />
          <child link="camera_rgb_optical_frame" />
        </joint>
        <link name="camera_rgb_optical_frame"/>
        <joint name="camera_joint" type="fixed">
          <origin xyz="0.17 0.0 0.1913" rpy="0.0 0.0 0.0"/>
          <parent link="base_link"/>
          <child link="camera_link"/>
        </joint>
        <joint name="camera_depth_joint" type="fixed">
          <origin xyz="0 -0.045 0" rpy="0 0 0" />
          <parent link="camera_link" />
          <child link="camera_depth_frame" />
        </joint>
        <link name="camera_depth_frame"/>
        <joint name="camera_depth_optical_joint" type="fixed">
          <origin xyz="0 0 0" rpy="-1.57079632679 0 -1.57079632679" />
          <parent link="camera_depth_frame" />
          <child link="camera_depth_optical_frame" />
        </joint>
        <link name="camera_depth_optical_frame"/>
         <!--  Asus mount  -->
        <joint name="mount_asus_xtion_pro_joint" type="fixed">
          <origin xyz="0.1685 -0.0050 0.1563" rpy="1.57079632679 0 -1.57079632679"/>
          <parent link="base_link"/>
          <child link="mount_asus_xtion_pro_link"/>
        </joint>  
        <link name="mount_asus_xtion_pro_link">
<!--          <visual>
            <origin xyz="0 0 0" rpy="0 0 0"/>
            <geometry>
              <mesh filename="package://evarobotmodel_description/meshes/asus_base.dae"/>
            </geometry>
            <material name="Black"/>
          </visual>  -->
          <collision>
            <origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
          <geometry>
            <box size="0.2760 0.0330 0.0120"/>
          </geometry>
          </collision>
          <inertial>
            <mass value="0.170 ...
(more)
edit retag flag offensive close merge delete

Comments

1

I cleaned your post, but I didn't understand everything. You should link the packages that you are using now, and where you are stuck with what you have tried. What about the second Google hit for "Realsense gazebo plugin"? Did you try it? Have you searched the questions on Gazebosim, like this one?

fvd gravatar image fvd  ( 2020-03-04 03:42:52 -0500 )edit

Thank you for the support , after many attempt I was able to make the simulation work with following the link :https://github.com/pal-robotics/realsense_gazebo_plugin/tree/kinetic-devel

after success I tested it with depthimage _to_laser but it didn't work "Could not convert depth image to laserscan: Cannot call rectifyPoint when distortion is unknown."

issue for the dpthimage_to_laser : https://github.com/SyrianSpock/realse...

for the problems I faced with realsense plugin I had to shift back to Kinect plugin.

if any solution please advice.

q8wwe gravatar image q8wwe  ( 2020-03-21 10:56:13 -0500 )edit
1

It would be great if you could post and accept what you wrote as an answer.

fvd gravatar image fvd  ( 2020-03-23 10:45:13 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
1

answered 2020-04-04 09:59:51 -0500

arminkazim gravatar image

updated 2020-04-14 02:12:47 -0500

Hey i found out how to at least use D435. First download this package from https://github.com/pal-robotics/reals... and put it into your catkinws src folder and then compile the catkin package. This will generate a shared library called librealsense_gazebo_plugin.so for you which is used in the files you gonna download in the next steps. you need to download the two xacro files https://github.com/pal-robotics-forks... _d435.gazebo.xacro and _d435.urdf.xacro put those two files in the package inside the urdf folder where you want your realsense to be simulated then in the file _d435.urdf.xacro change the line 13 from <xacro:include filename="$(find realsense2_description)/urdf/urdf _d435.gazebo.xacro"> to packagename with being the name of the package <xacro:include filename="$(find packagename)/urdf/urdf _d435.gazebo.xacro"> Then in the urdf file where you want to use the simulated realsense add the following code, while again replacing packagename with the name of the package you are using. and baselink which the link where you want the realsense camera to be joint on. <xacro:include filename="$(find packagename)/urdf/_d435.urdf.xacro"> <sensor_d435 parent="${prefix}base_link"></sensor_d435></xacro:include></xacro:include></xacro:include>

</sensor_d435> Afterwards when you launch file which uses this urdf model you will find the simulate realsense and you should see rostopics like /camera/color/image_raw

Furthermore in the file urdf _d435.gazebo.xacro file in line 139 you can change the parameter to true so you will get the point cloud you want.

edit flag offensive delete link more

Comments

Hi there.

I'm new about ROS and Gazebo. i'm trying to simulate the intel Realsense D435i into Gazebo for my master thesis, but following what you have said, I'm not able to obtain the camera model and to go on with the simulation. Can I ask you more datails about how you have solved this problem? I'm pretty sure that the problem in my case is at this step:

"Then in the urdf file where you want to use the simulated realsense add the following code, ... <xacro:include filename="$(find packagename)/urdf/_d435.urdf.xacro"> <sensor_d435 parent="${prefix}base_link"></sensor_d435></xacro:include></xacro:include></xacro:include> (why here there are 3 tags to close the xacro:include ?)"

The URDF file that you are talking about is the urdf file that contains also the desciption about the robot or is another urdf file? The camera ...(more)

AndreSpa gravatar image AndreSpa  ( 2020-04-29 17:42:35 -0500 )edit

Hello, is there something similar for D415 camera? I could not find any _d415 gazebo xacro file? From the intel specs, they seem to be quite different.

ThreeForElvenKings gravatar image ThreeForElvenKings  ( 2020-06-01 05:49:49 -0500 )edit
0

answered 2020-06-25 09:09:51 -0500

GPrathap gravatar image

Install https://github.com/pal-robotics/reals... (melodic-develbranch), then you may use this sdf file https://gist.github.com/GPrathap/044f... , Here I have some more stuff other than a just camera, hope you will able to figure it out. If not let's know, will help you..

edit flag offensive delete link more

Comments

Hi, I am able to add realsense camera to the iris drone but when i run the command

roslaunch realsense2_camera rs_camera.launch

it displays

I am not able to get what is the problem. And when i run the command rostopic list. I am able to see following topic

/camera/fisheye1/image_raw /camera/fisheye2/image_raw /camera/odom/sample /camera/odom/sample_throttled

but when i run rostopic echo /camera/odom/sample it shows

WARNING: topic [/camera/odom/sample] does not appear to be published yet

MWK gravatar image MWK  ( 2021-08-10 02:43:36 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-03-02 06:46:28 -0500

Seen: 3,324 times

Last updated: Jun 25 '20