5 from geometry_msgs.msg
import PoseStamped
6 from py_binding_tools
import roscpp_init
9 roscpp_init(
"mtc_tutorial")
16 task.name =
"generate pose"
19 currentState = stages.CurrentState(
"current state")
20 task.add(currentState)
24 pipelinePlanner = core.PipelinePlanner()
25 pipelinePlanner.planner =
"RRTConnectkConfigDefault"
26 planners = [(group, pipelinePlanner)]
29 connect = stages.Connect(
"connect1", planners)
30 connect.properties.configureInitFrom(core.Stage.PropertyInitializerSource.PARENT)
37 pose.header.frame_id =
"panda_link8"
40 generatePose = stages.GeneratePose(
"generate pose")
43 generatePose.setMonitoredStage(task[
"current state"])
44 generatePose.pose = pose
47 task.add(generatePose)
51 task.publish(task.solutions[0])