|
| MoveRelative (const std::string &name="move relative", const solvers::PlannerInterfacePtr &planner=solvers::PlannerInterfacePtr()) |
|
void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
|
void | setGroup (const std::string &group) |
|
void | setIKFrame (const geometry_msgs::PoseStamped &pose) |
| setters for IK frame
|
|
void | setIKFrame (const Eigen::Isometry3d &pose, const std::string &link) |
|
template<typename T > |
void | setIKFrame (const T &p, const std::string &link) |
|
void | setIKFrame (const std::string &link) |
|
void | setMinDistance (double distance) |
| set minimum / maximum distance to move
|
|
void | setMaxDistance (double distance) |
|
void | setMinMaxDistance (double min_distance, double max_distance) |
|
void | setPathConstraints (moveit_msgs::Constraints path_constraints) |
|
void | setDirection (const geometry_msgs::TwistStamped &twist) |
| perform twist motion on specified link
|
|
void | setDirection (const geometry_msgs::Vector3Stamped &direction) |
| translate link along given direction
|
|
void | setDirection (const std::map< std::string, double > &joint_deltas) |
| move specified joint variables by given amount
|
|
| PropagatingEitherWay (const std::string &name="propagating either way") |
|
void | restrictDirection (Direction dir) |
|
virtual void | computeForward (const InterfaceState &from) |
|
virtual void | computeBackward (const InterfaceState &to) |
|
virtual void | reset () |
| reset stage, clearing all solutions, interfaces, inherited properties.
|
|
const ContainerBase * | parent () const |
|
const std::string & | name () const |
|
void | setName (const std::string &name) |
|
uint32_t | introspectionId () const |
|
Introspection * | introspection () const |
|
void | setTimeout (double timeout) |
|
double | timeout () const |
| timeout of stage per computation
|
|
void | setMarkerNS (const std::string &marker_ns) |
|
const std::string & | markerNS () |
| marker namespace of solution markers
|
|
void | setTrajectoryExecutionInfo (TrajectoryExecutionInfo trajectory_execution_info) |
| Set and get info to use when executing the stage's trajectory.
|
|
TrajectoryExecutionInfo | trajectoryExecutionInfo () const |
|
void | forwardProperties (const InterfaceState &source, InterfaceState &dest) |
| forwarding of properties between interface states
|
|
std::set< std::string > | forwardedProperties () const |
|
void | setForwardedProperties (const std::set< std::string > &names) |
|
SolutionCallbackList::const_iterator | addSolutionCallback (SolutionCallback &&cb) |
| add function to be called for every newly found solution or failure
|
|
void | removeSolutionCallback (SolutionCallbackList::const_iterator which) |
| remove function callback
|
|
void | setCostTerm (const CostTermConstPtr &term) |
|
template<typename T , typename = std::enable_if_t<std::is_constructible<LambdaCostTerm, T>::value>> |
void | setCostTerm (T term) |
|
const ordered< SolutionBaseConstPtr > & | solutions () const |
|
const std::list< SolutionBaseConstPtr > & | failures () const |
|
size_t | numFailures () const |
|
void | silentFailure () |
| Call to increase number of failures w/o storing a (failure) trajectory.
|
|
bool | storeFailures () const |
| Should we generate failure solutions? Note: Always report a failure!
|
|
virtual void | explainFailure (std::ostream &os) const |
|
PropertyMap & | properties () |
| Get the stage's property map.
|
|
const PropertyMap & | properties () const |
|
void | setProperty (const std::string &name, const boost::any &value) |
| Set a previously declared property to a new value.
|
|
void | setProperty (const std::string &name, const char *value) |
| overload: const char* values are stored as std::string
|
|
void | reportPropertyError (const Property::error &e) |
| Analyze source of error and report accordingly.
|
|
double | getTotalComputeTime () const |
|
Perform a Cartesian motion relative to some link