TAMSVIZ
Visualization and annotation tool for ROS
mparser.cpp
1 // TAMSVIZ
2 // (c) 2020 Philipp Ruppel
3 
4 #include "mparser.h"
5 
6 #include <mutex>
7 #include <regex>
8 
9 std::shared_ptr<MessageParser::Node>
10 MessageParser::findType(const std::string &name, const std::string &ns) {
11  {
12  auto it = _data->type_map.find(name);
13  if (it != _data->type_map.end()) {
14  return it->second;
15  }
16  }
17  if (name == "Header") {
18  return findType("std_msgs/Header");
19  }
20  if (!ns.empty()) {
21  return findType(ns + "/" + name);
22  }
23  throw std::runtime_error("Unknown message type: " + name);
24 }
25 
26 void MessageParser::parseDefinition(
27  const std::shared_ptr<const MessageType> &type) {
28 
29  PROFILER("MessageParser::parseDefinition");
30 
31  if (_node && _node->hash == type->hash()) {
32  return;
33  }
34 
35  static std::mutex cache_mutex;
36  static std::unordered_map<std::string, std::shared_ptr<Node>> cache_map;
37 
38  {
39  std::lock_guard<std::mutex> lock(cache_mutex);
40  auto it = cache_map.find(type->hash());
41  if (it != cache_map.end()) {
42  _node = it->second;
43  return;
44  }
45  }
46 
47  LOG_INFO("parsing message description " << type->name() << " "
48  << type->hash());
49 
50  std::vector<std::function<void()>> linker_jobs;
51 
52  registerPrimitiveType<uint8_t>("bool");
53  registerPrimitiveType<int8_t>("byte");
54  registerPrimitiveType<uint8_t>("char");
55  registerPrimitiveType<int8_t>("int8");
56  registerPrimitiveType<uint8_t>("uint8");
57  registerPrimitiveType<int16_t>("int16");
58  registerPrimitiveType<uint16_t>("uint16");
59  registerPrimitiveType<int32_t>("int32");
60  registerPrimitiveType<uint32_t>("uint32");
61  registerPrimitiveType<int64_t>("int64");
62  registerPrimitiveType<uint64_t>("uint64");
63  registerPrimitiveType<float>("float32");
64  registerPrimitiveType<double>("float64");
65  registerType<TimeNode>("time");
66  registerType<DurationNode>("duration");
67  registerType<StringNode>("string");
68 
69  std::string multi_definition =
70  "MSG: " + type->name() + "\n" + type->definition();
71 
72  static std::regex message_seperator("\\n\\s*========+\\s*",
73  std::regex_constants::optimize);
74  std::vector<std::string> message_definitions(
75  std::sregex_token_iterator(multi_definition.begin(),
76  multi_definition.end(), message_seperator, -1),
77  std::sregex_token_iterator());
78 
79  std::shared_ptr<MessageNode> root_node;
80 
81  for (auto &message_type_and_definition : message_definitions) {
82 
83  static std::regex message_type_and_definition_regex(
84  "\\s*MSG:\\s*(\\S+)\\s*\\n([\\s\\S]*)");
85  std::smatch message_type_and_definition_match;
86  if (!std::regex_match(message_type_and_definition,
87  message_type_and_definition_match,
88  message_type_and_definition_regex)) {
89  throw std::runtime_error("Message definition format error");
90  }
91  std::string message_type_name = message_type_and_definition_match[1];
92  std::string message_definition = message_type_and_definition_match[2];
93 
94  // LOG_DEBUG(message_type_name);
95 
96  auto message_node = std::make_shared<MessageNode>();
97  registerType(message_type_name, message_node);
98 
99  if (!root_node) {
100  root_node = message_node;
101  }
102 
103  std::string message_namespace;
104  {
105  auto end = message_node->name.find('/');
106  if (end != std::string::npos) {
107  message_namespace = message_node->name.substr(0, end);
108  }
109  }
110 
111  std::string line;
112  std::stringstream message_definition_stream(message_definition);
113  while (std::getline(message_definition_stream, line)) {
114 
115  for (size_t i = 0; i < line.size(); i++) {
116  if (line[i] == '#') {
117  line.resize(i);
118  break;
119  }
120  }
121 
122  std::smatch match;
123 
124  {
125  static std::regex regex("\\s*", std::regex_constants::optimize);
126  if (std::regex_match(line, match, regex)) {
127  continue;
128  }
129  }
130 
131  {
132  static std::regex regex("\\s*(\\S+)\\s+([^\\s=]+)\\s*\\=\\s*(.*)",
133  std::regex_constants::optimize);
134  if (std::regex_match(line, match, regex)) {
135 
136  auto const_node = std::make_shared<ConstNode>();
137 
138  const_node->type_name = match[1];
139  const_node->name = match[2];
140  const_node->value_string = match[3];
141 
142  message_node->const_map[const_node->name] =
143  message_node->const_nodes.size();
144  message_node->const_nodes.push_back(const_node);
145 
146  continue;
147  }
148  }
149 
150  {
151  static std::regex regex(
152  "\\s*([^\\s\\[]+)\\s*(\\[([^\\]]*)\\])?\\s+(\\S+)\\s*",
153  std::regex_constants::optimize);
154  if (std::regex_match(line, match, regex)) {
155 
156  std::string field_name = match[4];
157  std::string type_name = match[1];
158  size_t field_index = message_node->field_nodes.size();
159 
160  message_node->field_map[field_name] = field_index;
161  message_node->field_names.push_back(field_name);
162 
163  if (match[2].str().empty()) {
164  linker_jobs.emplace_back([this, message_node, field_index,
165  type_name, message_namespace]() {
166  message_node->field_nodes[field_index] =
167  findType(type_name, message_namespace);
168  });
169  message_node->field_nodes.push_back(nullptr);
170  } else {
171  auto array_node = std::make_shared<ArrayNode>();
172  if (!match[3].str().empty()) {
173  array_node->has_fixed_element_count = true;
174  array_node->fixed_element_count = std::stoull(match[3]);
175  }
176  linker_jobs.emplace_back([this, type_name, array_node,
177  message_namespace]() {
178  array_node->element_node = findType(type_name, message_namespace);
179  });
180  message_node->field_nodes.push_back(array_node);
181  }
182 
183  continue;
184  }
185  }
186 
187  throw std::runtime_error("Malformed message definition line: " + line);
188  }
189  }
190 
191  for (auto &job : linker_jobs) {
192  job();
193  }
194 
195  root_node->init(*this);
196  root_node->hash = type->hash();
197 
198  _node = root_node;
199 
200  {
201  std::lock_guard<std::mutex> lock(cache_mutex);
202  cache_map[type->hash()] = root_node;
203  }
204 }
205 
206 void MessageParser::parse(const std::shared_ptr<const Message> &message) {
207  if (_data == nullptr || _data.use_count() > 1) {
208  // LOG_DEBUG("new data");
209  _data = std::make_shared<Data>();
210  _data->index = std::make_shared<Index>();
211  }
212  _data->message = message;
213  parseDefinition(message->type());
214  _data_start = 0;
215  _index_start = 0;
216  {
217  size_t p = 0;
218  _data->index->clear();
219  PROFILER("index");
220  _node->index(*this, p);
221  // LOG_DEBUG("s " << message->size() << " " << p);
222  }
223 }
224 
225 static void printIndent(std::ostream &stream, size_t indent) {
226  for (size_t i = 0; i < indent; i++) {
227  stream << " ";
228  }
229 }
230 
231 static void printImpl(const MessageParser &message, std::ostream &stream,
232  size_t indent) {
233  if (message.isMessage()) {
234  for (size_t i = 0; i < message.size(); i++) {
235  printIndent(stream, indent);
236  stream << message.fieldName(i) << ": ";
237  stream << "\n";
238  printImpl(message[i], stream, indent + 1);
239  }
240  return;
241  }
242  if (message.isArray()) {
243  for (size_t i = 0; i < message.size(); i++) {
244  printIndent(stream, indent);
245  stream << "-\n";
246  printImpl(message[i], stream, indent + 1);
247  }
248  return;
249  }
250  printIndent(stream, indent);
251  stream << message.toString() << "\n";
252 }
253 
254 void MessageParser::print(std::ostream &stream) const {
255  printImpl(*this, stream, 0);
256 }
257 
258 std::string MessageParser::print() const {
259  std::stringstream stream;
260  print(stream);
261  return stream.str();
262 }