|
5 | 5 | from ..bullet_world import BulletWorld, Object
|
6 | 6 |
|
7 | 7 | from typing import List, Tuple, Dict
|
8 |
| - |
9 |
| -topics = list(map(lambda x: x[0], rospy.get_published_topics())) |
10 |
| -try: |
11 |
| - from giskardpy.python_interface import GiskardWrapper |
12 |
| - from geometry_msgs.msg import PoseStamped, PointStamped, QuaternionStamped, Vector3Stamped |
13 |
| - from giskard_msgs.msg import WorldBody, MoveResult, CollisionEntry |
14 |
| - from giskard_msgs.srv import UpdateWorldRequest, UpdateWorld, UpdateWorldResponse, RegisterGroupResponse |
15 |
| - |
16 |
| - if "/giskard/command/goal" in topics: |
17 |
| - giskard_wrapper = GiskardWrapper() |
18 |
| - giskard_update_service = rospy.ServiceProxy("/giskard/update_world", UpdateWorld) |
19 |
| -except ModuleNotFoundError as e: |
20 |
| - rospy.logwarn("No Giskard topic available") |
21 |
| - |
| 8 | +from geometry_msgs.msg import PoseStamped, PointStamped, QuaternionStamped, Vector3Stamped |
| 9 | + |
| 10 | +giskard_wrapper = None |
| 11 | +giskard_update_service = None |
| 12 | +is_init = False |
| 13 | + |
| 14 | + |
| 15 | +def init_giskard_interface(): |
| 16 | + global giskard_wrapper |
| 17 | + global giskard_update_service |
| 18 | + global is_init |
| 19 | + if is_init: |
| 20 | + return |
| 21 | + topics = list(map(lambda x: x[0], rospy.get_published_topics())) |
| 22 | + try: |
| 23 | + from giskardpy.python_interface import GiskardWrapper |
| 24 | + from giskard_msgs.msg import WorldBody, MoveResult, CollisionEntry |
| 25 | + from giskard_msgs.srv import UpdateWorldRequest, UpdateWorld, UpdateWorldResponse, RegisterGroupResponse |
| 26 | + |
| 27 | + if "/giskard/command/goal" in topics: |
| 28 | + giskard_wrapper = GiskardWrapper() |
| 29 | + giskard_update_service = rospy.ServiceProxy("/giskard/update_world", UpdateWorld) |
| 30 | + is_init = True |
| 31 | + rospy.loginfo("Successfully initialized Giskard interface") |
| 32 | + else: |
| 33 | + rospy.logwarn("Giskard is not running, could not initialize Giskard interface") |
| 34 | + except ModuleNotFoundError as e: |
| 35 | + rospy.logwarn("Failed to import Giskard messages, giskard interface could not be initialized") |
22 | 36 |
|
23 | 37 | # Believe state management between pycram and giskard
|
24 | 38 |
|
| 39 | + |
25 | 40 | def initial_adding_objects() -> None:
|
26 | 41 | """
|
27 | 42 | Adds object that are loaded in the BulletWorld to the Giskard belief state, if they are not present at the moment.
|
@@ -53,6 +68,7 @@ def sync_worlds() -> None:
|
53 | 68 | belief state such that it matches the objects present in the BulletWorld and moving the robot to the position it is
|
54 | 69 | currently at in the BulletWorld.
|
55 | 70 | """
|
| 71 | + init_giskard_interface() |
56 | 72 | add_gripper_groups()
|
57 | 73 | bullet_object_names = set()
|
58 | 74 | for obj in BulletWorld.current_bullet_world.objects:
|
|
0 commit comments