silhouettematch.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 SilhouetteMatchDetectObject
40 from rc_reason_msgs.srv import CalibrateBasePlane
41 from rc_reason_msgs.srv import GetBasePlaneCalibration
42 from rc_reason_msgs.srv import DeleteBasePlaneCalibration
43 
44 from visualization_msgs.msg import Marker, MarkerArray
45 from std_msgs.msg import ColorRGBA
46 
47 from .rest_client import RestClient
48 from .transform_helpers import lc_to_marker, load_carrier_to_tf, match_to_tf
49 
50 
52 
53  def __init__(self):
54  ignored_parameters = ['load_carrier_crop_distance', 'load_carrier_model_tolerance']
55  super(SilhouetteMatchClient, self).__init__('rc_silhouettematch', ignored_parameters)
56 
57  # client only parameters
58  self.publish_tf = rospy.get_param("~publish_tf", True)
59  self.publish_markers = rospy.get_param("~publish_markers", True)
60 
61  self.pub_tf = rospy.Publisher('/tf', TFMessage, queue_size=10)
62  self.pub_markers = rospy.Publisher('visualization_marker_array', MarkerArray, queue_size=10)
63 
64  self.lc_markers = []
65 
66  self.add_rest_service(SilhouetteMatchDetectObject, 'detect_object', self.detect_cb)
67  self.add_rest_service(CalibrateBasePlane, 'calibrate_base_plane', self.calib_cb)
68  self.add_rest_service(GetBasePlaneCalibration, 'get_base_plane_calibration', self.calib_cb)
69  self.add_rest_service(DeleteBasePlaneCalibration, 'delete_base_plane_calibration', self.generic_cb)
70 
71  def generic_cb(self, srv_name, srv_type, request):
72  response = self.call_rest_service(srv_name, srv_type, request)
73  return response
74 
75  def detect_cb(self, srv_name, srv_type, request):
76  response = self.call_rest_service(srv_name, srv_type, request)
77  self.pub_matches(response.matches)
78  self.publish_lcs(response.load_carriers)
79  return response
80 
81  def calib_cb(self, srv_name, srv_type, request):
82  response = self.call_rest_service(srv_name, srv_type, request)
83  if response.return_code.value >= 0:
84  self.publish_base_plane_markers(response.plane, response.pose_frame)
85  return response
86 
87  def pub_matches(self, matches):
88  if not matches or not self.publish_tf:
89  return
90  transforms = [match_to_tf(i) for i in matches]
91  self.pub_tf.publish(TFMessage(transforms=transforms))
92 
93  def publish_lcs(self, lcs):
94  if lcs and self.publish_tf:
95  transforms = [load_carrier_to_tf(lc, i) for i, lc in enumerate(lcs)]
96  self.pub_tf.publish(TFMessage(transforms=transforms))
97  if self.publish_markers:
98  self.publish_lc_markers(lcs)
99 
100  def publish_lc_markers(self, lcs):
101  new_markers = []
102  for i, lc in enumerate(lcs):
103  m = lc_to_marker(lc, i, self.rest_name + "_lcs")
104  if i < len(self.lc_markers):
105  self.lc_markers[i] = m
106  else:
107  self.lc_markers.append(m)
108  new_markers.append(m)
109  for i in range(len(lcs), len(self.lc_markers)):
110  # delete old markers
111  self.lc_markers[i].action = Marker.DELETE
112  self.pub_markers.publish(MarkerArray(markers=self.lc_markers))
113  self.lc_markers = new_markers
114 
115  def publish_base_plane_markers(self, plane, pose_frame):
116  def create_marker(plane, id=0):
117  m = Marker(action=Marker.ADD, type=Marker.CYLINDER)
118  m.color = ColorRGBA(r=0.0, g=1.0, b=0.0, a=0.5)
119  m.header.frame_id = pose_frame
120  m.pose.position.x = -plane.coef[0] * plane.coef[3]
121  m.pose.position.y = -plane.coef[1] * plane.coef[3]
122  m.pose.position.z = -plane.coef[2] * plane.coef[3]
123  # quaternion yielding double the desired rotation (if normal is normalized):
124  # q.w = dot(zaxis, normal), q.xyz = cross(zaxis, normal)
125  # add quaternion with zero rotation (xyz=0, w=1) to get half the rotation from above
126  # and normalize again
127  q = Quaternion(x=-plane.coef[1], y=plane.coef[0], z=0.0, w=plane.coef[2] + 1.0)
128  norm = sqrt(q.x*q.x + q.y*q.y + q.z*q.z + q.w*q.w)
129  m.pose.orientation.x = q.x / norm
130  m.pose.orientation.y = q.y / norm
131  m.pose.orientation.w = q.z / norm
132  m.pose.orientation.x = q.z / norm
133  m.scale.x = 1.0
134  m.scale.y = 1.0
135  m.scale.z = 0.001
136  m.id = id
137  m.ns = self.rest_name + "_base_plane"
138  return m
139 
140  m = create_marker(plane)
141  self.pub_markers.publish(MarkerArray(markers=[m]))
142 
143 
144 def main():
145  client = SilhouetteMatchClient()
146 
147  try:
148  rospy.spin()
149  except KeyboardInterrupt:
150  pass
151 
152 
153 if __name__ == '__main__':
154  main()
rc_reason_clients.silhouettematch.SilhouetteMatchClient.publish_markers
publish_markers
Definition: silhouettematch.py:59
rc_reason_clients.silhouettematch.SilhouetteMatchClient.pub_markers
pub_markers
Definition: silhouettematch.py:62
rc_reason_clients.transform_helpers.lc_to_marker
def lc_to_marker(lc, lc_no, ns)
Definition: transform_helpers.py:47
rc_reason_clients.silhouettematch.SilhouetteMatchClient.publish_tf
publish_tf
Definition: silhouettematch.py:58
rc_reason_clients.silhouettematch.SilhouetteMatchClient.__init__
def __init__(self)
Definition: silhouettematch.py:53
rc_reason_clients.silhouettematch.SilhouetteMatchClient.publish_lcs
def publish_lcs(self, lcs)
Definition: silhouettematch.py:93
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.silhouettematch.SilhouetteMatchClient.lc_markers
lc_markers
Definition: silhouettematch.py:64
rc_reason_clients.silhouettematch.SilhouetteMatchClient.detect_cb
def detect_cb(self, srv_name, srv_type, request)
Definition: silhouettematch.py:75
rc_reason_clients.silhouettematch.SilhouetteMatchClient
Definition: silhouettematch.py:51
rc_reason_clients.silhouettematch.SilhouetteMatchClient.pub_matches
def pub_matches(self, matches)
Definition: silhouettematch.py:87
rc_reason_clients.transform_helpers.load_carrier_to_tf
def load_carrier_to_tf(lc, postfix)
Definition: transform_helpers.py:35
rc_reason_clients.silhouettematch.SilhouetteMatchClient.publish_base_plane_markers
def publish_base_plane_markers(self, plane, pose_frame)
Definition: silhouettematch.py:115
rc_reason_clients.transform_helpers.match_to_tf
def match_to_tf(match)
Definition: transform_helpers.py:62
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.silhouettematch.SilhouetteMatchClient.calib_cb
def calib_cb(self, srv_name, srv_type, request)
Definition: silhouettematch.py:81
rc_reason_clients.silhouettematch.main
def main()
Definition: silhouettematch.py:144
rc_reason_clients.silhouettematch.SilhouetteMatchClient.generic_cb
def generic_cb(self, srv_name, srv_type, request)
Definition: silhouettematch.py:71
rc_reason_clients.silhouettematch.SilhouetteMatchClient.pub_tf
pub_tf
Definition: silhouettematch.py:61
rc_reason_clients.rest_client.RestClient.rest_name
rest_name
Definition: rest_client.py:73
rc_reason_clients.silhouettematch.SilhouetteMatchClient.publish_lc_markers
def publish_lc_markers(self, lcs)
Definition: silhouettematch.py:100


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