Apollo Cyber Study (cyber/base 1)

我挺懷疑baidu的人在寫memory order的時侯, 是不是真的考慮清楚的

// Study : 後邊是研究記錄

cyber/base/macros.h

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
/******************************************************************************
* Copyright 2018 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/

#ifndef CYBER_BASE_MACROS_H_
#define CYBER_BASE_MACROS_H_

#include <cstdlib>
#include <new>

// Study: __builtin_expect is a function to let the compiler know the chance of the condition to be true
// , the compiler can do optimization in assembly level using this information
#if __GNUC__ >= 3
#define likely(x) (__builtin_expect((x), 1))
#define unlikely(x) (__builtin_expect((x), 0))
#else
#define likely(x) (x)
#define unlikely(x) (x)
#endif

// Study: The size of cache line, cache line is the a block that will be fetch from memory to cache
#define CACHELINE_SIZE 64

// Study: Meta-programming, used SFINTE. When the T type have the `func` function, it will be true,
// Otherwise it is false (since size of int is not 1)
// basically used to determine the exist of the func for T in compile time
// Can be mixed with the stl traits
#define DEFINE_TYPE_TRAIT(name, func) \
template <typename T> \
class name { \
private: \
template <typename Class> \
static char Test(decltype(&Class::func)*); \
template <typename> \
static int Test(...); \
\
public: \
static constexpr bool value = sizeof(Test<T>(nullptr)) == 1; \
}; \
\
template <typename T> \
constexpr bool name<T>::value;

// Study: Call the processer to pause (no operation)
// The different of rep;nop; to nop;nop; is that processor can optimize with this
inline void cpu_relax() { asm volatile("rep; nop" ::: "memory"); }

// Study: Allocate memory
inline void* CheckedMalloc(size_t size) {
void* ptr = std::malloc(size);
if (!ptr) {
throw std::bad_alloc();
}
return ptr;
}

// Study: Allocate memory and Clean location
inline void* CheckedCalloc(size_t num, size_t size) {
void* ptr = std::calloc(num, size);
if (!ptr) {
throw std::bad_alloc();
}
return ptr;
}

#endif // CYBER_BASE_MACROS_H_

cyber/base/atomic_fifo.h

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
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
/******************************************************************************
* Copyright 2018 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/

#ifndef CYBER_BASE_ATOMIC_FIFO_H_
#define CYBER_BASE_ATOMIC_FIFO_H_

#include <atomic>
#include <cstdlib>
#include <cstring>
#include <iostream>

#include "cyber/base/macros.h"

namespace apollo {
namespace cyber {

template <typename T>
class AtomicFIFO {
private:
struct Node {
T value;
};

public:
// Study: Singleton
static AtomicFIFO *GetInstance(int cap = 100) {
static AtomicFIFO *inst = new AtomicFIFO(cap);
return inst;
}

bool Push(const T &value);
bool Pop(T *value);
// insert();

private:
Node *node_arena_;
// Study: Align to maximize the memory access speed
alignas(CACHELINE_SIZE) std::atomic<uint32_t> head_;
alignas(CACHELINE_SIZE) std::atomic<uint32_t> commit_;
alignas(CACHELINE_SIZE) std::atomic<uint32_t> tail_;
int capacity_;

// Study: Only allow Singleton
explicit AtomicFIFO(int cap);
~AtomicFIFO();
AtomicFIFO(AtomicFIFO &) = delete;
AtomicFIFO &operator=(AtomicFIFO &) = delete;
};

template <typename T>
AtomicFIFO<T>::AtomicFIFO(int cap) : capacity_(cap) {
node_arena_ = static_cast<Node *>(malloc(capacity_ * sizeof(Node)));
memset(node_arena_, 0, capacity_ * sizeof(Node));

// Study: Set value to 0
head_.store(0, std::memory_order_relaxed);
tail_.store(0, std::memory_order_relaxed);
commit_.store(0, std::memory_order_relaxed);
}

template <typename T>
AtomicFIFO<T>::~AtomicFIFO() {
if (node_arena_ != nullptr) {
for (int i = 0; i < capacity_; i++) {
// Study: Call the T destructor manaully, since it is puted in the malloc region, it will not auto destruct
node_arena_[i].value.~T();
}
free(node_arena_);
}
}

template <typename T>
bool AtomicFIFO<T>::Push(const T &value) {
uint32_t oldt, newt;

// Study: Try push until success, return false if queue full
oldt = tail_.load(std::memory_order_acquire);
do {
uint32_t h = head_.load(std::memory_order_acquire);
uint32_t t = tail_.load(std::memory_order_acquire);

if (((t + 1) % capacity_) == h) return false;

newt = (oldt + 1) % capacity_;
// Study: If success, set tail_ to newt, otherwise set oldt to current tail_
// Ensure tails value sync
} while (!tail_.compare_exchange_weak(oldt, newt, std::memory_order_acq_rel,
std::memory_order_acquire));

(node_arena_ + oldt)->value = value;

// Study: commit_ is basically same as tail_, but it is used in pop.
// It can let the pop operation not block the push core part
while (unlikely(commit_.load(std::memory_order_acquire) != oldt)) cpu_relax();

// Study: After commit, this value can be pop in Pop()
commit_.store(newt, std::memory_order_release);

return true;
}

template <typename T>
bool AtomicFIFO<T>::Pop(T *value) {
uint32_t oldh, newh;

oldh = head_.load(std::memory_order_acquire);

// Study: Basically same logic as the push part, try pop until success. Return false if no element
do {
uint32_t h = head_.load(std::memory_order_acquire);
uint32_t c = commit_.load(std::memory_order_acquire);

if (h == c) return false;

newh = (oldh + 1) % capacity_;

*value = (node_arena_ + oldh)->value;
} while (!head_.compare_exchange_weak(oldh, newh, std::memory_order_acq_rel,
std::memory_order_acquire));

return true;
}

} // namespace cyber
} // namespace apollo

#endif // CYBER_BASE_ATOMIC_FIFO_H_

cyber/base/for_each.h

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
/******************************************************************************
* Copyright 2018 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/

#ifndef CYBER_BASE_FOR_EACH_H_
#define CYBER_BASE_FOR_EACH_H_

#include <type_traits>

#include "cyber/base/macros.h"

namespace apollo {
namespace cyber {
namespace base {

// Study: A trait to check whether the class have impl operator <
DEFINE_TYPE_TRAIT(HasLess, operator<) // NOLINT

// Study: If both of them have impl <, use it
template <class Value, class End>
typename std::enable_if<HasLess<Value>::value && HasLess<End>::value,
bool>::type
LessThan(const Value& val, const End& end) {
return val < end;
}

// Study: Otherwise, check equality.....
// Actually, I thing this function name is misleading. This will only make sense when using in FOR_EACH
template <class Value, class End>
typename std::enable_if<!HasLess<Value>::value || !HasLess<End>::value,
bool>::type
LessThan(const Value& val, const End& end) {
return val != end;
}

// Study: Loop until end, Be careful that i should not be a index, it should be a iterator or something similiar
#define FOR_EACH(i, begin, end) \
for (auto i = (true ? (begin) : (end)); \
apollo::cyber::base::LessThan(i, (end)); ++i)

} // namespace base
} // namespace cyber
} // namespace apollo

#endif // CYBER_BASE_FOR_EACH_H_

cyber/base/wait_strategy

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
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
/******************************************************************************
* Copyright 2018 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/

#ifndef CYBER_BASE_WAIT_STRATEGY_H_
#define CYBER_BASE_WAIT_STRATEGY_H_

#include <chrono>
#include <condition_variable>
#include <cstdlib>
#include <mutex>
#include <thread>

namespace apollo {
namespace cyber {
namespace base {

class WaitStrategy {
public:
// Study: One waiter is allow to pass
virtual void NotifyOne() {}
// Study: All waiter is allow to pass
virtual void BreakAllWait() {}
// Study: Wait here
virtual bool EmptyWait() = 0;
virtual ~WaitStrategy() {}
};

// Study: Blocked until allow to pass
class BlockWaitStrategy : public WaitStrategy {
public:
BlockWaitStrategy() {}
void NotifyOne() override { cv_.notify_one(); }

bool EmptyWait() override {
std::unique_lock<std::mutex> lock(mutex_);
cv_.wait(lock);
return true;
}

void BreakAllWait() { cv_.notify_all(); }

private:
std::mutex mutex_;
std::condition_variable cv_;
};


// Study: Sleeped and pass after the sleep time
class SleepWaitStrategy : public WaitStrategy {
public:
SleepWaitStrategy() {}
explicit SleepWaitStrategy(uint64_t sleep_time_us)
: sleep_time_us_(sleep_time_us) {}

bool EmptyWait() override {
std::this_thread::sleep_for(std::chrono::microseconds(sleep_time_us_));
return true;
}

void SetSleepTimeMicroSecends(uint64_t sleep_time_us) {
sleep_time_us_ = sleep_time_us;
}

private:
uint64_t sleep_time_us_ = 10000;
};

// Study: Reschedule this thread, let other thread use first
class YieldWaitStrategy : public WaitStrategy {
public:
YieldWaitStrategy() {}
bool EmptyWait() override {
std::this_thread::yield();
return true;
}
};

// Study: Just pass??????
class BusySpinWaitStrategy : public WaitStrategy {
public:
BusySpinWaitStrategy() {}
bool EmptyWait() override { return true; }
};

// Study: Like BlockWaitStrategy, but have a time limit. Return false if timeout
class TimeoutBlockWaitStrategy : public WaitStrategy {
public:
TimeoutBlockWaitStrategy() {}
explicit TimeoutBlockWaitStrategy(uint64_t timeout)
: time_out_(std::chrono::milliseconds(timeout)) {}

void NotifyOne() override { cv_.notify_one(); }

bool EmptyWait() override {
std::unique_lock<std::mutex> lock(mutex_);
if (cv_.wait_for(lock, time_out_) == std::cv_status::timeout) {
return false;
}
return true;
}

void BreakAllWait() { cv_.notify_all(); }

void SetTimeout(uint64_t timeout) {
time_out_ = std::chrono::milliseconds(timeout);
}

private:
std::mutex mutex_;
std::condition_variable cv_;
std::chrono::milliseconds time_out_;
};

} // namespace base
} // namespace cyber
} // namespace apollo

#endif // CYBER_BASE_WAIT_STRATEGY_H_

cyber/base/atomic_hash_map.h

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
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
/******************************************************************************
* Copyright 2018 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/

#ifndef CYBER_BASE_ATOMIC_HASH_MAP_H_
#define CYBER_BASE_ATOMIC_HASH_MAP_H_

#include <stdint.h>
#include <atomic>
#include <type_traits>
#include <utility>

namespace apollo {
namespace cyber {
namespace base {

// Study: TableSize must be power of 2
/**
* @brief A implementation of lock-free fixed size hash map
*
* @tparam K Type of key, must be integral
* @tparam V Type of value
* @tparam 128 Size of hash table
* @tparam 0 Type traits, use for checking types of key & value
*/
template <typename K, typename V, std::size_t TableSize = 128,
typename std::enable_if<std::is_integral<K>::value &&
(TableSize & (TableSize - 1)) == 0,
int>::type = 0>
class AtomicHashMap {
public:
AtomicHashMap() : capacity_(TableSize), mode_num_(capacity_ - 1) {}
AtomicHashMap(const AtomicHashMap &other) = delete;
AtomicHashMap &operator=(const AtomicHashMap &other) = delete;

// Study: Just get the key, and perform like a regular hash map
// The atomic part is in Bucket and Entry
// It DOESN'T provide a hash function,
// so the user must be careful with the key selection
bool Has(K key) {
uint64_t index = key & mode_num_;
return table_[index].Has(key);
}

bool Get(K key, V **value) {
uint64_t index = key & mode_num_;
return table_[index].Get(key, value);
}

bool Get(K key, V *value) {
uint64_t index = key & mode_num_;
V *val = nullptr;
bool res = table_[index].Get(key, &val);
if (res) {
*value = *val;
}
return res;
}

void Set(K key) {
uint64_t index = key & mode_num_;
table_[index].Insert(key);
}

void Set(K key, const V &value) {
uint64_t index = key & mode_num_;
table_[index].Insert(key, value);
}

// Study: Support right value passing
void Set(K key, V &&value) {
uint64_t index = key & mode_num_;
table_[index].Insert(key, std::forward<V>(value));
}

private:
// Study: The nodes in Bucket, actually same as a regular Node.
// Just used atomic for value and next
struct Entry {
Entry() {}
explicit Entry(K key) : key(key) {
value_ptr.store(new V(), std::memory_order_release);
}
Entry(K key, const V &value) : key(key) {
value_ptr.store(new V(value), std::memory_order_release);
}
Entry(K key, V &&value) : key(key) {
value_ptr.store(new V(std::forward<V>(value)), std::memory_order_release);
}
~Entry() { delete value_ptr.load(std::memory_order_acquire); }

K key = 0;
std::atomic<V *> value_ptr = {nullptr};
std::atomic<Entry *> next = {nullptr};
};

// Study: The real place for storing all value for ONE key
// It is a linked list inside
// Moreover, the atomic is promised here and Entry
class Bucket {
public:
Bucket() : head_(new Entry()) {}
~Bucket() {
Entry *ite = head_;
while (ite) {
auto tmp = ite->next.load(std::memory_order_acquire);
delete ite;
ite = tmp;
}
}

// Study: Too simple, don't explain
bool Has(K key) {
Entry *m_target = head_->next.load(std::memory_order_acquire);
while (Entry *target = m_target) {
if (target->key < key) {
m_target = target->next.load(std::memory_order_acquire);
continue;
} else {
return target->key == key;
}
}
return false;
}

// Study: Loop and return the ptr to the key element
bool Find(K key, Entry **prev_ptr, Entry **target_ptr) {
Entry *prev = head_;
Entry *m_target = head_->next.load(std::memory_order_acquire);
while (Entry *target = m_target) {
if (target->key == key) {
*prev_ptr = prev;
*target_ptr = target;
return true;
} else if (target->key > key) {
*prev_ptr = prev;
*target_ptr = target;
return false;
} else {
prev = target;
m_target = target->next.load(std::memory_order_acquire);
}
}
*prev_ptr = prev;
*target_ptr = nullptr;
return false;
}

// Study: Keep insert until success
void Insert(K key, const V &value) {
Entry *prev = nullptr;
Entry *target = nullptr;
Entry *new_entry = new Entry(key, value);
V *new_value = new V(value);
while (true) {
if (Find(key, &prev, &target)) {
// key exists, update value
auto old_val_ptr = target->value_ptr.load(std::memory_order_acquire);
if (target->value_ptr.compare_exchange_strong(
old_val_ptr, new_value, std::memory_order_acq_rel,
std::memory_order_relaxed)) {
delete new_entry;
return;
}
continue;
} else {
new_entry->next.store(target, std::memory_order_release);
if (prev->next.compare_exchange_strong(target, new_entry,
std::memory_order_acq_rel,
std::memory_order_relaxed)) {
// Insert success
delete new_value;
return;
}
// another entry has been inserted, retry
}
}
}

// Study: Same as above. All the below code is also simple so no explain
void Insert(K key, V &&value) {
Entry *prev = nullptr;
Entry *target = nullptr;
Entry *new_entry = new Entry(key, value);
auto new_value = new V(std::forward<V>(value));
while (true) {
if (Find(key, &prev, &target)) {
// key exists, update value
auto old_val_ptr = target->value_ptr.load(std::memory_order_acquire);
if (target->value_ptr.compare_exchange_strong(
old_val_ptr, new_value, std::memory_order_acq_rel,
std::memory_order_relaxed)) {
delete new_entry;
return;
}
continue;
} else {
new_entry->next.store(target, std::memory_order_release);
if (prev->next.compare_exchange_strong(target, new_entry,
std::memory_order_acq_rel,
std::memory_order_relaxed)) {
// Insert success
delete new_value;
return;
}
// another entry has been inserted, retry
}
}
}

void Insert(K key) {
Entry *prev = nullptr;
Entry *target = nullptr;
Entry *new_entry = new Entry(key);
auto new_value = new V();
while (true) {
if (Find(key, &prev, &target)) {
// key exists, update value
auto old_val_ptr = target->value_ptr.load(std::memory_order_acquire);
if (target->value_ptr.compare_exchange_strong(
old_val_ptr, new_value, std::memory_order_acq_rel,
std::memory_order_relaxed)) {
delete new_entry;
return;
}
continue;
} else {
new_entry->next.store(target, std::memory_order_release);
if (prev->next.compare_exchange_strong(target, new_entry,
std::memory_order_acq_rel,
std::memory_order_relaxed)) {
// Insert success
delete new_value;
return;
}
// another entry has been inserted, retry
}
}
}

bool Get(K key, V **value) {
Entry *prev = nullptr;
Entry *target = nullptr;
if (Find(key, &prev, &target)) {
*value = target->value_ptr.load(std::memory_order_acquire);
return true;
}
return false;
}

Entry *head_;
};

private:
Bucket table_[TableSize];
uint64_t capacity_;
uint64_t mode_num_;
};

} // namespace base
} // namespace cyber
} // namespace apollo

#endif // CYBER_BASE_ATOMIC_HASH_MAP_H_