MTC
|
#include <current_state.h>
Public Member Functions | |
CurrentState (const std::string &name="current state") | |
void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
bool | canCompute () const override |
void | compute () override |
![]() | |
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) |
![]() | |
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 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 Attributes | |
moveit::core::RobotModelConstPtr | robot_model_ |
planning_scene::PlanningScenePtr | scene_ |
![]() | |
StagePrivate * | pimpl_ |
Additional Inherited Members | |
![]() | |
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 > |
![]() | |
Generator (GeneratorPrivate *impl) | |
![]() | |
ComputeBase (ComputeBasePrivate *impl) | |
ComputeBase can only be instantiated by derived classes in stage.cpp. | |
![]() | |
Stage (StagePrivate *impl) | |
Stage can only be instantiated through derived classes. | |
Stage (const Stage &)=delete | |
Stage cannot be copied. | |
Fetch the current PlanningScene state via get_planning_scene service
|
overridevirtual |
initialize stage once before planning
When called, properties configured for initialization from parent are already defined. Push interfaces are not yet defined!
Reimplemented from moveit::task_constructor::Stage.