Go to the documentation of this file.00001 moveit_goal_builder {#mainpage}
00002 ===================
00003
00004 Goal builder for MoveIt's MoveGroup action.
00005
00006 This is useful for when you want to use the MoveGroup actionlib interface directly, instead of using the MoveGroup class.
00007 This allows you to poll when the action is done, which the normal MoveGroup interface does not allow you to do.
00008 In the demo linked below, for example, you can stop a MoveIt execution by shutting down the demo node with Ctrl+C.
00009
00010 - [Demo (for PR2)](https://github.com/jstnhuang/moveit_goal_builder/blob/indigo-devel/src/demo_main.cpp)
00011
00012 ## C++ example
00013
00014 ~~~{.cpp}
00015 moveit_goal_builder::Builder builder("base_link", "arms");
00016 builder.AddPoseGoal("r_wrist_roll_link", pose);
00017 builder.AddPathOrientationConstraint(orientation_constraint);
00018 builder.planning_time = 10.0;
00019 builder.num_planning_attempts = 3;
00020 builder.can_replan = true;
00021 builder.replan_attempts = 3;
00022
00023 moveit_msgs::MoveGroupGoal goal;
00024 builder.Build(&goal);
00025 ~~~
00026
00027 ## Python example
00028 ~~~{.py}
00029 # To move to a current robot pose with a few options changed.
00030 builder = MoveItGoalBuilder()
00031 builder.set_pose_goal(pose_stamped)
00032 builder.replan = True
00033 builder.replan_attempts = 10
00034 goal = builder.build()
00035 ~~~
00036
00037 ## C++ vs. Python
00038 The C++ and Python APIs are similar, but with a few differences:
00039 - The C++ version supports multi-arm goals, the Python version does not.
00040 - The Python version takes PoseStamped messages for the pose goal and transforms them when you call `build`.
00041 The C++ version takes Pose messages, which are assumed to be in the planning frame.