-
Notifications
You must be signed in to change notification settings - Fork 6
/
Copy pathtzc_vector.h
69 lines (50 loc) · 992 Bytes
/
tzc_vector.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
#ifndef __TZC_VECTOR_HPP__
#define __TZC_VECTOR_HPP__
namespace tzc_transport
{
template < class T >
class vector
{
public:
vector() : size_(0), ptr_(NULL) { }
vector(const vector & v) {
*this = v;
}
~vector() { }
vector & operator = (const vector & v) {
size_ = v.size_;
ptr_ = v.ptr_;
return *this;
}
T & operator [] (size_t i) const {
return ptr_[i];
}
T * data() const {
return ptr_;
}
size_t size() const {
return size_;
}
void resize(size_t s) {
size_ = s;
}
public:
size_t size_;
T * ptr_;
}; // class vector
} // tzc_transport
namespace ros
{
namespace serialization
{
template < class V > struct Serializer< ::tzc_transport::vector < V > >
{
template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)
{
stream.next(m.size_);
}
ROS_DECLARE_ALLINONE_SERIALIZER
};
} // namespace serialization
} // namespace ros
#endif // __TZC_VECTOR_HPP__