Go to the documentation of this file. 1 #ifndef AIKIDO_CONSTRAINT_DART_JOINTSTATESPACEHELPERS_HPP_
2 #define AIKIDO_CONSTRAINT_DART_JOINTSTATESPACEHELPERS_HPP_
12 namespace constraint {
17 template <
class Space>
19 std::shared_ptr<Space> _stateSpace);
27 std::shared_ptr<const statespace::dart::JointStateSpace> _stateSpace);
41 template <
class Space>
43 std::shared_ptr<Space> _stateSpace);
51 std::shared_ptr<const statespace::dart::JointStateSpace> _stateSpace);
64 template <
class Space>
66 std::shared_ptr<Space> _stateSpace);
73 std::shared_ptr<const statespace::dart::JointStateSpace> _stateSpace);
87 template <
class Space>
89 std::shared_ptr<Space> _stateSpace, std::unique_ptr<common::RNG> _rng);
98 std::shared_ptr<const statespace::dart::JointStateSpace> _stateSpace,
99 std::unique_ptr<common::RNG> _rng);
109 std::unique_ptr<common::RNG> _rng);
115 #include "detail/JointStateSpaceHelpers-impl.hpp"
117 #endif // AIKIDO_CONSTRAINT_DART_JOINTSTATESPACEHELPERS_HPP_
std::shared_ptr< const MetaSkeletonStateSpace > ConstMetaSkeletonStateSpacePtr
Definition: MetaSkeletonStateSpace.hpp:17
std::unique_ptr< Sampleable > createSampleableBounds(std::shared_ptr< const statespace::dart::JointStateSpace > _stateSpace, std::unique_ptr< common::RNG > _rng)
Create a Sampleabe constraint that can be used to sample values for the joint that are guarenteed to ...
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
std::unique_ptr< Sampleable > createSampleableBoundsFor(std::shared_ptr< Space > _stateSpace, std::unique_ptr< common::RNG > _rng)
Create a Sampleable constraint that can be used to sample a state that is guarenteed to lie within bo...
Definition: JointStateSpaceHelpers-impl.hpp:544
std::unique_ptr< Projectable > createProjectableBoundsFor(std::shared_ptr< Space > _stateSpace)
Create a Projectable that can be used to project a state from the given StateSpace back within bounds...
Definition: JointStateSpaceHelpers-impl.hpp:526
std::unique_ptr< Differentiable > createDifferentiableBounds(std::shared_ptr< const statespace::dart::JointStateSpace > _stateSpace)
Create differentiable bounds that can be applied to the given StateSpace The differentiable bounds ar...
std::unique_ptr< Testable > createTestableBoundsFor(std::shared_ptr< Space > _stateSpace)
Create a Testable constraint that can be used to determine if a given state lies within bounds set on...
Definition: JointStateSpaceHelpers-impl.hpp:535
std::unique_ptr< Differentiable > createDifferentiableBoundsFor(std::shared_ptr< Space > _stateSpace)
Create differentiable bounds that can be applied to the given StateSpace.
Definition: JointStateSpaceHelpers-impl.hpp:517
std::unique_ptr< Testable > createTestableBounds(std::shared_ptr< const statespace::dart::JointStateSpace > _stateSpace)
Create a Testable constraint that can be used to determine if the value of a joint is within the join...
Definition: FrameMarker.hpp:11
std::unique_ptr< Projectable > createProjectableBounds(std::shared_ptr< const statespace::dart::JointStateSpace > _stateSpace)
Create a Projectable that can be used to project the value of a joint back within joint limits.