pose_transform.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 <geometry_msgs/PoseWithCovarianceStamped.h>
35 
36 #include <string>
37 
39 
40 std::string to;
41 std::shared_ptr<tf2_ros::Buffer> tfbuf;
42 
44 
45 void cbPose(const geometry_msgs::PoseWithCovarianceStamped::Ptr& msg)
46 {
47  try
48  {
49  geometry_msgs::PoseStamped in;
50  geometry_msgs::PoseStamped out;
51  geometry_msgs::PoseWithCovarianceStamped out_msg;
52  in.header = msg->header;
53  in.header.stamp = ros::Time(0);
54  in.pose = msg->pose.pose;
55  geometry_msgs::TransformStamped trans = tfbuf->lookupTransform(
56  to, msg->header.frame_id, in.header.stamp, ros::Duration(0.5));
57  tf2::doTransform(in, out, trans);
58  out_msg = *msg;
59  out_msg.header = out.header;
60  out_msg.pose.pose = out.pose;
61  pub_pose.publish(out_msg);
62  }
63  catch (tf2::TransformException& e)
64  {
65  ROS_WARN("pose_transform: %s", e.what());
66  }
67 }
68 
69 int main(int argc, char** argv)
70 {
71  ros::init(argc, argv, "pose_transform");
72  ros::NodeHandle pnh("~");
73  ros::NodeHandle nh("");
74 
77  nh, "pose_in",
78  pnh, "pose_in", 1, cbPose);
79  pub_pose = neonavigation_common::compat::advertise<geometry_msgs::PoseWithCovarianceStamped>(
80  nh, "pose_out",
81  pnh, "pose_out", 1, false);
82  pnh.param("to_frame", to, std::string("map"));
83 
84  tfbuf.reset(new tf2_ros::Buffer);
86  ros::spin();
87 
88  return 0;
89 }
void publish(const boost::shared_ptr< M > &message) const
std::string to
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber subscribe(ros::NodeHandle &nh_new, const std::string &topic_new, ros::NodeHandle &nh_old, const std::string &topic_old, uint32_t queue_size, void(*fp)(M), const ros::TransportHints &transport_hints=ros::TransportHints())
void doTransform(const T &data_in, T &data_out, const geometry_msgs::TransformStamped &transform)
#define ROS_WARN(...)
ROSCPP_DECL void spin(Spinner &spinner)
void cbPose(const geometry_msgs::PoseWithCovarianceStamped::Ptr &msg)
ros::Publisher pub_pose
std::shared_ptr< tf2_ros::Buffer > tfbuf
int main(int argc, char **argv)


map_organizer
Author(s): Atsushi Watanabe
autogenerated on Tue Jul 9 2019 04:59:56