specialization of SimpleGraspBase to realize ungrasping More...
#include <simple_grasp.h>
Public Member Functions | |
SimpleUnGrasp (Stage::pointer &&generator=Stage::pointer(), const std::string &name="ungrasp") | |
![]() | |
void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
void | setEndEffector (const std::string &eef) |
void | setIKFrame (const Eigen::Isometry3d &pose, const std::string &link) |
void | setIKFrame (const geometry_msgs::PoseStamped &transform) |
set properties of IK solver More... | |
void | setIKFrame (const std::string &link) |
template<typename T > | |
void | setIKFrame (const T &transform, const std::string &link) |
allow setting IK frame from any type T that converts to Eigen::Isometry3d More... | |
void | setMaxIKSolutions (uint32_t max_ik_solutions) |
void | setObject (const std::string &object) |
SimpleGraspBase (const std::string &name) | |
![]() | |
bool | canCompute () const override |
void | compute () override |
SerialContainer (const std::string &name="serial container") | |
![]() | |
void | add (Stage::pointer &&stage) |
virtual void | clear () |
bool | explainFailure (std::ostream &os) const override |
Stage * | findChild (const std::string &name) const |
virtual void | insert (Stage::pointer &&stage, int before=-1) |
size_t | numChildren () const |
Stage * | operator[] (int index) const |
bool | pruning () const |
virtual Stage::pointer | remove (int pos) |
virtual Stage::pointer | remove (Stage *child) |
void | reset () override |
reset stage, clearing all solutions, interfaces, inherited properties. More... | |
void | setPruning (bool pruning) |
Explicitly enable/disable pruning. More... | |
bool | traverseChildren (const StageCallback &processor) const |
traverse direct children of this container, calling the callback for each of them More... | |
bool | traverseRecursively (const StageCallback &processor) const |
traverse all children of this container recursively More... | |
![]() | |
SolutionCallbackList::const_iterator | addSolutionCallback (SolutionCallback &&cb) |
add function to be called for every newly found solution or failure More... | |
const std::list< SolutionBaseConstPtr > & | failures () const |
std::set< std::string > | forwardedProperties () const |
void | forwardProperties (const InterfaceState &source, InterfaceState &dest) |
forwarding of properties between interface states More... | |
double | getTotalComputeTime () const |
Introspection * | introspection () const |
uint32_t | introspectionId () const |
const std::string & | markerNS () |
marker namespace of solution markers More... | |
const std::string & | name () const |
size_t | numFailures () const |
const ContainerBase * | parent () const |
PropertyMap & | properties () |
Get the stage's property map. More... | |
const PropertyMap & | properties () const |
void | removeSolutionCallback (SolutionCallbackList::const_iterator which) |
remove function callback More... | |
void | reportPropertyError (const Property::error &e) |
Analyze source of error and report accordingly. More... | |
void | setCostTerm (const CostTermConstPtr &term) |
template<typename T , typename = std::enable_if_t<std::is_constructible<LambdaCostTerm, T>::value>> | |
void | setCostTerm (T term) |
void | setForwardedProperties (const std::set< std::string > &names) |
void | setMarkerNS (const std::string &marker_ns) |
void | setName (const std::string &name) |
void | setProperty (const std::string &name, const boost::any &value) |
Set a previously declared property to a new value. More... | |
void | setProperty (const std::string &name, const char *value) |
overload: const char* values are stored as std::string More... | |
void | setTimeout (double timeout) |
void | setTrajectoryExecutionInfo (TrajectoryExecutionInfo trajectory_execution_info) |
Set and get info to use when executing the stage's trajectory. More... | |
void | silentFailure () |
Call to increase number of failures w/o storing a (failure) trajectory. More... | |
const ordered< SolutionBaseConstPtr > & | solutions () const |
bool | storeFailures () const |
Should we generate failure solutions? Note: Always report a failure! More... | |
double | timeout () const |
timeout of stage per computation More... | |
TrajectoryExecutionInfo | trajectoryExecutionInfo () const |
virtual | ~Stage () |
Additional Inherited Members | |
![]() | |
using | pointer = std::unique_ptr< ContainerBase > |
using | StageCallback = std::function< bool(const Stage &, unsigned int)> |
![]() | |
using | pointer = std::unique_ptr< Stage > |
enum | PropertyInitializerSource : uint8_t { DEFAULT = 0, MANUAL = 1, PARENT = 2, INTERFACE = 4 } |
using | SolutionCallback = std::function< void(const SolutionBase &)> |
using | SolutionCallbackList = std::list< SolutionCallback > |
![]() | |
void | setup (std::unique_ptr< Stage > &&generator, bool forward) |
![]() | |
void | onNewSolution (const SolutionBase &s) override |
called by a (direct) child when a new solution becomes available More... | |
SerialContainer (SerialContainerPrivate *impl) | |
![]() | |
ContainerBase (ContainerBasePrivate *impl) | |
![]() | |
Stage (const Stage &)=delete | |
Stage cannot be copied. More... | |
Stage (StagePrivate *impl) | |
Stage can only be instantiated through derived classes. More... | |
![]() | |
StagePrivate * | pimpl_ |
specialization of SimpleGraspBase to realize ungrasping
Definition at line 101 of file simple_grasp.h.
moveit::task_constructor::stages::SimpleUnGrasp::SimpleUnGrasp | ( | Stage::pointer && | generator = Stage::pointer() , |
const std::string & | name = "ungrasp" |
||
) |
Definition at line 253 of file simple_grasp.cpp.