Go to the documentation of this file.
30 namespace constraint {
46 using uniform::SE2BoxConstraint;
47 using uniform::SO2UniformSampler;
48 using uniform::SO3UniformSampler;
50 using dart::CollisionFree;
51 using dart::CollisionFreeOutcome;
56 using dart::FrameDifferentiable;
57 using dart::FramePairDifferentiable;
58 using dart::FrameTestable;
59 using dart::InverseKinematicsSampleable;
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< 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 > 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...
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.