cadmatch.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 math import sqrt
36 from tf2_msgs.msg import TFMessage
37 from geometry_msgs.msg import TransformStamped, Quaternion
38 
39 from rc_reason_msgs.srv import CadMatchDetectObject
40 
41 from visualization_msgs.msg import Marker, MarkerArray
42 from std_msgs.msg import ColorRGBA
43 
44 from .rest_client import RestClient
45 from .transform_helpers import lc_to_marker, load_carrier_to_tf, match_to_tf
46 
47 
49 
50  def __init__(self):
51  ignored_parameters = ['load_carrier_crop_distance', 'load_carrier_model_tolerance']
52  super(CadMatchClient, self).__init__('rc_cadmatch', ignored_parameters)
53 
54  # client only parameters
55  self.publish_tf = rospy.get_param("~publish_tf", True)
56  self.publish_markers = rospy.get_param("~publish_markers", True)
57 
58  self.pub_tf = rospy.Publisher('/tf', TFMessage, queue_size=10)
59  self.pub_markers = rospy.Publisher('visualization_marker_array', MarkerArray, queue_size=10)
60 
61  self.lc_markers = []
62 
63  self.add_rest_service(CadMatchDetectObject, 'detect_object', self.detect_cb)
64 
65  rospy.on_shutdown(self.stop)
66 
67  self.start()
68 
69  def start(self):
70  rospy.loginfo("starting %s", self.rest_name)
71  self.call_rest_service('start')
72 
73  def stop(self):
74  rospy.loginfo("stopping %s", self.rest_name)
75  self.call_rest_service('stop')
76 
77  def detect_cb(self, srv_name, srv_type, request):
78  response = self.call_rest_service(srv_name, srv_type, request)
79  self.pub_matches(response.matches)
80  self.publish_lcs(response.load_carriers)
81  return response
82 
83  def pub_matches(self, matches):
84  if not matches or not self.publish_tf:
85  return
86  transforms = [match_to_tf(i) for i in matches]
87  self.pub_tf.publish(TFMessage(transforms=transforms))
88 
89  def publish_lcs(self, lcs):
90  if lcs and self.publish_tf:
91  transforms = [load_carrier_to_tf(lc, i) for i, lc in enumerate(lcs)]
92  self.pub_tf.publish(TFMessage(transforms=transforms))
93  if self.publish_markers:
94  self.publish_lc_markers(lcs)
95 
96  def publish_lc_markers(self, lcs):
97  new_markers = []
98  for i, lc in enumerate(lcs):
99  m = lc_to_marker(lc, i, self.rest_name + "_lcs")
100  if i < len(self.lc_markers):
101  self.lc_markers[i] = m
102  else:
103  self.lc_markers.append(m)
104  new_markers.append(m)
105  for i in range(len(lcs), len(self.lc_markers)):
106  # delete old markers
107  self.lc_markers[i].action = Marker.DELETE
108  self.pub_markers.publish(MarkerArray(markers=self.lc_markers))
109  self.lc_markers = new_markers
110 
111 
112 def main():
113  client = CadMatchClient()
114 
115  try:
116  rospy.spin()
117  except KeyboardInterrupt:
118  pass
119 
120 
121 if __name__ == '__main__':
122  main()
rc_reason_clients.cadmatch.main
def main()
Definition: cadmatch.py:112
rc_reason_clients.transform_helpers.lc_to_marker
def lc_to_marker(lc, lc_no, ns)
Definition: transform_helpers.py:47
rc_reason_clients.cadmatch.CadMatchClient.publish_lc_markers
def publish_lc_markers(self, lcs)
Definition: cadmatch.py:96
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.cadmatch.CadMatchClient.pub_markers
pub_markers
Definition: cadmatch.py:59
rc_reason_clients.cadmatch.CadMatchClient.start
def start(self)
Definition: cadmatch.py:69
rc_reason_clients.cadmatch.CadMatchClient.detect_cb
def detect_cb(self, srv_name, srv_type, request)
Definition: cadmatch.py:77
rc_reason_clients.cadmatch.CadMatchClient.lc_markers
lc_markers
Definition: cadmatch.py:61
rc_reason_clients.transform_helpers.load_carrier_to_tf
def load_carrier_to_tf(lc, postfix)
Definition: transform_helpers.py:35
rc_reason_clients.cadmatch.CadMatchClient.publish_markers
publish_markers
Definition: cadmatch.py:56
rc_reason_clients.cadmatch.CadMatchClient.publish_tf
publish_tf
Definition: cadmatch.py:55
rc_reason_clients.cadmatch.CadMatchClient.pub_tf
pub_tf
Definition: cadmatch.py:58
rc_reason_clients.transform_helpers.match_to_tf
def match_to_tf(match)
Definition: transform_helpers.py:62
rc_reason_clients.cadmatch.CadMatchClient.pub_matches
def pub_matches(self, matches)
Definition: cadmatch.py:83
rc_reason_clients.cadmatch.CadMatchClient.publish_lcs
def publish_lcs(self, lcs)
Definition: cadmatch.py:89
rc_reason_clients.rest_client.RestClient
Definition: rest_client.py:70
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.cadmatch.CadMatchClient
Definition: cadmatch.py:48
rc_reason_clients.rest_client.RestClient.rest_name
rest_name
Definition: rest_client.py:73
rc_reason_clients.cadmatch.CadMatchClient.stop
def stop(self)
Definition: cadmatch.py:73
rc_reason_clients.cadmatch.CadMatchClient.__init__
def __init__(self)
Definition: cadmatch.py:50


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