4 Copyright (c) 2016, Aumann Florian, Borella Jocelyn, Hutmacher Robin, Karrenbauer Oliver, Meissner Pascal, Schleicher Ralf, Stoeckle Patrick, Trautmann Jeremias 7 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: 9 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. 11 2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. 13 3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. 15 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 26 from geometry_msgs.msg
import (Pose, PoseWithCovariance, PoseWithCovarianceStamped, Point, Quaternion, Twist, Vector3)
27 from asr_msgs.msg
import AsrObject
28 from actionlib
import *
30 from asr_next_best_view.msg
import RobotStateMessage
31 from asr_next_best_view.srv
import CalculateCameraPose, TriggerFrustumVisualization, GetPose
32 from sensor_msgs.msg
import JointState
33 from asr_world_model.srv
import PushFoundObject, PushFoundObjectList, GetFoundObjectList, EmptyViewportList
37 rospy.wait_for_service(
'/env/asr_world_model/push_found_object_list',timeout=3)
38 push_found_objects = rospy.ServiceProxy(
'/env/asr_world_model/push_found_object_list', PushFoundObjectList)
40 except (rospy.exceptions.ROSException, rospy.ServiceException)
as e:
41 rospy.logwarn(
"Could not find world_model service")
46 rospy.wait_for_service(
'/env/asr_world_model/get_found_object_list',timeout=3)
47 get_found_objects = rospy.ServiceProxy(
'/env/asr_world_model/get_found_object_list', GetFoundObjectList)
48 print get_found_objects()
49 except (rospy.exceptions.ROSException, rospy.ServiceException)
as e:
50 rospy.logwarn(
"Could not find world_model service")
55 rospy.wait_for_service(
'/env/asr_world_model/empty_viewport_list',timeout=3)
56 get_found_objects = rospy.ServiceProxy(
'/env/asr_world_model/empty_viewport_list', EmptyViewportList)
58 except (rospy.exceptions.ROSException, rospy.ServiceException)
as e:
59 rospy.logwarn(
"Could not find world_model service")
65 obj.type =
'CoffeeBox' 66 obj.header.frame_id =
'/camera_left_frame' 68 obj.providedBy =
'textured' 69 obj.colorName =
'textured' 70 obj.meshResourcePath =
'package://asr_object_database/rsc/databases/textured_objects/CoffeeBox/CoffeeBox.dae' 71 pose_cov = PoseWithCovariance()
72 pose_cov.pose.position.x = random.gauss(0,0.01)
73 pose_cov.pose.position.y = random.gauss(0,0.01) + random.randint(0, 1)
74 pose_cov.pose.position.z = 1.12
75 if random.randint(0, 5) == 0:
76 pose_cov.pose.position.x = pose_cov.pose.position.x + 1
77 q = tf.transformations.quaternion_from_euler(90, 0, 0,
'rzyx')
78 pose_cov.pose.orientation = Quaternion(*q)
79 obj.sampledPoses.append(pose_cov)
85 obj.header.frame_id =
'/camera_left_frame' 87 obj.providedBy =
'textured' 88 obj.colorName =
'textured' 89 obj.meshResourcePath =
'package://asr_object_database/rsc/databases/textured_objects/Smacks/Smacks.dae' 90 pose_cov = PoseWithCovariance()
91 pose_cov.pose.position.x = random.gauss(0,0.5)
92 pose_cov.pose.position.y = random.gauss(0,0.5)
93 pose_cov.pose.position.z = 1.12
94 q = tf.transformations.quaternion_from_euler(90, 0, 0,
'rzyx')
95 pose_cov.pose.orientation = Quaternion(*q)
96 obj.sampledPoses.append(pose_cov)
99 if __name__ ==
'__main__':
100 global detected_objects
102 rospy.init_node(
'test_world_model')
105 found_object = AsrObject()
107 object_list.append(found_object)
111 found_object = AsrObject()
113 object_list.append(found_object)
def push_object_in_wm(detected_objects)