transform_helpers.py
Go to the documentation of this file.
1 # Copyright 2021 Roboception GmbH
2 #
3 # Redistribution and use in source and binary forms, with or without
4 # modification, are permitted provided that the following conditions are met:
5 #
6 # * Redistributions of source code must retain the above copyright
7 # notice, this list of conditions and the following disclaimer.
8 #
9 # * Redistributions in binary form must reproduce the above copyright
10 # notice, this list of conditions and the following disclaimer in the
11 # documentation and/or other materials provided with the distribution.
12 #
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 HOLDER 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 from geometry_msgs.msg import TransformStamped
30 
31 from visualization_msgs.msg import Marker
32 from std_msgs.msg import ColorRGBA
33 
34 
35 def load_carrier_to_tf(lc, postfix):
36  tf = TransformStamped()
37  tf.header.frame_id = lc.pose.header.frame_id
38  tf.child_frame_id = "lc_{}".format(postfix)
39  tf.header.stamp = lc.pose.header.stamp
40  tf.transform.translation.x = lc.pose.pose.position.x
41  tf.transform.translation.y = lc.pose.pose.position.y
42  tf.transform.translation.z = lc.pose.pose.position.z
43  tf.transform.rotation = lc.pose.pose.orientation
44  return tf
45 
46 
47 def lc_to_marker(lc, lc_no, ns):
48  m = Marker(action=Marker.ADD, type=Marker.CUBE)
49  m.color = ColorRGBA(r=0.0, g=0.2, b=0.8, a=0.3)
50  m.header = lc.pose.header
51  m.ns = ns
52 
53  # FIXME: calculate actual bottom and sides
54  m.id = lc_no
55  m.pose = lc.pose.pose
56  m.scale.x = lc.outer_dimensions.x
57  m.scale.y = lc.outer_dimensions.y
58  m.scale.z = lc.outer_dimensions.z
59 
60  return m
61 
62 def match_to_tf(match):
63  tf = TransformStamped()
64  tf.header.frame_id = match.pose.header.frame_id
65  tf.child_frame_id = "{}_{}".format(match.template_id, match.uuid)
66  tf.header.stamp = match.pose.header.stamp
67  tf.transform.translation.x = match.pose.pose.position.x
68  tf.transform.translation.y = match.pose.pose.position.y
69  tf.transform.translation.z = match.pose.pose.position.z
70  tf.transform.rotation = match.pose.pose.orientation
71  return tf
rc_reason_clients.transform_helpers.lc_to_marker
def lc_to_marker(lc, lc_no, ns)
Definition: transform_helpers.py:47
rc_reason_clients.transform_helpers.load_carrier_to_tf
def load_carrier_to_tf(lc, postfix)
Definition: transform_helpers.py:35
rc_reason_clients.transform_helpers.match_to_tf
def match_to_tf(match)
Definition: transform_helpers.py:62


rc_reason_clients
Author(s):
autogenerated on Sat Nov 23 2024 03:19:24