landmark是路标点,apriltag、二维码等强特征,static landmark 的作用是用于快速定位的。
对landmark的观测是相对于Cartographer的tracking frame
,用户负责发布话题landmark
,类型cartographer_ros_msgs/LandmarkList
. cartographer订阅landmark
之后,会发布话题/landmark_poses_list
,类型visualization_msgs/MarkerArray
,在rviz上显示出来,用于确认cartographer计算出landmark在map坐标系中的坐标。 Cartographer负责建立landmark的约束,与栅格地图一起优化。
机器人应当一直运动以产生trajectory优化,如果机器人不动,无法触发优化,landmark无法加入图优化框架。landmark的观测应当是相对于 tracking frame
Try the following to see an impressive effect (only for testing):
假如进行以下步骤:
- 将 landmark 的权重设置的很大,比如 1e8
- 观测一个id为0的 landmark
- 把机器人开到另一个地方
- 又一个id为0的 landmark
第二次观测显然是错误的,但是由于landmark的极高权重, 机器人位姿会跳跃
lua 设置
设置 use_landmarks = true
,话题landmark
应具备一定频率,默认要求最低10Hz。话题的消息可以是空的,但必须提供,因为Cartographer严格给传感器数据按时间排序,使landmarks deterministic
. 但是也可以设置TRAJECTORY_BUILDER.collate_landmarks = false
,这样landmark就是non-deterministic
而且是非阻塞的。GPS也是同理。
landmarks_sampling_ratio = 1
landmark观测的权重比,当某个观测不太靠谱的时候,可以把1改为较小的权重,例如0.5,从而减小对整体优化的错误影响。
如果只获得landmark的相对位置,没有朝向,那就把landmark rotation weight设置为0
每个landmark的ID和坐标应当是unique而且是一一对应 |
源码
要知道tag在相机坐标系的位置,相机坐标系和base_link
之间的关系1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19void Node::HandleLandmarkMessage(
const int trajectory_id, const std::string& sensor_id,
const cartographer_ros_msgs::LandmarkList::ConstPtr& msg)
{
absl::MutexLock lock(&mutex_);
if (!sensor_samplers_.at(trajectory_id).landmark_sampler.Pulse())
return;
map_builder_bridge_.sensor_bridge(trajectory_id)->HandleLandmarkMessage(sensor_id, msg);
// 添加下面代码
geometry_msgs::TransformStamped stamped_transform;
stamped_transform.header.stamp = ros::Time::now();
stamped_transform.header.frame_id = "base_link";
stamped_transform.child_frame_id = "QR_Code";
stamped_transform.transform = ToGeometryMsgTransform(ToRigid3d(msg->landmarks[0].tracking_from_landmark_transform).inverse() );
tf_broadcaster_.sendTransform(stamped_transform);
}
1 | void Node::PublishLandmarkPosesList( |
publish_fake_random_landmarks.py
Cartographer提供这个文件发布假的landmark,不用仔细研究内容。 节点landmark_sampler
,发布话题landmark
,类型cartographer_ros_msgs/LandmarkList
。
这个节点不是一直发布landmark,有的消息是空的1
2
3
4
5
6
7header:
seq: 546
stamp:
secs: 1650511353
nsecs: 89869022
frame_id: ''
landmarks: []
有内容的消息是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
77header:
seq: 129
stamp:
secs: 1650511071
nsecs: 393965959
frame_id: ''
landmarks:
-
id: "112b2"
tracking_from_landmark_transform:
position:
x: 0.329674929632
y: 0.601299422592
z: 0.0813299308386
orientation:
x: -0.881422944417
y: 0.388576528204
z: -0.260058416952
w: 0.0668692347593
translation_weight: 100000.0
rotation_weight: 100000.0
-
id: "32c2b"
tracking_from_landmark_transform:
position:
x: 0.747269396167
y: 0.256305093347
z: 0.389155962116
orientation:
x: -0.349830783746
y: -0.891493805837
z: -0.163724271997
w: -0.236752148157
translation_weight: 100000.0
rotation_weight: 100000.0
-
id: "2c33a"
tracking_from_landmark_transform:
position:
x: 0.698094719569
y: 0.886938424567
z: 0.408522616781
orientation:
x: -0.242061311724
y: 0.292763269814
z: 0.419295012755
w: 0.824553019213
translation_weight: 100000.0
rotation_weight: 100000.0
-
id: "c3b1c"
tracking_from_landmark_transform:
position:
x: 0.703663491421
y: 0.146106286628
z: 0.589856404568
orientation:
x: -0.0750314150542
y: -0.80116295871
z: 0.151662985651
w: 0.574026601412
translation_weight: 100000.0
rotation_weight: 100000.0
-
id: "c12aa"
tracking_from_landmark_transform:
position:
x: 0.409531720117
y: 0.286439128213
z: 0.686302598836
orientation:
x: -0.326127457574
y: -0.221216268782
z: -0.89427654661
w: -0.212070040376
translation_weight: 100000.0
rotation_weight: 100000.0
参考:
Understanding the Landmark Observation Concept
Cartographer源码阅读——带Landmark的demo运行和测试