tf_projection_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2017, the neonavigation authors
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 copyright holder 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 
30 #include <ros/ros.h>
31 
32 #include <tf2/utils.h>
37 
38 #include <string>
39 
41 
43 {
44 private:
51 
52  double rate_;
53  double tf_tolerance_;
54  bool flat_;
57 
58  std::string source_frame_;
60  std::string parent_frame_;
61  std::string projected_frame_;
62 
63 public:
65  : nh_()
66  , pnh_("~")
68  {
69  if (pnh_.hasParam("base_link_frame") ||
70  pnh_.hasParam("projection_frame") ||
71  pnh_.hasParam("target_frame") ||
72  pnh_.hasParam("frame"))
73  {
74  ROS_ERROR(
75  "tf_projection parameters \"base_link_frame\", \"projection_frame\", \"target_frame\", and \"frame\" "
76  "are replaced by \"source_frame\", \"projection_surface_frame\", \"parent_frame\", and \"projected_frame\"");
77 
78  pnh_.param("base_link_frame", source_frame_, std::string("base_link"));
79  pnh_.param("projection_frame", projection_surface_frame_, std::string("map"));
80  pnh_.param("target_frame", parent_frame_, std::string("map"));
81  pnh_.param("frame", projected_frame_, std::string("base_link_projected"));
82  }
83  else
84  {
85  pnh_.param("source_frame", source_frame_, std::string("base_link"));
86  pnh_.param("projection_surface_frame", projection_surface_frame_, std::string("map"));
87  pnh_.param("parent_frame", parent_frame_, std::string("map"));
88  pnh_.param("projected_frame", projected_frame_, std::string("base_link_projected"));
89  }
90 
91  pnh_.param("hz", rate_, 10.0);
92  pnh_.param("tf_tolerance", tf_tolerance_, 0.1);
93  pnh_.param("flat", flat_, false);
94 
95  pnh_.param("project_posture", project_posture_, false);
96  pnh_.param("align_all_posture_to_source", align_all_posture_to_source_, false);
97  }
98  void process()
99  {
101  tf2::Stamped<tf2::Transform> trans_target;
102  try
103  {
104  tf2::fromMsg(
106  trans);
107  tf2::fromMsg(
109  trans_target);
110  }
111  catch (tf2::TransformException& e)
112  {
113  ROS_WARN_THROTTLE(1.0, "%s", e.what());
114  return;
115  }
116 
117  if (!trans.stamp_.isZero())
119 
120  if (project_posture_)
121  {
123  {
124  const tf2::Quaternion rot(trans.getRotation());
125  const tf2::Quaternion rot_yaw(tf2::Vector3(0.0, 0.0, 1.0), tf2::getYaw(rot));
126  const tf2::Transform rot_inv(rot_yaw * rot.inverse());
127  trans.setData(rot_inv * trans);
128  }
129  else
130  {
131  const float yaw = tf2::getYaw(trans.getRotation());
132  trans.setRotation(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), yaw));
133  }
134  }
135 
136  const tf2::Stamped<tf2::Transform> result(
137  track_odometry::projectTranslation(trans, trans_target),
138  trans.stamp_,
139  parent_frame_);
140 
141  geometry_msgs::TransformStamped trans_out = tf2::toMsg(result);
142  if (flat_)
143  {
144  const double yaw = tf2::getYaw(trans_out.transform.rotation);
145  trans_out.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), yaw));
146  }
147  trans_out.child_frame_id = projected_frame_;
148 
149  if (trans.stamp_.isZero())
150  {
152  }
153  else
154  {
155  tf_broadcaster_.sendTransform(trans_out);
156  }
157  }
158  void cbTimer(const ros::TimerEvent& event)
159  {
160  process();
161  }
162  void spin()
163  {
164  ros::Timer timer = nh_.createTimer(
166  ros::spin();
167  }
168 };
169 
170 int main(int argc, char* argv[])
171 {
172  ros::init(argc, argv, "tf_projection");
173 
174  TfProjectionNode proj;
175  proj.spin();
176 
177  return 0;
178 }
TfProjectionNode::nh_
ros::NodeHandle nh_
Definition: tf_projection_node.cpp:45
tf2_ros::StaticTransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
TfProjectionNode::flat_
bool flat_
Definition: tf_projection_node.cpp:54
TfProjectionNode::tf_static_broadcaster_
tf2_ros::StaticTransformBroadcaster tf_static_broadcaster_
Definition: tf_projection_node.cpp:49
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
tf2::Stamped::setData
void setData(const T &input)
tf2::getYaw
double getYaw(const A &a)
tf2::fromMsg
void fromMsg(const A &, B &b)
utils.h
ROS_WARN_THROTTLE
#define ROS_WARN_THROTTLE(period,...)
ros.h
TfProjectionNode::pnh_
ros::NodeHandle pnh_
Definition: tf_projection_node.cpp:46
TfProjectionNode::spin
void spin()
Definition: tf_projection_node.cpp:162
TfProjectionNode::tf_buffer_
tf2_ros::Buffer tf_buffer_
Definition: tf_projection_node.cpp:47
TfProjectionNode::projection_surface_frame_
std::string projection_surface_frame_
Definition: tf_projection_node.cpp:59
TfProjectionNode::TfProjectionNode
TfProjectionNode()
Definition: tf_projection_node.cpp:64
tf_projection.h
TfProjectionNode::tf_listener_
tf2_ros::TransformListener tf_listener_
Definition: tf_projection_node.cpp:48
tf2::Stamped
transform_broadcaster.h
main
int main(int argc, char *argv[])
Definition: tf_projection_node.cpp:170
tf2_ros::TransformListener
TfProjectionNode::project_posture_
bool project_posture_
Definition: tf_projection_node.cpp:55
tf2_ros::StaticTransformBroadcaster
TfProjectionNode::rate_
double rate_
Definition: tf_projection_node.cpp:52
TfProjectionNode::cbTimer
void cbTimer(const ros::TimerEvent &event)
Definition: tf_projection_node.cpp:158
TfProjectionNode
Definition: tf_projection_node.cpp:42
TfProjectionNode::parent_frame_
std::string parent_frame_
Definition: tf_projection_node.cpp:60
tf2_ros::TransformBroadcaster::sendTransform
void sendTransform(const geometry_msgs::TransformStamped &transform)
TfProjectionNode::source_frame_
std::string source_frame_
Definition: tf_projection_node.cpp:58
TfProjectionNode::process
void process()
Definition: tf_projection_node.cpp:98
TimeBase< Time, Duration >::isZero
bool isZero() const
tf2::Transform
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
tf2::Stamped::stamp_
ros::Time stamp_
tf2_ros::Buffer
ros::TimerEvent
TfProjectionNode::projected_frame_
std::string projected_frame_
Definition: tf_projection_node.cpp:61
track_odometry::projectTranslation
tf2::Transform projectTranslation(const tf2::Transform &trans, const tf2::Transform &trans_target)
Definition: tf_projection.cpp:35
transform_listener.h
TfProjectionNode::tf_tolerance_
double tf_tolerance_
Definition: tf_projection_node.cpp:53
tf2::Quaternion::inverse
Quaternion inverse() const
ros::Time
ROS_ERROR
#define ROS_ERROR(...)
tf2_ros::TransformBroadcaster
TfProjectionNode::align_all_posture_to_source_
bool align_all_posture_to_source_
Definition: tf_projection_node.cpp:56
static_transform_broadcaster.h
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2::Quaternion
tf2_geometry_msgs.h
tf2::toMsg
B toMsg(const A &a)
ros::spin
ROSCPP_DECL void spin()
tf2::TransformException
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
TfProjectionNode::tf_broadcaster_
tf2_ros::TransformBroadcaster tf_broadcaster_
Definition: tf_projection_node.cpp:50
tf2_ros::Buffer::lookupTransform
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, const ros::Duration timeout) const
ros::NodeHandle


track_odometry
Author(s): Atsushi Watanabe
autogenerated on Fri May 16 2025 02:15:18