-
Notifications
You must be signed in to change notification settings - Fork 559
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
There is still no example of two cameras for ROS2? no launch file #983
Comments
Yes, it should be possible. Is odometry computed externally? Here two examples, assuming using Depth-IR mode for realsense (IR emitter disabled). Make sure rtabmap_ros is built with
With external odometry: from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='rtabmap_sync', executable='rgbd_sync', name='rgbd_sync1', output='screen',
namespace='/realsense_camera1',
parameters=[{'approx_sync':False}],
remappings=[('rgb/image', 'infra1/image_rect_raw'),
('rgb/camera_info', 'infra1/camera_info'),
('depth/image', 'depth/image_rect_raw')]),
Node(
package='rtabmap_sync', executable='rgbd_sync', name='rgbd_sync2', output='screen',
namespace='/realsense_camera2',
parameters=[{'approx_sync':False}],
remappings=[('rgb/image', 'infra1/image_rect_raw'),
('rgb/camera_info', 'infra1/camera_info'),
('depth/image', 'depth/image_rect_raw')]),
Node(
package='rtabmap_slam', executable='rtabmap', output='screen',
parameters=[{'approx_sync':True, 'subscribe_rgbd':True, 'rgbd_cameras':2}],
remappings=[('rgbd_image0', '/realsense_camera1/rgbd_image'),
('rgbd_image1', '/realsense_camera2/rgbd_image'),
('odom', '/odom')],
arguments=['-d']),
]) With RTAB-Map's visual odometry: from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='rtabmap_sync', executable='rgbd_sync', name='rgbd_sync1', output='screen',
namespace='/realsense_camera1',
parameters=[{'approx_sync':False}],
remappings=[('rgb/image', 'infra1/image_rect_raw'),
('rgb/camera_info', 'infra1/camera_info'),
('depth/image', 'depth/image_rect_raw')]),
Node(
package='rtabmap_sync', executable='rgbd_sync', name='rgbd_sync2', output='screen',
namespace='/realsense_camera2',
parameters=[{'approx_sync':False}],
remappings=[('rgb/image', 'infra1/image_rect_raw'),
('rgb/camera_info', 'infra1/camera_info'),
('depth/image', 'depth/image_rect_raw')]),
Node(
package='rtabmap_odom', executable='rgbd_odometry', output='screen',
parameters=[{'approx_sync':True, 'subscribe_rgbd':True, 'rgbd_cameras':2}],
remappings=[('rgbd_image0', '/realsense_camera1/rgbd_image'),
('rgbd_image1', '/realsense_camera2/rgbd_image')]),
Node(
package='rtabmap_slam', executable='rtabmap', output='screen',
parameters=[{'approx_sync':True, 'subscribe_rgbd':True, 'rgbd_cameras':1}],
remappings=[('rgbd_image', 'rgbd_image'),
('odom', 'odom_rgbd_image')],
arguments=['-d']),
]) Note that in this example the realsense cameras would be started in different namespaces. You should also provide TF between the cameras and/or base frame of the robot. |
Thanks for the reply! This is my rtabmap_2cam.launch.py:
What is missing? I implemented almost everything I guess, but I can't just visualize the two mapClouds on Rviz. It says the rtabmap has not received anything, neither the rtabmap.rgbd_odometry:
Thank you! |
Verify that |
Hereby I confirm that this issue has been closed thanks to this pull request: #1002 |
I am trying to do an application with 3 realsense cameras, but I haven't found yet a solution for the remappings in ROS2. Is is possible?
The text was updated successfully, but these errors were encountered: