pick.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 
38 from rc_reason_msgs.srv import ComputeGrasps, DetectItems
39 
40 from visualization_msgs.msg import Marker, MarkerArray
41 from std_msgs.msg import ColorRGBA
42 
43 from .rest_client import RestClient
44 from .transform_helpers import lc_to_marker, load_carrier_to_tf
45 
46 
47 def grasp_to_tf(grasp, postfix):
48  tf = TransformStamped()
49  tf.header.frame_id = grasp.pose.header.frame_id
50  tf.child_frame_id = "grasp_".format(postfix)
51  tf.header.stamp = grasp.pose.header.stamp
52  tf.transform.translation.x = grasp.pose.pose.position.x
53  tf.transform.translation.y = grasp.pose.pose.position.y
54  tf.transform.translation.z = grasp.pose.pose.position.z
55  tf.transform.rotation = grasp.pose.pose.orientation
56  return tf
57 
58 
59 def item_to_tf(item, postfix):
60  tf = TransformStamped()
61  tf.header.frame_id = item.pose.header.frame_id
62  tf.child_frame_id = "boxitem_".format(postfix)
63  tf.header.stamp = item.pose.header.stamp
64  tf.transform.translation.x = item.pose.pose.position.x
65  tf.transform.translation.y = item.pose.pose.position.y
66  tf.transform.translation.z = item.pose.pose.position.z
67  tf.transform.rotation = item.pose.pose.orientation
68  return tf
69 
70 
72 
73  def __init__(self, rest_name):
74  ignored_parameters = ['load_carrier_crop_distance', 'load_carrier_model_tolerance']
75  super(PickClient, self).__init__(rest_name, ignored_parameters)
76 
77  # client only parameters
78  self.publish_tf = rospy.get_param("~publish_tf", True)
79  self.publish_markers = rospy.get_param("~publish_markers", True)
80 
81  self.pub_tf = rospy.Publisher('/tf', TFMessage, queue_size=10)
82  self.pub_markers = rospy.Publisher('visualization_marker_array', MarkerArray, queue_size=10)
83 
84  self.grasp_markers = []
85  self.lc_markers = []
86 
87  rospy.on_shutdown(self.stop)
88 
89  self.start()
90 
91  def start(self):
92  rospy.loginfo("starting %s", self.rest_name)
93  self.call_rest_service('start')
94 
95  def stop(self):
96  rospy.loginfo("stopping %s", self.rest_name)
97  self.call_rest_service('stop')
98 
99  def publish_lcs(self, lcs):
100  if lcs and self.publish_tf:
101  transforms = [load_carrier_to_tf(lc, i) for i, lc in enumerate(lcs)]
102  self.pub_tf.publish(TFMessage(transforms=transforms))
103  if self.publish_markers:
104  self.publish_lc_markers(lcs)
105 
106  def publish_grasps(self, grasps):
107  if grasps and self.publish_tf:
108  transforms = [grasp_to_tf(grasp, i) for i, grasp in enumerate(grasps)]
109  self.pub_tf.publish(TFMessage(transforms=transforms))
110  if self.publish_markers:
111  self.publish_grasps_markers(grasps)
112 
113  def publish_grasps_markers(self, grasps):
114  def create_marker(grasp, id):
115  m = Marker(action=Marker.ADD, type=Marker.SPHERE)
116  m.color = ColorRGBA(r=0.8, g=0.2, b=0.0, a=0.8)
117  m.scale.x = grasp.max_suction_surface_length
118  m.scale.y = grasp.max_suction_surface_width
119  m.scale.z = 0.001
120  m.header = grasp.pose.header
121  m.pose = grasp.pose.pose
122  m.id = i
123  m.ns = self.rest_name + "_grasps"
124  return m
125 
126  new_markers = []
127  for i, grasp in enumerate(grasps):
128  m = create_marker(grasp, i)
129  if i < len(self.grasp_markers):
130  self.grasp_markers[i] = m
131  else:
132  self.grasp_markers.append(m)
133  new_markers.append(m)
134  for i in range(len(grasps), len(self.grasp_markers)):
135  # delete old markers
136  self.grasp_markers[i].action = Marker.DELETE
137  self.pub_markers.publish(MarkerArray(markers=self.grasp_markers))
138  self.grasp_markers = new_markers
139 
140  def publish_lc_markers(self, lcs):
141  new_markers = []
142  for i, lc in enumerate(lcs):
143  m = lc_to_marker(lc, i, self.rest_name + "_lcs")
144  if i < len(self.lc_markers):
145  self.lc_markers[i] = m
146  else:
147  self.lc_markers.append(m)
148  new_markers.append(m)
149  for i in range(len(lcs), len(self.lc_markers)):
150  # delete old markers
151  self.lc_markers[i].action = Marker.DELETE
152  self.pub_markers.publish(MarkerArray(markers=self.lc_markers))
153  self.lc_markers = new_markers
154 
155 
157 
158  def __init__(self, rest_name):
159  super(ItemPickClient, self).__init__(rest_name)
160  self.add_rest_service(ComputeGrasps, 'compute_grasps', self.compute_grasps_cb)
161 
162  def compute_grasps_cb(self, srv_name, srv_type, request):
163  response = self.call_rest_service(srv_name, srv_type, request)
164  self.publish_lcs(response.load_carriers)
165  self.publish_grasps(response.grasps)
166  return response
167 
168 
170 
171  def __init__(self, rest_name):
172  super(BoxPickClient, self).__init__(rest_name)
173  self.add_rest_service(ComputeGrasps, 'compute_grasps', self.compute_grasps_cb)
174  self.add_rest_service(DetectItems, 'detect_items', self.detect_items_cb)
175 
176  def compute_grasps_cb(self, srv_name, srv_type, request):
177  response = self.call_rest_service(srv_name, srv_type, request)
178  self.publish_lcs(response.load_carriers)
179  self.publish_grasps(response.grasps)
180  self.publish_items(response.items)
181  return response
182 
183  def detect_items_cb(self, srv_name, srv_type, request):
184  response = self.call_rest_service(srv_name, srv_type, request)
185  self.publish_lcs(response.load_carriers)
186  self.publish_items(response.items)
187  return response
188 
189  def publish_items(self, items):
190  if not items:
191  return
192  if not self.publish_tf:
193  return
194  transforms = [item_to_tf(item, i) for i, item in enumerate(items)]
195  self.pub_tf.publish(TFMessage(transforms=transforms))
196 
197 
198 def main(rest_node='rc_itempick'):
199  if rest_node == 'rc_itempick':
200  client = ItemPickClient(rest_node)
201  elif rest_node == 'rc_boxpick':
202  client = BoxPickClient(rest_node)
203  else:
204  import logging
205  logging.error('unknown rest_node %s', rest_node)
206  exit(1)
207 
208  try:
209  rospy.spin()
210  except KeyboardInterrupt:
211  pass
212 
213 
215  main(rest_node='rc_itempick')
216 
217 
219  main(rest_node='rc_boxpick')
220 
221 
222 if __name__ == '__main__':
223  main()
def main(rest_node='rc_itempick')
Definition: pick.py:198
def detect_items_cb(self, srv_name, srv_type, request)
Definition: pick.py:183
def compute_grasps_cb(self, srv_name, srv_type, request)
Definition: pick.py:176
def item_to_tf(item, postfix)
Definition: pick.py:59
def call_rest_service(self, name, srv_type=None, request=None)
Definition: rest_client.py:158
def add_rest_service(self, srv_type, srv_name, callback)
Definition: rest_client.py:189
def publish_grasps_markers(self, grasps)
Definition: pick.py:113
def publish_lc_markers(self, lcs)
Definition: pick.py:140
def compute_grasps_cb(self, srv_name, srv_type, request)
Definition: pick.py:162
def rc_boxpick_client()
Definition: pick.py:218
def __init__(self, rest_name)
Definition: pick.py:171
def __init__(self, rest_name)
Definition: pick.py:73
def __init__(self, rest_name)
Definition: pick.py:158
def publish_items(self, items)
Definition: pick.py:189
def grasp_to_tf(grasp, postfix)
Definition: pick.py:47
def publish_grasps(self, grasps)
Definition: pick.py:106
def rc_itempick_client()
Definition: pick.py:214
def publish_lcs(self, lcs)
Definition: pick.py:99


rc_reason_clients
Author(s):
autogenerated on Sat Jun 17 2023 02:48:57