-
Notifications
You must be signed in to change notification settings - Fork 6
Expand file tree
/
Copy pathparser.py
More file actions
217 lines (174 loc) · 8.48 KB
/
parser.py
File metadata and controls
217 lines (174 loc) · 8.48 KB
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
#!/usr/bin/env python
import pprint
import rospkg
from pyparsing import *
# TODO: extract nodes, topics, services, etc from 'result'
# Compute Connections
# stateless functions
def parseActionStr(string, location, tokens):
if((len(tokens[0]) == 1) and (type(tokens[0][0]) == str)):
return tokens[0][0]
def parseActionDict(string, location, tokens):
dict_list = list()
for toks in tokens:
param_dict = dict()
for tok in toks:
param_dict[tok[0]] = tok[1]
dict_list.append(param_dict)
return dict_list
class ModelParser(object):
def __init__(self, model, isFile=True):
# OCB = Open Curly Bracket {}
# CCB = Close Curly Bracket }
# ORB = Open Round Bracket (
# CRB = Close Round Bracket )
# SQ = Single Quotes '
# OSB = Open Square Bracket [
# CSB = Close Square Bracket ]
OCB, CCB, ORB, CRB, SQ, OSB, CSB = map(Suppress, "{}()'[]")
name = Optional(SQ) + Word(printables,
excludeChars="{},'") + Optional(SQ)
real = Combine(Word(nums) + '.' + Word(nums))
listStr = Forward()
mapStr = Forward()
param_value = Forward()
sglQStr = QuotedString("'", multiline=True)
string_value = Dict(
Group(sglQStr + ZeroOrMore(OCB + param_value + CCB)))
string_value.setParseAction(parseActionStr)
values = (Combine(Optional("-") + real) | Combine(Optional("-") + Word(nums))).setParseAction(
lambda tokens: float(tokens[0])) | string_value | Keyword("false") | Keyword("true") | listStr | mapStr
_system = Keyword("RosSystem").suppress()
_name = CaselessKeyword("name").suppress()
_component = Keyword("RosComponents").suppress()
_interface = Keyword("ComponentInterface").suppress()
# Parameter Def
_parameters = Keyword("RosParameters").suppress()
_parameter = Keyword("RosParameter").suppress()
_ref_parameter = Keyword("RefParameter").suppress()
_value = Keyword("value").suppress()
# Subscriber Def
_subscribers = Keyword("RosSubscribers").suppress()
_subscriber = Keyword("RosSubscriber").suppress()
_ref_subscriber = Keyword("RefSubscriber").suppress()
# Subscriber Def
_publishers = Keyword("RosPublishers").suppress()
_publisher = Keyword("RosPublisher").suppress()
_ref_publisher = Keyword("RefPublisher").suppress()
# ServiceServers Def
_services = Keyword("RosSrvServers").suppress()
_service = Keyword("RosServiceServer").suppress()
_ref_service = Keyword("RefServer").suppress()
# ServiceClients Def
_srv_clients = Keyword("RosSrvClients").suppress()
_srv_client = Keyword("RosServiceClient").suppress()
_ref_srv_client = Keyword("RefClient").suppress()
# ActionServers Def
_action_servers = Keyword("RosActionServers").suppress()
_action_server = Keyword("RosActionServer").suppress(
) | Keyword("RosServer").suppress()
_ref_server = Keyword("RefServer").suppress() | Keyword("RefActionServer").suppress()
# Actio Clients Def
_action_clients = Keyword("RosActionClients").suppress()
_action_client = Keyword("RosActionClient").suppress(
) | Keyword("RosClient").suppress()
_ref_action_client = Keyword("RefClient").suppress() | Keyword("RefActionClient").suppress()
# Topic Connections Def
_topic_connections = Keyword("TopicConnections").suppress()
_topic_connection = Keyword("TopicConnection").suppress()
_from = Keyword("From").suppress()
_to = Keyword("To").suppress()
# global parameters Def
_g_parameters = Keyword("Parameters").suppress()
_g_parameter = Keyword("Parameter").suppress()
_type = Keyword("type").suppress()
listStr << delimitedList(Group(OCB + delimitedList(values) + CCB))
mapStr << (OSB + delimitedList(Group(OCB + delimitedList((Group(
sglQuotedString.setParseAction(removeQuotes) + Suppress(":") + values))) + CCB)) + CSB)
mapStr.setParseAction(parseActionDict)
param_value << _value + (values | listStr)
parameter = Group(_parameter + name("param_name") +
OCB + _ref_parameter + name("param_path") + param_value("param_value") + CCB)
parameters = (_parameters + OCB +
OneOrMore(parameter + Optional(",").suppress()) + CCB)
subscriber = Group(_subscriber + name("sub_name") +
OCB + _ref_subscriber + name("sub_path") + CCB)
subscribers = (_subscribers + OCB +
OneOrMore(subscriber + Optional(",").suppress()) + CCB)
publisher = Group(_publisher + name("pub_name") +
OCB + _ref_publisher + name("pub_path") + CCB)
publishers = (_publishers + OCB +
OneOrMore(publisher + Optional(",").suppress()) + CCB)
service = Group(_service + name("srv_name") +
OCB + _ref_service + name("srv_path") + CCB)
services = (_services + OCB +
OneOrMore(service + Optional(",").suppress()) + CCB)
srv_client = Group(_srv_client + name("srv_name") +
OCB + _ref_srv_client + name("srv_path") + CCB)
srv_clients = (_srv_clients + OCB +
OneOrMore(srv_client + Optional(",").suppress()) + CCB)
action_server = Group(_action_server + name("action_name") +
OCB + _ref_server + name("action_path") + CCB)
action_servers = (_action_servers + OCB +
OneOrMore(action_server + Optional(",").suppress()) + CCB)
action_client = Group(_action_client + name("action_name") +
OCB + _ref_action_client + name("action_path") + CCB)
action_clients = (_action_clients + OCB +
OneOrMore(action_client + Optional(",").suppress()) + CCB)
topic_connection = Group(_topic_connection + name("topic_name") +
OCB + _from + ORB + name("from") + CRB + _to +
ORB + name("to") + CRB + CCB)
topic_connections = (_topic_connections + OCB +
OneOrMore(topic_connection + Optional(",").suppress()) + CCB)
g_parameter = Group(_g_parameter + OCB + _name + name("param_name") +
_type + name("value_type") + param_value("param_value") + CCB)
g_parameters = (_g_parameters + OCB +
OneOrMore(g_parameter + Optional(",").suppress()) + CCB)
interface = Group(
_interface +
OCB +
_name + name("interface_name") +
Optional(parameters)("parameters") +
Optional(publishers)("publishers") +
Optional(subscribers)("subscribers") +
Optional(services)("services") +
Optional(srv_clients)("srv_clients") +
Optional(action_servers)("action_servers") +
Optional(action_clients)("action_clients") +
CCB)
self.rossystem_grammar = _system + \
OCB + \
_name + name("system_name") + \
_component + ORB + \
OneOrMore(interface + Optional(",").suppress())("interfaces") + CRB \
+ Optional(topic_connections)("topic_connections") \
+ Optional(g_parameters)("global_parameters") + CCB
self._model = model
self._isFile = isFile
def _parse_from_string(self):
self._result = self.rossystem_grammar.parseString(self._model)
def _parse_from_file(self):
self._result = self.rossystem_grammar.parseFile(self._model)
def parse(self):
self._result = ParseResults()
try:
if self._isFile:
self._parse_from_file()
else:
self._parse_from_string()
except ParseException as e:
print(ParseException.explain(e, depth=0)) # Should set a default 'result'?
return self._result
if __name__ == "__main__":
import os
rospack = rospkg.RosPack()
my_path = rospack.get_path('rosgraph_monitor')
path = os.path.join(
my_path, "resources/cob4-25.rossystem")
print(path)
parser = ModelParser(path)
try:
print(parser.parse().dump())
# print(parser.parse().interfaces[2].services)
except Exception as e:
print(e.args)