filter_chain.hpp
Go to the documentation of this file.
1 #pragma once
2 
11 #include <functional>
12 #include <memory>
13 #include <mutex>
14 #include <string>
15 #include <unordered_set>
16 #include <vector>
17 
18 #include <ros/common.h>
19 #if ROS_VERSION_MINIMUM(1, 15, 0)
20 #include <filters/filter_base.hpp>
21 #include <filters/filter_chain.hpp>
22 #else
23 #include <filters/filter_base.h>
24 #include <filters/filter_chain.h>
25 #endif
26 
27 #include <nodelet/nodelet.h>
28 
31 
32 namespace cras
33 {
34 
41 template<typename F>
43 {
44 public:
53  typedef ::std::function<
54  void(const F& data, const size_t filterNum, const ::std::string& name, const ::std::string& type)>
56 
66  typedef ::std::function<
67  void(const F& data, const size_t filterNum, const ::std::string& name, const ::std::string& type, bool success)>
69 
77  explicit FilterChain(const ::std::string& dataType, const FilterFinishedCallback& filterFinishedCallback = {},
79  const ::cras::LogHelperPtr& logHelper = ::std::make_shared<::cras::NodeLogHelper>());
80 
87  void setNodelet(const ::nodelet::Nodelet* nodelet);
88 
93  void setFilterStartCallback(const FilterStartCallback& callback);
94 
100 
108  bool update(const F& data_in, F& data_out);
109 
114  void disableFilter(const ::std::string& name);
115 
120  void enableFilter(const ::std::string& name);
121 
127  void setDisabledFilters(::std::unordered_set<::std::string> filters);
128 
133  ::std::unordered_set<::std::string> getDisabledFilters() const;
134 
140  bool clear();
141 
146  ::std::vector<::std::shared_ptr<::filters::FilterBase<F>>> getActiveFilters() const;
147 
148 protected:
154  void callStartCallback(const F& data, size_t filterNum);
155 
162  void callFinishedCallback(const F& data, size_t filterNum, bool succeeded);
163 
167  void updateActiveFilters();
168 
171 
174 
176  ::std::unordered_set<::std::string> disabledFilters;
177 
179  ::std::vector<::std::shared_ptr<::filters::FilterBase<F>>> activeFilters;
180 
182  mutable ::std::mutex activeFiltersMutex;
183 
185  bool initialized {false};
186 
187  // Parent class buffers are private, so we create our own
188 
191 
194 };
195 
196 }
197 
198 #include "impl/filter_chain.hpp"
cras::FilterChain::filterFinishedCallback
FilterFinishedCallback filterFinishedCallback
The optional callback to call when a filter finishes its work.
Definition: filter_chain.hpp:173
filters
cras
Definition: any.hpp:15
cras::FilterChain::updateActiveFilters
void updateActiveFilters()
Update the contents of activeFilters with just the filters that have not been disabled.
cras::FilterChain::getDisabledFilters
::std::unordered_set<::std::string > getDisabledFilters() const
Get which filters are temporarily disabled.
cras::FilterChain::callStartCallback
void callStartCallback(const F &data, size_t filterNum)
If filterStartCallback is set, call it.
cras::HasLogger
Convenience base class for providing this->log and getCrasLogger(). Just add it as a base to your cla...
Definition: log_utils.h:229
cras::FilterChain::FilterStartCallback
::std::function< void(const F &data, const size_t filterNum, const ::std::string &name, const ::std::string &type)> FilterStartCallback
Callback to be called before each filter processes the data.
Definition: filter_chain.hpp:55
cras::FilterChain
Definition: filter_chain.hpp:42
cras::FilterChain::FilterFinishedCallback
::std::function< void(const F &data, const size_t filterNum, const ::std::string &name, const ::std::string &type, bool success)> FilterFinishedCallback
Callback to be called after each filter processes the data.
Definition: filter_chain.hpp:68
data
data
cras::FilterChain::setDisabledFilters
void setDisabledFilters(::std::unordered_set<::std::string > filters)
Set which filters are temporarily disabled. This overrides any previous calls to disableFilter() and ...
filters::FilterChain
cras::FilterChain::setNodelet
void setNodelet(const ::nodelet::Nodelet *nodelet)
Inform this chain that it is running in the given nodelet, so that it can do appropriate optimization...
filter_base.hpp
cras::FilterChain::clear
bool clear()
Clear all filters from this chain. This function intentionally shadows filters::FilterChain::clear() ...
node.h
Log helper redirecting the logging calls to ROS_ macros.
cras::FilterChain::update
bool update(const F &data_in, F &data_out)
Do the filtering. This function intentionally shadows filters::FilterChain::update() which is non-vir...
cras::FilterChain::callFinishedCallback
void callFinishedCallback(const F &data, size_t filterNum, bool succeeded)
If filterFinishedCallback is set, call it.
cras::FilterChain::setFilterStartCallback
void setFilterStartCallback(const FilterStartCallback &callback)
Set the filter start callback.
cras::FilterChain::disabledFilters
::std::unordered_set<::std::string > disabledFilters
A set of filters that have been temporarily disabled.
Definition: filter_chain.hpp:176
log_utils.h
ROS logging helpers.
cras::FilterChain::setFilterFinishedCallback
void setFilterFinishedCallback(const FilterFinishedCallback &callback)
Set the filter finished callback.
cras::FilterChain::enableFilter
void enableFilter(const ::std::string &name)
Enable the temporarily disabled filter with the given name.
filter_chain.h
cras::LogHelperPtr
::cras::LogHelper::Ptr LogHelperPtr
Pointer to LogHelper.
Definition: log_utils.h:202
nodelet
nodelet.h
cras::FilterChain::buffer1
F buffer1
A temporary intermediate buffer.
Definition: filter_chain.hpp:193
cras::FilterChain::FilterChain
FilterChain(const ::std::string &dataType, const FilterFinishedCallback &filterFinishedCallback={}, const FilterStartCallback &filterStartCallback={}, const ::cras::LogHelperPtr &logHelper=::std::make_shared<::cras::NodeLogHelper >())
Construct a filter chain.
cras::FilterChain::buffer0
F buffer0
A temporary intermediate buffer.
Definition: filter_chain.hpp:190
filter_chain.hpp
cras::FilterChain::getActiveFilters
::std::vector<::std::shared_ptr<::filters::FilterBase< F > > > getActiveFilters() const
Get a copy of the list of active filters.
cras::FilterChain::disableFilter
void disableFilter(const ::std::string &name)
Temporarily disable the filter with the given name.
cras::FilterChain::activeFilters
::std::vector<::std::shared_ptr<::filters::FilterBase< F > > > activeFilters
A list of filters that should be treated as active and should act on the input data.
Definition: filter_chain.hpp:179
filter_base.h
cras::FilterChain::initialized
bool initialized
Whether this filter chain has been initialized (gets set by first update() and cleared by clear()).
Definition: filter_chain.hpp:185
cras::FilterChain::activeFiltersMutex
mutable ::std::mutex activeFiltersMutex
Mutex protecting activeFilters access.
Definition: filter_chain.hpp:182
cras::FilterChain::filterStartCallback
FilterStartCallback filterStartCallback
The optional callback to call when a filter starts its work.
Definition: filter_chain.hpp:170


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Mon Jun 17 2024 02:48:56