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

how to apply transform to data displayed in RVIZ?

asked 2011-03-10 04:52:28 -0500

blueskin gravatar image

updated 2011-03-11 05:23:40 -0500

Hello,

I am getting pointcloud data from different kinects which are facing each other and I am trying to visualize using "rviz". I want to apply a transform (rotate 180 around y-axis) to one of the point clouds and display it, any ideas on how do this? Thank you. My launch files: Kinect1_openni_node.launch, Kinect2_openni_node.launch, kinect_frames1.launch, kinect_frames2.launch As you can see in the image the opposite walls are displayed on the same side i.e. w.r.t to their (kinect's) axes. image description

UPDATE: Here's the output of the transforms

rosrun tf tf_echo /openni_depth_frame /openni_depth_optical_frame1
At time 1299860886.324
- Translation: [0.000, 0.000, 0.000]
- Rotation: in Quaternion [0.000, 0.000, 0.000, 1.000]
            in RPY [0.000, -0.000, 0.000]
rosrun tf tf_echo /openni_depth_frame /openni_depth_optical_frame2
At time 1299860897.873
- Translation: [0.000, 0.000, 0.000]
- Rotation: in Quaternion [-0.707, -0.001, 0.707, -0.001]
            in RPY [0.000, 1.570, -3.140]

Even then I don't see any change, it's the same as the image above. Am I missing any settings in RViz?? Best, CV

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
6

answered 2011-03-10 06:08:16 -0500

updated 2011-03-10 06:24:03 -0500

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

edit flag offensive delete link more

Comments

Ivan: I was looking exactly into it. I've set both kinects as children of /openni_depth_frame and corresponding frames as given in the links in the question. In RVIZ I've set, fixed frame: /openni_depth_frame & Target frame: <Fixed Frame>? is it right?
blueskin gravatar image blueskin  ( 2011-03-10 07:04:36 -0500 )edit
@blueskin: that should work.
Ivan Dryanovski gravatar image Ivan Dryanovski  ( 2011-03-10 07:11:18 -0500 )edit
Ivan: I also have separate node launch files. Should I change <param name="depth_frame_id" value="/openni_depth_optical_frame" /> to <param name="depth_frame_id" value="/openni_depth_optical_frame1" /> and 2 respectively? because I don't see any transformations being applied in either case
blueskin gravatar image blueskin  ( 2011-03-10 07:28:23 -0500 )edit
@blueskin: Yes, you are launching two separate nodes, one for each kinect. Each node should have the depth_frame_id parameter remapped to a unique value. This way you end up with two distinct optical frames. After that, follow the static tf instructions to link them with a common virtual frame
Ivan Dryanovski gravatar image Ivan Dryanovski  ( 2011-03-10 07:35:02 -0500 )edit
Hey Ivan, I've updated the question with transforms outputs, I don't see any transforms applied to the data. Could you please look at it.
blueskin gravatar image blueskin  ( 2011-03-11 02:35:47 -0500 )edit
@blueskin: Who is publishing the /openni_depth_frame /openni_depth_optical_frame1 link? Are you using the openni_node.launch file? If so, it calls kinect_frames.launch, which sets those to 0 (probably).
Ivan Dryanovski gravatar image Ivan Dryanovski  ( 2011-03-11 04:55:00 -0500 )edit
@Ivan: I've modified the launch files and launching appropriate launch files. Links for these files are provided in the question.
blueskin gravatar image blueskin  ( 2011-03-11 05:21:23 -0500 )edit
@blueskin: ok the transforms look good. Can you post your openni launch file as well?
Ivan Dryanovski gravatar image Ivan Dryanovski  ( 2011-03-11 05:29:08 -0500 )edit
1

answered 2011-03-10 05:09:57 -0500

raphael favier gravatar image

updated 2011-03-10 05:10:55 -0500

You need to place a tf frame where you need to place your kinect. Then do either one of these:

  1. Change the frame_id field in your point cloud with the new frame name
  2. Make your kinect frame a child of the newly created frame

Raph

edit flag offensive delete link more

Comments

a couple of questions: when you say "place a tf frame" what does that mean? And, how can I change the frame_id without copying the frame and changing frame_id of the copy? Also, I've added an image of my rviz. thank you
blueskin gravatar image blueskin  ( 2011-03-10 05:48:17 -0500 )edit
I meant broadcasting a new frame that you use for the kinect you need to rotate. Your problem is that your 2 kinects associate their point clouds with the same frame. check your kinect node, maybe you can set which frame the point cloud will be associated with.
raphael favier gravatar image raphael favier  ( 2011-03-10 05:56:40 -0500 )edit

Question Tools

Stats

Asked: 2011-03-10 04:52:28 -0500

Seen: 5,652 times

Last updated: Mar 11 '11