nodelet_with_shared_tf_buffer.hpp
Go to the documentation of this file.
1 #pragma once
2 
3 // SPDX-License-Identifier: BSD-3-Clause
4 // SPDX-FileCopyrightText: Czech Technical University in Prague
5 
12 #include <memory>
13 #include <string>
14 
15 #include <nodelet/nodelet.h>
17 #include <tf2_ros/buffer.h>
19 
22 
23 namespace cras
24 {
25 
26 namespace impl
27 {
28 // forward declaration
29 struct NodeletWithSharedTfBufferPrivate;
30 }
31 
37 {
38 public:
43  virtual void setBuffer(const ::std::shared_ptr<::tf2_ros::Buffer>& buffer) = 0;
44 
53  virtual ::cras::NodeletAwareTFBuffer& getBuffer() const = 0;
54 
59  virtual bool usesSharedBuffer() const = 0;
60 
64  virtual void reset() = 0;
65 };
66 
75 template <typename NodeletType = ::nodelet::Nodelet>
76 struct NodeletWithSharedTfBuffer : public virtual NodeletType, public ::cras::NodeletWithSharedTfBufferInterface,
78 {
79 public:
81  ~NodeletWithSharedTfBuffer() override;
82 
83  void setBuffer(const ::std::shared_ptr<::tf2_ros::Buffer>& buffer) override;
84  ::cras::NodeletAwareTFBuffer& getBuffer() const override;
85  ::std::shared_ptr<::cras::NodeletAwareTFBuffer> getBufferPtr() const;
86  bool usesSharedBuffer() const override;
87 
88  virtual void onInit();
89 
90  void reset() override;
91 
92 protected:
93  using NodeletType::getName;
94 
95 private:
97  ::std::unique_ptr<::cras::impl::NodeletWithSharedTfBufferPrivate> data;
98 };
99 
100 }
101 
102 #include "impl/nodelet_with_shared_tf_buffer.hpp"
cras::NodeletWithSharedTfBuffer::NodeletWithSharedTfBuffer
NodeletWithSharedTfBuffer()
cras::NodeletWithSharedTfBufferInterface::usesSharedBuffer
virtual bool usesSharedBuffer() const =0
Whether the buffer set using setBuffer() is used or a standalone buffer has been automatically create...
cras
Definition: any.hpp:15
cras::NodeletWithSharedTfBufferInterface::setBuffer
virtual void setBuffer(const ::std::shared_ptr<::tf2_ros::Buffer > &buffer)=0
Set the TF buffer to be used by the nodelet. If this method is not called, a standalone buffer is cre...
cras::NodeletWithSharedTfBuffer::reset
void reset() override
Reset the TF buffer. If a shared buffer is used, it is not reset by this call and its owner is respon...
buffer.h
cras::NodeletWithSharedTfBufferInterface::getBuffer
virtual ::cras::NodeletAwareTFBuffer & getBuffer() const =0
Get the TF buffer used by the nodelet. If none has been set by setBuffer(), a buffer is automatically...
cras::NodeletWithSharedTfBuffer::onInit
virtual void onInit()
cras::NodeletWithSharedTfBuffer::getBuffer
::cras::NodeletAwareTFBuffer & getBuffer() const override
Get the TF buffer used by the nodelet. If none has been set by setBuffer(), a buffer is automatically...
nodelet_aware_tf_buffer.h
TF buffer that can be correctly interrupted by nodelet unload.
cras::NodeletWithSharedTfBuffer::data
::std::unique_ptr<::cras::impl::NodeletWithSharedTfBufferPrivate > data
PIMPL.
Definition: nodelet_with_shared_tf_buffer.hpp:97
cras::NodeletWithSharedTfBufferInterface
Public non-template API of NodeletWithSharedTfBuffer. Dynamic_cast a nodelet to this type if you need...
Definition: nodelet_with_shared_tf_buffer.hpp:36
cras::NodeletWithSharedTfBuffer::usesSharedBuffer
bool usesSharedBuffer() const override
Whether the buffer set using setBuffer() is used or a standalone buffer has been automatically create...
transform_listener.h
macros_generated.h
cras::NodeletAwareTFBuffer
Definition: nodelet_aware_tf_buffer.h:27
cras::TimeJumpResettable
Interface for resettable nodes and nodelets. Automatic reset on time jumps.
Definition: resettable.h:78
cras::NodeletWithSharedTfBuffer::setBuffer
void setBuffer(const ::std::shared_ptr<::tf2_ros::Buffer > &buffer) override
Set the TF buffer to be used by the nodelet. If this method is not called, a standalone buffer is cre...
nodelet.h
cras::NodeletWithSharedTfBuffer::~NodeletWithSharedTfBuffer
~NodeletWithSharedTfBuffer() override
cras::NodeletWithSharedTfBuffer::getBufferPtr
::std::shared_ptr<::cras::NodeletAwareTFBuffer > getBufferPtr() const
cras::NodeletWithSharedTfBuffer
A nodelet mixin that allows to use a tf2_ros::Buffer provided by the nodelet manager (which should sa...
Definition: nodelet_with_shared_tf_buffer.hpp:76
resettable.h
Interface for resettable nodes and nodelets. Automatic reset on time jumps.
cras::NodeletWithSharedTfBufferInterface::reset
virtual void reset()=0
Reset the TF buffer. If a shared buffer is used, it is not reset by this call and its owner is respon...


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Dec 14 2024 03:51:04