Public Member Functions | Protected Attributes
constraint_samplers::UnionConstraintSampler Class Reference

This class exists as a union of constraint samplers. It contains a vector of constraint samplers, and will sample from each of them. More...

#include <union_constraint_sampler.h>

Inheritance diagram for constraint_samplers::UnionConstraintSampler:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool canService (const moveit_msgs::Constraints &constr) const
 No-op, as the union constraint sampler can act on anything.
virtual bool configure (const moveit_msgs::Constraints &constr)
 No-op, as the union constraint sampler is for already configured samplers.
const std::vector
< ConstraintSamplerPtr > & 
getSamplers () const
 Gets the sorted internal list of constraint samplers.
virtual bool project (robot_state::JointStateGroup *jsg, const robot_state::RobotState &ks, unsigned int max_attempts)
 Project a sample given the constraints, updating the joint state group. This function allows the parameter max_attempts to be set.
virtual bool sample (robot_state::JointStateGroup *jsg, const robot_state::RobotState &ks, unsigned int max_attempts)
 Produces a sample from all configured samplers.
 UnionConstraintSampler (const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::vector< ConstraintSamplerPtr > &samplers)
 Constructor, which will re-order its internal list of samplers on construction.

Protected Attributes

std::vector< ConstraintSamplerPtrsamplers_
 Holder for sorted internal list of samplers.

Detailed Description

This class exists as a union of constraint samplers. It contains a vector of constraint samplers, and will sample from each of them.

When asked to sample it will call the samplers in a sorted order that samples more general groups - like a robot's whole body - before sampling more specific groups, such as a robot's arm. Member samplers can operate on all or part of a joint state group vector, with later samplers potentially overwriting previous samplers.

Definition at line 57 of file union_constraint_sampler.h.


Constructor & Destructor Documentation

constraint_samplers::UnionConstraintSampler::UnionConstraintSampler ( const planning_scene::PlanningSceneConstPtr scene,
const std::string &  group_name,
const std::vector< ConstraintSamplerPtr > &  samplers 
)

Constructor, which will re-order its internal list of samplers on construction.

The samplers need not all refer to the same group, as long as all are part of the kinematic model. The sampler will sort the samplers based on a set of criteria - where A and B are two samplers being considered for swapping by a sort algorithm:

  • If the set of links updated by the group of A are a proper subset of the set of links updated by the group of B, A and B are not swapped. If the updated links of B are a proper set of the updated links of A, A and B are swapped.
  • Otherwise, the groups associated with A and B are either disjoint in terms of updated links or have an equivalent group. In this case, it is determined if any updated links in the group for A exist in the frame dependency of B, or vice-versa.
  • If A depends on B, and B depends on A, a warning message is printed that circular dependencies are likely to lead to bad samples. A and B are not swapped.
  • If one of the frame dependencies of B is a link updated by A, but not vice-versa, the samplers are swapped.
  • If one of the frame dependencies of A is a link updated by B, but not vice-versa, the samplers are not swapped.
  • If no dependency exists, the samplers are swapped according to alphabetical order.
Parameters:
[in]sceneThe planning scene
[in]group_nameThe group name is ignored, as each sampler already has a group name
[in]samplersA vector of already configured samplers that will be applied for future samples
Returns:

Definition at line 108 of file union_constraint_sampler.cpp.


Member Function Documentation

virtual bool constraint_samplers::UnionConstraintSampler::canService ( const moveit_msgs::Constraints &  constr) const [inline, virtual]

No-op, as the union constraint sampler can act on anything.

Parameters:
[in]constrConstraint message
Returns:
Always true

Definition at line 133 of file union_constraint_sampler.h.

virtual bool constraint_samplers::UnionConstraintSampler::configure ( const moveit_msgs::Constraints &  constr) [inline, virtual]

No-op, as the union constraint sampler is for already configured samplers.

Parameters:
[in]constrConstraint message
Returns:
Always true

Implements constraint_samplers::ConstraintSampler.

Definition at line 121 of file union_constraint_sampler.h.

Gets the sorted internal list of constraint samplers.

Returns:
The sorted internal list of constraint samplers

Definition at line 108 of file union_constraint_sampler.h.

bool constraint_samplers::UnionConstraintSampler::project ( robot_state::JointStateGroup jsg,
const robot_state::RobotState reference_state,
unsigned int  max_attempts 
) [virtual]

Project a sample given the constraints, updating the joint state group. This function allows the parameter max_attempts to be set.

Parameters:
[out]jsgThe joint state group which specifies the state to be projected, according to the constraints
[in]reference_stateReference state that will be used to do transforms or perform other actions
[in]max_attemptsThe maximum number of times to attempt to draw a sample. If no sample has been drawn in this number of attempts, false will be returned.
Returns:
True if a sample was successfully projected, false otherwise

Implements constraint_samplers::ConstraintSampler.

Definition at line 156 of file union_constraint_sampler.cpp.

bool constraint_samplers::UnionConstraintSampler::sample ( robot_state::JointStateGroup jsg,
const robot_state::RobotState ks,
unsigned int  max_attempts 
) [virtual]

Produces a sample from all configured samplers.

This function will call each sampler in sorted order independently of the group associated with the sampler. The function will also operate independently of the joint state group passed in as an argument. If any sampler fails, the sample fails altogether.

Parameters:
[in]jsgA joint state group, which only needs to have a valid associated kinematic model
[in]ksReference kinematic state that will be passed through to samplers
[in]max_attemptsMax attempts, which will be passed through to samplers
Returns:
True if all invidual samplers return true

Implements constraint_samplers::ConstraintSampler.

Definition at line 125 of file union_constraint_sampler.cpp.


Member Data Documentation

Holder for sorted internal list of samplers.

Definition at line 159 of file union_constraint_sampler.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:48