tf_pair.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Copyright (c) 2014, Willow Garage, Inc.
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions
8  * are met:
9  *
10  * * Redistributions of source code must retain the above copyright
11  * notice, this list of conditions and the following disclaimer.
12  * * Redistributions in binary form must reproduce the above
13  * copyright notice, this list of conditions and the following
14  * disclaimer in the documentation and/or other materials provided
15  * with the distribution.
16  * * Neither the name of the Willow Garage nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * Author: Julius Kammerl (jkammerl@willowgarage.com)
34  *
35  */
36 
37 
38 #include <tf/tfMessage.h>
39 #include <tf/transform_datatypes.h>
40 
41 
42 class TFPair
43 {
44 public:
45 
46  TFPair() :
47  is_okay(true),
48  angular_thres_(0.0f),
49  trans_thres_(0.0f),
50  updated_(false),
52  {
53  }
54 
55  TFPair(const std::string& source_frame,
56  const std::string& target_frame,
57  float angular_thres = 0.0f,
58  float trans_thres = 0.0f) :
59  is_okay(true),
60  source_frame_(source_frame),
61  target_frame_(target_frame),
62  angular_thres_(angular_thres),
63  trans_thres_(trans_thres),
64  updated_(false),
66  {
67  }
68 
69  ~TFPair()
70  {
71  }
72 
73  void setSourceFrame(const std::string& source_frame)
74  {
75  source_frame_ = source_frame;
76  updated_ = true;
77  }
78 
79  const std::string& getSourceFrame() const
80  {
81  return source_frame_;
82  }
83 
84  void setTargetFrame(const std::string& target_frame)
85  {
86  target_frame_ = target_frame;
87  updated_ = true;
88  }
89 
90  const std::string& getTargetFrame() const
91  {
92  return target_frame_;
93  }
94 
95  void setAngularThres(float angular_thres)
96  {
97  angular_thres_ = angular_thres;
98  updated_ = true;
99  }
100 
101  float getAngularThres()
102  {
104  }
105 
106  void setTransThres(float trans_thres)
107  {
108  trans_thres_ = trans_thres;
109  updated_ = true;
110  }
111 
112  float getTransThres()
113  {
114  return trans_thres_;
115  }
116 
117  void updateTransform(geometry_msgs::TransformStamped& update)
118  {
120  updated_ = true;
121  }
122 
123  void transmissionTriggered()
124  {
126  }
127 
128  bool updateNeeded()
129  {
130  bool result = false;
131 
132  if (updated_)
133  {
134  if (trans_thres_ == 0.0 || angular_thres_ == 0.0
138  {
139  result = true;
141  }
142  }
143 
144  updated_ = false;
145 
146  return result;
147  }
148 
149  const std::string getID()
150  {
152  }
153 
154 public:
155  bool is_okay;
156 private:
158  std::string source_frame_;
159  std::string target_frame_;
160 
161  float angular_thres_;
163 
166 
167  bool updated_;
168  bool first_transmission_;
169 
170 };
171 
tf::Transform::getRotation
Quaternion getRotation() const
TFPair::transmissionTriggered
void transmissionTriggered()
Definition: tf_pair.h:157
TFPair::setAngularThres
void setAngularThres(float angular_thres)
Definition: tf_pair.h:129
boost::shared_ptr
TFPair::setSourceFrame
void setSourceFrame(const std::string &source_frame)
Definition: tf_pair.h:107
TFPair::source_frame_
std::string source_frame_
Definition: tf_pair.h:192
TFPair::getTargetFrame
const std::string & getTargetFrame() const
Definition: tf_pair.h:124
TFPair::tf_received_
tf::Transform tf_received_
Definition: tf_pair.h:199
TFPair::is_okay
bool is_okay
Definition: tf_pair.h:189
tf::transformMsgToTF
static void transformMsgToTF(const geometry_msgs::Transform &msg, Transform &bt)
TFPair::~TFPair
~TFPair()
Definition: tf_pair.h:103
TFPair::updateTransform
void updateTransform(geometry_msgs::TransformStamped &update)
Definition: tf_pair.h:151
TFPair::trans_thres_
float trans_thres_
Definition: tf_pair.h:196
TFPair::tf_transmitted_
tf::Transform tf_transmitted_
Definition: tf_pair.h:198
TFPair::first_transmission_
bool first_transmission_
Definition: tf_pair.h:202
f
f
TFPair::target_frame_
std::string target_frame_
Definition: tf_pair.h:193
TFPair::getID
const std::string getID()
Definition: tf_pair.h:183
update
void update(const std::string &key, const XmlRpc::XmlRpcValue &v)
TFPairPtr
boost::shared_ptr< TFPair > TFPairPtr
Definition: tf_pair.h:172
TFPair::TFPair
TFPair()
Definition: tf_pair.h:80
TFPair::getAngularThres
float getAngularThres()
Definition: tf_pair.h:135
TFPair::angular_thres_
float angular_thres_
Definition: tf_pair.h:195
TFPair::getSourceFrame
const std::string & getSourceFrame() const
Definition: tf_pair.h:113
TFPair::setTransThres
void setTransThres(float trans_thres)
Definition: tf_pair.h:140
tf::Transform
transform_datatypes.h
TFPair::updated_
bool updated_
Definition: tf_pair.h:201
TFPair::updateNeeded
bool updateNeeded()
Definition: tf_pair.h:162
tf::Quaternion::angle
tfScalar angle(const Quaternion &q) const
TFPair::setTargetFrame
void setTargetFrame(const std::string &target_frame)
Definition: tf_pair.h:118
TFPair
Definition: tf_pair.h:42
tf::Transform::getOrigin
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
TFPair::getTransThres
float getTransThres()
Definition: tf_pair.h:146


tf2_web_republisher
Author(s): Julius Kammer
autogenerated on Wed Mar 2 2022 01:05:42