ros_introspection.hpp
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 #ifndef ROS_INTROSPECTION_HPP
36 #define ROS_INTROSPECTION_HPP
37 
38 #include <unordered_set>
42 #include "absl/types/span.h"
43 
44 namespace RosIntrospection{
45 
46 struct FlatMessage {
47 
49  const StringTree* tree;
50 
53  std::vector< std::pair<StringTreeLeaf, Variant> > value;
54 
57  std::vector< std::pair<StringTreeLeaf, std::string> > name;
58 
62  std::vector< std::pair<StringTreeLeaf, std::vector<uint8_t>>> blob;
63 };
64 
65 typedef std::vector< std::pair<std::string, Variant> > RenamedValues;
66 
67 class Parser{
68 
69 public:
70  Parser(): _rule_cache_dirty(true), _global_warnings(&std::cerr), _discard_large_array(true) {}
71 
72  void setMaxArrayPolicy( bool discard_entire_array )
73  {
74  _discard_large_array = discard_entire_array;
75  }
76 
90  void registerMessageDefinition(const std::string& message_identifier,
91  const ROSType &main_type,
92  const std::string& definition);
93 
100  void registerRenamingRules(const ROSType& type,
101  const std::vector<SubstitutionRule> &rules );
102 
109  const ROSMessageInfo* getMessageInfo(const std::string& msg_identifier) const;
110 
118  const ROSMessage *getMessageByType(const ROSType& type, const ROSMessageInfo &info) const;
119 
143  bool deserializeIntoFlatContainer(const std::string& msg_identifier,
144  absl::Span<uint8_t> buffer,
145  FlatMessage* flat_container_output,
146  const uint32_t max_array_size ) const;
147 
168  void applyNameTransform(const std::string& msg_identifier,
169  const FlatMessage& container,
170  RenamedValues* renamed_value );
171 
172  typedef std::function<void(const ROSType&, absl::Span<uint8_t>&)> VisitingCallback;
173 
186  void applyVisitorToBuffer(const std::string& msg_identifier, const ROSType &monitored_type,
187  absl::Span<uint8_t> &buffer,
188  VisitingCallback callback) const;
189 
190  template <typename T>
191  T extractField(const std::string& msg_identifier, const absl::Span<uint8_t> &buffer);
192 
193 
195  void setWarningsStream(std::ostream* output) { _global_warnings = output; }
196 
197 private:
198 
199 
200  struct RulesCache{
202  rule( &r ), pattern_head(nullptr), alias_head(nullptr)
203  {}
207  bool operator==(const RulesCache& other) { return this->rule == other.rule; }
208  };
209 
210  std::unordered_map<std::string, ROSMessageInfo> _registered_messages;
211  std::unordered_map<ROSType, std::unordered_set<SubstitutionRule>> _registered_rules;
212  std::unordered_map<std::string, std::vector<RulesCache>> _rule_caches;
213 
214  void updateRuleCache();
215 
217 
218  void createTrees(ROSMessageInfo &info, const std::string &type_name) const;
219 
220  std::ostream* _global_warnings;
221 
222  std::vector<int> _alias_array_pos;
223  std::vector<std::string> _formatted_string;
224  std::vector<int8_t> _substituted;
226 };
227 
228 //---------------------------------------------------
229 
230 template<typename T> inline
231 T Parser::extractField(const std::string &msg_identifier,
232  const absl::Span<uint8_t> &buffer)
233 {
234  T out;
235  bool found = false;
236 
237  const ROSMessageInfo* msg_info = getMessageInfo(msg_identifier);
238  if( msg_info == nullptr)
239  {
240  throw std::runtime_error("extractField: msg_identifier not registered. Use registerMessageDefinition" );
241  }
242 
243  const ROSType monitored_type (ros::message_traits::DataType<T>::value());
244 
245  if( getMessageByType( monitored_type, *msg_info) == nullptr)
246  {
247  throw std::runtime_error("extractField: message type doesn't contain this field type" );
248  }
249 
250  std::function<void(const MessageTreeNode*)> recursiveImpl;
251  size_t buffer_offset = 0;
252 
253  recursiveImpl = [&](const MessageTreeNode* msg_node)
254  {
255  if( found ) return;
256 
257  const ROSMessage* msg_definition = msg_node->value();
258  const ROSType& msg_type = msg_definition->type();
259 
260  size_t index_m = 0;
261 
262  if( msg_type == monitored_type )
263  {
264  ros::serialization::IStream is( buffer.data() + buffer_offset,
265  buffer.size() - buffer_offset );
267  found = true;
268  return;
269  }
270  // subfields
271  for (const ROSField& field : msg_definition->fields() )
272  {
273  if(field.isConstant() ) continue;
274 
275  const ROSType& field_type = field.type();
276 
277  int32_t array_size = field.arraySize();
278  if( array_size == -1)
279  {
280  ReadFromBuffer( buffer, buffer_offset, array_size );
281  }
282  //------------------------------------
283  if( field_type.isBuiltin() && field_type != monitored_type )
284  {
285  //fast skip
286  if( field_type.typeSize() >= 1 )
287  {
288  buffer_offset += field_type.typeSize() * array_size;
289  }
290  else{
291  ReadFromBufferToVariant( field_type.typeID(), buffer, buffer_offset );
292  }
293  }
294  else
295  {
296  for (int i=0; i<array_size; i++ )
297  {
298  recursiveImpl( msg_node->child(index_m) );
299  if( found ) return;
300  }
301  index_m++;
302  }
303  } // end for fields
304 
305  }; //end lambda
306 
307  //start recursion
308  recursiveImpl( msg_info->message_tree.croot() );
309 
310  return out;
311 }
312 
313 
314 
315 }
316 
317 #endif // ROS_INTROSPECTION_HPP
std::function< void(const ROSType &, absl::Span< uint8_t > &)> VisitingCallback
std::vector< std::string > _formatted_string
std::vector< std::pair< StringTreeLeaf, std::string > > name
NodeSet out
Variant ReadFromBufferToVariant(const absl::Span< uint8_t > &buffer, size_t &offset)
const std::vector< ROSField > & fields() const
Vector of fields.
Definition: ros_message.hpp:60
const StringTree * tree
Tree that the StringTreeLeaf(s) refer to.
std::vector< int > _alias_array_pos
Element of the tree. it has a single parent and N >= 0 children.
Definition: tree.hpp:54
int typeSize() const
If builtin, size of builtin, -1 means variable or undefined.
Definition: ros_type.hpp:132
constexpr pointer data() const noexcept
std::unordered_map< std::string, std::vector< RulesCache > > _rule_caches
const TreeNode< T > * croot() const
Constant pointer to the root of the tree.
Definition: tree.hpp:98
void setMaxArrayPolicy(bool discard_entire_array)
constexpr size_type size() const noexcept
std::unordered_map< ROSType, std::unordered_set< SubstitutionRule > > _registered_rules
std::unordered_map< std::string, ROSMessageInfo > _registered_messages
std::vector< std::pair< StringTreeLeaf, Variant > > value
T extractField(const std::string &msg_identifier, const absl::Span< uint8_t > &buffer)
std::vector< int8_t > _substituted
void ReadFromBuffer(const absl::Span< uint8_t > &buffer, size_t &offset, T &destination)
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
bool operator==(const RulesCache &other)
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 setWarningsStream(std::ostream *output)
Change where the warning messages are displayed.
int i
const char * definition()
void deserialize(Stream &stream, T &t)
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
RulesCache(const SubstitutionRule &r)


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