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

Multiple Kinect

asked 2011-10-13 20:07:38 -0500

Lorenzo gravatar image

updated 2016-10-24 09:01:16 -0500

ngrennan gravatar image

Hi! I am trying to use two kinects, one to perform human tracking and object recognition, and one to navigate (using pointcloud to laserscan).

I modified the openni_node.launch with two nodes and I adjusted the kinect_frames.launch. Both kinect publish the rgb image, but just one (apparently randomly) publishes the pointcloud.

Here are the files I modified

openni_node.launch

<launch>
  <arg name="debug" default="false"/>
  <arg if="$(arg debug)" name="launch_prefix" value="xterm -rv -e gdb -ex run -args"/>
  <arg unless="$(arg debug)" name="launch_prefix" value=""/>
  <node pkg="openni_camera" type="openni_node" name="openni_node1" output="screen" launch-prefix="$(arg launch_prefix)">
    <!--param name="topic" value="first" /-->
    <!--param name="device_id" value="2@3" --> <!-- this line uses device on usb bus 2 and addres 3 -->
    <param name="device_id" value="A00366A12990044A"/> <!-- this line uses device with given serial number -->

    <!--param name="device_id" value="#1" /-->

    <rosparam command="load" file="$(find openni_camera)/info/openni_params.yaml" />
    <param name="rgb_frame_id" value="/openni_rgb_optical_frame" />
    <param name="depth_frame_id" value="/openni_depth_optical_frame" />
    <param name="use_indices" value="false" />
    <param name="depth_registration" value="true" />
    <param name="image_mode" value="2" />
    <param name="depth_mode" value="2" />
    <param name="debayering" value="2" />
    <param name="depth_time_offset" value="0" />
    <param name="image_time_offset" value="0" />
  </node>
    <node pkg="openni_camera" type="openni_node" name="openni_node2" output="screen" launch-prefix="$(arg launch_prefix)">
    <!--param name="topic" value="first" /-->
    <param name="device_id" value="A00363A00048052A"/>

    <rosparam command="load" file="$(find openni_camera)/info/openni_params.yaml" />
    <remap from="camera" to="camera_2"/>
    <param name="rgb_frame_id" value="/openni_rgb_optical_frame_2" />
    <param name="depth_frame_id" value="/openni_depth_optical_frame_2" />
    <param name="use_indices" value="false" />
    <param name="depth_registration" value="true" />
    <param name="image_mode" value="2" />
    <param name="depth_mode" value="2" />
    <param name="debayering" value="2" />
    <param name="depth_time_offset" value="0" />
    <param name="image_time_offset" value="0" />
  </node>
  <include file="$(find openni_camera)/launch/kinect_frames.launch"/>
</launch>

kinect_frames.launch

<launch>
<!--  <node pkg="tf" type="static_transform_publisher" name="base_link_to_openni" args="-0.04 0 0 1.57 -1.57 0 /base_link /openni_camera 100" />  -->
  <node pkg="tf" type="static_transform_publisher" name="kinect_fake_laser" args="-0.155 -0.14 0.19 -1.57 0 0  /base_link /base_laser 100" />
  <node pkg="tf" type="static_transform_publisher" name="kinect_base_link" args="0.02 0 0 -3.14 0 0 /openni_camera /openni_depth_frame 100" />
  <node pkg="tf" type="static_transform_publisher" name="kinect_base_link1" args="0.04 0 0 -3.14 0 0 /openni_camera /openni_rgb_frame 100" />
  <node pkg="tf" type="static_transform_publisher" name="kinect_base_link2" args="0 0 0 3.14 0 0 /openni_depth_frame /openni_depth_optical_frame  100" />
  <node pkg="tf" type="static_transform_publisher" name="kinect_base_link3" args="0 0 0 3.14 0 0 /openni_rgb_frame /openni_rgb_optical_frame 100" />

  <node pkg="tf" type="static_transform_publisher" name="kinect_base_link0_2" args="-0.155 -0.14 0.19 3.14 0 -1.57 /base_link /openni_camera_2 100" />
  <node pkg="tf" type="static_transform_publisher" name="kinect_base_link_2" args="0.02 0 0 -3.14 0 0 /openni_camera_2 /openni_depth_frame_2 100" />
  <node pkg="tf" type="static_transform_publisher" name="kinect_base_link1_2" args="0.04 0 0 -3.14 0 0 /openni_camera_2 /openni_rgb_frame_2 100" />
  <node pkg="tf" type="static_transform_publisher" name="kinect_base_link2_2" args="0 0 0 3.14 0 0 /openni_depth_frame_2 /openni_depth_optical_frame_2  100" />
  <node pkg="tf" type="static_transform_publisher" name="kinect_base_link3_2" args="0 0 0 3.14 0 0 /openni_rgb_frame_2 /openni_rgb_optical_frame_2 100" />

</launch>

Thank ... (more)

edit retag flag offensive close merge delete

Comments

I was also trying this yesterday and was experiencing a similar problem. I haven't had a lot of time to play around with it, but I'll keep you updated If I find anything.
John Hoare gravatar image John Hoare  ( 2011-10-14 01:51:18 -0500 )edit

4 Answers

Sort by ยป oldest newest most voted
2

answered 2011-10-14 09:27:39 -0500

DimitriProsser gravatar image

I believe the issue is that both nodes are publishing to the same topic simultaneously. Since the topic name of each node is not a parameter, you cannot change the topic in the standard way. Instead, you must use the following in your launch file:

<node pkg="openni_camera" type="openni_node" name="openni_node1" output="screen" launch-prefix="$(arg launch_prefix)">
   <remap from="camera/depth/points" to="camera/depth/points1" />
   ...
</node>

<node pkg="openni_camera" type="openni_node" name="openni_node2" output="screen" launch-prefix="$(arg launch_prefix)">
   <remap from="camera/depth/points" to="camera/depth/points2" />
   ...
</node>
edit flag offensive delete link more

Comments

Thanks I tried but didn't work. Neither topic was published it seemed. .launch file I used -> http://pastebin.com/HbLhy5wF
130s gravatar image 130s  ( 2011-11-30 10:23:10 -0500 )edit
I'm a little skeptical since "openni_node" in rxgraph doesn't publish any topic regarding images even under default config. But when I tried modifying kinect.launch which publishes camera/depth/**, program even got stuck in the middle and didn't progress. .launch file -> http://pastebin.com/C3cgmA4w
130s gravatar image 130s  ( 2011-11-30 10:23:39 -0500 )edit
2

answered 2011-10-18 22:26:55 -0500

Daniel Canelhas gravatar image

If you look at the source for the openni_camera device_kinect.h you'll see that the kinect doesn't support hardware synchronization.

Based on this, I think you might get interference if the cameras are pointed towards the same area. To solve this in software, you might have to devise a way of intermittently shutting the IR light projector off for alternating sensors (probably by hacking the drivers somehow?), settling for half the framerate (at best). You could make an experiment by connecting the cameras to separate computers and checking what results you get in the overlapping fov.

If the sensors never look at the same space, perhaps there is a way to force them to work simultaneously anyway. I hope you find an answer :)

edit flag offensive delete link more
0

answered 2012-03-06 18:37:36 -0500

tfoote gravatar image

There also may be issues if you are plugging both Kinects into the same USB bus. A USB 2.0 Bus can only support one Kinect datastream.

edit flag offensive delete link more

Comments

Yeah...we resolved the issue creating ROS services that activate and deactivate the kinect data stream, so we can switch at will from one kinect to the other.

Lorenzo gravatar image Lorenzo  ( 2012-03-06 22:35:46 -0500 )edit
1

Hi Lorenzo can you elucidate more on this above statement

sai gravatar image sai  ( 2012-11-06 19:05:48 -0500 )edit

Hi, what we did is using the built-in function of the openni_driver to create ros services to enable or disable the streams and we manage it at a higher level.

Lorenzo gravatar image Lorenzo  ( 2012-11-08 20:51:39 -0500 )edit
1

I wrote the code of the 2 services here, so you can have an idea on how to do it: http://dl.dropbox.com/u/369118/start_stop.cpp

Lorenzo gravatar image Lorenzo  ( 2012-11-08 20:51:56 -0500 )edit

thanks for that..

sai gravatar image sai  ( 2012-11-09 02:02:40 -0500 )edit
0

answered 2011-10-18 21:31:43 -0500

Lorenzo gravatar image

I remapped all the topics. Now when I launch both the camera nodes, if I visualize everything on rviz, I obtain a frame transformation time error (for both camera) from /camera_rgb_optical_frame to every other fixed frame I use and sometimes maybe due to the same issue I can visualize just 1 kinect data stream (apparently randomly).

I have to mention that pointcloud_to_laserscan (used for the navigation kinect) has this launch file:

<launch>

  <!-- openni_manager -->
  <node pkg="nodelet" type="nodelet" name="openni_manager" output="screen" respawn="true" args="manager"/>

  <!-- throttling -->
  <node pkg="nodelet" type="nodelet" name="pointcloud_throttle" args="load pointcloud_to_laserscan/CloudThrottle openni_manager">
    <param name="max_rate" value="20"/>
    <remap from="cloud_in" to="/camera/depth/points2"/>
    <remap from="cloud_out" to="cloud_throttled"/>
  </node>

  <!-- fake laser -->
  <node pkg="nodelet" type="nodelet" name="kinect_laser" args="load pointcloud_to_laserscan/CloudToScan openni_manager">
    <param name="output_frame_id" value="/base_laser"/>
    <remap from="cloud" to="cloud_throttled"/>
  </node>
</launch>

If a use one kinect at times everything works fine. Is it possible to use more than one kinect?

Thank you for the help

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2011-10-13 20:07:38 -0500

Seen: 2,299 times

Last updated: Mar 06 '12