39 from moveit_commander
import RobotCommander, PlanningSceneInterface, roscpp_initialize, roscpp_shutdown
40 from geometry_msgs.msg
import PoseStamped
42 if __name__==
'__main__':
45 rospy.init_node(
'moveit_py_demo', anonymous=
True)
47 scene = PlanningSceneInterface()
48 robot = RobotCommander()
52 scene.remove_world_object(
"pole")
53 scene.remove_world_object(
"table")
54 scene.remove_world_object(
"part")
58 p.header.frame_id = robot.get_planning_frame()
59 p.pose.position.x = 0.7
60 p.pose.position.y = -0.4
61 p.pose.position.z = 0.85
62 p.pose.orientation.w = 1.0
63 scene.add_box(
"pole", p, (0.3, 0.1, 1.0))
65 p.pose.position.y = -0.2
66 p.pose.position.z = 0.175
67 scene.add_box(
"table", p, (0.5, 1.5, 0.35))
69 p.pose.position.x = 0.6
70 p.pose.position.y = -0.7
71 p.pose.position.z = 0.5
72 scene.add_box(
"part", p, (0.15, 0.1, 0.3))
77 robot.right_arm.pick(
"part")
def roscpp_initialize(args)