tf2_sensor_msgs.py
Go to the documentation of this file.
00001 # Copyright (c) 2008, Willow Garage, Inc.
00002 # All rights reserved.
00003 # 
00004 # Redistribution and use in source and binary forms, with or without
00005 # modification, are permitted provided that the following conditions are met:
00006 # 
00007 #     * Redistributions of source code must retain the above copyright
00008 #       notice, this list of conditions and the following disclaimer.
00009 #     * Redistributions in binary form must reproduce the above copyright
00010 #       notice, this list of conditions and the following disclaimer in the
00011 #       documentation and/or other materials provided with the distribution.
00012 #     * Neither the name of the Willow Garage, Inc. nor the names of its
00013 #       contributors may be used to endorse or promote products derived from
00014 #       this software without specific prior written permission.
00015 # 
00016 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00017 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00018 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00019 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00020 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00021 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00022 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00023 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00024 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00025 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00026 # POSSIBILITY OF SUCH DAMAGE.
00027 
00028 from sensor_msgs.msg import PointCloud2
00029 from sensor_msgs.point_cloud2 import read_points, create_cloud
00030 import PyKDL
00031 import rospy
00032 import tf2_ros
00033 
00034 def to_msg_msg(msg):
00035     return msg
00036 
00037 tf2_ros.ConvertRegistration().add_to_msg(PointCloud2, to_msg_msg)
00038 
00039 def from_msg_msg(msg):
00040     return msg
00041 
00042 tf2_ros.ConvertRegistration().add_from_msg(PointCloud2, from_msg_msg)
00043 
00044 def transform_to_kdl(t):
00045     return PyKDL.Frame(PyKDL.Rotation.Quaternion(t.transform.rotation.x, t.transform.rotation.y,
00046                                                  t.transform.rotation.z, t.transform.rotation.w),
00047                        PyKDL.Vector(t.transform.translation.x, 
00048                                     t.transform.translation.y, 
00049                                     t.transform.translation.z))
00050 
00051 # PointStamped
00052 def do_transform_cloud(cloud, transform):
00053     t_kdl = transform_to_kdl(transform)
00054     points_out = []
00055     for p_in in read_points(cloud):
00056         p_out = t_kdl * PyKDL.Vector(p_in[0], p_in[1], p_in[2])
00057         points_out.append((p_out[0], p_out[1], p_out[2]) + p_in[3:])
00058     res = create_cloud(transform.header, cloud.fields, points_out)
00059     return res
00060 tf2_ros.TransformRegistration().add(PointCloud2, do_transform_cloud)


tf2_sensor_msgs
Author(s): Vincent Rabaud
autogenerated on Mon Oct 2 2017 02:25:04