Comments (15)
Hi,
Is the link (zed_simple_camera_node.cpp) of the camera node is the right one? I see only left and depth topics published.
The error indicates that there are messages without header.frame_id defined. Make sure that your camera node publishes also the TF (e.g., /left_frame, /right_frame and/or /depth_frame linked to a /stereo_camera), which doesn't seem to do in your last image.
cheers
from rtabmap_ros.
Yes the link is right for zed camera driver in ros . I have modified it to add right image . The frame ids were not added (you correctly pointed out mistake . thanks for it) i added it later .Still there is no data published on /odom topic .If i try to check the message rate it shows no value . Can u help . Here is a screenshot with image , camera info , and rqt_graph . thanks for help
from rtabmap_ros.
If you are based on this file, I recommend to set the same timestamp for all your published messages (header.stamp). stereo_odometry node assumes by default (approx_sync=false
) that all messages have exactly the same timestamp. Well, only do that if your cameras are really synchronized, if not, you can set approx_sync=true
.
Another thing, is it your right camera_info shown on the right terminal, it seems missing the P(0,3) value (baseline). Is the camera calibrated using this tutorial?
cheers
from rtabmap_ros.
Hi all,
I'm the developer of the driver you are speaking about.
I've chosen to not publish right image because with ZED SDK you have depth
image "gratis"...
About tf, the driver does not publish it by default because I prefer to use
"state publisher" node for static frame (add the camera to your robot
descriptor).
However if you think that something must be changed in my code please feel
free change it and to make a pull request so i can update it... I wrote the
driver very quickly and I have not tested it with other ROS nodes, so I'm
sure that there is something wrong 😉
Thank you for your help
Cheers
Walter
Walter Lucetti
email: [email protected]
web: www.robot-home.it - www.opencv.it
project: http://myzharbot.robot-home.it
Il 06/Ott/2015 16:31, "matlabbe" [email protected] ha scritto:
If you are based on this file, I recommend to set the same timestamp for
all your published messages (header.stamp). stereo_odometry
http://wiki.ros.org/rtabmap_ros#stereo_odometry node assumes by default
(approx_sync=false) that all messages have exactly the same timestamp.Another thing, is it your right camera_info shown on the right terminal,
it seems missing the P(0,3) value (baseline). Is the camera calibrated
using this tutorial
http://wiki.ros.org/camera_calibration/Tutorials/StereoCalibration?cheers
—
Reply to this email directly or view it on GitHub
#35 (comment)
.
from rtabmap_ros.
Thanks for the information. In this case, @shabhu18, you could use rgbd_mapping.launch
instead of stereo_mapping.launch
with left and depth images.
@Myzhar The stereo_odometry and rgbd_odometry nodes need that the transform from the frame_id
of the left/right/depth messages is linked to the fixed frame_id
of the robot (like base_link
). If the depth image is registered with the left image, you can set the frame_id
of the depth messages as left
directly (we will then not need any TF between the two cameras).
Example of a combined launch file:
<launch>
<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="camera_base_link"
args="$(arg optical_rotate) base_link left 100" />
<node pkg="ros_simple_zed_cuda_driver" type="zed_simple_camera_node" name="zed_simple_camera_node"/>
<node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen">
<remap from="rgb/image" to="stereo/left/image_rect"/>
<remap from="depth/image" to="stereo/depth/image_rect"/>
<remap from="rgb/camera_info" to="stereo/left/camera_info"/>
</node>
</launch>
cheers
from rtabmap_ros.
Hi matlabbe,
that's exactly what I meant.
Since Stereolabs SDK calculates depth map automatically using CUDA and
since RGB images, Disparity Map and Depth Map are automatically rectified
and synchronized its "easier" using ZED Camera similarly to an RGBD sensor,
so you do not spend calculation power to perform Stereo elaboration TWO
TIMES.
Furthermore, from what I verified, depth map calculated by Stereolabs SDK
is really really well done.
Finally, you do not need to calibrate the system by yourself using the
checkboard, Stereolabs provides intrinsic matrix... and also distortion and
extrinsic parameters, that you do not need since images are rectified.
Walt
2015-10-07 2:11 GMT+02:00 matlabbe [email protected]:
Thanks for the information. In this case, @shabhu18
https://github.com/shabhu18, you could use rgbd_mapping.launch instead
of stereo_mapping.launch with left and depth images.@Myzhar https://github.com/Myzhar The stereo_odometry
http://wiki.ros.org/rtabmap_ros#stereo_odometry and rgbd_odometry
http://wiki.ros.org/rtabmap_ros#rgbd_odometry nodes need that the
transform from the frame_id of the left/right/depth messages is linked to
the fixed frame_id of the robot (like base_link). If the depth image is
registered with the left image, you can set the frame_id of the depth
messages as left directly (we will then not need any TF between the two
cameras).Example of a combined launch file:
cheers
—
Reply to this email directly or view it on GitHub
#35 (comment)
.
Walter "Myzhar" Lucetti
email [email protected]
web: www.robot-home.it http://www.robot-home.it/ - www.opencv.it
http://www.opencv.it/
project: http://myzharbot.robot-home.it
from rtabmap_ros.
hii,
finally i edited the launch file for stereo_odometry node with approx_sync=true.Added baseline in pixels in P matrix.(thanks for ur suggestion ) The node ran with no problem .The value of odometry i am getting i zero for both rotation and translation matrix .It is also not printing the number of inliners .
here is screenshot. Every value is zero . Can u help .
from rtabmap_ros.
The odometry cannot be computed for some reasons. Can you record a small rosbag (10 sec) with only the camera running? So I can try it here (I guessed your topics from your previous post):
$ rosbag record /stereo_camera/left/image_rect/compressed /stereo_camera/right/image_rect/compressed /stereo_camera/left/camera_info /stereo_camera/right/camera_info /tf
from rtabmap_ros.
I have recorded the bag file . Can u please check the error .No tf has been published in bag files.The images here are mono8 images . please change in launch file and check.
https://drive.google.com/file/d/0B5N_gJxysT-FNTE0Qlg1VWlHMGc/view?usp=sharing
EDIT: just for info:
path: [hidden]
version: 2.0
duration: 12.0s
start: [hidden]
end: [hidden]
size: 216.6 MB
messages: 1916
compression: none [145/145 chunks]
types: dynamic_reconfigure/Config [958f16a05573709014982821e6822580]
dynamic_reconfigure/ConfigDescription [757ce9d44ba8ddd801bb30bc456f946f]
rosgraph_msgs/Log [acffd30cd6b6de30f120938c17c593fb]
sensor_msgs/CameraInfo [c9a58c1b0b154e0e6da7578cb991d214]
sensor_msgs/CompressedImage [8f7a12909da2c9d3332d540a0977563f]
sensor_msgs/Image [060021388200f6f0f447d0fcd9c64743]
theora_image_transport/Packet [33ac4e14a7cff32e7e0d65f18bb410f3]
topics: /rosout 448 msgs : rosgraph_msgs/Log (2 connections)
/rosout_agg 432 msgs : rosgraph_msgs/Log
/stereo_camera/depth/camera_info 144 msgs : sensor_msgs/CameraInfo
/stereo_camera/depth/image_rect 144 msgs : sensor_msgs/Image
/stereo_camera/depth/image_rect/compressed/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/stereo_camera/depth/image_rect/compressed/parameter_updates 1 msg : dynamic_reconfigure/Config
/stereo_camera/depth/image_rect/compressedDepth 145 msgs : sensor_msgs/CompressedImage
/stereo_camera/depth/image_rect/compressedDepth/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/stereo_camera/depth/image_rect/compressedDepth/parameter_updates 1 msg : dynamic_reconfigure/Config
/stereo_camera/depth/image_rect/theora 3 msgs : theora_image_transport/Packet
/stereo_camera/depth/image_rect/theora/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/stereo_camera/depth/image_rect/theora/parameter_updates 1 msg : dynamic_reconfigure/Config
/stereo_camera/left/camera_info 72 msgs : sensor_msgs/CameraInfo
/stereo_camera/left/image_rect 72 msgs : sensor_msgs/Image
/stereo_camera/left/image_rect/compressed 72 msgs : sensor_msgs/CompressedImage
/stereo_camera/left/image_rect/compressed/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/stereo_camera/left/image_rect/compressed/parameter_updates 1 msg : dynamic_reconfigure/Config
/stereo_camera/left/image_rect/compressedDepth/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/stereo_camera/left/image_rect/compressedDepth/parameter_updates 1 msg : dynamic_reconfigure/Config
/stereo_camera/left/image_rect/theora 75 msgs : theora_image_transport/Packet
/stereo_camera/left/image_rect/theora/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/stereo_camera/left/image_rect/theora/parameter_updates 1 msg : dynamic_reconfigure/Config
/stereo_camera/right/camera_info 72 msgs : sensor_msgs/CameraInfo
/stereo_camera/right/image_rect 72 msgs : sensor_msgs/Image
/stereo_camera/right/image_rect/compressed 72 msgs : sensor_msgs/CompressedImage
/stereo_camera/right/image_rect/compressed/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/stereo_camera/right/image_rect/compressed/parameter_updates 1 msg : dynamic_reconfigure/Config
/stereo_camera/right/image_rect/compressedDepth/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/stereo_camera/right/image_rect/compressedDepth/parameter_updates 1 msg : dynamic_reconfigure/Config
/stereo_camera/right/image_rect/theora 75 msgs : theora_image_transport/Packet
/stereo_camera/right/image_rect/theora/parameter_descriptions 1 msg : dynamic_reconfigure/ConfigDescription
/stereo_camera/right/image_rect/theora/parameter_updates 1 msg : dynamic_reconfigure/Config
Here the the file of the driver used
https://drive.google.com/folderview?id=0B5N_gJxysT-FdlNRbkdBMXBiVm8&usp=sharing
Thank for all ur help.
from rtabmap_ros.
Thanks for the rosbag, I have done two examples:
Stereo mapping
-
test_stereo.launch
:<launch> <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="camera_base_link" args="$(arg optical_rotate) base_link stereo_camera 100" /> <param name="use_sim_time" type="bool" value="true"/> <!-- only with rosbag --> <node pkg="rtabmap_ros" type="stereo_odometry" name="stereo_odometry" output="screen"> <remap from="left/image_rect" to="stereo_camera/left/image_rect"/> <remap from="right/image_rect" to="stereo_camera/right/image_rect"/> <remap from="left/camera_info" to="stereo_camera/left/camera_info"/> <remap from="right/camera_info" to="stereo_camera/right/camera_info"/> <param name="approx_sync" type="bool" value="true"/> <param name="Odom/EstimationType" type="string" value="1"/> <!-- 3D->2D PnP reprojection --> </node> <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="--delete_db_on_start"> <remap from="left/image_rect" to="stereo_camera/left/image_rect"/> <remap from="right/image_rect" to="stereo_camera/right/image_rect"/> <remap from="left/camera_info" to="stereo_camera/left/camera_info"/> <remap from="right/camera_info" to="stereo_camera/right/camera_info"/> <param name="subscribe_depth" type="bool" value="false"/> <param name="subscribe_stereo" type="bool" value="true"/> <param name="stereo_approx_sync" type="bool" value="true"/> <param name="LccBow/EstimationType" type="string" value="1"/> <!-- 3D->2D PnP reprojection --> <param name="Mem/SaveDepth16Format" type="string" value="false"/> </node> <node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz"> <remap from="left/image_rect" to="stereo_camera/left/image_rect"/> <remap from="right/image_rect" to="stereo_camera/right/image_rect"/> <remap from="left/camera_info" to="stereo_camera/left/camera_info"/> <remap from="right/camera_info" to="stereo_camera/right/camera_info"/> <param name="subscribe_stereo" type="bool" value="true"/> <param name="stereo_approx_sync" type="bool" value="true"/> <param name="subscribe_odom_info" type="bool" value="true"/> </node> </launch>
The right camera_info must be modified with a baseline in meters. So instead of -84000 for P(0,3), it should be -84 (to have a baseline of 0.12 m). Without that, the scale of the trajectory is huge (like the RGB-D example below).
Run:
$roslaunch test_stereo.launch
$rosbag play --clock 2015-10-08-18-33-17.bag
RGB-D mapping
-
test_rgbd.launch
:<launch> <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="camera_base_link" args="$(arg optical_rotate) base_link stereo_camera 100" /> <param name="use_sim_time" type="bool" value="true"/> <!-- only with rosbag --> <node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen"> <remap from="rgb/image" to="stereo_camera/left/image_rect"/> <remap from="depth/image" to="stereo_camera/depth/image_rect"/> <remap from="rgb/camera_info" to="stereo_camera/left/camera_info"/> <param name="Odom/EstimationType" type="string" value="1"/> <!-- 3D->2D PnP reprojection --> </node> <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="--delete_db_on_start"> <remap from="rgb/image" to="stereo_camera/left/image_rect"/> <remap from="depth/image" to="stereo_camera/depth/image_rect"/> <remap from="rgb/camera_info" to="stereo_camera/left/camera_info"/> <param name="LccBow/EstimationType" type="string" value="1"/> <!-- 3D->2D PnP reprojection --> <param name="Mem/SaveDepth16Format" type="string" value="false"/> </node> <node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz"> <remap from="rgb/image" to="stereo_camera/left/image_rect"/> <remap from="depth/image" to="stereo_camera/depth/image_rect"/> <remap from="rgb/camera_info" to="stereo_camera/left/camera_info"/> <param name="subscribe_depth" type="bool" value="true"/> <param name="subscribe_odom_info" type="bool" value="true"/> </node> </launch>
The depth format seems to be in mm instead of meters, which create large maps. You will even need to go in rtabmapviz->Preferences->3D Rendering, scroll down for Maximum depth under Map column, set 0 m instead of 4 meters, otherwise you will not see the map's clouds. The node generating depth images in 32 bits float format should be in meters (this is the default format used by openni, openni2 or freenect nodes).
EDIT Make sure to have this commit of rtabmap package, otherwise the odometry node will complain about depth conversion to 16bits failure.
Run:
$roslaunch test_rgbd.launch
$rosbag play --clock 2015-10-08-18-33-17.bag
Cheers,
Mathieu
from rtabmap_ros.
Is there a way to incorporate IMU into the RGBD odometry from the Zed example above?
from rtabmap_ros.
There is no direct way to do that in RTAB-Map, however, you can look at the robot_pose_ekf node that can merge odometry from different sources.
from rtabmap_ros.
Thanks for all your help and support i am really grateful .
I am also getting same issue as in
#39 . Slight flicking it shows red screen. How did you got such a good map from bag. What parameters you set can you share .
My map is showing just current point cloud ,Is it due to constant flicking odometery getting lost message.
from rtabmap_ros.
The bag contains not compatible depth format and camera_info. Some things to do for your node publishing the images (as explained above):
- The P(0,3) value of the right camera info should be divided by 1000 (e.g., instead of -84000, it should be -84) to have the baseline in meters
- The depth values should be divided by 1000 to have them in meters instead of mm for a 32FC1 format. You can also keep the values in mm, but change the depth format to 16UC1.
For the parameters, they are those shown in the launch examples above. If you still have flickering problems, post a new bag with the modified camera_info and depth values.
from rtabmap_ros.
I was having the same issue. It turned out to be a USB issue that I am yet to track down. I believe it was the USB3 repeater I was using, but when I tried it again in the AM I no longer had an issue. What appeared to be happening to me was the Zed wasnt connecting to the computer properly and would lose frame because of under utilization of the GPU.
If you check your GPU usage with nvidia-smi -l you should see 80+% load when the Zed is running. If thats not the case and youre using an extension of any sort or a USB port that isn't connected to a hub on the mobo (any front port on your computer case or a USB3 card plugged into the mobo via the connecting cable, not PCI) try plugging the Zed cable directly into a USB3 port on the mobo and give it a test.
from rtabmap_ros.
Related Issues (20)
- 'No map received' when using rtabmap with RPI4 & Realsense D435i HOT 1
- issues with rtabmap melodic-devel branch HOT 1
- RTAB-MAP+ORBSLAM2 input RGBD data, detect stereo camera, then the rtab-map just finish initialization HOT 2
- RTABMAP republish doesn't accept camera input topic HOT 5
- Apriltags_ros with RTABMAP Integration HOT 14
- Loop Closure Notification In Map Data Callback HOT 2
- Hello, I tried using VINSFUSION as the odom input for rtabmap HOT 5
- How to choose between Scan-to-Scan or Scan-to-Map approach for 3D LiDAR odometry? HOT 2
- unstable sensor message could lead rtabmap_ros DoS HOT 5
- My rtabmap has no image, and the LaserScan is broken in rviz. HOT 10
- How to set "advance" parameters for each node in Python HOT 3
- exit code -6 when running rtabmap.launch on RPI4 ROS noetic HOT 14
- Negative stereo baseline using OAK-D PoE HOT 1
- ROS2 Rtabmap_viz build error HOT 1
- We received odometry message, but we cannot get the corresponding TF world->camera_depth_optical_frame at data stamp 154.517000s error HOT 3
- mapping object detection data HOT 4
- Problems with path planning using d435i camera navigation HOT 3
- Resolution parameter explanation HOT 2
- How to get the rtabmap slam working and correct the pose estimate for base_link using Robot_localization Odom HOT 9
- ROS2 Humble runs rtabmap slam, there is data in /mapData but no 3D map appears in rviz2 HOT 5
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from rtabmap_ros.