ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
In electric, I am getting about ~0.35Xreal-time on my desktop (i7 quad), if you are getting 0.03xreal-time, something is wrong. Can you try profiling it with your favorite profiler (e.g. valgrind) and post some results?
The 0.35Xreal-time should be improvable too, but let start with the 0.03X problem?
2 | report result for testing w/o camera |
In electric, I am getting about ~0.35Xreal-time on my desktop (i7 quad), if you are getting 0.03xreal-time, something is wrong. Can you try profiling it with your favorite profiler (e.g. valgrind) and post some results?
The 0.35Xreal-time should be improvable too, but let start with the 0.03X problem?
I tried turning off all the cameras and I am getting about 1.4Xreal-time. Can the camera sensor generation be throttled?
3 | narrowed down to 1 camera |
In electric, I am getting about ~0.35Xreal-time on my desktop (i7 quad), if you are getting 0.03xreal-time, something is wrong. Can you try profiling it with your favorite profiler (e.g. valgrind) and post some results?
The 0.35Xreal-time should be improvable too, but let start with the 0.03X problem?
I tried turning off all the cameras kinect camera by commenting out following line in the urdf
<xacro:cob_kinect_gazebo_v0 name="${name}" ros_topic="${ros_topic}"/>
and I am getting about 1.4Xreal-time. Can the camera sensor generation be throttled?
4 | No.4 Revision |
In electric, I am getting about ~0.35Xreal-time on my desktop (i7 quad), if you are getting 0.03xreal-time, something is wrong. Can you try profiling it with your favorite profiler (e.g. valgrind) and post some results?
The 0.35Xreal-time should be improvable too, but let start with the 0.03X problem?
I tried turning off the kinect camera by commenting out following line in the urdf
<xacro:cob_kinect_gazebo_v0 name="${name}" ros_topic="${ros_topic}"/>
and I am getting about 1.4Xreal-time. Can the camera sensor generation be throttled?
<?xml version="1.0"?>
<root xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="cob_kinect_gazebo_v0" params="name ros_topic">
<gazebo reference="${name}_frame">
<sensor:camera name="${name}_sensor">
<imageFormat>R8G8B8</imageFormat>
<imageSize>320 240</imageSize>
<hfov>57</hfov>
<nearClip>0.01</nearClip>
<farClip>5</farClip>
<updateRate>1.0</updateRate>
<baseline>0.2</baseline>
<controller:gazebo_ros_openni_kinect name="${name}_controller" plugin="libgazebo_ros_openni_kinect.so">
<alwaysOn>true</alwaysOn>
<updateRate>1.0</updateRate>
<imageTopicName>/${ros_topic}/image_raw</imageTopicName>
<pointCloudTopicName>/${ros_topic}/points</pointCloudTopicName>
<cameraInfoTopicName>/${ros_topic}/camera_info</cameraInfoTopicName>
<frameName>/${name}_frame</frameName>
<pointCloudCutoff>0.5</pointCloudCutoff>
<distortion_k1>0.00000001</distortion_k1>
<distortion_k2>0.00000001</distortion_k2>
<distortion_k3>0.00000001</distortion_k3>
<distortion_t1>0.00000001</distortion_t1>
<distortion_t2>0.00000001</distortion_t2>
</controller:gazebo_ros_openni_kinect>
</sensor:camera>
<material value="Gazebo/Red" />
<turnGravityOff>true</turnGravityOff>
</gazebo>
</xacro:macro>
</root>
and you should see drastic improvements in speed.
5 | No.5 Revision |
In electric, I am getting about ~0.35Xreal-time on my desktop (i7 quad), if you are getting 0.03xreal-time, something is wrong. Can you try profiling it with your favorite profiler (e.g. valgrind) and post some results?
The 0.35Xreal-time should be improvable too, but let start with the 0.03X problem?
I tried turning off the kinect camera by commenting out following line in the urdf
<xacro:cob_kinect_gazebo_v0 name="${name}" ros_topic="${ros_topic}"/>
and I am getting about 1.4Xreal-time. Taking a closer look, the current i code was using gazebo_ros_block_laser plugin with 160X160 configuration. A better way to implement this is to use the gazebo_ros_openni_kinect plugin, for example, update your kinect.gazebo.xacro file to look something like this:
<?xml version="1.0"?>
<root xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="cob_kinect_gazebo_v0" params="name ros_topic">
<gazebo reference="${name}_frame">
<sensor:camera name="${name}_sensor">
<imageFormat>R8G8B8</imageFormat>
<imageSize>320 240</imageSize>
<hfov>57</hfov>
<nearClip>0.01</nearClip>
<farClip>5</farClip>
<updateRate>1.0</updateRate>
<baseline>0.2</baseline>
<controller:gazebo_ros_openni_kinect name="${name}_controller" plugin="libgazebo_ros_openni_kinect.so">
<alwaysOn>true</alwaysOn>
<updateRate>1.0</updateRate>
<imageTopicName>/${ros_topic}/image_raw</imageTopicName>
<pointCloudTopicName>/${ros_topic}/points</pointCloudTopicName>
<cameraInfoTopicName>/${ros_topic}/camera_info</cameraInfoTopicName>
<frameName>/${name}_frame</frameName>
<pointCloudCutoff>0.5</pointCloudCutoff>
<distortion_k1>0.00000001</distortion_k1>
<distortion_k2>0.00000001</distortion_k2>
<distortion_k3>0.00000001</distortion_k3>
<distortion_t1>0.00000001</distortion_t1>
<distortion_t2>0.00000001</distortion_t2>
</controller:gazebo_ros_openni_kinect>
</sensor:camera>
<material value="Gazebo/Red" />
<turnGravityOff>true</turnGravityOff>
</gazebo>
</xacro:macro>
</root>
and you should see drastic improvements in speed.
6 | No.6 Revision |
In electric, I am getting about ~0.35Xreal-time on my desktop (i7 quad), if you are getting 0.03xreal-time, something is wrong. Can you try profiling it with your favorite profiler (e.g. valgrind) and post some results?
The 0.35Xreal-time should be improvable too, but let start with the 0.03X problem?
I tried turning off the kinect camera by commenting out following line in the urdf
<xacro:cob_kinect_gazebo_v0 name="${name}" ros_topic="${ros_topic}"/>
and I am getting about 1.4Xreal-time. Taking a closer look, the current code was using gazebo_ros_block_laser plugin with 160X160 configuration. A better way to implement this is to use the gazebo_ros_openni_kinect plugin, for example, update your kinect.gazebo.xacro file to look something like this:
<?xml version="1.0"?>
<root xmlns:sensor="http://playerstage.sourceforge.net/gazebo/xmlschema/#sensor"
xmlns:controller="http://playerstage.sourceforge.net/gazebo/xmlschema/#controller"
xmlns:interface="http://playerstage.sourceforge.net/gazebo/xmlschema/#interface"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="cob_kinect_gazebo_v0" params="name ros_topic">
<gazebo reference="${name}_frame">
<sensor:camera name="${name}_sensor">
<imageFormat>R8G8B8</imageFormat>
<imageSize>320 240</imageSize>
<hfov>57</hfov>
<nearClip>0.01</nearClip>
<farClip>5</farClip>
<updateRate>1.0</updateRate>
<baseline>0.2</baseline>
<controller:gazebo_ros_openni_kinect name="${name}_controller" plugin="libgazebo_ros_openni_kinect.so">
<alwaysOn>true</alwaysOn>
<updateRate>1.0</updateRate>
<imageTopicName>/${ros_topic}/image_raw</imageTopicName>
<pointCloudTopicName>/${ros_topic}/points</pointCloudTopicName>
<cameraInfoTopicName>/${ros_topic}/camera_info</cameraInfoTopicName>
<frameName>/${name}_frame</frameName>
<pointCloudCutoff>0.5</pointCloudCutoff>
<distortion_k1>0.00000001</distortion_k1>
<distortion_k2>0.00000001</distortion_k2>
<distortion_k3>0.00000001</distortion_k3>
<distortion_t1>0.00000001</distortion_t1>
<distortion_t2>0.00000001</distortion_t2>
</controller:gazebo_ros_openni_kinect>
</sensor:camera>
<material value="Gazebo/Red" />
<turnGravityOff>true</turnGravityOff>
</gazebo>
</xacro:macro>
</root>
and you should see drastic improvements in speed.
Aside from performance gains, fundamentally, a depth camera like Kinect is better modeled by a gazebo_ros_camera/gazebo_ros_openni_kinect than gazebo_ros_block_laser. In gazebo_ros_block_laser, the scan angles are constant as you make a horizontal or vertical scan, but for kinect, you actually want equal size pixels for each ray trace, which means the angle between rays as you scan vertically or horizontally is not constant.