Coder Social home page Coder Social logo

realsense_gazebo_plugin's Introduction

Intel RealSense Gazebo ROS plugin and model

Simulattion of the Realsense R200 sensor in Gazebo.

Quickstart

Build the plugin

catkin build realsense_gazebo_plugin

Test it by running

roslaunch realsense_gazebo_plugin realsense.launch

Run the unittests

After building the plugin, you can run the unittests

rostest realsense_gazebo_plugin realsense_streams.test

Run the point cloud demo

Using depth_image_proc package, we can generate a point cloud from the depth image by running

roslaunch realsense_gazebo_plugin realsense.launch # in terminal 1
roslaunch realsense_gazebo_plugin depth_proc.launch # in terminal 2

Then open Rviz, and display the /realsense/camera/depth_registered/points topic, you should see something like this Point cloud in Rviz

Run from URDF

roslaunch realsense_gazebo_plugin realsense_urdf.launch

This will behave the same as realsense.launch mentioned above, with the difference that it spawns the model from a URDF (see urdf folder). You can reuse this to plug the sensor in the robot of your choice.

Dependencies

This requires Gazebo 6 or higher and catkin tools for building.

The package has been tested on ROS melodic on Ubuntu 18.04 with Gazebo 9.

Acknowledgement

This is continuation of work done by guiccbr for Intel Corporation.

Thanks to Danfoa for contributing the URDF integration.

realsense_gazebo_plugin's People

Contributors

awesome-manuel avatar danfoa avatar felixvd avatar manman88 avatar marcoesposito1988 avatar shylent avatar syrianspock avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar

realsense_gazebo_plugin's Issues

Two cameras publishing different topics but with the same image

I want two cameras in my world.

I've followed the example of multi_rs200_simulation.xacro and modified the location of the cameras there.

In my launch file I load the robot_description parameter and spawn it. Each camera is publishing its topics correctly, e.g.:

/right_r200/camera/color/image_raw
/left_r200/camera/color/image_raw

The problem is that the contents of the image is the same!

Any hint?

Thanks!

Conversion of sensor type[depth] not supported.

Hi,
I am a newbie in Ros and trying to run realsense_gazebo_plugin but getting some warnings. On running following command roslaunch realsense_gazebo_plugin realsense.launch, I am getting below warning messages:

[Wrn] [msgs.cc:1852] Conversion of sensor type[depth] not supported.
[Wrn] [Event.cc:61] Warning: Deleting a connection right after creation. Make sure to save the ConnectionPtr from a Connect call

RealSensePlugin: The rs_camera plugin is attach to model realsense_camera
[Wrn] [msgs.cc:1852] Conversion of sensor type[depth] not supported.
[ INFO] [1573849778.403345017, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1573849778.432398530, 0.041000000]: Physics dynamic reconfigure ready.
[Wrn] [Event.cc:61] Warning: Deleting a connection right after creation. Make sure to save the ConnectionPtr from a Connect call
[Wrn] [msgs.cc:1852] Conversion of sensor type[depth] not supported.
[Wrn] [msgs.cc:1852] Conversion of sensor type[depth] not supported.
[Wrn] [Publisher.cc:141] Queue limit reached for topic /gazebo/default/pose/local/info, deleting message. This warning is printed only once.
[Wrn] [msgs.cc:1852] Conversion of sensor type[depth] not supported.
[Wrn] [msgs.cc:1852] Conversion of sensor type[depth] not supported.

I don't have any idea why I am getting above warnings. But, when I ignored these warnings and run following command: roslaunch realsense_gazebo_plugin depth_proc.launch and then start rviz and added pointcloud2 display and set topic /r200/camera/depth_registered/points, I am not getting output. Could someone please guide me on this? I would really appreciate your help.

How to open rviz to display the point cloud of r200

Hello, thanks a lot for this interesting project. I have followed your instructions to successfully run

roslaunch realsense_gazebo_plugin realsense.launch
roslaunch realsense_gazebo_plugin depth_proc.launch

Then I want to open rviz to display the point cloud information, so I just run

rosrun rviz rviz

But I display nothing 😞 , maybe I did not display the image or information correctly. Could u pls explain more, thank you.

Multiples: Light [sun] not found, DepthBuffer error for RenderTarget

Hi, I've just cloned your repo and switched to kinetic-devel (command git checkout --track origin/kinetic-devel), then build with catkin_make; everything seemed to go well.
However, now trying to test it (command roslaunch realsense_gazebo_plugin realsense.launch) I've got the following:

...
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 10.0.2.15
[Wrn] [msgs.cc:1655] Conversion of sensor type[depth] not suppported.
[ INFO] [1540292352.124613569]: Realsense Gazebo ROS plugin loading.

RealSensePlugin: The realsense_camera plugin is attach to model realsense_camera
[Wrn] [msgs.cc:1655] Conversion of sensor type[depth] not suppported.
[Err] [Scene.cc:2927] Light [sun] not found. Use topic ~/factory/light to spawn a new light.
[ INFO] [1540292352.465098998, 0.023000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1540292352.549587152, 0.094000000]: Physics dynamic reconfigure ready.
gzserver: /build/ogre-1.9-mqY1wq/ogre-1.9-1.9.0+dfsg1/OgreMain/src/OgreRenderSystem.cpp:546: virtual void Ogre::RenderSystem::setDepthBufferFor(Ogre::RenderTarget*): Assertion bAttached && "A new DepthBuffer for a RenderTarget was created, but after creation" "it says it's incompatible with that RT"' failed.
Aborted (core dumped)
[gazebo-2] process has died
...

Running Ubuntu 16.04 LTS, ROS Lunar, Gazebo 9.0

Simulating Multiple Cameras

I am using the kinetic-devel branch with Gazebo 7, but have updated my xacro and launch files to add a prefix to my realsense cameras so multiple can be used in one simulation. I would like to generate multiple instances of the services such that I can map using multiple robots in Gazebo with a RealSense. When the plugin loads I get this error:
[ERROR] [1540430934.136868574, 0.323000000]: Tried to advertise a service that is already advertised in this node [/realsense/set_camera_info]

I would like to initialize each sensor in the ns of my individual robots. Is there any support for this/am I doing something wrong?

Thank you in advance.

RViz & GAZEBO not opening up

I build the catkin command. Running depth image command in one terminal and realsense command as mentioned in your Readme. But RViz and GAZEBO doesnt open as you have shown the picture. Help me out to clear this error.

Gazebo 7, no function SimTime

Quick note, to fix the following catkin_make error for Gazebo 7 on Ubuntu 16.04 with ROS Kinetic:

/home/amerk/catkin_ws/src/external_lib/realsense_gazebo_plugin/src/RealSensePlugin.cpp:123:42: error: ‘class gazebo::physics::World’ has no member named ‘SimTime’
   this->transportNode->Init(this->world->SimTime()); # and Name()

The function names SimTime() and Name() are now GetSimTime() and GetName() respectively.

Thanks for the great library!

Camera intrinsics and baseline

Are the camera parameters (intrinsics and baseline) the same as the actual R200? Can this plugin reliably be used to do simulations, e.g. for SLAM? In the meantime, thank you for providing this ROS interface, it's saved me quite the headache converting from SDF!

Errors occured when building

Hello everyone, I'm using ROS Kinetic and Gazebo 7. I got these following issues when catkin_make. Did anybody got the same please give me a hand to solve it! Thank you guys pretty much!

[ 96%] Built target rtabmapviz
[ 96%] Building CXX object realsense_gazebo_plugin/CMakeFiles/test_realsense_streams.dir/test/realsense_streams_test.cpp.o
[ 97%] Built target rosflight_sil_plugin
[ 98%] Built target imu_plugin
[ 98%] Built target odometry_plugin
[ 98%] Built target magnetometer_plugin
[ 98%] Built target airspeed_plugin
[100%] Built target barometer_plugin
[100%] Built target GPS_plugin
In file included from /usr/include/gazebo-7/gazebo/rendering/ogre_gazebo.h:61:0,
from /usr/include/gazebo-7/gazebo/rendering/Camera.hh:50,
from /usr/include/gazebo-7/gazebo/rendering/DepthCamera.hh:28,
from /home/datvu/catkin_ws/src/realsense_gazebo_plugin/include/realsense_gazebo_plugin/RealSensePlugin.h:24,
from /home/datvu/catkin_ws/src/realsense_gazebo_plugin/include/realsense_gazebo_plugin/gazebo_ros_realsense.h:4,
from /home/datvu/catkin_ws/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp:1:
/usr/include/OGRE/Terrain/OgreTerrainPaging.h:33:35: fatal error: OgrePagedWorldSection.h: No such file or directory
compilation terminated.
In file included from /usr/include/gazebo-7/gazebo/rendering/ogre_gazebo.h:61:0,
from /usr/include/gazebo-7/gazebo/rendering/Camera.hh:50,
from /usr/include/gazebo-7/gazebo/rendering/DepthCamera.hh:28,
from /home/datvu/catkin_ws/src/realsense_gazebo_plugin/include/realsense_gazebo_plugin/RealSensePlugin.h:24,
from /home/datvu/catkin_ws/src/realsense_gazebo_plugin/src/RealSensePlugin.cpp:17:
/usr/include/OGRE/Terrain/OgreTerrainPaging.h:33:35: fatal error: OgrePagedWorldSection.h: No such file or directory
compilation terminated.
realsense_gazebo_plugin/CMakeFiles/realsense_gazebo_plugin.dir/build.make:86: recipe for target 'realsense_gazebo_plugin/CMakeFiles/realsense_gazebo_plugin.dir/src/gazebo_ros_realsense.cpp.o' failed
make[2]: *** [realsense_gazebo_plugin/CMakeFiles/realsense_gazebo_plugin.dir/src/gazebo_ros_realsense.cpp.o] Error 1
make[2]: *** Waiting for unfinished jobs....
realsense_gazebo_plugin/CMakeFiles/realsense_gazebo_plugin.dir/build.make:62: recipe for target 'realsense_gazebo_plugin/CMakeFiles/realsense_gazebo_plugin.dir/src/RealSensePlugin.cpp.o' failed
make[2]: *** [realsense_gazebo_plugin/CMakeFiles/realsense_gazebo_plugin.dir/src/RealSensePlugin.cpp.o] Error 1
CMakeFiles/Makefile2:8539: recipe for target 'realsense_gazebo_plugin/CMakeFiles/realsense_gazebo_plugin.dir/all' failed
make[1]: *** [realsense_gazebo_plugin/CMakeFiles/realsense_gazebo_plugin.dir/all] Error 2
make[1]: *** Waiting for unfinished jobs....
[100%] Linking CXX executable /home/datvu/catkin_ws/devel/lib/realsense_gazebo_plugin/test_realsense_streams
[100%] Built target test_realsense_streams
Makefile:138: recipe for target 'all' failed
make: *** [all] Error 2
Invoking "make -j4 -l4" failed

Running the Roslaunch Command Fails to Bring Up Gazebo

After successfully building the project, running "roslaunch realsense_gazebo_plugin realsense.launch" shows the following in the command line

image

but does not bring up Gazebo. Can you guys please assist me with this? Thank you.

Kinetic + Gazebo9

could this Realsense_plugin rightly run in kinetic + Gazebo 9? now when I run this plugin in Gazebo 9 . There is no rostopic about /realsense

No transform from [depth] to [origin]

Hi,
I test the plugin by
roslaunch realsense_gazebo_plugin realsense_urdf.launch
roslaunch realsense_gazebo_plugin depth_proc.launch
rosrun rviz rviz
Only the transform from color to origin is ok, as you can see from the image below:
2019-03-26 11-42-22屏幕截图
The tf tree is below:
2019-03-26 13-08-58屏幕截图

Is there any bug?
Another question: where does the link origin come from?

No points published for kinetic devel

Hey there,

just tested the kinetic-devel branch unittests:

ostest realsense_gazebo_plugin realsense_streams.test
... logging to /home/mlamprecht/.ros/log/rostest-mlamprecht-pc-8945.log
[ROSUNIT] Outputting test results to /home/mlamprecht/.ros/test_results/realsense_gazebo_plugin/rostest-test_realsense_streams.xml
[ INFO] [1573634895.473643669]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1573634895.474245803]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1573634895.957811694]: Realsense Gazebo ROS plugin loading.

RealSensePlugin: The realsense_camera plugin is attach to model realsense_camera
[ INFO] [1573634896.075718407, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1573634896.096323756, 0.042000000]: Physics dynamic reconfigure ready.
[Testcase: testrealsense_plugin_test] ... ERROR!
ERROR: max time [60.0s] allotted for test [realsense_plugin_test] of type [realsense_gazebo_plugin/test_realsense_streams]
  File "/usr/lib/python2.7/unittest/case.py", line 329, in run
    testMethod()
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rostest/runner.py", line 148, in fn
    self.test_parent.run_test(test)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rostest/rostest_parent.py", line 132, in run_test
    return self.runner.run_test(test)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/launch.py", line 684, in run_test
    (test.time_limit, test.test_name, test.package, test.type))
--------------------------------------------------------------------------------

[ROSTEST]-----------------------------------------------------------------------


SUMMARY
 * RESULT: FAIL
 * TESTS: 0
 * ERRORS: 1
 * FAILURES: 0

If I try to see the point cloud, no points are published. This is what I did:

roslaunch realsense_gazebo_plugin realsense.launch # in terminal 1
roslaunch realsense_gazebo_plugin depth_proc.launch # in terminal 2
Then open Rviz, and display the /realsense/camera/depth_registered/points topic, you should see something like this 

Why are there 2 IR cameras and 4 Gazebo sensors?

From what I understand, the SR300 has one IR projector, one IR camera and one RGB camera. However, in the URDF I see these 4 joints/links, and a Gazebo sensor that is spawned for each of them:

    <link name="${prefix}color" />
    <link name="${prefix}depth" />
    <link name="${prefix}ired1" />
    <link name="${prefix}ired2" />

What do the ired1 and ired2 cameras mean? Shouldn't there only be one? Thanks in advance.

PS: I am asking because I would like to make a URDF for the SR305, but I am confused since there is only one IR sensor in the CAD file.

can't rostopic echo pointcloud with gazebo 9

$ rostopic echo /realsense/camera/depth_registered/points
WARNING: no messages received and simulated time is active.
Is /clock being published?

The nodes are starting up without errors, but I can't echo the realsense topics. This is on Ubuntu 16.04, Kinetic, Gazebo 9.

Gazebo plugin d435i

Hello
I want to use D435 with my robot manipulator.
But I don't get any idea to integrate the sensor with my manipulator.
My requirements are
1. I want to attach the D435 with my manipulator's base link
2. want to launch with my manipulator package
3. want to use all available sensor data format.

Please help me to figure it out..
Thanks in advance

the topic of /realsense/camera/depth_registered/points publish no message

Hi,
I test the plugin by
roslaunch realsense_gazebo_plugin realsense_urdf.launch
roslaunch realsense_gazebo_plugin depth_proc.launch
rosrun rviz rviz
But I can't see the point cloud. I echo the topic of /realsense/camera/depth_registered/points publish no message, It tell me there is no message as the image below:
2019-04-04 09-59-12屏幕截图

Getting this issue when building

Ubuntu 16.04 Xenial, AMD64

/home/vuwij/hummingbird_ws/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp: In member function ‘virtual void gazebo::GazeboRosRealsense::OnNewFrame(gazebo::rendering::CameraPtr, gazebo::transport::PublisherPtr)’: /home/vuwij/hummingbird_ws/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp:57:44: error: ‘class gazebo::physics::World’ has no member named ‘SimTime’ common::Time current_time = this->world->SimTime();

add this Camera to iris gazebo has problem.

Hi, I am going to add this camera to Iris gazebo, but although it seems that the camera has been added in gazebo, the drone can't take off. This result will be output in the shell.
[vehicle_spawn_jiaxing_HP_ENVY_15_Notebook_PC_17373_511406443193350206-5] process has finished cleanly log file: /home/jiaxing/.ros/log/39dbee0e-cae8-11e8-bce5-70188b8817cd/vehicle_spawn_jiaxing_HP_ENVY_15_Notebook_PC_17373_511406443193350206-5*.log
No takeoff command line. and there is no connection between quadrotor and QGC.
I was wondering if it was the way I added makes error. I used two methods. The first attempt was to combine the iris and camera directly through the sdf file, and the problem I mentioned above appeared. The second type of addition via xacro files is also problematic. The same error,can not take off, no connection.
Dose somebody successfully add this camera to IRIS and use them to sitl simulation? I have been trying for a long time to find an answer online, but it has not progressed. I am very sorry that I have raised such a simple question. Thank you for your answer.
Thomas

Loading from a *.xacro file and parameters list?

Hi,
Sorry if this is a trivial question, this is the first time i am using a gazebo ros sensor plugin.
Is there a parameter list of the plugin and how to access it? (i.e. similar to the realsense ros driver paramters which set topics path and activate/desactivate the different color/ir/depth streams).
Additionally, do you have a example of how to load the plugin from a *.xacro file?
Thanks!

Inconsistent 'horizontal_fov' and 'focal' parameters

While driving a robot around in gazebo, I noticed that the pointcloud produced from the realsense depth image was incorrect:

image
image
All I did between taking these screenshots was rotate the robot in place.

The published static map accurately shows the location of walls in the world to within 1 cell, and some custom (and thoroughly tested) code publishes the necessary transforms such that the pose of the robot in the map frame exactly matches its pose in gazebo. In short, pointclouds should align with the lines on the map and the observed problem is not due to odometry errors. Based on this knowledge, and the fact that I have not seen these kinds of errors when running the exact same world with a Kinect on a Turtlebot, I concluded that the problem must be within realsense_gazebo_plugin.
Additional configuration info: Gazebo 7; realsense_gazebo_plugin: 244629d

I checked the source code and found where the focal length is defined (463.889) and calculated the corresponding horizontal fov: 2*arctan(640/(2*463.889)) = 1.208. However, the default value for horizontal_fov in urdf/realsense-RS200.macro.xacro is 1.047.

I replaced 1.047 with 1.208 for all of the cameras and reloaded my simulation. The result:
image
image

Based on the above analysis, I feel reasonably confident in asserting that the provided values for the parameters are inconsistent and that at least one of them needs to be changed. Ideally, focal would be determined by horizontal_fov, though I'm not certain how that would be done.

Attach camera to robot model

Hello! I have a robot model in gazebo. How can I attach the camera instance to my robot using urdf? I have tried it copying the content of realsense_urdf.launch:

<param
    name="robot_description"
    command="$(find xacro)/xacro '$(find realsense_gazebo_plugin)/urdf/rs200_simulation.xacro'"
/>
<node
    name="spawn_model"
    pkg="gazebo_ros"
    type="spawn_model"
    args="-urdf -param robot_description -model rs200"
/>
<node name="state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>

in the simulation.launch of my project where I spawn the robot, and I created the camera instance too in the model.xacro of the robot:

<!-- Import macro for realsense-RS200 camera-->
<xacro:include filename="$(find realsense_gazebo_plugin)/urdf/realsense-RS200.macro.xacro"/>
<!-- Create camera instance -->
<xacro:realsense-rs200 prefix="" parent="base_link">
    <origin xyz="0 0 1.0" rpy="0 0 0" />   
</xacro:realsense-rs200>

but it doesn't link to the robot and spawns in a separated model called rs200. If I replace the rs200 in this line

args="-urdf -param robot_description -model rs200"

by the name of my robot model, the camera appears but the robot not.

The D matrix is empty

Getting error:
Cannot call rectifyPoint when distortion is unknown.
This is the camera_info topic echo, which shows that the D matrix is empty:
distortion_model: ''

D: []
K: [463.8890075683594, 0.0, 320.0, 0.0, 463.8890075683594, 240.0, 0.0, 0.0, 1.0]
R: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
P: [463.8890075683594, 0.0, 320.0, 0.0, 0.0, 463.8890075683594, 240.0, 0.0, 0.0, 0.0, 1.0, 0.0]

libRealSensePlugin.so: Undefined symbol

Hi, I am currently on Gazebo-9, Ubuntu 18.04 and Melodic. I am getting
libRealSensePlugin.so: undefined symbol: _ZN19camera_info_manager17CameraInfoManagerC1EN3ros10NodeHandleERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEESA_
when I tried to spawn a Realsense model in gazebo. Any tips?

Test Fails

I'm using ROS kinetic with gazebo 7
running the unit tests fails with the followinr error
[Testcase: testrealsense_plugin_test] ... ERROR!
ERROR: max time [60.0s] allotted for test [realsense_plugin_test] of type [realsense_gazebo_plugin/test_realsense_streams]
File "/usr/lib/python2.7/unittest/case.py", line 329, in run
testMethod()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/rostest/runner.py", line 148, in fn
self.test_parent.run_test(test)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/rostest/rostest_parent.py", line 132, in run_test
return self.runner.run_test(test)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/launch.py", line 684, in run_test
(test.time_limit, test.test_name, test.package, test.type))

[ROSTEST]-----------------------------------------------------------------------

SUMMARY

  • RESULT: FAIL
  • TESTS: 0
  • ERRORS: 1
  • FAILURES: 0

Also when launching the realsense.launch file
this warning appears : Conversion of sensor type[depth] not suppported.
and gazebo doesn't open

depth not available

Hi,

I was looking for a Gazebo plugin of realsense and tried this project.

When launching the "demo" here is an output :
[Wrn] [msgs.cc:1655] Conversion of sensor type[depth] not suppported.
--> depth topic is not published.
Any ideas ?

Here are the published topic :
$ rostopic list
/clock
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/set_link_state
/gazebo/set_model_state
/realsense/camera/color/image_raw
/realsense/camera/color/image_raw/compressed
/realsense/camera/color/image_raw/compressed/parameter_descriptions
/realsense/camera/color/image_raw/compressed/parameter_updates
/realsense/camera/color/image_raw/compressedDepth
/realsense/camera/color/image_raw/compressedDepth/parameter_descriptions
/realsense/camera/color/image_raw/compressedDepth/parameter_updates
/realsense/camera/color/image_raw/theora
/realsense/camera/color/image_raw/theora/parameter_descriptions
/realsense/camera/color/image_raw/theora/parameter_updates
/realsense/camera/ir/image_raw
/realsense/camera/ir/image_raw/compressed
/realsense/camera/ir/image_raw/compressed/parameter_descriptions
/realsense/camera/ir/image_raw/compressed/parameter_updates
/realsense/camera/ir/image_raw/compressedDepth
/realsense/camera/ir/image_raw/compressedDepth/parameter_descriptions
/realsense/camera/ir/image_raw/compressedDepth/parameter_updates
/realsense/camera/ir/image_raw/theora
/realsense/camera/ir/image_raw/theora/parameter_descriptions
/realsense/camera/ir/image_raw/theora/parameter_updates
/realsense/camera/ir2/image_raw
/realsense/camera/ir2/image_raw/compressed
/realsense/camera/ir2/image_raw/compressed/parameter_descriptions
/realsense/camera/ir2/image_raw/compressed/parameter_updates
/realsense/camera/ir2/image_raw/compressedDepth
/realsense/camera/ir2/image_raw/compressedDepth/parameter_descriptions
/realsense/camera/ir2/image_raw/compressedDepth/parameter_updates
/realsense/camera/ir2/image_raw/theora
/realsense/camera/ir2/image_raw/theora/parameter_descriptions
/realsense/camera/ir2/image_raw/theora/parameter_updates
/rosout
/rosout_agg

Gazebo 7 + ROS kinetics used

Thanks
Bertrand

Color and Depth frames misalignment

Good day,

I developed the URDF format version of the camera Gazebo model and while testing its performance in ROS, I notice that there is a misalignment in the color projected onto the pointcloud, it seems to be a constant offset in the Y axis of about two to three centimeters (see for example the groud color projected into the table, and the coke can red projected into the wall), making color clustering not feasible.

color_error

I also found that the depth frame has some misalignment, see image below:
depth_error

On my gazebo simulation objects are placed like this.

gazebo

I though at first that the error was on my URDF definition, but I tested and the same offset occurs with your .sdf gazebo model.

No link elements found in urdf file

I'm using ros kinetic with gazebo 7.16

No link elements found in urdf file
`[ERROR] [1583184299.047995028]: No link elements found in urdf file
[robot_state_publisher-2] process has died [pid 5282, exit code 255, cmd /opt/ros/kinetic/lib/robot_state_publisher/state_publisher __name:=robot_state_publisher __log:=/home/moh/.ros/log/44847174-5ccc-11ea-99f3-b8ca3a911d19/robot_state_publisher-2.log].
log file: /home/moh/.ros/log/44847174-5ccc-11ea-99f3-b8ca3a911d19/robot_state_publisher-2*.log

`

testCameraInfo Fails

After following the setup instructions for the kinetic-devel branch and running:
rostest realsense_gazebo_plugin realsense_streams.test

I get the below output:

[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testStream][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testResolution][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testCameraInfo][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testStream][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testResolution][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testCameraInfo][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testStream][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testResolution][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testCameraInfo][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testStream][passed]
[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testResolution][passed]

But then I get the following error:

[realsense_gazebo_plugin.rosunit-realsense_plugin_test/testCameraInfo][FAILURE]-
/home/josh/catkin_ws/src/realsense_gazebo_plugin/test/realsense_streams_test.cpp:205
Value of: encoding_recv
Actual: "16UC1"
Expected: "mono16"

Test Failed ROS-kinetic Gazebo-7

I'm using ROS kinetic with gazebo 7 and cloned the folder from "kinetic-devel" branch.
This is the command that I run,
rostest realsense_gazebo_plugin realsense_streams.test
and here are the output,

... logging to /home/tahoun/.ros/log/rostest-mTahoun-Precision-5520-24014.log
[ROSUNIT] Outputting test results to /home/tahoun/.ros/test_results/realsense_gazebo_plugin/rostest-test_realsense_streams.xml
[ INFO] [1580468558.084234952]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1580468558.084696070]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...

RealSensePlugin: The rs_camera plugin is attach to model realsense_camera
[ INFO] [1580468558.856333616, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1580468558.907369463, 0.071000000]: Physics dynamic reconfigure ready.
[Testcase: testrealsense_plugin_test] ... ERROR!
ERROR: max time [60.0s] allotted for test [realsense_plugin_test] of type [realsense_gazebo_plugin/test_realsense_streams]
  File "/usr/lib/python2.7/unittest/case.py", line 329, in run
    testMethod()
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rostest/runner.py", line 148, in fn
    self.test_parent.run_test(test)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/rostest/rostest_parent.py", line 132, in run_test
    return self.runner.run_test(test)
  File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/launch.py", line 684, in run_test
    (test.time_limit, test.test_name, test.package, test.type))
--------------------------------------------------------------------------------

[ROSTEST]-----------------------------------------------------------------------


SUMMARY
 * RESULT: FAIL
 * TESTS: 0
 * ERRORS: 1
 * FAILURES: 0

rostest log file is in /home/tahoun/.ros/log/rostest-mTahoun-Precision-5520-24014.log

Also, here is attached the log file,
rostest-mTahoun-Precision-5520-24014.log

Thanks in advance and waiting for your reply.
Regards,

Namespace issue

Hello.
I'm wondering if there is a clean way to run everything when the whole project is developed under a 'robot' namespace. This means that the names in tf tree are prepended with 'robot' (ex. 'robot/color', 'robot/depth', ...) and so topics should be prepended as well (ex. 'robot/r200...')
I don't see any way to do this "cleanly" with this package.
Topics can be prepended by changing:
plugin name="${prefix}r200" filename="librealsense_gazebo_plugin.so"
to:
plugin name="robot/${prefix}r200" filename="librealsense_gazebo_plugin.so"

Header frame_ids should be prepended as well by changing:
prefix>${prefix}</prefix
to:
prefix>robot/${prefix}</prefix,
but this seems to cause a segmentation fault and isn't really semantically correct.

So my question is: Is there a way to add namespaces to topic publishing?

launch error

Error [parser_urdf.cc:2608] Unable to call parseURDF on robot model
Error [parser.cc:273] parse as old deprecated model file failed.
Error [parser.cc:614] Unable to read file[/home/try/Desktop/SimulationFiles/navigation/mybot_ws/src/gazeboRS/models/realsense_camera/model.sdf]
Error [parser.cc:688] Error reading element
Error [parser.cc:348] Unable to read element
Error: Could not find the 'robot' element in the xml file
at line 81 in /build/buildd/urdfdom-0.2.10+dfsg/urdf_parser/src/model.cpp
Error [parser_urdf.cc:2608] Unable to call parseURDF on robot model
Error [parser.cc:273] parse as old deprecated model file failed.
Error [Server.cc:300] Unable to read sdf file[/home/try/Desktop/SimulationFiles/navigation/mybot_ws/src/gazeboRS/worlds/realsense.world]
gzserver: /usr/include/boost/thread/pthread/recursive_mutex.hpp:101: boost::recursive_mutex::~recursive_mutex(): Assertion `!pthread_mutex_destroy(&m)' failed.
Aborted (core dumped)
[gazebo-2] process has died [pid 14248, exit code 134, cmd /opt/ros/indigo/lib/gazebo_ros/gzserver -r --verbose -e ode /home/try/Desktop/SimulationFiles/navigation/mybot_ws/src/gazeboRS/worlds/realsense.world __name:=gazebo __log:=/home/try/.ros/log/d7c27010-df27-11e6-bd79-68a3c43c0c01/gazebo-2.log].
log file: /home/try/.ros/log/d7c27010-df27-11e6-bd79-68a3c43c0c01/gazebo-2*.log


Hi,
I get this error when I run the command (roslaunch realsense_gazebo_plugin realsense.launch )

ROSTEST Command fails

I have pasted the error .Please go through and let me know what is the mistake.

logging to /home/sp/.ros/log/rostest-hp-omen-8339.log
[ROSUNIT] Outputting test results to /home/sp/.ros/test_results/realsense_gazebo_plugin/rostest-test_realsense_streams.xml
[Testcase: testrealsense_plugin_test] ... ERROR!
ERROR: max time [60.0s] allotted for test [realsense_plugin_test] of type [realsense_gazebo_plugin/test_realsense_streams]
File "/usr/lib/python2.7/unittest/case.py", line 329, in run
testMethod()
File "/opt/ros/kinetic/lib/python2.7/dist-packages/rostest/runner.py", line 148, in fn
self.test_parent.run_test(test)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/rostest/rostest_parent.py", line 132, in run_test
return self.runner.run_test(test)
File "/opt/ros/kinetic/lib/python2.7/dist-packages/roslaunch/launch.py", line 684, in run_test
(test.time_limit, test.test_name, test.package, test.type))

[ROSTEST]-----------------------------------------------------------------------

SUMMARY

  • RESULT: FAIL
  • TESTS: 0
  • ERRORS: 1
  • FAILURES: 0

rostest log file is in /home/sp/.ros/log/rostest-hp-omen-8339.log

Error Building in Noetic

I have tried to build in noetic but getting protoc/protocbuf error, is there an updated version which works in noetic, Ubuntu 20.04, Gazebo 11

build failed

I'm new to ROS and I don't know how to fix this,
I'm struggling with creating a 2 workspaces that don't interfere eachother.
I want to use this RealSense r200 for simulation with Gazebo.

This is the terminal output:

catkin build realsense_gazebo_plugin
-----------------------------------------------------------------------------
Profile:                     default
Extending:          [cached] /home/pete/ws/devel:/opt/ros/kinetic
Workspace:                   /home/pete/catkin_ws
-----------------------------------------------------------------------------
Source Space:       [exists] /home/pete/catkin_ws/src
Log Space:          [exists] /home/pete/catkin_ws/logs
Build Space:        [exists] /home/pete/catkin_ws/build
Devel Space:        [exists] /home/pete/catkin_ws/devel
Install Space:      [unused] /home/pete/catkin_ws/install
DESTDIR:            [unused] None
-----------------------------------------------------------------------------
Devel Space Layout:          linked
Install Space Layout:        None
-----------------------------------------------------------------------------
Additional CMake Args:       None
Additional Make Args:        None
Additional catkin Make Args: None
Internal Make Job Server:    True
Cache Job Environments:      False
-----------------------------------------------------------------------------
Whitelisted Packages:        None
Blacklisted Packages:        None
-----------------------------------------------------------------------------
Workspace configuration appears valid.
-----------------------------------------------------------------------------
[build] Found '1' packages in 0.0 seconds.                                     
[build] Package table is up to date.                                           
Starting  >>> realsense_gazebo_plugin                                          
_______________________________________________________________________________
Errors     << realsense_gazebo_plugin:make /home/pete/catkin_ws/logs/realsense_gazebo_plugin/build.make.001.log
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/RealSensePlugin.cpp: In member function ‘virtual void gazebo::RealSensePlugin::Load(gazebo::physics::ModelPtr, sdf::ElementPtr)’:
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/RealSensePlugin.cpp:123:42: error: ‘class gazebo::physics::World’ has no member named ‘Name’
   this->transportNode->Init(this->world->Name());
                                          ^
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/RealSensePlugin.cpp: In member function ‘virtual void gazebo::RealSensePlugin::OnNewFrame(gazebo::rendering::CameraPtr, gazebo::transport::PublisherPtr)’:
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/RealSensePlugin.cpp:169:46: error: ‘class gazebo::physics::World’ has no member named ‘SimTime’
   msgs::Set(msg.mutable_time(), this->world->SimTime());
                                              ^
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/RealSensePlugin.cpp: In member function ‘virtual void gazebo::RealSensePlugin::OnNewDepthFrame()’:
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/RealSensePlugin.cpp:218:46: error: ‘class gazebo::physics::World’ has no member named ‘SimTime’
   msgs::Set(msg.mutable_time(), this->world->SimTime());
                                              ^
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp: In member function ‘virtual void gazebo::GazeboRosRealsense::OnNewFrame(gazebo::rendering::CameraPtr, gazebo::transport::PublisherPtr)’:
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp:57:44: error: ‘class gazebo::physics::World’ has no member named ‘SimTime’
   common::Time current_time = this->world->SimTime();
                                            ^
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp: In member function ‘virtual void gazebo::GazeboRosRealsense::OnNewDepthFrame()’:
/home/pete/catkin_ws/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp:122:44: error: ‘class gazebo::physics::World’ has no member named ‘SimTime’
   common::Time current_time = this->world->SimTime();
                                            ^
make[2]: *** [CMakeFiles/realsense_gazebo_plugin.dir/src/gazebo_ros_realsense.cpp.o] Fehler 1
make[2]: *** Auf noch nicht beendete Prozesse wird gewartet …
make[2]: *** [CMakeFiles/realsense_gazebo_plugin.dir/src/RealSensePlugin.cpp.o] Fehler 1
make[1]: *** [CMakeFiles/realsense_gazebo_plugin.dir/all] Fehler 2
make: *** [all] Fehler 2
cd /home/pete/catkin_ws/build/realsense_gazebo_plugin; catkin build --get-env realsense_gazebo_plugin | catkin env -si  /usr/bin/make --jobserver-fds=6,7 -j; cd -
...............................................................................
Failed     << realsense_gazebo_plugin:make           [ Exited with code 2 ]    
Failed    <<< realsense_gazebo_plugin                [ 33.4 seconds ]          
[build] Summary: 0 of 1 packages succeeded.                                    
[build]   Ignored:   None.                                                     
[build]   Warnings:  None.                                                     
[build]   Abandoned: None.                                                     
[build]   Failed:    1 packages failed.                                        
[build] Runtime: 33.5 seconds total.                

And this is the log file:

Not searching for unused variables given on the command line.
�[36m--�[0m The C compiler identification is GNU 5.4.0
�[36m--�[0m The CXX compiler identification is GNU 5.4.0
�[36m--�[0m Check for working C compiler: /usr/bin/cc
�[36m--�[0m Check for working C compiler: /usr/bin/cc -- works
�[36m--�[0m Detecting C compiler ABI info
�[36m--�[0m Detecting C compiler ABI info - done
�[36m--�[0m Detecting C compile features
�[36m--�[0m Detecting C compile features - done
�[36m--�[0m Check for working CXX compiler: /usr/bin/c++
�[36m--�[0m Check for working CXX compiler: /usr/bin/c++ -- works
�[36m--�[0m Detecting CXX compiler ABI info
�[36m--�[0m Detecting CXX compiler ABI info - done
�[36m--�[0m Detecting CXX compile features
�[36m--�[0m Detecting CXX compile features - done
�[36m--�[0m Using CATKIN_DEVEL_PREFIX: /home/pete/catkin_ws/devel/.private/realsense_gazebo_plugin
�[36m--�[0m Using CMAKE_PREFIX_PATH: /home/pete/catkin_ws/devel;/home/pete/ws/devel;/opt/ros/kinetic
�[36m--�[0m This workspace overlays: /home/pete/catkin_ws/devel;/home/pete/ws/devel;/opt/ros/kinetic
�[36m--�[0m Found PythonInterp: /usr/bin/python (found version "2.7.12")
�[36m--�[0m Using PYTHON_EXECUTABLE: /usr/bin/python
�[36m--�[0m Using Debian Python package layout
�[36m--�[0m Using empy: /usr/bin/empy
�[36m--�[0m Using CATKIN_ENABLE_TESTING: ON
�[36m--�[0m Call enable_testing()
�[36m--�[0m Using CATKIN_TEST_RESULTS_DIR: /home/pete/catkin_ws/build/realsense_gazebo_plugin/test_results
�[36m--�[0m Found gmock sources under '/usr/src/gmock': gmock will be built
�[36m--�[0m Looking for pthread.h
�[36m--�[0m Looking for pthread.h - found
�[36m--�[0m Looking for pthread_create
�[36m--�[0m Looking for pthread_create - not found
�[36m--�[0m Looking for pthread_create in pthreads
�[36m--�[0m Looking for pthread_create in pthreads - not found
�[36m--�[0m Looking for pthread_create in pthread
�[36m--�[0m Looking for pthread_create in pthread - found
�[36m--�[0m Found Threads: TRUE
�[36m--�[0m Found gtest sources under '/usr/src/gmock': gtests will be built
�[36m--�[0m Using Python nosetests: /usr/bin/nosetests-2.7
�[36m--�[0m catkin 0.7.11
�[36m--�[0m Using these message generators: gencpp;geneus;genlisp;gennodejs;genpy
�[36m--�[0m Boost version: 1.58.0
�[36m--�[0m Found the following Boost libraries:
�[36m--�[0m   thread
�[36m--�[0m   chrono
�[36m--�[0m   system
�[36m--�[0m   date_time
�[36m--�[0m   atomic
�[36m--�[0m Found Protobuf: /usr/lib/x86_64-linux-gnu/libprotobuf.so
�[36m--�[0m Boost version: 1.58.0
�[36m--�[0m Looking for OGRE...
�[36m--�[0m OGRE_PREFIX_WATCH changed.
�[36m--�[0m Found PkgConfig: /usr/bin/pkg-config (found version "0.29.1")
�[36m--�[0m Checking for module 'OGRE'
�[36m--�[0m   Found OGRE, version 1.9.0
�[36m--�[0m Found Ogre Ghadamon (1.9.0)
�[36m--�[0m Found OGRE: optimized;/usr/lib/x86_64-linux-gnu/libOgreMain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreMain.so
�[36m--�[0m Looking for OGRE_Paging...
�[36m--�[0m Found OGRE_Paging: optimized;/usr/lib/x86_64-linux-gnu/libOgrePaging.so;debug;/usr/lib/x86_64-linux-gnu/libOgrePaging.so
�[36m--�[0m Looking for OGRE_Terrain...
�[36m--�[0m Found OGRE_Terrain: optimized;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so;debug;/usr/lib/x86_64-linux-gnu/libOgreTerrain.so
�[36m--�[0m Looking for OGRE_Property...
�[36m--�[0m Found OGRE_Property: optimized;/usr/lib/x86_64-linux-gnu/libOgreProperty.so;debug;/usr/lib/x86_64-linux-gnu/libOgreProperty.so
�[36m--�[0m Looking for OGRE_RTShaderSystem...
�[36m--�[0m Found OGRE_RTShaderSystem: optimized;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so;debug;/usr/lib/x86_64-linux-gnu/libOgreRTShaderSystem.so
�[36m--�[0m Looking for OGRE_Volume...
�[36m--�[0m Found OGRE_Volume: optimized;/usr/lib/x86_64-linux-gnu/libOgreVolume.so;debug;/usr/lib/x86_64-linux-gnu/libOgreVolume.so
�[36m--�[0m Looking for OGRE_Overlay...
�[36m--�[0m Found OGRE_Overlay: optimized;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so;debug;/usr/lib/x86_64-linux-gnu/libOgreOverlay.so
�[36m--�[0m Configuring done
�[36m--�[0m Generating done
�[36m--�[0m Build files have been written to: /home/pete/catkin_ws/build/realsense_gazebo_plugin

thanks in advance

protobuf Version verification failed

Hi,
After I run roslaunch realsense_gazebo_plugin realsense.launch, error about protobuf version occur:

[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.0.131
[Wrn] [msgs.cc:1655] Conversion of sensor type[depth] not suppported.
[Wrn] [Event.cc:87] Warning: Deleteing a connection right after creation. Make sure to save the ConnectionPtr from a Connect call
[libprotobuf FATAL google/protobuf/stubs/common.cc:61] This program requires version 3.4.0 of the Protocol Buffer runtime library, but the installed version is 2.6.1.  Please update your library.  If you compiled the program yourself, make sure that your headers are from the same version of Protocol Buffers as your link-time library.  (Version verification failed in "/home/wang/ridgeback_cartographer_ws/protobuf/src/google/protobuf/descriptor.pb.cc".)
terminate called after throwing an instance of 'google::protobuf::FatalException'
  what():  This program requires version 3.4.0 of the Protocol Buffer runtime library, but the installed version is 2.6.1.  Please update your library.  If you compiled the program yourself, make sure that your headers are from the same version of Protocol Buffers as your link-time library.  (Version verification failed in "/home/wang/ridgeback_cartographer_ws/protobuf/src/google/protobuf/descriptor.pb.cc".)
Aborted (core dumped)

What confuse me is Version verification failed in "/home/wang/ridgeback_cartographer_ws/protobuf/src/google/protobuf/descriptor.pb.cc".), the workspace mentioned here is not the workspace include the launch file, and if I delete the /home/wang/ridgeback_cartographer_ws, the error still be the same. How can I delete the link between the protobuf and /home/wang/ridgeback_cartographer_ws?

Gazebo doesnt openup

Hi Syrian, I tried using the same package and cloned it for kinetic branch and when i try running the two commands in different terminal Gazebo doesnt openup. it shows Depth warning as there is some topics not publishing on the same.

Can you help me in clearing this error.

camera_info message for your package

Hi, I am trying to convert the depth image output by the realsense_gazebo_plugin into a point cloud, using the depth_image_proc package (in ROS's image_pipeline). However, this requires camera_info information. (rgb/camera_info is a subscribed topic.)

Would you be able to add a camera_info topic for the simulated realsense_camera?

If not, can you provide values for the following fields of the sensor_msgs/CameraInfo.msg for this simulated realsense_camera, so that others can add that topic themselves to their clones of your package if they wish?

std_msgs/Header header
uint32 height
uint32 width
string distortion_model
float64[] D
float64[9] K
float64[9] R
float64[12] P
uint32 binning_x
uint32 binning_y
sensor_msgs/RegionOfInterest roi

(Source: sensor_msgs/CameraInfo.msg definition - http://docs.ros.org/api/sensor_msgs/html/msg/CameraInfo.html)

Thank you! This package has been very useful to me so far, and with camera_info added, will be even more so :-)

Has no memeber named ‘SimTime’

Got this error while building it:

/home/catkin_ws/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp: In member function ‘virtual void gazebo::GazeboRosRealsense::OnNewFrame(gazebo::rendering::CameraPtr, gazebo::transport::PublisherPtr)’:
/home/hasan/catkin_ws/src/realsense_gazebo_plugin/src/gazebo_ros_realsense.cpp:57:44: error: ‘class gazebo::physics::World’ has no member named ‘SimTime’
common::Time current_time = this->world->SimTime();

can't download realsense model

I am getting following error while trying to run
roslaunch realsense_gazebo_plugin realsense.launch

... logging to /home/arpit/.ros/log/42c1fe42-1d82-11e7-b849-4ccc6a67057c/roslaunch-littleone-14170.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://128.2.7.87:44544/

SUMMARY

PARAMETERS

  • /rosdistro: indigo
  • /rosversion: 1.11.20
  • /use_sim_time: True

NODES
/
gazebo (gazebo_ros/gzserver)

auto-starting new master
process[master]: started with pid [14182]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 42c1fe42-1d82-11e7-b849-4ccc6a67057c
process[rosout-1]: started with pid [14195]
started core service [/rosout]
process[gazebo-2]: started with pid [14198]
Gazebo multi-robot simulator, version 7.6.0
Copyright (C) 2012 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[Err] [Plugin.hh:165] Failed to load plugin //home/arpit/ros_wss/catkin_ws/install/lib/libgazebo_ros_paths_plugin.so: libgazebo_common.so.2: cannot open shared object file: No such file or directory
[Err] [Plugin.hh:165] Failed to load plugin //home/arpit/ros_wss/catkin_ws/install/lib/libgazebo_ros_api_plugin.so: libgazebo_common.so.2: cannot open shared object file: No such file or directory
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 128.2.7.87
[Wrn] [ModelDatabase.cc:340] Getting models from[http://gazebosim.org/models/]. This may take a few seconds.
[Err] [ModelDatabase.cc:414] Unable to download model[model://realsense_camera]
[Err] [SystemPaths.cc:410] File or path does not exist[""]
Error [parser.cc:689] Unable to find uri[model://realsense_camera]

When I go to gazebo models I can't find any realsense file. Kindly let me know how to get this working.

Thanks

URDF: camera origins broken if link rs200_camera is not direct child of world

Hi,
I'm trying to figure out how to attach your rs200 to my robot's URDF: the problem is that while using your URDF structure (rs200_simulation.xacro) everything is ok, each camera has its vertex in the correct position:
screenshot from 2018-10-23 18-21-27
(it can be seen by setting <visualize>1</visualize> in realsense-RS200.macro.xacro:151,173,195)

However if I attach the camera to any other link that isn't called world each camera cone collapse in rs200 origin, as follows:
screenshot from 2018-10-26 12-15-22

This result can be reproduced using this simple URDF:

<?xml version="1.0"?>
<!--Develped by Daniel Ordonez 22.05.2018 - [email protected]
  INFORMATION:
    This is an example of how to use the realsense-rs200 macro function.
-->
<robot name="robot_with_rs200" xmlns:xacro="http://ros.org/wiki/xacro">
    <!-- Import macro for realsense-RS200 camera-->
    <xacro:include filename="$(find realsense_gazebo_plugin)/urdf/realsense-RS200.macro.xacro"/>
    <!-- Create camera instance -->
    <xacro:realsense-rs200/>
    
    <!-- Gazebo world link required to position the robot with respect to origin-->
    <link name="world"/>

    <link name="box">
        <visual>
        <origin rpy="0 0 0" xyz="0 0 0"/>
        <geometry>
            <box size="0.1 0.1 0.1"/>
        </geometry>
        </visual>
    </link>

    <!-- Place camera referenced to box frame-->
    <joint name="realsense_joint" type="fixed">
        <parent link="box"/>
        <child link="rs200_camera"/>
        <origin rpy="0 0 0" xyz="0 0 0.2"/>
    </joint>

    <joint name="world_joint" type="fixed">
        <parent link="world"/>
        <child link="box"/>
        <origin rpy="0 0 0" xyz="0 0 0.1"/>
    </joint>
</robot>

Err:Light [sun] not found. Use topic ~/factory/light to spawn a new light.

Hi,
platform:ubunut16.04 ros-kinetic gazebo7
I want to run roslaunch realsense_gazebo_plugin realsense.launch, error occur:

SUMMARY
========

PARAMETERS
 * /rosdistro: kinetic
 * /rosversion: 1.12.14
 * /use_sim_time: True

NODES
  /
    gazebo (gazebo_ros/gzserver)

auto-starting new master
process[master]: started with pid [11032]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to 4b5b99b8-4ea0-11e9-a4ce-2016b9896a4d
process[rosout-1]: started with pid [11045]
started core service [/rosout]
process[gazebo-2]: started with pid [11049]
Gazebo multi-robot simulator, version 7.0.0
Copyright (C) 2012-2016 Open Source Robotics Foundation.
Released under the Apache 2 License.
http://gazebosim.org

[ INFO] [1553478598.640800789]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1553478598.641189456]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[Msg] Waiting for master.
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.0.131
[Wrn] [msgs.cc:1655] Conversion of sensor type[depth] not suppported.
[ INFO] [1553478599.694139673]: Realsense Gazebo ROS plugin loading.

RealSensePlugin: The realsense_camera plugin is attach to model realsense_camera
[Wrn] [msgs.cc:1655] Conversion of sensor type[depth] not suppported.
[Err] [Scene.cc:2927] Light [sun] not found. Use topic ~/factory/light to spawn a new light.
[ INFO] [1553478599.824697864, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1553478599.848389284, 0.044000000]: Physics dynamic reconfigure ready.
[Wrn] [msgs.cc:1655] Conversion of sensor type[depth] not suppported.
[Wrn] [msgs.cc:1655] Conversion of sensor type[depth] not suppported.

It seems like the duplicate of the issue
But I didn't use virtualbox and I test my version of opengl by glxinfo | grep OpenGL,
The verison is OpenGL version string: 4.6.0 NVIDIA 410.48.
And the environment variable GAZEBO_MODEL_PATH is GAZEBO_MODEL_PATH=/home/wang/interRealsense/r200_gazebo_plugin_ws/src/realsense_gazebo_plugin/models:/home/wang/.gazebo/models. It seems like no problem.
Can you provide some advice? Thanks a lot!

update

The alternative roslaunch realsense_gazebo_plugin realsense_urdf.launch seems work well.

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.