tf_filter.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * fkie_message_filters
4  * Copyright © 2018-2020 Fraunhofer FKIE
5  * Author: Timo Röhling
6  *
7  * Licensed under the Apache License, Version 2.0 (the "License");
8  * you may not use this file except in compliance with the License.
9  * You may obtain a copy of the License at
10  *
11  * http://www.apache.org/licenses/LICENSE-2.0
12  *
13  * Unless required by applicable law or agreed to in writing, software
14  * distributed under the License is distributed on an "AS IS" BASIS,
15  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16  * See the License for the specific language governing permissions and
17  * limitations under the License.
18  *
19  ****************************************************************************/
20 
21 #ifndef INCLUDE_FKIE_MESSAGE_FILTERS_TF_FILTER_H_
22 #define INCLUDE_FKIE_MESSAGE_FILTERS_TF_FILTER_H_
23 
24 #include "filter.h"
25 #include <tf2/buffer_core.h>
26 #include <ros/node_handle.h>
28 
29 namespace fkie_message_filters
30 {
31 
37 enum class TfFilterResult
38 {
51 };
52 
71 template<class... Inputs>
72 class TfFilter : public Filter<IO<Inputs...>, IO<Inputs...>>
73 {
74 public:
76  using FilterFailureCB = std::function<void(const Inputs&..., TfFilterResult)>;
77 
82  TfFilter() noexcept {}
94  TfFilter(tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, const ros::NodeHandle& nh) noexcept;
107  TfFilter(tf2::BufferCore& bc, const std::string& target_frame, uint32_t queue_size, ros::CallbackQueueInterface* cbq) noexcept;
119  TfFilter(tf2::BufferCore& bc, const ros::V_string& target_frames, uint32_t queue_size, const ros::NodeHandle& nh) noexcept;
132  TfFilter(tf2::BufferCore& bc, const ros::V_string& target_frames, uint32_t queue_size, ros::CallbackQueueInterface* cbq) noexcept;
144  void init(tf2::BufferCore& bc, uint32_t queue_size, const ros::NodeHandle& nh) noexcept;
157  void init(tf2::BufferCore& bc, uint32_t queue_size, ros::CallbackQueueInterface* cbq) noexcept;
164  void set_target_frame (const std::string& target_frame);
171  void set_target_frames (const ros::V_string& target_frames);
178  void reset() noexcept override;
189 protected:
190  void receive (const Inputs&... in) override;
191 private:
192  using MessageTuple = std::tuple<Inputs...>;
193  struct Impl;
194  class RosCB;
195  std::shared_ptr<Impl> impl_;
196  void transformable(tf2::TransformableRequestHandle request_handle, const std::string& target_frame, const std::string& source_frame, ros::Time time, tf2::TransformableResult result);
197  void report_failure (std::unique_lock<std::mutex>&, const MessageTuple&, TfFilterResult);
198  void send_message (std::unique_lock<std::mutex>&, const MessageTuple& m);
199 };
200 
201 template<class... Inputs>
202 class TfFilter<IO<Inputs...>> : public TfFilter<Inputs...> {};
203 
204 } // namespace fkie_message_filters
205 
206 #include "tf_filter_impl.h"
207 
208 #endif /* INCLUDE_FKIE_MESSAGE_FILTERS_TF_FILTER_H_ */
fkie_message_filters
Definition: buffer.h:33
node_handle.h
Filter
filter.h
fkie_message_filters::TfFilterResult
TfFilterResult
TF transformation results.
Definition: tf_filter.h:55
fkie_message_filters::TfFilter::set_filter_failure_function
void set_filter_failure_function(FilterFailureCB cb)
Register callback for failed transforms.
Definition: tf_filter_impl.h:246
fkie_message_filters::IO
Group multiple data types as filter input or output.
Definition: io.h:45
ros
fkie_message_filters::TfFilterResult::TransformFailed
@ TransformFailed
The requested transform is unavailable.
callback_queue_interface.h
fkie_message_filters::TfFilter::receive
void receive(const Inputs &... in) override
Process incoming data.
Definition: tf_filter_impl.h:254
fkie_message_filters::TfFilterResult::QueueOverflow
@ QueueOverflow
The message has been dropped because of a queue overflow.
fkie_message_filters::TfFilterResult::UnknownFailure
@ UnknownFailure
Unknown failure reason.
fkie_message_filters::TfFilter::report_failure
void report_failure(std::unique_lock< std::mutex > &, const MessageTuple &, TfFilterResult)
Definition: tf_filter_impl.h:339
fkie_message_filters::TfFilter::set_target_frames
void set_target_frames(const ros::V_string &target_frames)
Choose the TF target frames.
Definition: tf_filter_impl.h:213
fkie_message_filters::TfFilter::transformable
void transformable(tf2::TransformableRequestHandle request_handle, const std::string &target_frame, const std::string &source_frame, ros::Time time, tf2::TransformableResult result)
Definition: tf_filter_impl.h:299
TransformableRequestHandle
uint64_t TransformableRequestHandle
fkie_message_filters::TfFilter< Inputs... >::MessageTuple
std::tuple< Inputs... > MessageTuple
Definition: tf_filter.h:210
fkie_message_filters::TfFilter
Wait for TF transformations for incoming messages.
Definition: tf_filter.h:90
fkie_message_filters::TfFilterResult::EmptyFrameID
@ EmptyFrameID
The message has an empty TF frame ID and cannot be transformed.
buffer_core.h
fkie_message_filters::TfFilter::send_message
void send_message(std::unique_lock< std::mutex > &, const MessageTuple &m)
Definition: tf_filter_impl.h:364
fkie_message_filters::TfFilterResult::TransformAvailable
@ TransformAvailable
Success.
tf2::BufferCore
fkie_message_filters::TfFilter::reset
void reset() noexcept override
Reset filter state.
Definition: tf_filter_impl.h:232
std
fkie_message_filters::TfFilter::impl_
std::shared_ptr< Impl > impl_
Definition: tf_filter.h:212
tf2
fkie_message_filters::TfFilter::FilterFailureCB
std::function< void(const Inputs &..., TfFilterResult)> FilterFailureCB
Callback for failed transform queries.
Definition: tf_filter.h:94
fkie_message_filters::TfFilter::init
void init(tf2::BufferCore &bc, uint32_t queue_size, const ros::NodeHandle &nh) noexcept
Initialize the filter.
Definition: tf_filter_impl.h:207
fkie_message_filters::TfFilterResult::TransformExpired
@ TransformExpired
The requested transform is no longer available, likely because the message is too old.
ros::V_string
std::vector< std::string > V_string
fkie_message_filters::TfFilter::TfFilter
TfFilter() noexcept
Empty constructor.
Definition: tf_filter.h:100
TransformableResult
TransformableResult
ros::CallbackQueueInterface
ros::NodeHandle
fkie_message_filters::TfFilter::set_target_frame
void set_target_frame(const std::string &target_frame)
Choose the TF target frame.
Definition: tf_filter_impl.h:226
tf_filter_impl.h


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Wed Mar 2 2022 00:18:57