|
MTC
|
#include <generate_place_pose.h>


Public Member Functions | |
| GeneratePlacePose (const std::string &name="place pose") | |
| void | compute () override |
| void | setObject (const std::string &object) |
Public Member Functions inherited from moveit::task_constructor::stages::GeneratePose | |
| GeneratePose (const std::string &name="generate pose") | |
| void | reset () override |
| reset stage, clearing all solutions, interfaces, inherited properties. | |
| bool | canCompute () const override |
| void | compute () override |
| void | setPose (const geometry_msgs::PoseStamped &pose) |
Public Member Functions inherited from moveit::task_constructor::MonitoringGenerator | |
| MonitoringGenerator (const std::string &name="monitoring generator", Stage *monitored=nullptr) | |
| void | setMonitoredStage (Stage *monitored) |
| void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
Public Member Functions inherited from moveit::task_constructor::Generator | |
| Generator (const std::string &name="generator") | |
| void | spawn (InterfaceState &&from, InterfaceState &&to, SubTrajectory &&trajectory) |
| void | spawn (InterfaceState &&state, SubTrajectory &&trajectory) |
| void | spawn (InterfaceState &&state, double cost) |
Public Member Functions inherited from moveit::task_constructor::Stage | |
| 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 bool | explainFailure (std::ostream &) 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 |
Protected Member Functions | |
| void | onNewSolution (const SolutionBase &s) override |
| called by monitored stage when a new solution was generated | |
Protected Member Functions inherited from moveit::task_constructor::stages::GeneratePose | |
| void | onNewSolution (const SolutionBase &s) override |
| called by monitored stage when a new solution was generated | |
Protected Member Functions inherited from moveit::task_constructor::MonitoringGenerator | |
| MonitoringGenerator (MonitoringGeneratorPrivate *impl) | |
Protected Member Functions inherited from moveit::task_constructor::Generator | |
| Generator (GeneratorPrivate *impl) | |
Protected Member Functions inherited from moveit::task_constructor::ComputeBase | |
| ComputeBase (ComputeBasePrivate *impl) | |
| ComputeBase can only be instantiated by derived classes in stage.cpp. | |
Protected Member Functions inherited from moveit::task_constructor::Stage | |
| Stage (StagePrivate *impl) | |
| Stage can only be instantiated through derived classes. | |
| Stage (const Stage &)=delete | |
| Stage cannot be copied. | |
Additional Inherited Members | |
Public Types inherited from moveit::task_constructor::Stage | |
| enum | PropertyInitializerSource : uint8_t { DEFAULT = 0 , MANUAL = 1 , PARENT = 2 , INTERFACE = 4 } |
| using | pointer = std::unique_ptr< Stage > |
| using | SolutionCallback = std::function< void(const SolutionBase &)> |
| using | SolutionCallbackList = std::list< SolutionCallback > |
Protected Attributes inherited from moveit::task_constructor::stages::GeneratePose | |
| ordered< const SolutionBase * > | upstream_solutions_ |
Protected Attributes inherited from moveit::task_constructor::Stage | |
| StagePrivate * | pimpl_ |
Simple IK pose generator to place an attached object in a specific pose
The "pose" property, inherited from GeneratePose specifies the target pose of the grasped object. This stage transforms this pose into a target pose for the ik_frame