Skip to content

Commit

Permalink
[fix] the position of the box in the "Move Group Python Interface" (m…
Browse files Browse the repository at this point in the history
  • Loading branch information
sjahr authored Oct 13, 2020
1 parent 40bd382 commit 3c90b71
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 4 deletions.
2 changes: 2 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@ This repository is currently built automatically by two systems. Travis builds t
If you want to test the tutorials by generating the html pages locally on your machine, use the ``build_locally`` script.
It has been tested on Ubuntu 16.04 with ROS Kinetic pre-installed. Run in the root of the moveit_tutorials package:

> **_NOTE:_** [rosdoc_lite](https://wiki.ros.org/rosdoc_lite) is needed to run the build_locally.sh script!
export ROS_DISTRO=kinetic # 16.04
export ROS_DISTRO=melodic # 18.04
export ROS_DISTRO=noetic # 20.04
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -366,13 +366,13 @@ def add_box(self, timeout=4):
##
## Adding Objects to the Planning Scene
## ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
## First, we will create a box in the planning scene at the location of the left finger:
## First, we will create a box in the planning scene between the fingers:
box_pose = geometry_msgs.msg.PoseStamped()
box_pose.header.frame_id = "panda_leftfinger"
box_pose.header.frame_id = "panda_hand"
box_pose.pose.orientation.w = 1.0
box_pose.pose.position.z = 0.07 # slightly above the end effector
box_pose.pose.position.z = 0.11 # above the panda_hand frame
box_name = "box"
scene.add_box(box_name, box_pose, size=(0.1, 0.1, 0.1))
scene.add_box(box_name, box_pose, size=(0.075, 0.075, 0.075))

## END_SUB_TUTORIAL
# Copy local variables back to class variables. In practice, you should use the class
Expand Down

0 comments on commit 3c90b71

Please sign in to comment.