RTAB-MAP GUI IS BLANK
so, the RTAB-map gui is blank for me , i am publishing all the tf frames , looked at the depth image and rgb image topics and they are publishing accurately as well but the rtabmap gui is completely blank , this is my launch file(rtabmap nodes are at the bottom)
#!/usr/bin/env python3
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription, ExecuteProcess
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node
from launch.actions import TimerAction
from ament_index_python.packages import get_package_share_directory
import os
def generate_launch_description():
px4_dir = os.path.join(os.getenv('HOME'), 'PX4-Autopilot')
common_parameters = [{
'subscribe_depth': True,
'subscribe_rgbd': False,
'subscribe_stereo': False,
'subscribe_odom_info': True,
'approx_sync': True,
'subscribe_imu': True,
'use_sim_time': True,
'always_check_imu_tf': False,
'load_db': False,
'wait_imu_to_init': True,
'approx_sync_max_interval': 0.01
#'queue_size': 10,
#'sync_queue_size': 10,
}]
return LaunchDescription([
ExecuteProcess(
cmd=['gnome-terminal', '--', 'make', '-C', px4_dir, 'px4_sitl', 'gz_x500_depth_baylands'],
output='screen',
shell=True
),
ExecuteProcess(
cmd=['gnome-terminal', '--', ' ./QGroundControl-x86_64.AppImage'],
cwd=os.path.expanduser('~'),
output='screen',
shell=True
),
ExecuteProcess(
cmd=['MicroXRCEAgent','udp4', '--port', '8888']
),
Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[
"/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/image@sensor_msgs/msg/[email protected]",
"/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/camera_info@sensor_msgs/msg/[email protected]",
"/depth_camera@sensor_msgs/msg/[email protected]",
"/depth_camera/points@sensor_msgs/msg/[email protected]"
],
output='screen'
),
Node(
package='px4_ros_bridge',
executable='px4_imu_bridge',
output='screen'
),
Node(
package='px4_ros_bridge',
executable='px4_odom_bridge',
output='screen'
),
Node(
package='drone_slam_pkg',
executable='odom_drone_tf',
output='screen'
),
Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=['0','0','0','0','0','0','base_link','x500_depth_0'],
output='screen'
),
Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=['0.12', '0.03', '0.242', '0', '0', '0', 'x500_depth_0', 'camera_link'],
output='screen'
),
Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=['0.0123', '-0.03', '0.01878', '0', '0', '0', 'camera_link', 'IMX214'],
output='screen'
),
Node(
package='tf2_ros',
executable='static_transform_publisher',
arguments=['0.01233', '-0.03', '0.01878', '0', '0', '0', 'camera_link', 'StereoOV7251'],
output='screen'
),
# TimerAction(
# period=8.0,
# actions=[
# ExecuteProcess(
# cmd=[
# 'gnome-terminal', '--', 'ros2', 'launch', 'rtabmap_launch', 'rtabmap.launch.py',
# 'rtabmap_args:=--delete_db_on_start',
# 'rgb_topic:=/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/image',
# 'depth_topic:=/depth_camera',
# 'camera_info_topic:=/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/camera_info',
# 'subscribe_rgbd:=true',
# 'frame_id:=x500_depth_0/camera_link/StereoOV7251',
# 'approx_sync:=false',
# 'wait_imu_to_init:=true',
# 'imu_topic:=/imu/data',
# 'odom_topic:=/odom',
# 'rviz:=true',
# 'use_sim_time:=true'
# ],
# output='screen'
# )
# ]
# )
Node(
package='rtabmap_odom',
executable='rgbd_odometry',
output='screen',
parameters=common_parameters + [{
'frame_id': 'base_link',
'odom_frame_id': 'odom',
'publish_tf': True
}],
remappings=[
('rgb/image', '/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/image'),
('rgb/camera_info', '/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/camera_info'),
('depth/image', '/depth_camera'),
('odom_px4', '/odom'),
('imu', '/imu/data')
]
),
Node(
package='rtabmap_slam',
executable='rtabmap',
output='screen',
parameters=common_parameters + [{
'frame_id': 'base_link',
'map_frame_id': 'map',
'odom_frame_id': 'odom',
'publish_tf': True,
'odom_sensor_sync': True
}],
remappings=[
('rgb/image', '/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/image'),
('rgb/camera_info', '/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/camera_info'),
('depth/image', '/depth_camera'),
('odom_px4', '/odom'),
('imu', '/imu/data')
]
),
Node(
package='rtabmap_viz',
executable='rtabmap_viz',
output='screen',
parameters=common_parameters,
remappings=[
('rgb/image', '/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/image'),
('rgb/camera_info', '/world/baylands/model/x500_depth_0/link/camera_link/sensor/IMX214/camera_info'),
('depth/image', '/depth_camera'),
('odom_px4', '/odom'),
('imu', '/imu/data')
]
),
Node(
package='rviz2',
executable='rviz2',
parameters=common_parameters,
arguments=['-d', os.path.join(
get_package_share_directory('rtabmap_rviz_plugins'), 'launch', 'rtabmap.rviz')],
output='screen'
)
])
I suggest to add namespace='rtabmap' parameter to rtabmap's nodes, so that some topics don't clash with topics already published by px4/gazebo. For example, px4 and rgbd_odometry are both publishing on same /odom topic, which can add difficulty to debug.
- Is the
odomoutput topic ofrgbd_odometrypublished? - Are there warning logs on terminal about "Not received topics since 5 seconds..."
- It is not clear who is publishing
odom->base_link, px4? or rgbd_odometry? - Who is publishing
map->odom? normally rtabmap would publish that frame. If you cannot removemapframe from TF because it is published by px4 or gazebo, you could set'odom_frame_id': 'map'with'map_frame_id': 'vslam'for rtabmap_slam node, so that you will end up with a TF tree likevslam -> map -> odom -> base_link ...
Thanks for your response.
The main issue was because of timestamps as the odom and imu topic were using real time , the GUI works after I changed them to use simulation time.
The odom->base_link is published based on px4's odometry values. Should it be published by rgbd_odometry and I should try to fuse them both ? I don't think odom->base_link was automatically published when I ran rtabmap so I added it from px4.
The map->odom is published from rtabmap.
Is odom->base_link published by px4 already "accurate enough"? Then you may use it directly and not start rgbd_odometry at all (could be a good first step for integration). Other option is to set px4 odom frame a guess_frame_id for rgbd_odometry, while setting odom_frame_id for rgbd_odometry to vo (or something different than default odom). Note that we used a slightly different approach in this example to feed back odom/localization like a GPS (or vision_pose) to PX4.
The average rate of rtabmap publishing map TF should be around 20 Hz, not 10000 Hz (which seems published by a static TF publisher somewhere), that why I was asking.
Yeah,the map TF is around 180 Hz , I guess I should manually reduce it while implementing it on hardware to reduce computational load. Just to be Clear, you mean feeding the vo from rgbd_odometry back to px4 (which handles the fusion) and leaving everything intact?
I recently ported rtabmap_drone_example to ROS2. You may give a try, ros2 instructions are here.