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

Revision history [back]

It should just be a matter of editing the openni_node.launch file that comes with the installation. There are examples of how to choose an openni_camera with different types of enumeration. Here is the launch file in Mercurial: https://kforge.ros.org/openni/openni_ros/file/6794bbd92d89/openni_camera/launch/openni_node.launch

Just copy the <node ...&gt;<="" node=""> for the Kinect and add the enumeration of the second device.

Also the ROS stack for the Kinect (https://github.com/ros-pkg-git/kinect) has a built in launch file kinect2x.launch (https://github.com/ros-pkg-git/kinect/blob/master/kinect_camera/launch/kinect2x.launch)

It should just be a matter of editing the openni_node.launch file that comes with the installation. There are examples of how to choose an openni_camera with different types of enumeration. Here is the launch file in Mercurial: https://kforge.ros.org/openni/openni_ros/file/6794bbd92d89/openni_camera/launch/openni_node.launch

Just copy the <node ...&gt;<="" node=""> node section for the Kinect and add the enumeration of the second device.

Also the ROS stack for the Kinect (https://github.com/ros-pkg-git/kinect) has a built in launch file kinect2x.launch (https://github.com/ros-pkg-git/kinect/blob/master/kinect_camera/launch/kinect2x.launch)

It should just be a matter of editing the openni_node.launch file that comes with the installation. There are examples of how to choose an openni_camera with different types of enumeration. Here is the launch file in Mercurial: https://kforge.ros.org/openni/openni_ros/file/6794bbd92d89/openni_camera/launch/openni_node.launch

Just copy the node section for the Kinect and add the enumeration of the second device.

<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="device_id" value="#1"/> <!-- this line uses first enumerated device -->
    <rosparam command="load" file="$(find openni_camera)/info/openni_params.yaml" />
    <param name="rgb_frame_id" value="/openni_rgb_optical_frame1" />
    <param name="depth_frame_id" value="/openni_depth_optical_frame1" />
    <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="device_id" value="#2"/> <!-- this line uses second enumerated device -->
    <rosparam command="load" file="$(find openni_camera)/info/openni_params.yaml" />
    <param name="rgb_frame_id" value="/openni_rgb_optical_frame2" />
    <param name="depth_frame_id" value="/openni_depth_optical_frame2" />
    <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>

Also the ROS stack for the Kinect (https://github.com/ros-pkg-git/kinect) has a built in You will also want to update your kinect_frames launch file kinect2x.launch (https://github.com/ros-pkg-git/kinect/blob/master/kinect_camera/launch/kinect2x.launch)for the pair of kinects. I would suggest pursuing a URDF file and joint_state_publisher, as the static transforms can become mind-numbing after a while.

It should just be a matter of editing the openni_node.launch file that comes with the installation. There are examples of how to choose an openni_camera with different types of enumeration. Here is the launch file in Mercurial: https://kforge.ros.org/openni/openni_ros/file/6794bbd92d89/openni_camera/launch/openni_node.launch

Just copy the node section for the Kinect and add the enumeration of the second device.

<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="device_id" value="#1"/> <!-- this line uses first enumerated device -->
    <rosparam command="load" file="$(find openni_camera)/info/openni_params.yaml" />
    <param name="rgb_frame_id" value="/openni_rgb_optical_frame1" />
    <param name="depth_frame_id" value="/openni_depth_optical_frame1" />
    <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="device_id" value="#2"/> <!-- this line uses second enumerated device -->
    <rosparam command="load" file="$(find openni_camera)/info/openni_params.yaml" />
    <param name="rgb_frame_id" value="/openni_rgb_optical_frame2" />
    <param name="depth_frame_id" value="/openni_depth_optical_frame2" />
    <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>

You will also want to update your kinect_frames launch file for the pair of kinects. I would suggest pursuing a URDF file and joint_state_publisher, as the static transforms can become mind-numbing after a while.