ros_introspection.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright 2016-2017 Davide Faconti
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage, Inc. nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 * *******************************************************************/
34 
35 
36 #include <boost/algorithm/string.hpp>
37 #include <boost/utility/string_ref.hpp>
38 #include <boost/lexical_cast.hpp>
39 #include <boost/regex.hpp>
40 #include <boost/algorithm/string/regex.hpp>
41 #include <functional>
44 
45 namespace RosIntrospection {
46 
47 void Parser::createTrees(ROSMessageInfo& info, const std::string &type_name) const
48 {
49  std::function<void(const ROSMessage*, StringTreeNode*, MessageTreeNode* )> recursiveTreeCreator;
50 
51  recursiveTreeCreator = [&](const ROSMessage* msg_definition, StringTreeNode* string_node, MessageTreeNode* msg_node)
52  {
53  // note: should use reserve here, NOT resize
54  const size_t NUM_FIELDS = msg_definition->fields().size();
55 
56  string_node->children().reserve( NUM_FIELDS );
57  msg_node->children().reserve( NUM_FIELDS );
58 
59  for (const ROSField& field : msg_definition->fields() )
60  {
61  if(field.isConstant() == false) {
62 
63  // Let's add first a child to string_node
64  string_node->addChild( field.name() );
65  StringTreeNode* new_string_node = &(string_node->children().back());
66  if( field.isArray())
67  {
68  new_string_node->children().reserve(1);
69  new_string_node = new_string_node->addChild("#");
70  }
71 
72  const ROSMessage* next_msg = nullptr;
73  // builtin types will not trigger a recursion
74  if( field.type().isBuiltin() == false)
75  {
76  next_msg = getMessageByType( field.type(), info );
77  if( next_msg == nullptr)
78  {
79  throw std::runtime_error("This type was not registered " );
80  }
81  msg_node->addChild( next_msg );
82  MessageTreeNode* new_msg_node = &(msg_node->children().back());
83  recursiveTreeCreator(next_msg, new_string_node, new_msg_node);
84  }
85  } //end of field.isConstant()
86  } // end of for fields
87  };//end of lambda
88 
89  info.string_tree.root()->setValue( type_name );
90  info.message_tree.root()->setValue( &info.type_list.front() );
91  //TODO info.type_tree.root()->value() =
92  // start recursion
93  recursiveTreeCreator( &info.type_list.front(),
94  info.string_tree.root(),
95  info.message_tree.root());
96 }
97 
98 inline bool operator ==( const std::string& a, const absl::string_view& b)
99 {
100  return ( a.size() == b.size() && std::strncmp( a.data(), b.data(), a.size()) == 0);
101 }
102 
103 inline bool FindPattern(const std::vector<absl::string_view> &pattern,
104  size_t index, const StringTreeNode *tail,
105  const StringTreeNode **head)
106 {
107  if( tail->value() == pattern[index] )
108  {
109  index++;
110  }
111  else{ // mismatch
112  if( index > 0 ){
113  // reset counter;
114  FindPattern( pattern, 0, tail, head);
115  return false;
116  }
117  index = 0;
118  }
119 
120  if( index == pattern.size()){
121  *head = ( tail );
122  return true;
123  }
124 
125  bool found = false;
126 
127  for (auto& child: tail->children() ) {
128 
129  found = FindPattern( pattern, index, &child, head);
130  if( found) break;
131  }
132  return found;
133 }
134 
135 
136 void Parser::registerRenamingRules(const ROSType &type, const std::vector<SubstitutionRule> &given_rules)
137 {
138  std::unordered_set<SubstitutionRule>& rule_set = _registered_rules[type];
139  for(const auto& rule: given_rules)
140  {
141  if( rule_set.find( rule ) == rule_set.end() )
142  {
143  rule_set.insert( rule );
144  _rule_cache_dirty = true;
145  }
146  }
147 }
148 
150 {
151  if( _rule_cache_dirty == false)
152  {
153  return;
154  }
155  else{
156  _rule_cache_dirty = false;
157  }
158  for(const auto& rule_it: _registered_rules )
159  {
160  const ROSType& type = rule_it.first;
161  const std::unordered_set<SubstitutionRule>& rule_set = rule_it.second;
162 
163  for(const auto& msg_it: _registered_messages)
164  {
165  const std::string& msg_identifier = msg_it.first;
166  const ROSMessageInfo& msg_info = msg_it.second;
167 
168  if( getMessageByType(type, msg_info) )
169  {
170  std::vector<RulesCache>& cache_vector = _rule_caches[msg_identifier];
171  for(const auto& rule: rule_set )
172  {
173  RulesCache cache(rule);
174  FindPattern( cache.rule->pattern(), 0, msg_info.string_tree.croot(), &cache.pattern_head );
175  FindPattern( cache.rule->alias(), 0, msg_info.string_tree.croot(), &cache.alias_head );
176  if( cache.pattern_head && cache.alias_head
177  && std::find( cache_vector.begin(), cache_vector.end(), cache) == cache_vector.end()
178  )
179  {
180  cache_vector.push_back( std::move(cache) );
181  }
182  }
183  }
184  }
185  }
186 }
187 
188 
189 
190 void Parser::registerMessageDefinition(const std::string &msg_definition,
191  const ROSType &main_type,
192  const std::string &definition)
193 {
194  if( _registered_messages.count(msg_definition) > 0 )
195  {
196  return; //already registered
197  }
198  _rule_cache_dirty = true;
199 
200  const boost::regex msg_separation_regex("^=+\\n+");
201 
202  std::vector<std::string> split;
203  std::vector<const ROSType*> all_types;
204 
205  boost::split_regex(split, definition, msg_separation_regex);
206 
207  ROSMessageInfo info;
208  info.type_list.reserve( split.size() );
209 
210  for (size_t i = 0; i < split.size(); ++i)
211  {
212  ROSMessage msg( split[i] );
213  if( i == 0)
214  {
215  msg.mutateType( main_type );
216  }
217 
218  info.type_list.push_back( std::move(msg) );
219  all_types.push_back( &(info.type_list.back().type()) );
220  }
221 
222  for( ROSMessage& msg: info.type_list )
223  {
224  msg.updateMissingPkgNames( all_types );
225  }
226  //------------------------------
227 
228  createTrees(info, msg_definition);
229 
230  // std::cout << info.string_tree << std::endl;
231  // std::cout << info.message_tree << std::endl;
232  _registered_messages.insert( std::make_pair(msg_definition, std::move(info) ) );
233 }
234 
235 const ROSMessageInfo *Parser::getMessageInfo(const std::string &msg_identifier) const
236 {
237  auto it = _registered_messages.find(msg_identifier);
238  if( it != _registered_messages.end() )
239  {
240  return &(it->second);
241  }
242  return nullptr;
243 }
244 
245 const ROSMessage* Parser::getMessageByType(const ROSType &type, const ROSMessageInfo& info) const
246 {
247  for(const ROSMessage& msg: info.type_list) // find in the list
248  {
249  if( msg.type() == type )
250  {
251  return &msg;
252  }
253  }
254  return nullptr;
255 }
256 
257 void Parser::applyVisitorToBuffer(const std::string &msg_identifier,
258  const ROSType& monitored_type,
259  absl::Span<uint8_t> &buffer,
260  Parser::VisitingCallback callback) const
261 {
262  const ROSMessageInfo* msg_info = getMessageInfo(msg_identifier);
263 
264  if( msg_info == nullptr)
265  {
266  throw std::runtime_error("extractField: msg_identifier not registered. Use registerMessageDefinition" );
267  }
268  if( getMessageByType( monitored_type, *msg_info) == nullptr)
269  {
270  // you will not find it. Skip it;
271  return;
272  }
273 
274  std::function<void(const MessageTreeNode*)> recursiveImpl;
275  size_t buffer_offset = 0;
276 
277  recursiveImpl = [&](const MessageTreeNode* msg_node)
278  {
279  const ROSMessage* msg_definition = msg_node->value();
280  const ROSType& msg_type = msg_definition->type();
281 
282  const bool matching = ( msg_type == monitored_type );
283 
284  uint8_t* prev_buffer_ptr = buffer.data() + buffer_offset;
285  size_t prev_offset = buffer_offset;
286 
287  size_t index_m = 0;
288 
289  for (const ROSField& field : msg_definition->fields() )
290  {
291  if(field.isConstant() ) continue;
292 
293  const ROSType& field_type = field.type();
294 
295  int32_t array_size = field.arraySize();
296  if( array_size == -1)
297  {
298  ReadFromBuffer( buffer, buffer_offset, array_size );
299  }
300 
301  //------------------------------------
302 
303  if( field_type.isBuiltin() )
304  {
305  for (int i=0; i<array_size; i++ )
306  {
307  //Skip
308  ReadFromBufferToVariant( field_type.typeID(), buffer, buffer_offset );
309  }
310  }
311  else{
312  // field_type.typeID() == OTHER
313  for (int i=0; i<array_size; i++ )
314  {
315  recursiveImpl( msg_node->child(index_m) );
316  }
317  index_m++;
318  }
319  } // end for fields
320  if( matching )
321  {
322  absl::Span<uint8_t> view( prev_buffer_ptr, buffer_offset - prev_offset);
323  callback( monitored_type, view );
324  }
325  }; //end lambda
326 
327  //start recursion
328  recursiveImpl( msg_info->message_tree.croot() );
329 }
330 
331 bool Parser::deserializeIntoFlatContainer(const std::string& msg_identifier,
332  absl::Span<uint8_t> buffer,
333  FlatMessage* flat_container,
334  const uint32_t max_array_size ) const
335 {
336 
337  bool entire_message_parse = true;
338  const ROSMessageInfo* msg_info = getMessageInfo(msg_identifier);
339 
340  size_t value_index = 0;
341  size_t name_index = 0;
342  size_t blob_index = 0;
343 
344  if( msg_info == nullptr)
345  {
346  throw std::runtime_error("deserializeIntoFlatContainer: msg_identifier not registerd. Use registerMessageDefinition" );
347  }
348  size_t buffer_offset = 0;
349 
350  std::function<void(const MessageTreeNode*,StringTreeLeaf,bool)> deserializeImpl;
351 
352  deserializeImpl = [&](
353  const MessageTreeNode* msg_node,
354  const StringTreeLeaf& tree_leaf,
355  bool DO_STORE)
356  {
357  const ROSMessage* msg_definition = msg_node->value();
358  size_t index_s = 0;
359  size_t index_m = 0;
360 
361  for (const ROSField& field : msg_definition->fields() )
362  {
363  if(field.isConstant() ) continue;
364 
365  const ROSType& field_type = field.type();
366 
367  auto new_tree_leaf = tree_leaf;
368  new_tree_leaf.node_ptr = tree_leaf.node_ptr->child(index_s);
369 
370  int32_t array_size = field.arraySize();
371  if( array_size == -1)
372  {
373  ReadFromBuffer( buffer, buffer_offset, array_size );
374  }
375  if( field.isArray())
376  {
377  new_tree_leaf.index_array.push_back(0);
378  new_tree_leaf.node_ptr = new_tree_leaf.node_ptr->child(0);
379  }
380 
381  bool IS_BLOB = false;
382 
383  // Stop storing it if is NOT a blob and a very large array.
384  if( array_size > static_cast<int32_t>(max_array_size))
385  {
386  if( builtinSize(field_type.typeID()) == 1){
387  IS_BLOB = true;
388  }
389  else{
390  if( _discard_large_array ){
391  DO_STORE = false;
392  }
393  entire_message_parse = false;
394  }
395  }
396 
397  if( IS_BLOB ) // special case. This is a "blob", typically an image, a map, etc.
398  {
399  if( flat_container->blob.size() <= blob_index)
400  {
401  const size_t increased_size = std::max( size_t(32), flat_container->blob.size() * 3/2);
402  flat_container->blob.resize( increased_size );
403  }
404  if( buffer_offset + array_size > buffer.size() )
405  {
406  throw std::runtime_error("Buffer overrun in deserializeIntoFlatContainer (blob)");
407  }
408  if( DO_STORE )
409  {
410  flat_container->blob[blob_index].first = new_tree_leaf ;
411  std::vector<uint8_t>& blob = flat_container->blob[blob_index].second;
412  blob_index++;
413  blob.resize( array_size );
414  std::memcpy( blob.data(), &buffer[buffer_offset], array_size);
415  }
416  buffer_offset += array_size;
417  }
418  else // NOT a BLOB
419  {
420  bool DO_STORE_ARRAY = DO_STORE;
421  for (int i=0; i<array_size; i++ )
422  {
423  if( DO_STORE_ARRAY && i >= max_array_size )
424  {
425  DO_STORE_ARRAY = false;
426  }
427 
428  if( field.isArray() && DO_STORE_ARRAY )
429  {
430  new_tree_leaf.index_array.back() = i;
431  }
432 
433  if( field_type.typeID() == STRING )
434  {
435  if( flat_container->name.size() <= name_index)
436  {
437  const size_t increased_size = std::max( size_t(32), flat_container->name.size() * 3/2);
438  flat_container->name.resize( increased_size );
439  }
440  std::string& name = flat_container->name[name_index].second;//read directly inside an existing std::string
441  ReadFromBuffer<std::string>( buffer, buffer_offset, name );
442 
443  if( DO_STORE_ARRAY )
444  {
445  flat_container->name[name_index].first = new_tree_leaf ;
446  name_index++;
447  }
448  }
449  else if( field_type.isBuiltin() )
450  {
451  if( flat_container->value.size() <= value_index)
452  {
453  const size_t increased_size = std::max( size_t(32), flat_container->value.size() * 3/2);
454  flat_container->value.resize( increased_size );
455  }
456 
457  Variant var = ReadFromBufferToVariant( field_type.typeID(),
458  buffer,
459  buffer_offset );
460  if( DO_STORE_ARRAY )
461  {
462  flat_container->value[value_index] = std::make_pair( new_tree_leaf, std::move(var) );
463  value_index++;
464  }
465  }
466  else{ // field_type.typeID() == OTHER
467 
468  deserializeImpl(msg_node->child(index_m),
469  new_tree_leaf,
470  DO_STORE_ARRAY);
471  }
472  } // end for array_size
473  }
474 
475  if( field_type.typeID() == OTHER )
476  {
477  index_m++;
478  }
479  index_s++;
480  } // end for fields
481  }; //end of lambda
482 
483 
484  flat_container->tree = &msg_info->string_tree;
485 
486  StringTreeLeaf rootnode;
487  rootnode.node_ptr = msg_info->string_tree.croot();
488 
489  deserializeImpl( msg_info->message_tree.croot(),
490  rootnode,
491  true);
492 
493  flat_container->name.resize( name_index );
494  flat_container->value.resize( value_index );
495  flat_container->blob.resize( blob_index );
496 
497  if( buffer_offset != buffer.size() )
498  {
499  throw std::runtime_error("buildRosFlatType: There was an error parsing the buffer" );
500  }
501  return entire_message_parse;
502 }
503 
505 {
506  return s.size() == 1 && s[0] == '#';
507 }
508 
510 {
511  return s.size() == 1 && s[0] == '@';
512 }
513 
514 // given a leaf of the tree, that can have multiple index_array,
515 // find the only index which corresponds to the # in the pattern
517  const StringTreeNode* pattern_head )
518 {
519  const StringTreeNode* node_ptr = leaf.node_ptr;
520 
521  int pos = leaf.index_array.size() -1;
522 
523  while( node_ptr )
524  {
525  if( node_ptr != pattern_head )
526  {
527  if( isNumberPlaceholder( node_ptr->value() ))
528  {
529  pos--;
530  }
531  }
532  else{
533  return pos;
534  }
535  node_ptr = node_ptr->parent();
536  } // end while
537  return -1;
538 }
539 
540 template <typename VectorType>
541 inline void JoinStrings( const VectorType& vect, const char separator, std::string& destination)
542 {
543  size_t count = 0;
544  for(const auto &v: vect ) count += v.size();
545 
546  // the following approach seems to be faster
547  // https://github.com/facontidavide/InterestingBenchmarks/blob/master/StringAppend_vs_Memcpy.md
548 
549  destination.resize( count + vect.size() -1 );
550 
551  char* buffer = &destination[0];
552  size_t buff_pos = 0;
553 
554  for (size_t c = 0; c < vect.size()-1; c++)
555  {
556  const size_t S = vect[c].size();
557  std::memcpy( &buffer[buff_pos], vect[c].data(), S );
558  buff_pos += S;
559  buffer[buff_pos++] = separator;
560  }
561  std::memcpy( &buffer[buff_pos], vect.back().data(), vect.back().size() );
562 }
563 
564 void Parser::applyNameTransform(const std::string& msg_identifier,
565  const FlatMessage& container,
566  RenamedValues *renamed_value )
567 {
568  if( _rule_cache_dirty )
569  {
570  updateRuleCache();
571  }
572  auto rule_found = _rule_caches.find(msg_identifier);
573 
574  const size_t num_values = container.value.size();
575  const size_t num_names = container.name.size();
576 
577  renamed_value->resize( container.value.size() );
578  //DO NOT clear() renamed_value
579 
580  _alias_array_pos.resize( num_names );
581  _formatted_string.reserve( num_values );
582  _formatted_string.clear();
583 
584  _substituted.resize( num_values );
585  for(size_t i=0; i<num_values; i++) { _substituted[i] = false; }
586 
587  // size_t renamed_index = 0;
588 
589  if( rule_found != _rule_caches.end() )
590  {
591  const std::vector<RulesCache>& rules_cache = rule_found->second;
592 
593  for(const RulesCache& cache: rules_cache)
594  {
595  const SubstitutionRule* rule = cache.rule;
596  const StringTreeNode* pattern_head = cache.pattern_head;
597  const StringTreeNode* alias_head = cache.alias_head;
598 
599  if( !pattern_head || !alias_head ) continue;
600 
601  for (size_t n=0; n<num_names; n++)
602  {
603  const StringTreeLeaf& name_leaf = container.name[n].first;
604  _alias_array_pos[n] = PatternMatchAndIndexPosition(name_leaf, alias_head);
605  }
606 
607  for(size_t value_index = 0; value_index<num_values; value_index++)
608  {
609  if( _substituted[value_index]) continue;
610 
611  const auto& value_leaf = container.value[value_index];
612 
613  const StringTreeLeaf& leaf = value_leaf.first;
614 
615  int pattern_array_pos = PatternMatchAndIndexPosition(leaf, pattern_head);
616 
617  if( pattern_array_pos>= 0) // -1 if pattern doesn't match
618  {
619  const std::string* new_name = nullptr;
620 
621  for (size_t n=0; n < num_names; n++)
622  {
623  const auto & it = container.name[n];
624  const StringTreeLeaf& alias_leaf = it.first;
625 
626  if( _alias_array_pos[n] >= 0 ) // -1 if pattern doesn't match
627  {
628  if( alias_leaf.index_array[ _alias_array_pos[n] ] ==
629  leaf.index_array[ pattern_array_pos] )
630  {
631  new_name = &(it.second);
632  break;
633  }
634  }
635  }
636 
637  //--------------------------
638  if( new_name )
639  {
641 
642  const StringTreeNode* node_ptr = leaf.node_ptr;
643 
644  int position = leaf.index_array.size()-1;
645 
646  while( node_ptr != pattern_head)
647  {
648  const absl::string_view& str_val = node_ptr->value();
649 
650  if( isNumberPlaceholder( str_val ) )
651  {
652  char buffer[16];
653  const int number = leaf.index_array[position--];
654  int str_size = print_number( buffer, number );
655  _formatted_string.push_back( std::string(buffer, str_size) );
656  concatenated_name.push_back( _formatted_string.back() );
657  }
658  else{
659  concatenated_name.push_back( str_val );
660  }
661  node_ptr = node_ptr->parent();
662  }
663 
664  for (int s = rule->substitution().size()-1; s >= 0; s--)
665  {
666  const absl::string_view& str_val = rule->substitution()[s];
667 
668  if( isSubstitutionPlaceholder(str_val) )
669  {
670  concatenated_name.push_back( *new_name );
671  position--;
672  }
673  else{ concatenated_name.push_back( str_val ); }
674  }
675 
676  for (size_t p = 0; p < rule->pattern().size() && node_ptr; p++)
677  {
678  node_ptr = node_ptr->parent();
679  }
680 
681  while( node_ptr )
682  {
683  absl::string_view str_val = node_ptr->value();
684 
685  if( isNumberPlaceholder(str_val) )
686  {
687  char buffer[16];
688  const int number = leaf.index_array[position--];
689  int str_size = print_number( buffer, number );
690  _formatted_string.push_back( std::string(buffer, str_size) );
691  concatenated_name.push_back( _formatted_string.back() );
692  }
693  else{
694  concatenated_name.push_back( str_val );
695  }
696  node_ptr = node_ptr->parent();
697  }
698 
699  //------------------------
700  auto& renamed_pair = (*renamed_value)[value_index];
701 
702  std::reverse(concatenated_name.begin(), concatenated_name.end());
703  JoinStrings( concatenated_name, '/', renamed_pair.first);
704  renamed_pair.second = value_leaf.second ;
705 
706  _substituted[value_index] = true;
707 
708  }// end if( new_name )
709  }// end if( PatternMatching )
710  } // end for values
711  } // end for rules
712  } //end rule found
713 
714  for(size_t value_index=0; value_index< container.value.size(); value_index++)
715  {
716  if( !_substituted[value_index] )
717  {
718  const std::pair<StringTreeLeaf, Variant> & value_leaf = container.value[value_index];
719 
720  std::string& destination = (*renamed_value)[value_index].first;
721  value_leaf.first.toStr( destination );
722  (*renamed_value)[value_index].second = value_leaf.second ;
723  }
724  }
725 }
726 
727 }
728 
729 
int v
std::function< void(const ROSType &, absl::Span< uint8_t > &)> VisitingCallback
const ROSMessageInfo * getMessageInfo(const std::string &msg_identifier) const
getMessageInfo provides some metadata amout a registered ROSMessage.
const ChildrenVector & children() const
Definition: tree.hpp:68
int print_number(char *buffer, uint16_t value)
The StringTreeLeaf is, as the name suggests, a leaf (terminal node) of a StringTree. It provides the pointer to the node and a list of numbers that represent the index that corresponds to the placeholder "#".
iterator end() noexcept
std::vector< std::string > _formatted_string
std::vector< std::pair< StringTreeLeaf, std::string > > name
Variant ReadFromBufferToVariant(const absl::Span< uint8_t > &buffer, size_t &offset)
void push_back(const value_type &t)
const std::vector< ROSField > & fields() const
Vector of fields.
Definition: ros_message.hpp:60
const StringTree * tree
Tree that the StringTreeLeaf(s) refer to.
TreeNode< T > * root()
Mutable pointer to the root of the tree.
Definition: tree.hpp:101
std::vector< int > _alias_array_pos
XmlRpcServer s
void applyVisitorToBuffer(const std::string &msg_identifier, const ROSType &monitored_type, absl::Span< uint8_t > &buffer, VisitingCallback callback) const
applyVisitorToBuffer is used to pass a callback that is invoked every time a chunk of memory storing ...
std::vector< ROSMessage > type_list
Definition: ros_message.hpp:84
Element of the tree. it has a single parent and N >= 0 children.
Definition: tree.hpp:54
const ROSMessage * getMessageByType(const ROSType &type, const ROSMessageInfo &info) const
getMessageByType provides a pointer to a ROSMessage stored in ROSMessageInfo.
const TreeNode * parent() const
Definition: tree.hpp:63
constexpr pointer data() const noexcept
std::unordered_map< std::string, std::vector< RulesCache > > _rule_caches
int PatternMatchAndIndexPosition(const StringTreeLeaf &leaf, const StringTreeNode *pattern_head)
void applyNameTransform(const std::string &msg_identifier, const FlatMessage &container, RenamedValues *renamed_value)
applyNameTransform is used to create a vector of type RenamedValues from the vector FlatMessage::valu...
const TreeNode< T > * croot() const
Constant pointer to the root of the tree.
Definition: tree.hpp:98
const std::vector< absl::string_view > & alias() const
bool operator==(const std::string &a, const absl::string_view &b)
void JoinStrings(const VectorType &vect, const char separator, std::string &destination)
bool isSubstitutionPlaceholder(const absl::string_view &s)
const std::vector< absl::string_view > & substitution() const
constexpr size_type size() const noexcept
constexpr size_type size() const noexcept
std::unordered_map< ROSType, std::unordered_set< SubstitutionRule > > _registered_rules
int builtinSize(const BuiltinType c)
std::unordered_map< std::string, ROSMessageInfo > _registered_messages
InlinedVector< uint16_t, 8 > index_array
void mutateType(const ROSType &new_type)
Definition: ros_message.hpp:64
std::vector< std::pair< StringTreeLeaf, Variant > > value
const TreeNode * child(size_t index) const
Definition: tree.hpp:71
const std::vector< absl::string_view > & pattern() const
const T & value() const
Definition: tree.hpp:65
bool deserializeIntoFlatContainer(const std::string &msg_identifier, absl::Span< uint8_t > buffer, FlatMessage *flat_container_output, const uint32_t max_array_size) const
deserializeIntoFlatContainer takes a raw buffer of memory and extract information from it...
std::vector< int8_t > _substituted
void ReadFromBuffer(const absl::Span< uint8_t > &buffer, size_t &offset, T &destination)
bool isNumberPlaceholder(const absl::string_view &s)
char name[1]
const char * msg
const StringTreeNode * node_ptr
bool FindPattern(const std::vector< absl::string_view > &pattern, size_t index, const StringTreeNode *tail, const StringTreeNode **head)
const ROSType & type() const
Definition: ros_message.hpp:62
def msg_type(f)
std::vector< std::pair< StringTreeLeaf, std::vector< uint8_t > > > blob
def field_type(f)
std::vector< std::pair< std::string, Variant > > RenamedValues
constexpr const_pointer data() const noexcept
TreeNode * addChild(const T &child)
Definition: tree.hpp:170
A ROSMessage will contain one or more ROSField(s). Each field is little more than a name / type pair...
Definition: ros_field.hpp:52
void updateMissingPkgNames(const std::vector< const ROSType * > &all_types)
Definition: ros_message.cpp:73
empty_struct data[sizeof(T)/sizeof(empty_struct)]
iterator begin() noexcept
int i
BuiltinType typeID() const
If type is builtin, returns the id. BuiltinType::OTHER otherwise.
Definition: ros_type.hpp:137
bool isBuiltin() const
True if the type is ROS builtin.
Definition: ros_type.hpp:127
void registerRenamingRules(const ROSType &type, const std::vector< SubstitutionRule > &rules)
registerRenamingRules is used to register the renaming rules. You MUST use registerMessageDefinition ...
int n
void registerMessageDefinition(const std::string &message_identifier, const ROSType &main_type, const std::string &definition)
A single message definition will (most probably) generate myltiple ROSMessage(s). In fact the "child"...
void createTrees(ROSMessageInfo &info, const std::string &type_name) const


ros_type_introspection
Author(s): Davide Faconti
autogenerated on Thu May 16 2019 02:39:09