28 from sensor_msgs.msg
import PointCloud2
37 tf2_ros.ConvertRegistration().add_to_msg(PointCloud2, to_msg_msg)
42 tf2_ros.ConvertRegistration().add_from_msg(PointCloud2, from_msg_msg)
45 return PyKDL.Frame(PyKDL.Rotation.Quaternion(t.transform.rotation.x, t.transform.rotation.y,
46 t.transform.rotation.z, t.transform.rotation.w),
47 PyKDL.Vector(t.transform.translation.x,
48 t.transform.translation.y,
49 t.transform.translation.z))
55 for p_in
in read_points(cloud):
56 p_out = t_kdl * PyKDL.Vector(p_in[0], p_in[1], p_in[2])
57 points_out.append((p_out[0], p_out[1], p_out[2]) + p_in[3:])
58 res = create_cloud(transform.header, cloud.fields, points_out)
60 tf2_ros.TransformRegistration().add(PointCloud2, do_transform_cloud)
def do_transform_cloud(cloud, transform)