Public Member Functions | List of all members
moveit::task_constructor::stages::SimpleUnGrasp Class Reference

specialization of SimpleGraspBase to realize ungrasping More...

#include <simple_grasp.h>

Inheritance diagram for moveit::task_constructor::stages::SimpleUnGrasp:
Inheritance graph
[legend]

Public Member Functions

 SimpleUnGrasp (Stage::pointer &&generator=Stage::pointer(), const std::string &name="ungrasp")
 
- Public Member Functions inherited from moveit::task_constructor::stages::SimpleGraspBase
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)
 
- Public Member Functions inherited from moveit::task_constructor::SerialContainer
bool canCompute () const override
 
void compute () override
 
 SerialContainer (const std::string &name="serial container")
 
- Public Member Functions inherited from moveit::task_constructor::ContainerBase
void add (Stage::pointer &&stage)
 
virtual void clear ()
 
bool explainFailure (std::ostream &os) const override
 
StagefindChild (const std::string &name) const
 
virtual void insert (Stage::pointer &&stage, int before=-1)
 
size_t numChildren () const
 
Stageoperator[] (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...
 
- Public Member Functions inherited from moveit::task_constructor::Stage
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
 
Introspectionintrospection () 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 ContainerBaseparent () const
 
PropertyMapproperties ()
 Get the stage's property map. More...
 
const PropertyMapproperties () 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

- Public Types inherited from moveit::task_constructor::ContainerBase
using pointer = std::unique_ptr< ContainerBase >
 
using StageCallback = std::function< bool(const Stage &, unsigned int)>
 
- Public Types inherited from moveit::task_constructor::Stage
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 >
 
- Protected Member Functions inherited from moveit::task_constructor::stages::SimpleGraspBase
void setup (std::unique_ptr< Stage > &&generator, bool forward)
 
- Protected Member Functions inherited from moveit::task_constructor::SerialContainer
void onNewSolution (const SolutionBase &s) override
 called by a (direct) child when a new solution becomes available More...
 
 SerialContainer (SerialContainerPrivate *impl)
 
- Protected Member Functions inherited from moveit::task_constructor::ContainerBase
 ContainerBase (ContainerBasePrivate *impl)
 
- Protected Member Functions inherited from moveit::task_constructor::Stage
 Stage (const Stage &)=delete
 Stage cannot be copied. More...
 
 Stage (StagePrivate *impl)
 Stage can only be instantiated through derived classes. More...
 
- Protected Attributes inherited from moveit::task_constructor::Stage
StagePrivate * pimpl_
 

Detailed Description

specialization of SimpleGraspBase to realize ungrasping

Definition at line 101 of file simple_grasp.h.

Constructor & Destructor Documentation

◆ SimpleUnGrasp()

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.


The documentation for this class was generated from the following files:


core
Author(s):
autogenerated on Sat May 3 2025 02:40:11