Only released in EOL distros:
Package Summary
The moveit_goal_builder package
- Maintainer status: developed
- Maintainer: Justin Huang <jstn AT cs.washington DOT edu>
- Author:
- License: BSD
- Source: git https://github.com/jstnhuang/moveit_goal_builder.git (branch: indigo-devel)
Use GitHub to report bugs or submit feature requests. [View active issues]
Overview
moveit_goal_builder is a library for building MoveGroup action goals. This is useful for when you want to use the MoveGroup actionlib interface directly, instead of using the MoveGroup class. This allows you to poll when the action is done, which the normal MoveGroup interface does not allow you to do.
C++ example
To build a goal, create a new moveit_goal_builder::Builder, add a goal, some constraints, and set other options. Then, call Build():
1 #include "moveit_goal_builder/builder.h"
2
3 moveit_goal_builder::Builder builder("base_link", "arms");
4 builder.AddPoseGoal("r_wrist_roll_link", pose);
5 builder.AddPathOrientationConstraint(orientation_constraint);
6 builder.planning_time = 10.0;
7 builder.num_planning_attempts = 2;
8 builder.can_replan = true;
9 builder.replan_attempts = 3;
10
11 moveit_msgs::MoveGroupGoal goal;
12 builder.Build(&goal);
Python example
Differences between C++ and Python
The C++ and Python APIs are similar, but with a few differences:
- The C++ version supports multi-arm goals, the Python version does not.
The Python version takes geometry_msgs/PoseStamped messages for the pose goal and transforms them when you call build. The C++ version takes geometry_msgs/Pose messages, which are assumed to be in the planning frame.