From 3c90b71c79038ef916f95ffeaf68b9cadc4cc628 Mon Sep 17 00:00:00 2001 From: Sebastian Jahr <44898064+sjahr@users.noreply.github.com> Date: Tue, 13 Oct 2020 22:35:14 +0200 Subject: [PATCH] [fix] the position of the box in the "Move Group Python Interface" (#543) --- README.md | 2 ++ .../scripts/move_group_python_interface_tutorial.py | 8 ++++---- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index 6978a1851..96f71573a 100644 --- a/README.md +++ b/README.md @@ -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 diff --git a/doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py b/doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py index 266f02a0a..3c9b9a19d 100755 --- a/doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py +++ b/doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py @@ -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