Skip to content

Commit 6e495df

Browse files
authored
Merge pull request cram2#109 from Tigul/fix-interface-imports
Fix interface imports
2 parents 6255e9c + aa613b3 commit 6e495df

File tree

2 files changed

+50
-28
lines changed

2 files changed

+50
-28
lines changed

src/pycram/external_interfaces/giskard.py

Lines changed: 30 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -5,23 +5,38 @@
55
from ..bullet_world import BulletWorld, Object
66

77
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")
2236

2337
# Believe state management between pycram and giskard
2438

39+
2540
def initial_adding_objects() -> None:
2641
"""
2742
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:
5368
belief state such that it matches the objects present in the BulletWorld and moving the robot to the position it is
5469
currently at in the BulletWorld.
5570
"""
71+
init_giskard_interface()
5672
add_gripper_groups()
5773
bullet_object_names = set()
5874
for obj in BulletWorld.current_bullet_world.objects:

src/pycram/external_interfaces/robokudo.py

Lines changed: 20 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,16 +1,30 @@
11
import rospy
22
import actionlib
33

4-
from robokudo_msgs.msg import ObjectDesignator as robokudo_ObjetDesignator
5-
from robokudo_msgs.msg import QueryAction, QueryGoal, QueryResult
4+
65
from ..designator import ObjectDesignatorDescription
76
from ..pose import Pose
87
from ..local_transformer import LocalTransformer
98
from ..bullet_world import BulletWorld
109
from ..enums import ObjectType
1110

11+
is_init = False
12+
13+
14+
def init_robokudo_interface():
15+
global is_init
16+
if is_init:
17+
return
18+
try:
19+
from robokudo_msgs.msg import ObjectDesignator as robokudo_ObjetDesignator
20+
from robokudo_msgs.msg import QueryAction, QueryGoal, QueryResult
21+
is_init = True
22+
rospy.loginfo("Successfully initialized robokudo interface")
23+
except ModuleNotFoundError as e:
24+
rospy.logwarn(f"Could not import RoboKudo messages, RoboKudo interface could not be initialized")
25+
1226

13-
def msg_from_obj_desig(obj_desc: ObjectDesignatorDescription) -> robokudo_ObjetDesignator:
27+
def msg_from_obj_desig(obj_desc: ObjectDesignatorDescription) -> 'robokudo_ObjetDesignator':
1428
"""
1529
Creates a RoboKudo Object designator from a PyCRAM Object Designator description
1630
@@ -24,7 +38,7 @@ def msg_from_obj_desig(obj_desc: ObjectDesignatorDescription) -> robokudo_ObjetD
2438
return obj_msg
2539

2640

27-
def make_query_goal_msg(obj_desc: ObjectDesignatorDescription) -> QueryGoal:
41+
def make_query_goal_msg(obj_desc: ObjectDesignatorDescription) -> 'QueryGoal':
2842
"""
2943
Creates a QueryGoal message from a PyCRAM Object designator description for the use of Querying RobotKudo.
3044
@@ -50,7 +64,9 @@ def query(object_desc: ObjectDesignatorDescription) -> ObjectDesignatorDescripti
5064
:param object_desc: The object designator description which describes the object that should be perceived
5165
:return: An object designator for the found object, if there was an object that fitted the description.
5266
"""
67+
init_robokudo_interface()
5368
global query_result
69+
5470
def active_callback():
5571
rospy.loginfo("Send query to Robokudo")
5672

@@ -80,15 +96,5 @@ def feedback_callback(msg):
8096
pose = lt.transform_pose(pose, "map")
8197

8298
pose_candidates[source] = pose
83-
# pose_candidates.append(pose)
84-
85-
# for possible_pose in query_result.res[0].pose:
86-
# pose = Pose.from_pose_stamped(possible_pose)
87-
# pose.frame = BulletWorld.current_bullet_world.robot.get_link_tf_frame(pose.frame)
88-
89-
# lt = LocalTransformer()
90-
# pose = lt.transform_pose(pose, "map")
91-
92-
# pose_candidates.append(pose)
9399

94100
return pose_candidates

0 commit comments

Comments
 (0)