关于ros 中msg、srv消息的md5值计算。
官方解释
http://wiki.ros.org/ROS/Technical%20Overview#Message_serialization_and_msg_MD5_sums
Message serialization and msg MD5 sums
Messages are serialized in a very compact representation that roughly corresponds to a c-struct-like serialization of the message data in little endian format. The compact representation means that two nodes communicating must agree on the layout of the message data.
Message types (msgs) in ROS are versioned using a special MD5 sum calculation of the msg text. In general, client libraries do not implement this MD5 sum calculation directly, instead storing this MD5 sum in auto-generated message source code using the output of roslib/scripts/gendeps. For reference, this MD5 sum is calculated from the MD5 text of the .msg file, where the MD5 text is the .msg text with:
comments removed
whitespace removed
package names of dependencies removed
constants reordered ahead of other declarations
In order to catch changes that occur in embedded message types, the MD5 text is concatenated with the MD5 text of each of the embedded types, in the order that they appear.
翻译
消息序列化和消息MD5 sums
消息以非常紧凑的表示形式进行序列化,该表示形式相当于以小尾 格式(little endian format)对消息数据进行 c结构体 式的序列化。紧凑表示意味着通信的两个节点必须就消息数据的布局达成一致。
ROS中的消息类型(msg)使用msg文本的特殊MD5 sum计算进行版本控制。
一般来说,客户端库不会直接实现此MD5 sum计算,
而是使用roslib/scripts/gendeps的输出,将这个MD5 sum存储在自动生成的消息源代码中。作为参考,此MD5 sum是对.msg文件的 MD5文本 进行计算得出的,其中 MD5文本 就是.msg文本,处理有:
删除注释
删除空白
删除依赖项的包名称
常量排列在其他声明之前
为了捕捉嵌入消息类型中发生的更改,MD5文本将按照它们出现的顺序与每个嵌入类型的MD5文本连接起来。
常量靠前排列举例
rosmsg show rosserial_msgs/TopicInfo
uint16 ID_PUBLISHER=0
uint16 ID_SUBSCRIBER=1
uint16 ID_SERVICE_SERVER=2
uint16 ID_SERVICE_CLIENT=4
uint16 ID_PARAMETER_REQUEST=6
uint16 ID_LOG=7
uint16 ID_TIME=10
uint16 ID_TX_STOP=11
uint16 topic_id
string topic_name
string message_type
string md5sum
int32 buffer_size
消息为空时
rosmsg md5 std_msgs/Empty
d41d8cd98f00b204e9800998ecf8427e
即
md5("")=d41d8cd98f00b204e9800998ecf8427e
如包含多个数据的消息
https://github.com/ros-drivers/rosserial/blob/melodic-devel/rosserial_arduino/msg/Adc.msg
md5(
"uint16 adc0
uint16 adc1
uint16 adc2
uint16 adc3
uint16 adc4
uint16 adc5"
)=6d7853a614e2e821319068311f2af25b
消息类型有嵌套时md5的计算
以std_msgs/MultiArrayLayout为例讲解一下
使用rosmsg show std_msgs/MultiArrayLayout命令可以快捷的得到清晰的嵌套关系
rosmsg show std_msgs/MultiArrayLayout
std_msgs/MultiArrayDimension[] dim
string label
uint32 size
uint32 stride
uint32 data_offset
它包含了MultiArrayDimension数组类型的dim 和uint32类型的data_offset
其中MultiArrayDimension的msg文件里是这样定义的
string label # label of given dimension 维度标签
uint32 size # size of given dimension (in type units)包含子维度的个数//E文怎么理解?
uint32 stride # stride of given dimension 这一维的跨度,这一维包含数据量
MultiArrayDimension的md5
md5(
"string label
uint32 size
uint32 stride"
)=4cd0c83a8683deae40ecdac60e53bfa8 暂时放着待用
我们再看std_msgs/MultiArrayLayout的定义,并解读注释
源码+我的简译标注:
# The multiarray declares a generic multi-dimensional array of a
# particular data type. Dimensions are ordered from outer most
# to inner most.
#这个多维数据布局的定义,是为了界定多维数组的数据结构而声明的
#针对特定数据类型的、通用的、多维的数组。
#维度是从最外到内的顺序(体->面->线->点)排列。
MultiArrayDimension[] dim # Array of dimension properties维度定义
uint32 data_offset # padding elements at front of data 在多维数组数据之前的 数据量。
# Accessors should ALWAYS be written in terms of dimension stride
# and specified outer-most dimension first.
# 强调顺序(体->面->线->点)排列
# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]
#算法
# A standard, 3-channel 640x480 image with interleaved color channels
# would be specified as:
#为了更好理解我们给它的标签重命名加以解释
# dim[0].label = "height"#这个名字起 image
# dim[0].size = 480#它包含480个低维度row单位,#跨度921600 个基本单位
# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)跨度是图片的大小
# dim[1].label = "width" #这个名字起row
# dim[1].size = 640 #它包含640个pix单位
# dim[1].stride = 3*640 = 1920 #跨度1920个基本单位
# dim[2].label = "channel"#这个名字起pix,包含了3个基本单位(是具体什么单位要看使用包含MultiArrayLayout消息的数据类型?待)
# dim[2].size = 3
# dim[2].stride = 3
#
# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.
这个msg文件内容除去注释是这样的。
std_msgs/MultiArrayDimension[] dim
uint32 data_offset
去掉包名、[],把MultiArrayDimension替换为那个放着待用的md5字串得到
4cd0c83a8683deae40ecdac60e53bfa8 dim
uint32 data_offset
md5(
"4cd0c83a8683deae40ecdac60e53bfa8 dim
uint32 data_offset"
)=0fed2a11c13e11c5571b4e2a995a91a3
//疑问:替换为什么把[]去掉了,消息验证是否会冲突? where is the "[]",why dont like this?
4cd0c83a8683deae40ecdac60e53bfa8[] dim
uint32 data_offset
//
命令
rosmsg md5 std_msgs/MultiArrayLayout
0fed2a11c13e11c5571b4e2a995a91a3
srv
实际上它由两个消息组成
srv分为请求消息和响应消息两部分用"---"分割
std_srvs/Empty
rossrv show std_srvs/Empty
---
request:
空字串
md5("")=d41d8cd98f00b204e9800998ecf8427e
response:
空字串
md5("")=d41d8cd98f00b204e9800998ecf8427e
srv:
rossrv md5 std_srvs/Empty
d41d8cd98f00b204e9800998ecf8427e
空字串+空字串还是空字串 也就是说request和response之间没有"\n"
说明 md5("")=d41d8cd98f00b204e9800998ecf8427e
非空srv RequestParam
https://github.com/ros-drivers/rosserial/blob/melodic-devel/rosserial_msgs/srv/RequestParam.srv
string name
---
int32[] ints
float32[] floats
string[] strings
request:
md5("string name")=c1f3d28f1b044c871e6eff2e9fc3c667
response:
md5(
"int32[] ints
float32[] floats
string[] strings"
)=9f0e98bda65981986ddf53afa7a40e49
srv:
md5(
"string nameint32[] ints
float32[] floats
string[] strings"
)=d7a0c2be00c9fd03cc69f2863de9c4d9
rossrv md5 rosserial_msgs/RequestParam
d7a0c2be00c9fd03cc69f2863de9c4d9
std_srvs/SetBool
rossrv show std_srvs/SetBool
bool data
---
bool success
string message
md5计算
request:
md5("bool data")=8b94c1b53db61fb6aed406028ad6332a
response:
md5(
"bool success
string message"
)=937c9679a518e3a18d831e57125ea522
srv:
md5(
"bool databool success
string message"
)=09fb03525b03e7ea1fd3992bafd87e16
rossrv md5 std_srvs/SetBool
09fb03525b03e7ea1fd3992bafd87e16
总结
md5计算的两个注意点,过程中 msg 消息递归处理时类型的 "[]" 被剔除了,srv中requset和response两个消息之间没有"\n",所以空srv和空msg的md5值一样。
下面是计算md5的部分源码
def compute_md5_text(msg_context, spec):
"""
Compute the text used for md5 calculation. MD5 spec states that we
removes comments and non-meaningful whitespace. We also strip
packages names from type names. For convenience sake, constants are
reordered ahead of other declarations, in the order that they were
originally defined.
:returns: text for ROS MD5-processing, ``str``
"""
package = spec.package
buff = StringIO()
#常量靠前放
for c in spec.constants:
buff.write("%s %s=%s\n"%(c.type, c.name, c.val_text))
for type_, name in zip(spec.types, spec.names):
msg_type = bare_msg_type(type_) #剔除[],只留类型名
# md5 spec strips package names
if is_builtin(msg_type):
buff.write("%s %s\n"%(type_, name))#内建类型直接写
else:
# recursively generate md5 for subtype. have to build up
# dependency representation for subtype in order to
# generate md5 递归的处理引用类型
sub_pkg, _ = names.package_resource_name(msg_type)
sub_pkg = sub_pkg or package
sub_spec = msg_context.get_registered(msg_type)
sub_md5 = compute_md5(msg_context, sub_spec)
buff.write("%s %s\n"%(sub_md5, name))
return buff.getvalue().strip() # remove trailing new line
def _compute_hash(msg_context, spec, hash):
"""
subroutine of compute_md5()
:param msg_context: :class:`MsgContext` instance to load dependencies into/from.
:param spec: :class:`MsgSpec` to compute hash for.
:param hash: hash instance
"""
# accumulate the hash
# - root file
if isinstance(spec, MsgSpec):#msg类型
hash.update(compute_md5_text(msg_context, spec).encode())
elif isinstance(spec, SrvSpec):#srv类型将request和response的内容连起来做md5(注意它们之间没有"\n")
hash.update(compute_md5_text(msg_context, spec.request).encode())
hash.update(compute_md5_text(msg_context, spec.response).encode())
else:
raise Exception("[%s] is not a message or service"%spec)
return hash.hexdigest()
def compute_md5(msg_context, spec):
"""
Compute md5 hash for message/service
:param msg_context: :class:`MsgContext` instance to load dependencies into/from.
:param spec: :class:`MsgSpec` to compute md5 for.
:returns: md5 hash, ``str``
"""
return _compute_hash(msg_context, spec, hashlib.md5())
//generator.py一窥调用
def srv_generator(msg_context, spec, search_path):
#...
#... genmsg.msg_loader.load_depends 加载解析到spec,
genmsg.msg_loader.load_depends(msg_context, spec, search_path)
md5 = genmsg.compute_md5(msg_context, spec)
yield "class %s(object):"%name
yield " _type = '%s'"%fulltype
yield " _md5sum = '%s'"%md5
yield " _request_class = %s"%req
yield " _response_class = %s"%resp
opt\ros\melodic\x64\lib\site-packages\genmsg\msg_loader.py节选
def load_msg_from_string(msg_context, text, full_name):
"""
Load message specification from a string.
NOTE: this will register the message in the *msg_context*.
:param msg_context: :class:`MsgContext` for finding loaded dependencies
:param text: .msg text , ``str``
:returns: :class:`MsgSpec` specification
:raises: :exc:`InvalidMsgSpec` If syntax errors or other problems are detected in file
"""
log("load_msg_from_string", full_name)
package_name, short_name = package_resource_name(full_name)
#解析出类型、名称,常量
types = []
names = []
constants = []
for orig_line in text.split('\n'):
clean_line = _strip_comments(orig_line)
if not clean_line:
continue #ignore empty lines
if CONSTCHAR in clean_line:
constants.append(_load_constant_line(orig_line))#填入常量
else:
field_type, name = _load_field_line(orig_line, package_name)
types.append(field_type)#填入类型、名称(id对应的)
names.append(name)
spec = MsgSpec(types, names, constants, text, full_name, package_name)#-------------生成MsgSpec类返回
msg_context.register(full_name, spec)
return spec
def load_srv_from_string(msg_context, text, full_name):
"""
Load :class:`SrvSpec` from the .srv file.
"""
text_in = StringIO()
text_out = StringIO()
accum = text_in
for l in text.split('\n'):
l = l.split(COMMENTCHAR)[0].strip() #strip comments
if l.startswith(IODELIM): #lenient, by request
accum = text_out
else:
accum.write(l+'\n')
# create separate MsgSpec objects for each half of file
msg_in = load_msg_from_string(msg_context, text_in.getvalue(), '%sRequest'%(full_name))#-----load_msg_from_string
msg_out = load_msg_from_string(msg_context, text_out.getvalue(), '%sResponse'%(full_name))
return SrvSpec(msg_in, msg_out, text, full_name)#---------------------------------由两个MsgSpec生成一个SrvSpec返回
def load_srv_from_file(msg_context, file_path, full_name):
"""
Convert the .srv representation in the file to a :class:`SrvSpec` instance.
"""
log("Load spec from %s %s\n"%(file_path, full_name))
#打开并读出文件 text
with open(file_path, 'r') as f:
text = f.read()
spec = load_srv_from_string(msg_context, text, full_name)#string转换成SrvSpec类-------load_srv_from_string
msg_context.set_file('%sRequest'%(full_name), file_path)
msg_context.set_file('%sResponse'%(full_name), file_path)
return spec