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

RealSense D435 gazebo plugin

asked 2020-04-03 11:56:57 -0500

didrif14 gravatar image

updated 2022-03-03 09:39:55 -0500

lucasw gravatar image

Hello, I am new to ROS and trying to replace the Kinect gazebo plugin with a RealSense plugin. The plugin I want to use is this one:

https://github.com/pal-robotics/reals...

However, there are no documentation of how to use the plugin. Are anyone familiar with this plugin, or similar plugins?

So far I have cloned the repository to my /catkin_ws/src and catkin_make, which successfully created the

libgazebo_librealsense_gazebo_plugin.so

I would appreciate some guidance on how to correctly configure this plugin.

I have uploaded all my files to github:

https://github.com/didrif14/megatrond

When i load the model, only my robot shows up, not the camera, and no topics are published.

I think it may have something to do with a catkin_make error, because I get the following output whenever i catkin_make:

[  0%] Built target tf2_msgs_generate_messages_lisp
[  0%] Built target std_msgs_generate_messages_eus
[  0%] Built target roscpp_generate_messages_lisp
[  0%] Built target roscpp_generate_messages_eus
[  0%] Built target std_msgs_generate_messages_lisp
[  0%] Built target rosgraph_msgs_generate_messages_lisp
[  0%] Built target rosgraph_msgs_generate_messages_eus
[  0%] Built target roscpp_generate_messages_cpp
[  0%] Built target rosgraph_msgs_generate_messages_py
[  0%] Built target rosgraph_msgs_generate_messages_nodejs
[  0%] Built target rosgraph_msgs_generate_messages_cpp
[  0%] Built target roscpp_generate_messages_py
[  0%] Built target std_msgs_generate_messages_nodejs
[  0%] Built target std_msgs_generate_messages_py
[  0%] Built target roscpp_generate_messages_nodejs
[  0%] Built target std_msgs_generate_messages_cpp
[  0%] Built target trajectory_msgs_generate_messages_nodejs
[  0%] Built target trajectory_msgs_generate_messages_cpp
[  0%] Built target gazebo_msgs_generate_messages_nodejs
[  0%] Built target trajectory_msgs_generate_messages_eus
[  0%] Built target trajectory_msgs_generate_messages_lisp
[  0%] Built target trajectory_msgs_generate_messages_py
[  0%] Built target gazebo_msgs_generate_messages_eus
[  0%] Built target gazebo_msgs_generate_messages_cpp
[  0%] Built target gazebo_msgs_generate_messages_py
[  0%] Built target gazebo_msgs_generate_messages_lisp
[  0%] Built target dynamic_reconfigure_generate_messages_py
[  0%] Built target dynamic_reconfigure_generate_messages_nodejs
[  0%] Built target dynamic_reconfigure_generate_messages_eus
[  0%] Built target dynamic_reconfigure_generate_messages_lisp
[  0%] Built target dynamic_reconfigure_gencfg
[  0%] Built target dynamic_reconfigure_generate_messages_cpp
[  0%] Built target tf_generate_messages_cpp
[  0%] Built target sensor_msgs_generate_messages_cpp
[  0%] Built target tf_generate_messages_lisp
[  0%] Built target tf2_msgs_generate_messages_eus
[  0%] Built target std_srvs_generate_messages_py
[  0%] Built target tf2_msgs_generate_messages_nodejs
[  0%] Built target sensor_msgs_generate_messages_eus
[  0%] Built target std_srvs_generate_messages_lisp
[  0%] Built target tf_generate_messages_nodejs
[  0%] Built target geometry_msgs_generate_messages_lisp
[  0%] Built target geometry_msgs_generate_messages_nodejs
[  0%] Built target geometry_msgs_generate_messages_cpp
[  0%] Built target actionlib_msgs_generate_messages_nodejs
[  0%] Built target actionlib_generate_messages_eus
[  0%] Built target gazebo_ros_gencfg
[  0%] Built target tf_generate_messages_eus
[  0%] Built target sensor_msgs_generate_messages_py
[  0%] Built target actionlib_msgs_generate_messages_cpp
[  0%] Built target sensor_msgs_generate_messages_lisp
[  0%] Built target geometry_msgs_generate_messages_eus
[  0%] Built target std_srvs_generate_messages_cpp
[  0%] Built target geometry_msgs_generate_messages_py
[  0%] Built target std_srvs_generate_messages_eus
[  0%] Built target sensor_msgs_generate_messages_nodejs
[  0%] Built target std_srvs_generate_messages_nodejs
[  0%] Built target actionlib_generate_messages_nodejs
[  0%] Built target actionlib_generate_messages_py
[  0%] Built target tf_generate_messages_py
[  0%] Built target actionlib_msgs_generate_messages_eus
[  0%] Built target actionlib_generate_messages_cpp
[  0%] Built target actionlib_generate_messages_lisp
[  0%] Built target actionlib_msgs_generate_messages_lisp
[  0%] Built target tf2_msgs_generate_messages_cpp
[  0%] Built target actionlib_msgs_generate_messages_py
[  0%] Built target tf2_msgs_generate_messages_py
[100%] Built target realsense_gazebo_plugin

Thank you in advance!

edit retag flag offensive close merge delete

Comments

Hi all! I have a question, please help me. I'm new to using Gazebo and need the Intel Realsense Depth Camera(D-Series) plugins too, i'm working on ROS Kinetic and Gazebo version 7. So can I get any Intel Realsense plugin on my system? Thank you all guys!

rabbittt gravatar image rabbittt  ( 2020-04-05 04:23:40 -0500 )edit

3 Answers

Sort by ยป oldest newest most voted
3

answered 2020-11-03 13:45:59 -0500

issaiass gravatar image

I ported it using the realsense2_description from the intel repo and the realsense_gazebo_plugin package from pal robotics repo

check in my github:

https://github.com/issaiass/realsense_gazebo_plugin
https://github.com/issaiass/realsense2_description
edit flag offensive delete link more

Comments

Hi -- thanks for making this resource available! I'm having some problems after building, sourcing, and running as described in the readme. RViz shows 'no transform from [] to [base_link]' for all of the transforms, and as a result none of the sensing elements are visualized. Any tips? Thanks

EDIT: issue resolved -- I needed the ROS package 'robot_state_publisher'

gribgrob_k gravatar image gribgrob_k  ( 2022-08-24 16:01:44 -0500 )edit
2

answered 2020-04-04 10:02:17 -0500

arminkazim gravatar image

updated 2021-11-14 09:43:13 -0500

lucasw gravatar image

Hey i found out. 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.sofor 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/_d435.gazebo.xacro "/>

to packagename with being the name of the package

<xacro:include filename="$(find packagename)/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>

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_ra

edit flag offensive delete link more

Comments

Thank you, I really appreciate your effort! This seems to be a good approach. When I tried. my robot was spawned, however the camera was not visible in gazebo and the topics were not published. I created a virtual link where I want the D435 to be attached and parsed this into the sensor macro. I must be doing something wrong. I have uploaded all my files here: https://github.com/didrif14/megatrond Any chance you could take a quick look to see if I have messed up?

didrif14 gravatar image didrif14  ( 2020-04-05 07:45:20 -0500 )edit

have you checked that the .so file got compiled. You should find it in your catkin workspace in the devel folder inside the lib folder its name would be librealsense_gazebo_plugin.so also in line 13 add the following <origin xyz="0.0 0.2 0" rpy="0 0 0"/> inside the </sensor_d435> maybe that helps

arminkazim gravatar image arminkazim  ( 2020-04-14 01:50:10 -0500 )edit

Yes, the .so file is created. I think the problem is related to a catkin make error, alot of the messages stop at 0% build. This does not happen if I remove the realsense_gazebo_plugin package.

I have updated the post with the build output. Have you encountered this before?

What ROS and gazebo version are you using?

didrif14 gravatar image didrif14  ( 2020-04-15 04:55:48 -0500 )edit

i am using ros melodic and gazebo version 9. Then i tried out your repository. For me with your files the camera never showed and so no rostopics would become available, i nailed your problem down to <xacro:include filename="$(find megatrond_description)/urdf/_D435.urdf.xacro"> going somehow wrong. Then i replaced your two files _D435.urdf.xacro and _D435.gazebo.xacro with the original ones and only change the line 11 in https://github.com/pal-robotics-forks... and line 60 to <mesh filename="package://megatrond_description/meshes/d435.dae"> and it worked. So i guess there is something wrong with those two files of you.</mesh></xacro:include>

arminkazim gravatar image arminkazim  ( 2020-04-15 09:13:21 -0500 )edit

Hello. I have the same problem. Practically including the camera description, the gazebo simulation comes up correctly but the camera never spawn and so the topics are never available. If someone have solved this problem, i would appreciate any halp. Thanks!

AndreSpa gravatar image AndreSpa  ( 2020-05-01 07:31:30 -0500 )edit
1

i'm using same camera RealSense D435 the camera visible in gazebo and the topics were not published. if you solve problem let me know.

khaled gabr gravatar image khaled gabr  ( 2020-09-01 13:13:30 -0500 )edit
1

answered 2020-04-03 15:17:15 -0500

updated 2020-04-03 15:20:12 -0500

Not sure if this helps, but it looks like the full list of realsense_gazebo_plugin configurable parameters are listed in this file: https://github.com/pal-robotics/realsense_gazebo_plugin/blob/melodic-devel/src/RealSensePlugin.cpp

<depthUpdateRate> (numeric)
<colorUpdateRate> (numeric)
<infraredUpdateRate> (numeric)
<rangeMinDepth> (numeric)
<rangeMaxDepth> (numeric)
<depthTopicName> (string)
<depthCameraInfoTopicName> (string)
<colorTopicName> (string)
<colorCameraInfoTopicName> (string)
<infrared1TopicName> (string)
<infrared1CameraInfoTopicName> (string)
<infrared2TopicName> (string)
<infrared2CameraInfoTopicName> (string)
<colorOpticalframeName> (string)
<depthOpticalframeName> (string)
<infrared1OpticalframeName> (string)
<infrared2OpticalframeName> (string)
<pointCloud> (boolean)
<pointCloudTopicName> (string)
<pointCloudCutoff> (numeric)
<pointCloudCutoffMax> (numeric)
<prefix> (string)
<robotNamespace> (string)

Might have been a good idea for the author to include the full list of configurables along with data types and example usages and default values in the README file.

edit flag offensive delete link more

Comments

Thank you for the response. Yes, I tried to include those as parameters, but nothing really happened. I did however find the original repository, which this plugin is built upon, and I copied the plugin parameters from that. At this point I get a message saying:

Realsense Gazebo ROS plugin loading.
RealSensePlugin: The realsense_camera plugin is attach to model megatrond

But it also says comes with an error stating:

[gazebo-3] process has died [pid 27784, exit code 139, cmd /opt/ros/melodic/lib/gazebo_ros/gzserver -e ode worlds/empty.world __name:=gazebo __log:=/home/megatrond/.ros/log/79dee886-75e5-11ea-91ce-049226d415d8/gazebo-3.log].
log file: /home/megatrond/.ros/log/79dee886-75e5-11ea-91ce-049226d415d8/gazebo-3*.log [controller_spawner-7] process has died [pid 27801, exit code 1, cmd /opt/ros/melodic/lib/controller_manager/spawner joint_state_controller vel_ctrl_frw vel_ctrl_flw vel_ctrl_rrw vel_ctrl_rlw --timeout 60

Which dosn't show when I remove the plugin

didrif14 gravatar image didrif14  ( 2020-04-03 15:38:12 -0500 )edit

So just for fun, I cloned and built the original plugin for the RS200 camera. It built fine but seemed to not do anything when I dragged the realsense camera model into my Gazebo. Gazebo showed the visual for it, but no topics were ever published from it. When I tried to drag in a coke_can model afterwards, it never showed up. So I'm not sure the original plugin really works properly. It might be spinning and tying up the CPU or something.

Kurt Leucht gravatar image Kurt Leucht  ( 2020-04-03 16:03:54 -0500 )edit
1

I'm stuck on ROS kinetic and Gazebo 7.0, so that could be why it doesn't work for me.

Kurt Leucht gravatar image Kurt Leucht  ( 2020-04-03 16:38:45 -0500 )edit

That's interesting. I have however encountered people who have gotten this plugin to work, so it may just be what you suggested concerning your system specifications. Anyways, thank you for giving it a shot!

didrif14 gravatar image didrif14  ( 2020-04-05 07:55:00 -0500 )edit

For future reference here is an example of how to use this plugin might people need it. A detailed explanation video created by @issaiass can be found here.

rickstaa gravatar image rickstaa  ( 2020-12-01 07:38:45 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2020-04-03 11:56:57 -0500

Seen: 8,079 times

Last updated: Nov 14 '21