MTC
|
#include <connect.h>
Public Types | |
enum | MergeMode : uint8_t { SEQUENTIAL = 0 , WAYPOINTS = 1 } |
using | GroupPlannerVector = std::vector< std::pair< std::string, solvers::PlannerInterfacePtr > > |
![]() | |
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 > |
Public Member Functions | |
Connect (const std::string &name="connect", const GroupPlannerVector &planners={}) | |
void | setMaxDistance (double max_distance) |
void | setPathConstraints (moveit_msgs::Constraints path_constraints) |
void | reset () override |
reset stage, clearing all solutions, interfaces, inherited properties. | |
void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
void | compute (const InterfaceState &from, const InterfaceState &to) override |
![]() | |
Connecting (const std::string &name="connecting") | |
![]() | |
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 | |
bool | compatible (const InterfaceState &from_state, const InterfaceState &to_state) const override |
compare consistency of planning scenes | |
SolutionSequencePtr | makeSequential (const std::vector< robot_trajectory::RobotTrajectoryConstPtr > &sub_trajectories, const std::vector< planning_scene::PlanningSceneConstPtr > &intermediate_scenes, const InterfaceState &from, const InterfaceState &to) |
SubTrajectoryPtr | merge (const std::vector< robot_trajectory::RobotTrajectoryConstPtr > &sub_trajectories, const std::vector< planning_scene::PlanningSceneConstPtr > &intermediate_scenes, const moveit::core::RobotState &state) |
![]() | |
void | connect (const InterfaceState &from, const InterfaceState &to, const SolutionBasePtr &solution) |
register solution as a solution connecting states from -> to | |
void | connect (const InterfaceState &from, const InterfaceState &to, SubTrajectory &&trajectory) |
convienency methods consuming a SubTrajectory | |
void | connect (const InterfaceState &from, const InterfaceState &to, SubTrajectory &&trajectory, double cost) |
![]() | |
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. | |
Protected Attributes | |
GroupPlannerVector | planner_ |
moveit::core::JointModelGroupPtr | merged_jmg_ |
std::list< SubTrajectory > | subsolutions_ |
std::list< InterfaceState > | states_ |
![]() | |
StagePrivate * | pimpl_ |
Connect arbitrary InterfaceStates by motion planning
The states may differ in various planning groups. To connect both states, the planners provided for individual sub groups are applied in the specified order. Each planner only plan for joints within the corresponding planning group. Finally, an attempt is made to merge the sub trajectories of individual planning results. If this fails, the sequential planning result is returned.
|
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.