generate_pose.py
Go to the documentation of this file.
1 #! /usr/bin/env python3
2 # -*- coding: utf-8 -*-
3 
4 from moveit.task_constructor import core, stages
5 from geometry_msgs.msg import PoseStamped
6 from py_binding_tools import roscpp_init
7 import time
8 
9 roscpp_init("mtc_tutorial")
10 
11 # Specify the planning group
12 group = "panda_arm"
13 
14 # Create a task
15 task = core.Task()
16 task.name = "generate pose"
17 
18 # Get the current robot state
19 currentState = stages.CurrentState("current state")
20 task.add(currentState)
21 
22 # Create a planner instance that is used to connect
23 # the current state to the grasp approach pose
24 pipelinePlanner = core.PipelinePlanner()
25 pipelinePlanner.planner = "RRTConnectkConfigDefault"
26 planners = [(group, pipelinePlanner)]
27 
28 # Connect the two stages
29 connect = stages.Connect("connect1", planners)
30 connect.properties.configureInitFrom(core.Stage.PropertyInitializerSource.PARENT)
31 task.add(connect)
32 
33 # [initAndConfigGeneratePose]
34 # create an example pose wrt. the origin of the
35 # panda arm link8
36 pose = PoseStamped()
37 pose.header.frame_id = "panda_link8"
38 
39 # Calculate the inverse kinematics for the current robot state
40 generatePose = stages.GeneratePose("generate pose")
41 
42 # spwan a pose whenever there is a solution of the monitored stage
43 generatePose.setMonitoredStage(task["current state"])
44 generatePose.pose = pose
45 
46 # Add the stage to the task hierarchy
47 task.add(generatePose)
48 # [initAndConfigGeneratePose]
49 
50 if task.plan():
51  task.publish(task.solutions[0])
52 time.sleep(1)
moveit::task_constructor


demo
Author(s): Robert Haschke , Simon Goldstein , Henning Kayser
autogenerated on Sat May 3 2025 02:40:30