Go to the documentation of this file.    1 #ifndef AIKIDO_CONSTRAINT_TESTABLEINTERSECTION_HPP_ 
    2 #define AIKIDO_CONSTRAINT_TESTABLEINTERSECTION_HPP_ 
   10 namespace constraint {
 
   25       std::vector<ConstTestablePtr> _constraints
 
   26       = std::vector<ConstTestablePtr>());
 
   35   std::unique_ptr<TestableOutcome> 
createOutcome() 
const override;
 
   55 #endif // AIKIDO_CONSTRAINT_TESTABLEINTERSECTION_HPP_ 
 
 
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
 
A testable constraint grouping a set of testable constraint.
Definition: TestableIntersection.hpp:17
 
void testConstraintStateSpaceOrThrow(const ConstTestablePtr &constraint)
 
Constraint which can be tested.
Definition: Testable.hpp:17
 
std::shared_ptr< const StateSpace > ConstStateSpacePtr
Definition: StateSpace.hpp:15
 
statespace::ConstStateSpacePtr getStateSpace() const override
Returns StateSpace in which this constraint operates.
 
std::unique_ptr< TestableOutcome > createOutcome() const override
Return an instance of DefaultTestableOutcome, since this class doesn't have a more specialized Testab...
 
Base class for constraint outcomes.
Definition: TestableOutcome.hpp:13
 
TestableIntersection(statespace::ConstStateSpacePtr _stateSpace, std::vector< ConstTestablePtr > _constraints=std::vector< ConstTestablePtr >())
Construct a TestableIntersection on a specific StateSpace.
 
std::vector< ConstTestablePtr > mConstraints
Definition: TestableIntersection.hpp:47
 
Definition: StateSpace.hpp:167
 
#define AIKIDO_DECLARE_POINTERS(X)
Definition: pointers.hpp:21
 
bool isSatisfied(const aikido::statespace::StateSpace::State *state, TestableOutcome *outcome=nullptr) const override
Returns true if state satisfies this constraint.
 
void addConstraint(ConstTestablePtr constraint)
Add a Testable to the conjunction.
 
statespace::ConstStateSpacePtr mStateSpace
Definition: TestableIntersection.hpp:46
 
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13