ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
Let's say your first kinect has a frame of openni_camera_1, and your second kinect has a frame of openni_camera_2.
You could make one the child of the other, but I find it cleaner to make them both children of a common virtual frame frame. Let's call that frame kinect_link.
You need to publish a static transform between the link frame and each kinect. One of the transforms can just be the identity, and the other one will be a 180 y-axis rotation. If you're using launch files, the following lines will create the static publishers:
<node pkg="tf" type="static_transform_publisher" name="kinect_link_to_kinect_1"
args="0 0 0 0 0 0 /kinect_link /openni_camera_1 10" />
<node pkg="tf" type="static_transform_publisher" name="kinect_link_to_kinect_2"
args="0 0 0 0 3.14159 0 /kinect_link /openni_camera_2 10" />
Next, when you run rviz, simply set the fixed_frame filed to kinect_link.
Now, the example I gave only accounts for the rotation between the kinects. You probably want to tweak the transforms so that they account for the displacement between them as well.
PS. Are you sure you want a rotation around the y-axis? It might actually be the z-axis.
2 | No.2 Revision |
Let's say your first kinect has a frame of openni_camera_1, and your second kinect has a frame of openni_camera_2.
You could make one the child of the other, but I find it cleaner to make them both children of a common virtual frame frame. Let's call that frame kinect_link.
You need to publish a static transform between the link frame and each kinect. One of the transforms can just be the identity, and the other one will be a 180 y-axis rotation. If you're using launch files, the following lines will create the static publishers:
<node pkg="tf" type="static_transform_publisher" name="kinect_link_to_kinect_1"
args="0 0 0 0 0 0 /kinect_link /openni_camera_1 10" />
<node pkg="tf" type="static_transform_publisher" name="kinect_link_to_kinect_2"
args="0 0 0 0 3.14159 0 /kinect_link /openni_camera_2 10" />
Next, when you run rviz, simply set the fixed_frame filed to kinect_link.
Now, the example I gave only accounts for the rotation between the kinects. You probably want to tweak the transforms so that they account for the displacement between them as well.
PS. Are you sure you want a rotation around the y-axis? It might actually be the z-axis.
UPDATE: It looks like getting your two kinects to output in different frames takes a little work. The openni_camera driver allows you to set these parameters: rgb_frame_id and depth_frame_id. These are set by default to openni_rgb_optical_frame and openni_depth_optical_frame. However, if you are using the openni_node launch file, it sets these as children to an openni_camera frame. So you would have to rewrite the kinect_frames launch file and make two versions of it, one for each kinect