Ignition Gazebo

API Reference

1.0.2
Component.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2018 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  */
17 #ifndef IGNITION_GAZEBO_COMPONENTS_COMPONENT_HH_
18 #define IGNITION_GAZEBO_COMPONENTS_COMPONENT_HH_
19 
20 #include <cstdint>
21 #include <memory>
22 #include <string>
23 #include <sstream>
24 #include <utility>
25 
26 #include <ignition/common/Console.hh>
27 
28 #include <ignition/gazebo/config.hh>
29 #include <ignition/gazebo/Export.hh>
30 #include <ignition/gazebo/Types.hh>
31 
33 template<typename T> struct IsSharedPtr:
34  std::false_type
35 {
36 };
37 
39 template<typename T> struct IsSharedPtr<std::shared_ptr<T>>:
40  std::true_type
41 {
42 };
43 
52 template<typename DataType, typename Identifier,
53  typename Stream =
54  decltype(std::declval<std::ostream &>() << std::declval<DataType const &>()),
55  typename std::enable_if<
57  std::is_convertible<Stream, std::ostream &>::value,
58  int>::type = 0>
59 std::ostream &toStream(std::ostream &_out, DataType const &_data)
60 {
61  _out << _data;
62  return _out;
63 }
64 
74 template<typename DataType, typename Identifier,
75  typename Stream =
76  decltype(std::declval<std::ostream &>() << std::declval<
77  typename DataType::element_type const &>()),
78  typename std::enable_if<
80  std::is_convertible<Stream, std::ostream &>::value,
81  int>::type = 0>
82 std::ostream &toStream(std::ostream &_out, DataType const &_data)
83 {
84  _out << *_data;
85  return _out;
86 }
87 
96 template<typename DataType, typename Identifier, typename... Ignored>
97 std::ostream &toStream(std::ostream &_out, DataType const &,
98  Ignored const &..., ...)
99 {
100  static bool warned{false};
101  if (!warned)
102  {
103  ignwarn << "Trying to serialize component with data type ["
104  << typeid(DataType).name() << "], which doesn't have "
105  << "`operator<<`. Component will not be serialized." << std::endl;
106  warned = true;
107  }
108  return _out;
109 }
110 
119 template<typename DataType, typename Identifier,
120  typename Stream =
121  decltype(std::declval<std::istream &>() >> std::declval<DataType &>()),
122  typename std::enable_if<
124  std::is_convertible<Stream, std::istream &>::value,
125  int>::type = 0>
126 std::istream &fromStream(std::istream &_in, DataType &_data)
127 {
128  _in >> _data;
129  return _in;
130 }
131 
141 template<typename DataType, typename Identifier,
142  typename Stream =
143  decltype(std::declval<std::istream &>() >> std::declval<
144  typename DataType::element_type &>()),
145  typename std::enable_if<
147  std::is_convertible<Stream, std::istream &>::value,
148  int>::type = 0>
149 std::istream &fromStream(std::istream &_in, DataType &_data)
150 {
151  _in >> *_data;
152  return _in;
153 }
154 
163 template<typename DataType, typename Identifier, typename... Ignored>
164 std::istream &fromStream(std::istream &_in, DataType const &,
165  Ignored const &..., ...)
166 {
167  static bool warned{false};
168  if (!warned)
169  {
170  ignwarn << "Trying to deserialize component with data type ["
171  << typeid(DataType).name() << "], which doesn't have "
172  << "`operator>>`. Component will not be deserialized." << std::endl;
173  warned = true;
174  }
175  return _in;
176 }
177 
178 namespace ignition
179 {
180 namespace gazebo
181 {
182 // Inline bracket to help doxygen filtering.
183 inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
184 namespace components
185 {
186  // Forward declarations.
187  template<typename DataType> class ComponentPrivate;
188 
192  using NoData = std::add_lvalue_reference<void>;
193 
196  {
198  public: BaseComponent() = default;
199 
201  public: virtual ~BaseComponent() = default;
202 
212  public: friend std::ostream &operator<<(
213  std::ostream &_out, const BaseComponent &_component)
214  {
215  _component.Serialize(_out);
216  return _out;
217  }
218 
228  public: friend std::istream &operator>>(
229  std::istream &_in, BaseComponent &_component)
230  {
231  _component.Deserialize(_in);
232  return _in;
233  }
234 
243  protected: virtual void Serialize(std::ostream &/*_out*/) const
244  {
245  ignwarn << "Trying to serialize copmponent which hasn't implemented "
246  << "the `Serialize` function. Component will not be serialized."
247  << std::endl;
248  };
249 
258  protected: virtual void Deserialize(std::istream &/*_in*/)
259  {
260  ignwarn << "Trying to deserialize copmponent which hasn't implemented "
261  << "the `Deserialize` function. Component will not be "
262  << "deserialized." << std::endl;
263  };
264 
269  public: virtual ComponentTypeId TypeId() const = 0;
270  };
271 
289  template <typename DataType, typename Identifier>
290  class Component: public BaseComponent
291  {
293  public: Component();
294 
297  public: explicit Component(const DataType &_data);
298 
301  public: explicit Component(DataType &&_data);
302 
305  public: Component(const Component &_component);
306 
309  public: Component(Component &&_component) noexcept = default;
310 
312  public: ~Component() override = default;
313 
317  public: Component &operator=(
318  Component &&_component) noexcept = default;
319 
323  public: Component &operator=(const Component &_component);
324 
328  public: bool operator==(const Component &_component) const;
329 
333  public: bool operator!=(const Component &_component) const;
334 
335  // Documentation inherited
336  public: ComponentTypeId TypeId() const override;
337 
338  // Documentation inherited
339  public: void Serialize(std::ostream &_out) const override;
340 
341  // Documentation inherited
342  public: void Deserialize(std::istream &_in) override;
343 
346  public: DataType &Data();
347 
350  public: const DataType &Data() const;
351 
353  private: std::unique_ptr<ComponentPrivate<DataType>> dataPtr;
354 
357  public: inline static ComponentTypeId typeId{0};
358  };
359 
368  template <typename Identifier>
369  class Component<NoData, Identifier> : public BaseComponent
370  {
375  public: bool operator==(const Component<NoData, Identifier> &) const;
376 
381  public: bool operator!=(const Component<NoData, Identifier> &) const;
382 
387  public: friend std::ostream &operator<<(std::ostream &_out,
389  {
390  return _out;
391  }
392 
397  public: friend std::istream &operator>>(std::istream &_in,
399  {
400  return _in;
401  }
402 
403  // Documentation inherited
404  public: uint64_t TypeId() const override;
405 
408  public: inline static ComponentTypeId typeId{0};
409  };
410 
411  template <typename DataType>
412  class ComponentPrivate
413  {
415  public: ComponentPrivate() = default;
416 
419  public: explicit ComponentPrivate(DataType _data)
420  : data(std::move(_data))
421  {
422  }
423 
425  public: DataType data;
426  };
427 
429  template <typename DataType, typename Identifier>
431  : dataPtr(std::make_unique<ComponentPrivate<DataType>>())
432  {
433  }
434 
436  template <typename DataType, typename Identifier>
438  : dataPtr(std::make_unique<ComponentPrivate<DataType>>(_data))
439  {
440  }
441 
443  template <typename DataType, typename Identifier>
445  : dataPtr(std::make_unique<ComponentPrivate<DataType>>(std::move(_data)))
446  {
447  }
448 
450  template <typename DataType, typename Identifier>
452  const Component<DataType, Identifier> &_component)
453  : dataPtr(std::make_unique<ComponentPrivate<DataType>>(
454  _component.Data()))
455  {
456  }
457 
459  template <typename DataType, typename Identifier>
461  {
462  return this->dataPtr->data;
463  }
464 
466  template <typename DataType, typename Identifier>
468  {
469  return this->dataPtr->data;
470  }
471 
473  template <typename DataType, typename Identifier>
476  {
477  this->dataPtr->data = _component.Data();
478  return *this;
479  }
480 
482  template <typename DataType, typename Identifier>
485  {
486  return this->dataPtr->data == _component.Data();
487  }
488 
490  template <typename DataType, typename Identifier>
493  {
494  return this->dataPtr->data != _component.Data();
495  }
496 
498  template <typename DataType, typename Identifier>
499  void Component<DataType, Identifier>::Serialize(std::ostream &_out) const
500  {
501  toStream<DataType, Identifier>(_out, this->Data());
502  }
503 
505  template <typename DataType, typename Identifier>
507  {
508  fromStream<DataType, Identifier>(_in, this->Data());
509  }
510 
512  template <typename DataType, typename Identifier>
514  {
515  return typeId;
516  }
517 
519  template <typename Identifier>
521  const Component<NoData, Identifier> &) const
522  {
523  return true;
524  }
525 
527  template <typename Identifier>
529  const Component<NoData, Identifier> &) const
530  {
531  return false;
532  }
533 
535  template <typename Identifier>
537  {
538  return typeId;
539  }
540 }
541 }
542 }
543 }
544 #endif
friend std::ostream & operator<<(std::ostream &_out, const BaseComponent &_component)
Stream insertion operator. It exposes the component&#39;s serialized state which can be recreated by oper...
Definition: Component.hh:212
DataType data
The data being wrapped.
Definition: Component.hh:425
Component()
Default constructor.
Definition: Component.hh:430
bool operator!=(const Component &_component) const
Inequality operator.
Definition: Component.hh:492
static ComponentTypeId typeId
Unique ID for this component type. This is set through the Factory registration.
Definition: Component.hh:357
bool operator==(const Component &_component) const
Equality operator.
Definition: Component.hh:484
std::add_lvalue_reference< void > NoData
Convenient type to be used by components that don&#39;t wrap any data. I.e. they act as tags and their pr...
Definition: Component.hh:192
void Serialize(std::ostream &_out) const override
Fills a stream with a serialized version of the component. By default, it will leave the stream empty...
Definition: Component.hh:499
ComponentTypeId TypeId() const override
Returns the unique ID for the component&#39;s type. The ID is derived from the name that is manually chos...
Definition: Component.hh:513
virtual void Deserialize(std::istream &)
Fills a component based on a stream with a serialized data. By default, it will do nothing...
Definition: Component.hh:258
virtual void Serialize(std::ostream &) const
Fills a stream with a serialized version of the component. By default, it will leave the stream empty...
Definition: Component.hh:243
std::ostream & toStream(std::ostream &_out, DataType const &_data)
Helper template to call stream operators only on types that support them. This version is called for ...
Definition: Component.hh:59
friend std::istream & operator>>(std::istream &_in, BaseComponent &_component)
Stream extraction operator. It parses the component&#39;s serialized state which is created by operator<<...
Definition: Component.hh:228
std::istream & fromStream(std::istream &_in, DataType &_data)
Helper template to call extract operators only on types that support them. This version is called for...
Definition: Component.hh:126
friend std::ostream & operator<<(std::ostream &_out, const Component< NoData, Identifier > &)
Components with no data are always serialize to an empty string.
Definition: Component.hh:387
Helper trait to determine if a type is shared_ptr or not.
Definition: Component.hh:33
Component & operator=(Component &&_component) noexcept=default
Move assignment operator.
uint64_t ComponentTypeId
A unique identifier for a component type. A component type must be derived from components::BaseCompo...
Definition: Types.hh:71
void Deserialize(std::istream &_in) override
Fills a component based on a stream with a serialized data. By default, it will do nothing...
Definition: Component.hh:506
Specialization for components that don&#39;t wrap any data. This class to be used to create simple compon...
Definition: Component.hh:369
ComponentPrivate(DataType _data)
Constructor.
Definition: Component.hh:419
A component type that wraps any data type. The intention is for this class to be used to create simpl...
Definition: Component.hh:290
friend std::istream & operator>>(std::istream &_in, Component< NoData, Identifier > &)
Components with no data are always serialize to an empty string.
Definition: Component.hh:397
This library is part of the Ignition Robotics project.
Definition: Altimeter.hh:25
DataType & Data()
Get the mutable component data.
Definition: Component.hh:460
Base class for all components.
Definition: Component.hh:195