Skip to content

Commit 3a1a00a

Browse files
NFiedlerv4hnrhaschke
authored
Extends information on collision objects in python interface (#717)
Co-authored-by: Michael Görner <[email protected]> Co-authored-by: Robert Haschke <[email protected]>
1 parent 5fa48ff commit 3a1a00a

File tree

1 file changed

+5
-2
lines changed

1 file changed

+5
-2
lines changed

doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -342,13 +342,16 @@ def wait_for_state_update(
342342
##
343343
## Ensuring Collision Updates Are Received
344344
## ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
345-
## If the Python node dies before publishing a collision object update message, the message
345+
## If the Python node was just created (https://github.com/ros/ros_comm/issues/176),
346+
## or dies before actually publishing the scene update message, the message
346347
## could get lost and the box will not appear. To ensure that the updates are
347348
## made, we wait until we see the changes reflected in the
348349
## ``get_attached_objects()`` and ``get_known_object_names()`` lists.
349350
## For the purpose of this tutorial, we call this function after adding,
350351
## removing, attaching or detaching an object in the planning scene. We then wait
351-
## until the updates have been made or ``timeout`` seconds have passed
352+
## until the updates have been made or ``timeout`` seconds have passed.
353+
## To avoid waiting for scene updates like this at all, initialize the
354+
## planning scene interface with ``synchronous = True``.
352355
start = rospy.get_time()
353356
seconds = rospy.get_time()
354357
while (seconds - start < timeout) and not rospy.is_shutdown():

0 commit comments

Comments
 (0)