TransformBroadcaster.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016, Bielefeld University, CITEC
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: Robert Haschke <rhaschke@techfak.uni-bielefeld.de>
30  */
31 
32 #include "TransformBroadcaster.h"
33 #include <mutex>
34 
38 std::shared_ptr<tf2_ros::StaticTransformBroadcaster> getBroadCasterInstance() {
39  static std::mutex m;
40  static std::weak_ptr<tf2_ros::StaticTransformBroadcaster> singleton_;
41 
42  std::lock_guard<std::mutex> lock(m);
43  if (singleton_.expired()) {
44  auto result = std::make_shared<tf2_ros::StaticTransformBroadcaster>();
45  singleton_ = result;
46  return result;
47  }
48  return singleton_.lock();
49 }
50 
51 TransformBroadcaster::TransformBroadcaster(const QString& parent_frame,
52  const QString& child_frame,
53  QObject* parent)
54  : QObject(parent), broadcaster_(getBroadCasterInstance()), valid_(false), enabled_(false) {
55  setPosition(0, 0, 0);
56  setQuaternion(0, 0, 0, 1);
57 
58  setParentFrame(parent_frame);
59  setChildFrame(child_frame);
60 
61  enabled_ = true;
62  check();
63  send();
64 }
65 
66 const geometry_msgs::TransformStamped& TransformBroadcaster::value() const {
67  return msg_;
68 }
69 
70 void TransformBroadcaster::setValue(const geometry_msgs::TransformStamped& tf) {
71  msg_ = tf;
72  check();
73  send();
74 }
75 
76 void TransformBroadcaster::setPose(const geometry_msgs::Pose& pose) {
77  bool old = enabled_;
78  enabled_ = false;
79 
80  const geometry_msgs::Point& p = pose.position;
81  setPosition(p.x, p.y, p.z);
82 
83  const geometry_msgs::Quaternion& q = pose.orientation;
84  setQuaternion(q.x, q.y, q.z, q.w);
85 
86  enabled_ = old;
87  send();
88 }
89 
91  return enabled_;
92 }
93 
94 void TransformBroadcaster::setEnabled(bool bEnabled) {
95  enabled_ = bEnabled;
96  check();
97  send();
98 }
99 
100 void TransformBroadcaster::setDisabled(bool bDisabled) {
101  setEnabled(!bDisabled);
102 }
103 
104 void TransformBroadcaster::setParentFrame(const QString& frame) {
105  msg_.header.frame_id = frame.toStdString();
106  check();
107  send();
108 }
109 
110 void TransformBroadcaster::setChildFrame(const QString& frame) {
111  msg_.child_frame_id = frame.toStdString();
112  check();
113  send();
114 }
115 
116 void TransformBroadcaster::setPosition(const Eigen::Vector3d& p) {
117  setPosition(p.x(), p.y(), p.z());
118 }
119 
120 void TransformBroadcaster::setQuaternion(const Eigen::Quaterniond& q) {
121  setQuaternion(q.x(), q.y(), q.z(), q.w());
122 }
123 
124 void TransformBroadcaster::setPosition(double x, double y, double z) {
125  msg_.transform.translation.x = x;
126  msg_.transform.translation.y = y;
127  msg_.transform.translation.z = z;
128  send();
129 }
130 
131 void TransformBroadcaster::setQuaternion(double x, double y, double z, double w) {
132  msg_.transform.rotation.x = x;
133  msg_.transform.rotation.y = y;
134  msg_.transform.rotation.z = z;
135  msg_.transform.rotation.w = w;
136  send();
137 }
138 
140  if (enabled_ && valid_) {
141  msg_.header.stamp = ros::Time::now();
142  ++msg_.header.seq;
143  broadcaster_->sendTransform(msg_);
144  ros::spinOnce();
145  }
146 }
147 
149  valid_ = !msg_.header.frame_id.empty() && !msg_.child_frame_id.empty() &&
150  msg_.header.frame_id != msg_.child_frame_id;
151 }
void setDisabled(bool bDisabled=true)
const geometry_msgs::TransformStamped & value() const
void setQuaternion(const Eigen::Quaterniond &q)
void setChildFrame(const QString &frame)
geometry_msgs::TransformStamped msg_
void setParentFrame(const QString &frame)
void setEnabled(bool bEnabled=true)
TransformBroadcaster(const QString &parent_frame="", const QString &child_frame="", QObject *parent=nullptr)
void setPosition(const Eigen::Vector3d &p)
static Time now()
void setPose(const geometry_msgs::Pose &pose)
std::shared_ptr< tf2_ros::StaticTransformBroadcaster > getBroadCasterInstance()
void setValue(const geometry_msgs::TransformStamped &tf)
ROSCPP_DECL void spinOnce()
std::shared_ptr< tf2_ros::StaticTransformBroadcaster > broadcaster_


agni_tf_tools
Author(s): Robert Haschke
autogenerated on Tue Apr 13 2021 02:29:55