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>
36 
37 #include <string>
38 
40 
42 {
43 private:
49 
50  double rate_;
51  double tf_tolerance_;
52  bool flat_;
54 
55  std::string source_frame_;
57  std::string parent_frame_;
58  std::string projected_frame_;
59 
60 public:
62  : nh_()
63  , pnh_("~")
64  , tf_listener_(tf_buffer_)
65  {
66  if (pnh_.hasParam("base_link_frame") ||
67  pnh_.hasParam("projection_frame") ||
68  pnh_.hasParam("target_frame") ||
69  pnh_.hasParam("frame"))
70  {
71  ROS_ERROR(
72  "tf_projection parameters \"base_link_frame\", \"projection_frame\", \"target_frame\", and \"frame\" "
73  "are replaced by \"source_frame\", \"projection_surface_frame\", \"parent_frame\", and \"projected_frame\"");
74 
75  pnh_.param("base_link_frame", source_frame_, std::string("base_link"));
76  pnh_.param("projection_frame", projection_surface_frame_, std::string("map"));
77  pnh_.param("target_frame", parent_frame_, std::string("map"));
78  pnh_.param("frame", projected_frame_, std::string("base_link_projected"));
79  }
80  else
81  {
82  pnh_.param("source_frame", source_frame_, std::string("base_link"));
83  pnh_.param("projection_surface_frame", projection_surface_frame_, std::string("map"));
84  pnh_.param("parent_frame", parent_frame_, std::string("map"));
85  pnh_.param("projected_frame", projected_frame_, std::string("base_link_projected"));
86  }
87 
88  pnh_.param("hz", rate_, 10.0);
89  pnh_.param("tf_tolerance", tf_tolerance_, 0.1);
90  pnh_.param("flat", flat_, false);
91  pnh_.param("project_posture", project_posture_, false);
92  }
93  void process()
94  {
96  tf2::Stamped<tf2::Transform> trans_target;
97  try
98  {
100  tf_buffer_.lookupTransform(projection_surface_frame_, source_frame_, ros::Time(0), ros::Duration(0.1)),
101  trans);
102  tf2::fromMsg(
103  tf_buffer_.lookupTransform(parent_frame_, projection_surface_frame_, trans.stamp_, ros::Duration(0.1)),
104  trans_target);
105  }
106  catch (tf2::TransformException& e)
107  {
108  ROS_WARN_ONCE("%s", e.what());
109  return;
110  }
111 
112  if (project_posture_)
113  {
114  const float yaw = tf2::getYaw(trans.getRotation());
115  trans.setRotation(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), yaw));
116  }
117 
118  const tf2::Stamped<tf2::Transform> result(
119  track_odometry::projectTranslation(trans, trans_target),
120  trans.stamp_ + ros::Duration(tf_tolerance_),
121  parent_frame_);
122 
123  geometry_msgs::TransformStamped trans_out = tf2::toMsg(result);
124  if (flat_)
125  {
126  const float yaw = tf2::getYaw(trans_out.transform.rotation);
127  trans_out.transform.rotation = tf2::toMsg(tf2::Quaternion(tf2::Vector3(0.0, 0.0, 1.0), yaw));
128  }
129  trans_out.child_frame_id = projected_frame_;
130 
131  tf_broadcaster_.sendTransform(trans_out);
132  }
133  void cbTimer(const ros::TimerEvent& event)
134  {
135  process();
136  }
137  void spin()
138  {
139  ros::Timer timer = nh_.createTimer(
140  ros::Duration(1.0 / rate_), &TfProjectionNode::cbTimer, this);
141  ros::spin();
142  }
143 };
144 
145 int main(int argc, char* argv[])
146 {
147  ros::init(argc, argv, "tf_projection");
148 
149  TfProjectionNode proj;
150  proj.spin();
151 
152  return 0;
153 }
void cbTimer(const ros::TimerEvent &event)
virtual geometry_msgs::TransformStamped lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration timeout) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_WARN_ONCE(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ros::Time stamp_
void fromMsg(const A &, B &b)
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
tf2_ros::TransformBroadcaster tf_broadcaster_
void sendTransform(const geometry_msgs::TransformStamped &transform)
ros::NodeHandle nh_
double getYaw(const A &a)
B toMsg(const A &a)
tf2::Transform projectTranslation(const tf2::Transform &trans, const tf2::Transform &trans_target)
tf2_ros::Buffer tf_buffer_
std::string projection_surface_frame_
bool hasParam(const std::string &key) const
tf2_ros::TransformListener tf_listener_
ros::NodeHandle pnh_
#define ROS_ERROR(...)
int main(int argc, char *argv[])
std::string projected_frame_


track_odometry
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 05:00:05