zed camera frame won't rotate to map

classic Classic list List threaded Threaded
5 messages Options
Reply | Threaded
Open this post in threaded view
|

zed camera frame won't rotate to map

bbeckvold
This post was updated on .
I have been battling this for a couple days and i don't know why this isn't lining up.

I am using the zed camera and trying to make a map on the same frame. The camera matched the odom frame, which makes sense beacuse i'm using the zed odom, however rtabmap is trying to make a map from a frame that has been rotated above (optical rotate?). I have tried adjusting the zed_tf.launch file to link the camera frame to the map frame that rtabmap published the proj_map on. I think this shouldn't be this tricky but what would i need to rotate to get them to line up? Any help with this would be greatly appreciated. Thanks.

I have included the relevant launch files.

demo_turtlebot_mapping.launch
test_zed.launch
zed_tf.launch

Reply | Threaded
Open this post in threaded view
|

Re: zed camera frame won't rotate to map

bbeckvold
Also, the tf tree would probably be helpful.

Reply | Threaded
Open this post in threaded view
|

Re: zed camera frame won't rotate to map

matlabbe
Administrator
Hi,

Following this tutorial with the ZED it works (using rtabmap's odometry), but trying to use ZED odometry like in your setup, I had difficulties too. The problem is that zed_wrapper_node publishes camera info messages with the wrong "frame_id". Instead of "zed_current_frame", it should be "ZED_left_camera". You can change it here.

So adding the right optical rotation, here is a minimal launch file (to use ZED's odometry):

<launch>

<arg name="camera"          default="zed"/>

<arg name="pi/2" value="1.5707963267948966" />
<arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" />

<node pkg="tf" type="static_transform_publisher" name="$(arg camera)_base_link3"
    args="$(arg optical_rotate) $(arg camera)_current_frame ZED_left_camera 100" />

<node name="zed_wrapper_node" pkg="zed_wrapper" type="zed_wrapper_node"/>

<node name="rviz" pkg="rviz" type="rviz" />

<group ns="rtabmap">
   <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
	  <param name="frame_id"            type="string" value="$(arg camera)_current_frame"/>
	
	  <remap from="rgb/image"       to="/rgb/image_rect_color"/>
  	  <remap from="depth/image"     to="/depth/depth_registered"/>
  	  <remap from="rgb/camera_info" to="/rgb/camera_info"/>
          <remap from="odom" to="/odom"/>
   </node>
</group>

</launch>
It is important that rtabmap node is subscribed to "/odom" (don't use "odom_frame_id" parameter) because zed_wrapper_node won't publish TF or estimate odometry if no one is connected on this topic.



cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: zed camera frame won't rotate to map

radisc85
This post was updated on .
Hi,

I was too, trying to run rtabmap with zed odometry and i stumble on the upward cloud problem.

I tried this setup with the latest versions of wrapper and sdk, but i'm still recieving this message,


i think i'm missing a static transform or some default frame name has changed since the version you are showing

Thank you very much

EDIT: Eureka, it works! I needed to add some other transform and specify some other values, here's my launch file:

<launch>

<arg name="camera"          default="zed"/>

<arg name="pi/2" value="1.5707963267948966" />
<arg name="optical_rotate" value="0 0 0 -$(arg pi/2) 0 -$(arg pi/2)" />
<arg name="no_rotate" value="0 0 0 0 0 0 1" />
<arg name="tf_prefix" default="" />
<arg name="stereo_namespace"        default="zed"/>


<node pkg="tf" type="static_transform_publisher" name="$(arg camera)_base_link3"
    args="$(arg optical_rotate) $(arg camera)_current_frame ZED_left_camera 100" />

  <node pkg="tf2_ros" type="static_transform_publisher" name="zed_base_link4"
    args="0 0 1.0 -$(arg pi/2) 0 -$(arg pi/2) $(arg tf_prefix)/zed_current_frame depth_frame" />

<node name="zed_wrapper_node" pkg="zed_wrapper" type="zed_wrapper_node">
        <param name="odometry_frame"        value="zed_initial_frame" />
        <param name="base_frame"            value="zed_current_frame" />
</node>


<group ns="rtabmap">
   <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
	  <param name="frame_id"            type="string" value="$(arg camera)_current_frame"/>
	
	  <remap from="rgb/image"       to="/rgb/image_rect_color"/>
  	  <remap from="depth/image"     to="/depth/depth_registered"/>
  	  <remap from="rgb/camera_info" to="/rgb/camera_info"/>
      <remap from="odom" to="/odom"/>
	  
	  <param name="odom_frame_id" value=""/>
   </node>
</launch>
Reply | Threaded
Open this post in threaded view
|

Re: zed camera frame won't rotate to map

matlabbe
Administrator
Thx for the comment, I updated the tutorial with latest zed_ros_wrapper version.

cheers,
Mathieu