Aikido
TestableIntersection.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_CONSTRAINT_TESTABLEINTERSECTION_HPP_
2 #define AIKIDO_CONSTRAINT_TESTABLEINTERSECTION_HPP_
3 
4 #include <memory>
5 #include <vector>
6 
8 
9 namespace aikido {
10 namespace constraint {
11 
13 
14 class TestableIntersection : public Testable
18 {
19 public:
25  std::vector<ConstTestablePtr> _constraints
26  = std::vector<ConstTestablePtr>());
27 
28  // Documentation inherited.
29  bool isSatisfied(
31  TestableOutcome* outcome = nullptr) const override;
32 
35  std::unique_ptr<TestableOutcome> createOutcome() const override;
36 
37  // Documentation inherited.
39 
43  void addConstraint(ConstTestablePtr constraint);
44 
45 private:
47  std::vector<ConstTestablePtr> mConstraints;
48 
49  void testConstraintStateSpaceOrThrow(const ConstTestablePtr& constraint);
50 };
51 
52 } // namespace constraint
53 } // namespace aikido
54 
55 #endif // AIKIDO_CONSTRAINT_TESTABLEINTERSECTION_HPP_
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::constraint::TestableIntersection
A testable constraint grouping a set of testable constraint.
Definition: TestableIntersection.hpp:17
aikido::constraint::TestableIntersection::testConstraintStateSpaceOrThrow
void testConstraintStateSpaceOrThrow(const ConstTestablePtr &constraint)
aikido::constraint::Testable
Constraint which can be tested.
Definition: Testable.hpp:17
aikido::statespace::ConstStateSpacePtr
std::shared_ptr< const StateSpace > ConstStateSpacePtr
Definition: StateSpace.hpp:15
aikido::constraint::TestableIntersection::getStateSpace
statespace::ConstStateSpacePtr getStateSpace() const override
Returns StateSpace in which this constraint operates.
aikido::constraint::TestableIntersection::createOutcome
std::unique_ptr< TestableOutcome > createOutcome() const override
Return an instance of DefaultTestableOutcome, since this class doesn't have a more specialized Testab...
aikido::constraint::TestableOutcome
Base class for constraint outcomes.
Definition: TestableOutcome.hpp:13
aikido::constraint::TestableIntersection::TestableIntersection
TestableIntersection(statespace::ConstStateSpacePtr _stateSpace, std::vector< ConstTestablePtr > _constraints=std::vector< ConstTestablePtr >())
Construct a TestableIntersection on a specific StateSpace.
Testable.hpp
aikido::constraint::TestableIntersection::mConstraints
std::vector< ConstTestablePtr > mConstraints
Definition: TestableIntersection.hpp:47
aikido::statespace::StateSpace::State
Definition: StateSpace.hpp:167
AIKIDO_DECLARE_POINTERS
#define AIKIDO_DECLARE_POINTERS(X)
Definition: pointers.hpp:21
aikido::constraint::TestableIntersection::isSatisfied
bool isSatisfied(const aikido::statespace::StateSpace::State *state, TestableOutcome *outcome=nullptr) const override
Returns true if state satisfies this constraint.
aikido::constraint::TestableIntersection::addConstraint
void addConstraint(ConstTestablePtr constraint)
Add a Testable to the conjunction.
aikido::constraint::TestableIntersection::mStateSpace
statespace::ConstStateSpacePtr mStateSpace
Definition: TestableIntersection.hpp:46
aikido::constraint::ConstTestablePtr
std::shared_ptr< const Testable > ConstTestablePtr
Definition: Testable.hpp:13