Re: Hesai QT128 with Zed2i and external fused Odometry
Posted by aninath93 on
URL: http://official-rtab-map-forum.206.s1.nabble.com/Hesai-QT128-with-Zed2i-and-external-fused-Odometry-tp9512p9531.html
Thank you for the reply, I appreciate you. I did go through FLOAM after your post and you are right they do not support 128 rings.
So that leaves me at least in this configuration for robustness (robot localization (wheels + imu + icp_odom) to compute for odom and RGB from Zed2i for loop closures with April tags integration. That brings me to me to this launch file and ekf parameters, does this configuration makes sense ? Or Am I still missing something ?
"" ros__parameters:
frequency: 50.0
two_d_mode: true
publish_tf: true
use_control: false
map_frame: map
odom_frame: odom
base_link_frame: base_link
world_frame: odom
transform_time_offset: 0.0
sensor_timeout: 0.1
#x , y , z,
#roll , pitch , yaw,
#vx , vy , vz,
#vroll , vpitch, vyaw,
#ax , ay , az
odom0: /odom
odom0_config: [false, false, false,
false, false, false,
true, true, false,
false, false, true,
false, false, false]
imu0: /zed2i/zed_node/imu/data
imu0_remove_gravitational_acceleration: true
imu0_queue_size: 2
imu0_config: [false, false, false,
false, false, false,
false, false, false,
false, false, true,
true, false, false]
odom1: /odom_icp
odom1_config: [true, true, false,
false, false, true,
false, false, false,
false, false, false,
false, false, false]
"""
""Launch file
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable
from launch.substitutions import LaunchConfiguration
from launch.conditions import IfCondition, UnlessCondition
from launch_ros.actions import Node
def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time')
deskewing = LaunchConfiguration('deskewing')
return LaunchDescription([
# Launch arguments
DeclareLaunchArgument(
'use_sim_time', default_value='false',
description='Use simulation (Gazebo) clock if true'),
DeclareLaunchArgument(
'deskewing', default_value='true',
description='Enable lidar deskewing'),
# Compute quaternion of the IMU
Node(
package='imu_filter_madgwick', executable='imu_filter_madgwick_node', output='screen',
parameters=[{'use_mag': False,
'world_frame':'enu',
'publish_tf':False}],
remappings=[
('imu/data_raw', '/zed2i/zed_node/imu/data')
('imu/data', '/zed2i/zed_node/imu/data/filtered')
]),
Node(
package='rtabmap_odom', executable='icp_odometry', output='screen',
parameters=[{
'frame_id':'base_link',
'odom_frame_id':'odom',
'wait_for_transform':0.2,
'expected_update_rate':15.0,
'deskewing':deskewing,
'use_sim_time':use_sim_time,
'deskewing_slerp':False,
}],
remappings=[
('scan_cloud', '/lidar_points1')
('odom','/odom_icp')
],
arguments=[
'Icp/PointToPlane', 'true',
'Icp/Iterations', '10',
'Icp/VoxelSize', '0.1',
'Icp/Epsilon', '0.001',
'Icp/PointToPlaneK', '20',
'Icp/PointToPlaneRadius', '0',
'Icp/MaxTranslation', '2',
'Icp/MaxCorrespondenceDistance', '1',
'Icp/Strategy', '1',
'Icp/OutlierRatio', '0.7',
'Icp/CorrespondenceRatio', '0.01',
'Odom/ScanKeyFrameThr', '0.4',
'OdomF2M/ScanSubtractRadius', '0.1',
'OdomF2M/ScanMaxSize', '15000',
'OdomF2M/BundleAdjustment', 'false',
]),
Node(
package='rtabmap_slam', executable='rtabmap', output='screen',
parameters=[{
'frame_id':'base_link',
'subscribe_depth':False,
'subscribe_rgb':True,
'subscribe_scan_cloud':True,
'approx_sync':True,
'wait_for_transform':0.2,
'use_sim_time':use_sim_time,
}],
remappings=[
('scan_cloud', 'assembled_cloud')
('rgb/image', '/zed2i/zed_node/rgb/image_rect_color')
('rgb/camera_info', '/zed2i/zed_node/rgb/camera_info')
('imu', '/zed2i/zed_node/imu/data/filtered')
],
arguments=[
'-d', # This will delete the previous database (~/.ros/rtabmap.db)
'RGBD/ProximityMaxGraphDepth', '0',
'RGBD/ProximityPathMaxNeighbors', '1',
'RGBD/AngularUpdate', '0.05',
'RGBD/LinearUpdate', '0.05',
'RGBD/CreateOccupancyGrid', 'false',
'Mem/NotLinkedNodesKept', 'false',
'Mem/STMSize', '30',
'Mem/LaserScanNormalK', '20',
'Reg/Strategy', '1',
'Icp/VoxelSize', '0.1',
'Icp/PointToPlaneK', '20',
'Icp/PointToPlaneRadius', '0',
'Icp/PointToPlane', 'true',
'Icp/Iterations', '10',
'Icp/Epsilon', '0.001',
'Icp/MaxTranslation', '3',
'Icp/MaxCorrespondenceDistance', '1',
'Icp/Strategy', '1',
'Icp/OutlierRatio', '0.7',
'Icp/CorrespondenceRatio', '0.2',
]),
Node(
package='rtabmap_viz', executable='rtabmap_viz', output='screen',
parameters=[{
'frame_id':'base_link',
'odom_frame_id':'odom',
'subscribe_odom_info':True,
'subscribe_scan_cloud':True,
'approx_sync':False,
'use_sim_time':use_sim_time,
}],
remappings=[
('scan_cloud', 'odom_filtered_input_scan')
]),
Node(
package='rtabmap_util', executable='point_cloud_assembler', output='screen',
parameters=[{
'max_clouds':10,
'fixed_frame_id':'',
'use_sim_time':use_sim_time,
}],
remappings=[
('cloud', 'odom_filtered_input_scan')
]),
]) ""
Do I need add anything else apart from April tags Node and tf relation for better loop closures ?
Also is there any documentation or previous references for integration with Nav2 stack and localization using AMCL side to use the map above with integration of Rtabmap ? What would your thoughts be in the environment for localization using Rtabmap vs AMCL ?
Also for 2d occupancy grid map creation do I need to subscribe to depth topic and make this to true ? ('RGBD/CreateOccupancyGrid', 'false',)
Appreciate your reply and time.
Thanks
Ani