理解了序列化,再回到ROS。我們發現,ROS沒有采用第三方的序列化工具,而是選擇自己實現,代碼在roscpp_core項目下的roscpp_serialization中,見下圖。這個功能涉及的代碼量不是很多。
為什么ROS不使用現成的序列化工具或者庫呢?可能ROS誕生的時候(2007年),有些序列化庫可能還不存在(protobuf誕生于2008年),更有可能是ROS的創造者認為當時沒有合適的工具。
1.2.1 serialization.h
核心的函數都在serialization.h里,簡而言之,里面使用了C語言標準庫的memcpy函數把消息拷貝到流中。
下面來看一下具體的實現。
序列化功能的特點是要處理很多種數據類型,針對每種具體的類型都要實現相應的序列化函數。
為了盡量減少代碼量,ROS使用了模板的概念,所以代碼里有一堆的template。
從后往前梳理,先看Stream這個結構體吧。在C++里結構體和類基本沒什么區別,結構體里也可以定義函數。
Stream翻譯為流,流是一個計算機中的抽象概念,前面我們提到過字節流,它是什么意思呢?
在需要傳輸數據的時候,我們可以把數據想象成傳送帶上連續排列的一個個被傳送的物體,它們就是一個流。
更形象的,可以想象磁帶或者圖靈機里連續的紙帶。在文件讀寫、使用串口、網絡Socket通信等領域,流經常被使用。例如我們常用的輸入輸出流:
cout<<"helllo"; 由于使用很多,流的概念也在演變。想了解更多可以看這里。
struct Stream
{
// Returns a pointer to the current position of the stream
inline uint8_t* getData() { return data_; }
// Advances the stream, checking bounds, and returns a pointer to the position before it was advanced.
// throws StreamOverrunException if len would take this stream past the end of its buffer
ROS_FORCE_INLINE uint8_t* advance(uint32_t len)
{
uint8_t* old_data = data_;
data_ += len;
if (data_ > end_)
{
// Throwing directly here causes a significant speed hit due to the extra code generated for the throw statement
throwStreamOverrun();
}
return old_data;
}
// Returns the amount of space left in the stream
inline uint32_t getLength() { return static_cast< uint32_t >(end_ - data_); }
protected:
Stream(uint8_t* _data, uint32_t _count) : data_(_data), end_(_data + _count) {}
private:
uint8_t* data_;
uint8_t* end_;
};
注釋表明Stream是個基類,輸入輸出流IStream和OStream都繼承自它。
Stream的成員變量data_是個指針,指向序列化的字節流開始的位置,它的類型是uint8_t。
在Ubuntu系統中,uint8_t的定義是typedef unsigned char uint8_t;
所以uint8_t就是一個字節,可以用size_of()函數檢驗。data_指向的空間就是保存字節流的。
輸出流類OStream用來序列化一個對象,它引用了serialize函數,如下。
struct OStream : public Stream
{
static const StreamType stream_type = stream_types::Output;
OStream(uint8_t* data, uint32_t count) : Stream(data, count) {}
/* Serialize an item to this output stream*/
template< typename T >
ROS_FORCE_INLINE void next(const T& t)
{
serialize(*this, t);
}
template< typename T >
ROS_FORCE_INLINE OStream& operator< (const T& t)
{
serialize(*this, t);
return *this;
}
};
輸入流類IStream用來反序列化一個字節流,它引用了deserialize函數,如下。
struct ROSCPP_SERIALIZATION_DECL IStream : public Stream
{
static const StreamType stream_type = stream_types::Input;
IStream(uint8_t* data, uint32_t count) : Stream(data, count) {}
/* Deserialize an item from this input stream */
template< typename T >
ROS_FORCE_INLINE void next(T& t)
{
deserialize(*this, t);
}
template< typename T >
ROS_FORCE_INLINE IStream& operator >>(T& t)
{
deserialize(*this, t);
return *this;
}
};
自然,serialize函數和deserialize函數就是改變數據形式的地方,它們的定義在比較靠前的地方。它們都接收兩個模板,都是內聯函數,然后里面沒什么東西,只是又調用了Serializer類的成員函數write和read。所以,serialize和deserialize函數就是個二道販子。
// Serialize an object. Stream here should normally be a ros::serialization::OStream
template< typename T, typename Stream >
inline void serialize(Stream& stream, const T& t)
{
Serializer< T >::write(stream, t);
}
// Deserialize an object. Stream here should normally be a ros::serialization::IStream
template< typename T, typename Stream >
inline void deserialize(Stream& stream, T& t)
{
Serializer< T >::read(stream, t);
}
所以,我們來分析Serializer類,如下。我們發現,write和read函數又調用了類型里的serialize函數和deserialize函數。
頭別暈,這里的serialize和deserialize函數跟上面的同名函數不是一回事。
注釋中說:“Specializing the Serializer class is the only thing you need to do to get the ROS serialization system to work with a type”(要想讓ROS的序列化功能適用于其它的某個類型,你唯一需要做的就是特化這個Serializer類)。
這就涉及到的另一個知識點——模板特化(template specialization)。
template< typename T > struct Serializer
{
// Write an object to the stream. Normally the stream passed in here will be a ros::serialization::OStream
template< typename Stream >
inline static void write(Stream& stream, typename boost::call_traits< T >::param_type t)
{
t.serialize(stream.getData(), 0);
}
// Read an object from the stream. Normally the stream passed in here will be a ros::serialization::IStream
template< typename Stream >
inline static void read(Stream& stream, typename boost::call_traits< T >::reference t)
{
t.deserialize(stream.getData());
}
// Determine the serialized length of an object.
inline static uint32_t serializedLength(typename boost::call_traits< T >::param_type t)
{
return t.serializationLength();
}
};
接著又定義了一個帶參數的宏函數ROS_CREATE_SIMPLE_SERIALIZER(Type),然后把這個宏作用到了ROS中的10種基本數據類型,分別是:uint8_t, int8_t, uint16_t, int16_t, uint32_t, int32_t, uint64_t, int64_t, float, double。
說明這10種數據類型的處理方式都是類似的??吹竭@里大家應該明白了,write和read函數都使用了memcpy函數進行數據的移動。
注意宏定義中的template<>語句,這正是模板特化的標志,關鍵詞template后面跟一對尖括號。
關于模板特化可以看這里。
#define ROS_CREATE_SIMPLE_SERIALIZER(Type)
template< > struct Serializer Type >
{
template< typename Stream > inline static void write(Stream& stream, const Type v)
{
memcpy(stream.advance(sizeof(v)), &v, sizeof(v) );
}
template< typename Stream > inline static void read(Stream& stream, Type& v)
{
memcpy(&v, stream.advance(sizeof(v)), sizeof(v) );
}
inline static uint32_t serializedLength(const Type&)
{
return sizeof(Type);
}
};
ROS_CREATE_SIMPLE_SERIALIZER(uint8_t)
ROS_CREATE_SIMPLE_SERIALIZER(int8_t)
ROS_CREATE_SIMPLE_SERIALIZER(uint16_t)
ROS_CREATE_SIMPLE_SERIALIZER(int16_t)
ROS_CREATE_SIMPLE_SERIALIZER(uint32_t)
ROS_CREATE_SIMPLE_SERIALIZER(int32_t)
ROS_CREATE_SIMPLE_SERIALIZER(uint64_t)
ROS_CREATE_SIMPLE_SERIALIZER(int64_t)
ROS_CREATE_SIMPLE_SERIALIZER(float)
ROS_CREATE_SIMPLE_SERIALIZER(double)
對于其它類型的數據,例如bool、std::string、std::vector、ros::Time、ros::Duration、boost::array等等,它們各自的處理方式有細微的不同,所以不再用上面的宏函數,而是用模板特化的方式每種單獨定義,這也是為什么serialization.h這個文件這么冗長。
對于int、double這種單個元素的數據,直接用上面特化的Serializer類中的memcpy函數實現序列化。
對于vector、array這種多個元素的數據類型怎么辦呢?方法是分成幾種情況,對于固定長度簡單類型的(fixed-size simple types),還是用各自特化的Serializer類中的memcpy函數實現,沒啥太大區別。
對于固定但是類型不簡單的(fixed-size non-simple types)或者既不固定也不簡單的(non-fixed-size, non-simple types)或者固定但是不簡單的(fixed-size, non-simple types),用for循環遍歷,一個元素一個元素的單獨處理。
那怎么判斷一個數據是不是固定是不是簡單呢?這是在roscpp_traits文件夾中的message_traits.h完成的。
其中采用了萃取Type Traits,這是相對高級一點的編程技巧了,筆者也不太懂。
對序列化的介紹暫時就到這里了,有一些細節還沒講,等筆者看懂了再補。
-
機器人
+關注
關注
211文章
28390瀏覽量
206949 -
操作系統
+關注
關注
37文章
6808瀏覽量
123291 -
函數
+關注
關注
3文章
4329瀏覽量
62575 -
ROS
+關注
關注
1文章
278瀏覽量
17004
發布評論請先 登錄
相關推薦
評論