Posted by
xsasdA on
URL: http://official-rtab-map-forum.206.s1.nabble.com/How-to-improve-mapping-accuracy-based-on-ArUco-identification-code-tp8393p9266.html
Hello Mathieu,
I have some updates and follow-up-questions.
I was able to get a bag file working now and tried to apply the Marker/Priors parameter like so:
1
2
3 | <param name="Optimizer/PriorsIgnored" type="bool" value="false" />
<param name="Marker/Priors" type="string"
value="1 -3.56 1.583 0.50 0 1.5708 0|2 -1.495 1.605 4.91 0 3.14159 0" />
|
I was able to obtain a good map with loop closure. Unfortunately, the map frame didnt get transformed correctly, although marker/priors was set and markers got detected.
This is the actual output in rviz after running rtabmap node:

This is the desired output, with using parameter Marker/Priors to transform the map frame:

(the painted coordinate system with distance 0.45 to the corner of the room is the desired coordinate origin, with x facing downwards, z left and y up and the real output of the map frame is measured to be around 1.2m)
I also looked up the generated pointcloud and the graphview, if the transformation was later applied to it, but unfortunately not: The coordinate system is still the same.

Do you know why the map_frame/pointcloud does not get transformed correctly? What do I need to change?
Attachments:
node output of rtabmap:
roslaunch_output.txt (I usually can ignore the tf warning, after restarting the bag file it is most likely gone.)
roslaunch file:
roslaunch_file.txt
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95 | <launch>
<arg name="rviz" default="true" />
<param name="/use_sim_time" value="true" />
<node pkg="tf" type="static_transform_publisher" name="base_to_d435_1_tf"
args="0.375 -0.35 0.825 -0.52 0.0 3.14 /base_link /d435_1_link 200" />
<node pkg="tf" type="static_transform_publisher" name="base_to_d435_2_tf"
args="0.375 0.35 0.825 0.52 0.0 0.0 /base_link /d435_2_link 200" />
<node pkg="tf" type="static_transform_publisher" name="base_to_t265_tf"
args="0.36 0.0 0.95 0.0 0.0 0.0 /base_link /t265_link 200" />
<node pkg="tf" type="static_transform_publisher" name="base_to_d415_tf"
args="0.36 0.02 0.92 0.0 0.0 0.0 /base_link /d415_link 200" />
<node pkg="tf" type="static_transform_publisher" name="base_to_vlp16_tf"
args="0.0 0.0 1.254 1.57 0.0 0.0 /base_link /velodyne 200" />
<group ns="rtabmap">
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen"
args="--delete_db_on_start">
<remap from="rgbd_image0" to="/d435_1/rgbd_image" />
<remap from="rgbd_image1" to="/d435_2/rgbd_image" />
<remap from="odom" to="/t265/odom/sample" />
<remap from="scan_cloud" to="/velodyne_points" />
<param name="subscribe_rgb" type="bool" value="false" />
<param name="subscribe_depth" type="bool" value="false" />
<param name="subscribe_rgbd" type="bool" value="true" />
<param name="subscribe_scan_cloud" type="bool" value="true" />
<param name="odom_topic" value="/t265/odom/sample" />
<param name="scan_cloud_topic" value="/velodyne_points" />
<param name="odom_frame_id" type="string" value="t265_odom_frame" />
<param name="odom_tf_angular_variance" type="double" value="0.0005" />
<param name="odom_tf_linear_variance" type="double" value="0.0001" />
<param name="frame_id" type="string" value="base_link" />
<param name="rgbd_cameras" type="int" value="2" />
<param name="Grid/FromDepth" type="string" value="false" />
<param name="Vis/EstimationType" type="string" value="0" />
<param name="approx_sync" type="bool" value="true" />
<param name="cloud_noise_filtering_radius" value="0.05" />
<param name="cloud_noise_filtering_min_neighbors" value="2" />
<param name="Reg/Force3DoF" value="true" />
<param name="RGBD/NeighborLinkRefining" value="true" />
<param name="Reg/Strategy" value="1" />
<param name="Kp/MaxFeatures" type="string" value="10000" />
<param name="RGBD/LoopClosureReextractFeatures" type="bool" value="true" />
<param name="Optimizer/Strategy" type="string" value="1" />
<param name="Optimizer/PriorsIgnored" type="bool" value="false" />
<param name="Marker/Priors" type="string"
value="1 -3.56 1.583 0.50 0 1.5708 0|2 -1.495 1.605 4.91 0 3.14159 0" />
<param name="Icp/VoxelSize" type="string" value="0.5" />
<param name="Icp/MaxCorrespondenceDistance" type="string" value="0.1" />
</node>
</group>
<param name="robot_description" textfile="platform.urdf" />
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" />
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" />
<node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" output="screen"
args="-d mapping_2d_edited.rviz" />
<arg name="launch_prefix" default="" />
<arg name="node_namespace" default="apriltag_ros_continuous_node" />
<arg name="camera_name" default="/d415" />
<arg name="camera_frame" default="d415_link" />
<arg name="image_topic" default="/color/image_raw" />
<rosparam command="load"
file="$(find apriltag_ros)/config/settings.yaml" ns="$(arg node_namespace)" />
<rosparam command="load" file="$(find apriltag_ros)/config/tags.yaml" ns="$(arg node_namespace)" />
<node pkg="apriltag_ros" type="apriltag_ros_continuous_node" name="$(arg node_namespace)"
clear_params="true" output="screen" launch-prefix="$(arg launch_prefix)">
<remap from="image_rect" to="$(arg camera_name)/$(arg image_topic)" />
<remap from="camera_info" to="$(arg camera_name)/camera_info" />
<param name="camera_frame" type="str" value="$(arg camera_frame)" />
<param name="publish_tag_detections_image" type="bool" value="true" />
</node>
</launch>
|
rtabmap database file:
RTABMap DB File (MS OneDrive)
bag file: (Its not optimal, stopped to early on tag2, thats why it is only detected while moving and therefore introduces some error.)
Bag File (MS OneDrive) (If you are prompted to login, just navigate back to the previous site or press ALT+LEFT ARROW and it should work.)
rviz output after playing rosbag:

tf_tree:

What is also strange is that when I want to query transformations between "base_link" and "tag1" with "tf_echo" or "tf_monitor", this does not work. tf_echo outputs
Could not find a connection between 'tag1' and 'base_link' because they are not part of the same tree.Tf has two or more unconnected trees.
and tf_monitor waits forever for this tf. But this should work, because "base_link" -> "d415_link" -> ... -> "d415_color_optical_frame" -> "tag1", as you can see in the picture.
Best regards
xsasda