Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
moveit::task_constructor::stages::Connect Class Reference

#include <connect.h>

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

Public Types

using GroupPlannerVector = std::vector< std::pair< std::string, solvers::PlannerInterfacePtr > >
 
enum  MergeMode : uint8_t { SEQUENTIAL = 0, WAYPOINTS = 1 }
 
- 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 >
 

Public Member Functions

void compute (const InterfaceState &from, const InterfaceState &to) override
 
 Connect (const std::string &name="connect", const GroupPlannerVector &planners={})
 
void init (const moveit::core::RobotModelConstPtr &robot_model) override
 
void reset () override
 reset stage, clearing all solutions, interfaces, inherited properties. More...
 
void setMaxDistance (double max_distance)
 
void setPathConstraints (moveit_msgs::Constraints path_constraints)
 
- Public Member Functions inherited from moveit::task_constructor::Connecting
 Connecting (const std::string &name="connecting")
 
- 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...
 
virtual bool explainFailure (std::ostream &) const
 
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 ()
 

Protected Member Functions

bool compatible (const InterfaceState &from_state, const InterfaceState &to_state) const override
 compare consistency of planning scenes More...
 
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)
 
- Protected Member Functions inherited from moveit::task_constructor::Connecting
void connect (const InterfaceState &from, const InterfaceState &to, const SolutionBasePtr &solution)
 register solution as a solution connecting states from -> to More...
 
void connect (const InterfaceState &from, const InterfaceState &to, SubTrajectory &&trajectory)
 convienency methods consuming a SubTrajectory More...
 
void connect (const InterfaceState &from, const InterfaceState &to, SubTrajectory &&trajectory, double cost)
 
- Protected Member Functions inherited from moveit::task_constructor::ComputeBase
 ComputeBase (ComputeBasePrivate *impl)
 ComputeBase can only be instantiated by derived classes in stage.cpp. More...
 
- 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

moveit::core::JointModelGroupPtr merged_jmg_
 
GroupPlannerVector planner_
 
std::list< InterfaceStatestates_
 
std::list< SubTrajectorysubsolutions_
 
- Protected Attributes inherited from moveit::task_constructor::Stage
StagePrivate * pimpl_
 

Detailed Description

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.

Definition at line 64 of file connect.h.

Member Typedef Documentation

◆ GroupPlannerVector

using moveit::task_constructor::stages::Connect::GroupPlannerVector = std::vector<std::pair<std::string, solvers::PlannerInterfacePtr> >

Definition at line 76 of file connect.h.

Member Enumeration Documentation

◆ MergeMode

Enumerator
SEQUENTIAL 
WAYPOINTS 

Definition at line 70 of file connect.h.

Constructor & Destructor Documentation

◆ Connect()

moveit::task_constructor::stages::Connect::Connect ( const std::string &  name = "connect",
const GroupPlannerVector planners = {} 
)

Definition at line 53 of file connect.cpp.

Member Function Documentation

◆ compatible()

bool moveit::task_constructor::stages::Connect::compatible ( const InterfaceState from_state,
const InterfaceState to_state 
) const
overrideprotectedvirtual

compare consistency of planning scenes

Reimplemented from moveit::task_constructor::Connecting.

Definition at line 107 of file connect.cpp.

◆ compute()

void moveit::task_constructor::stages::Connect::compute ( const InterfaceState from,
const InterfaceState to 
)
overridevirtual

Implements moveit::task_constructor::Connecting.

Definition at line 138 of file connect.cpp.

◆ init()

void moveit::task_constructor::stages::Connect::init ( const moveit::core::RobotModelConstPtr &  robot_model)
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.

Definition at line 74 of file connect.cpp.

◆ makeSequential()

SolutionSequencePtr moveit::task_constructor::stages::Connect::makeSequential ( const std::vector< robot_trajectory::RobotTrajectoryConstPtr > &  sub_trajectories,
const std::vector< planning_scene::PlanningSceneConstPtr > &  intermediate_scenes,
const InterfaceState from,
const InterfaceState to 
)
protected

Definition at line 196 of file connect.cpp.

◆ merge()

SubTrajectoryPtr moveit::task_constructor::stages::Connect::merge ( const std::vector< robot_trajectory::RobotTrajectoryConstPtr > &  sub_trajectories,
const std::vector< planning_scene::PlanningSceneConstPtr > &  intermediate_scenes,
const moveit::core::RobotState state 
)
protected

Definition at line 232 of file connect.cpp.

◆ reset()

void moveit::task_constructor::stages::Connect::reset ( )
overridevirtual

reset stage, clearing all solutions, interfaces, inherited properties.

Reimplemented from moveit::task_constructor::Connecting.

Definition at line 67 of file connect.cpp.

◆ setMaxDistance()

void moveit::task_constructor::stages::Connect::setMaxDistance ( double  max_distance)
inline

Definition at line 79 of file connect.h.

◆ setPathConstraints()

void moveit::task_constructor::stages::Connect::setPathConstraints ( moveit_msgs::Constraints  path_constraints)
inline

Definition at line 80 of file connect.h.

Member Data Documentation

◆ merged_jmg_

moveit::core::JointModelGroupPtr moveit::task_constructor::stages::Connect::merged_jmg_
protected

Definition at line 98 of file connect.h.

◆ planner_

GroupPlannerVector moveit::task_constructor::stages::Connect::planner_
protected

Definition at line 97 of file connect.h.

◆ states_

std::list<InterfaceState> moveit::task_constructor::stages::Connect::states_
protected

Definition at line 100 of file connect.h.

◆ subsolutions_

std::list<SubTrajectory> moveit::task_constructor::stages::Connect::subsolutions_
protected

Definition at line 99 of file connect.h.


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


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