tagdetect.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright 2021 Roboception GmbH
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 #
11 # * Redistributions in binary form must reproduce the above copyright
12 # notice, this list of conditions and the following disclaimer in the
13 # documentation and/or other materials provided with the distribution.
14 #
15 # * Neither the name of the {copyright_holder} nor the names of its
16 # contributors may be used to endorse or promote products derived from
17 # this software without specific prior written permission.
18 #
19 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 # POSSIBILITY OF SUCH DAMAGE.
30 
31 from __future__ import absolute_import
32 
33 import rospy
34 
35 from tf2_msgs.msg import TFMessage
36 from geometry_msgs.msg import TransformStamped
37 from visualization_msgs.msg import Marker, MarkerArray
38 from std_msgs.msg import ColorRGBA
39 
40 from rc_reason_msgs.srv import DetectTags
41 
42 from .rest_client import RestClient
43 
44 
45 def tag_to_tf(tag):
46  tf = TransformStamped()
47  tf.header.frame_id = tag.header.frame_id
48  tf.child_frame_id = "{}_{}".format(tag.tag.id, tag.instance_id)
49  tf.header.stamp = tag.header.stamp
50  tf.transform.translation.x = tag.pose.pose.position.x
51  tf.transform.translation.y = tag.pose.pose.position.y
52  tf.transform.translation.z = tag.pose.pose.position.z
53  tf.transform.rotation = tag.pose.pose.orientation
54  return tf
55 
56 
58 
59  def __init__(self, rest_name):
60  super(TagClient, self).__init__(rest_name)
61  self.tag_markers = []
62 
63  self.publish_tf = rospy.get_param("~publish_tf", True)
64  self.publish_markers = rospy.get_param("~publish_markers", True)
65 
66  self.pub_tf = rospy.Publisher('/tf', TFMessage, queue_size=10)
67  self.pub_markers = rospy.Publisher('visualization_marker_array', MarkerArray, queue_size=10)
68 
69  rospy.on_shutdown(self.stop)
70 
71  self.start()
72 
73  self.add_rest_service(DetectTags, 'detect', self.detect_callback)
74 
75 
76  def start(self):
77  rospy.loginfo("starting %s", self.rest_name)
78  self.call_rest_service('start')
79 
80  def stop(self):
81  rospy.loginfo("stopping %s", self.rest_name)
82  self.call_rest_service('stop')
83 
84  def detect_callback(self, srv_name, srv_type, request):
85  response = self.call_rest_service(srv_name, srv_type, request)
86  if response.return_code.value == 0:
87  self.publish_tags(response.tags)
88  return response
89 
90  def publish_tags(self, tags):
91  if tags and self.publish_tf:
92  transforms = [tag_to_tf(tag) for tag in tags]
93  self.pub_tf.publish(TFMessage(transforms=transforms))
94  if self.publish_markers:
95  self.publish_tag_markers(tags)
96 
97  def publish_tag_markers(self, tags):
98  def create_marker(tag, id):
99  m = Marker(action=Marker.ADD, type=Marker.CUBE)
100  m.color = ColorRGBA(r=0.0, g=1.0, b=0.0, a=0.5)
101  m.header.stamp = tag.pose.header.stamp
102  m.header.frame_id = "{}_{}".format(tag.tag.id, tag.instance_id)
103  m.pose.orientation.w = 1.0
104  m.pose.position.x = tag.tag.size / 2
105  m.pose.position.y = tag.tag.size / 2
106  m.pose.position.z = 0.001 / 2
107  m.scale.x = tag.tag.size
108  m.scale.y = tag.tag.size
109  m.scale.z = 0.001
110  m.id = id
111  m.ns = self.rest_name+ "_tags"
112  return m
113 
114  new_markers = []
115  for i, tag in enumerate(tags):
116  m = create_marker(tag, i)
117  if i < len(self.tag_markers):
118  self.tag_markers[i] = m
119  else:
120  self.tag_markers.append(m)
121  new_markers.append(m)
122  for i in range(len(tags), len(self.tag_markers)):
123  # delete old markers
124  self.tag_markers[i].action = Marker.DELETE
125  self.pub_markers.publish(MarkerArray(markers=self.tag_markers))
126  self.tag_markers = new_markers
127 
128 
129 def main(rest_node='rc_april_tag_detect'):
130  client = TagClient(rest_node)
131 
132  try:
133  rospy.spin()
134  except KeyboardInterrupt:
135  pass
136 
137 
139  main(rest_node='rc_april_tag_detect')
140 
141 
143  main(rest_node='rc_qr_code_detect')
144 
145 
146 if __name__ == '__main__':
147  main()
rc_reason_clients.tagdetect.TagClient.publish_markers
publish_markers
Definition: tagdetect.py:64
rc_reason_clients.tagdetect.TagClient.publish_tag_markers
def publish_tag_markers(self, tags)
Definition: tagdetect.py:97
rc_reason_clients.tagdetect.TagClient
Definition: tagdetect.py:57
rc_reason_clients.tagdetect.TagClient.tag_markers
tag_markers
Definition: tagdetect.py:61
rc_reason_clients.rest_client.RestClient.add_rest_service
def add_rest_service(self, srv_type, srv_name, callback)
Definition: rest_client.py:193
rc_reason_clients.tagdetect.TagClient.start
def start(self)
Definition: tagdetect.py:76
rc_reason_clients.tagdetect.TagClient.detect_callback
def detect_callback(self, srv_name, srv_type, request)
Definition: tagdetect.py:84
rc_reason_clients.tagdetect.TagClient.publish_tf
publish_tf
Definition: tagdetect.py:63
rc_reason_clients.tagdetect.TagClient.publish_tags
def publish_tags(self, tags)
Definition: tagdetect.py:90
rc_reason_clients.tagdetect.rc_april_tag_detect_client
def rc_april_tag_detect_client()
Definition: tagdetect.py:138
rc_reason_clients.tagdetect.main
def main(rest_node='rc_april_tag_detect')
Definition: tagdetect.py:129
rc_reason_clients.tagdetect.rc_qr_code_detect_client
def rc_qr_code_detect_client()
Definition: tagdetect.py:142
rc_reason_clients.rest_client.RestClient
Definition: rest_client.py:70
rc_reason_clients.tagdetect.TagClient.__init__
def __init__(self, rest_name)
Definition: tagdetect.py:59
rc_reason_clients.rest_client.RestClient.call_rest_service
def call_rest_service(self, name, srv_type=None, request=None)
Definition: rest_client.py:162
rc_reason_clients.tagdetect.TagClient.pub_tf
pub_tf
Definition: tagdetect.py:66
rc_reason_clients.tagdetect.TagClient.stop
def stop(self)
Definition: tagdetect.py:80
rc_reason_clients.tagdetect.TagClient.pub_markers
pub_markers
Definition: tagdetect.py:67
rc_reason_clients.rest_client.RestClient.rest_name
rest_name
Definition: rest_client.py:73
rc_reason_clients.tagdetect.tag_to_tf
def tag_to_tf(tag)
Definition: tagdetect.py:45


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