Aikido
|
#include <sstream>
#include "aikido/common/memory.hpp"
#include "aikido/common/metaprogramming.hpp"
#include "aikido/constraint/Satisfied.hpp"
#include "aikido/constraint/uniform/RnBoxConstraint.hpp"
#include "aikido/constraint/uniform/RnConstantSampler.hpp"
#include "aikido/constraint/uniform/SE2BoxConstraint.hpp"
#include "aikido/constraint/uniform/SO2UniformSampler.hpp"
#include "aikido/constraint/uniform/SO3UniformSampler.hpp"
#include "aikido/statespace/dart/RnJoint.hpp"
#include "aikido/statespace/dart/SE2Joint.hpp"
#include "aikido/statespace/dart/SE3Joint.hpp"
#include "aikido/statespace/dart/SO2Joint.hpp"
#include "aikido/statespace/dart/SO3Joint.hpp"
#include "aikido/statespace/dart/WeldJoint.hpp"
Go to the source code of this file.
Namespaces | |
aikido | |
Format of serialized trajectory in YAML. | |
aikido::constraint | |
aikido::constraint::dart | |
aikido::constraint::dart::detail | |
Typedefs | |
using | aikido::constraint::dart::detail::JointStateSpaceTypeList = common::type_list< const statespace::dart::R0Joint, const statespace::dart::R1Joint, const statespace::dart::R2Joint, const statespace::dart::R3Joint, const statespace::dart::R6Joint, const statespace::dart::SO2Joint, const statespace::dart::SO3Joint, const statespace::dart::SE2Joint, const statespace::dart::SE3Joint, const statespace::dart::WeldJoint > |
Functions | |
template<int N, class OutputConstraint > | |
std::unique_ptr< OutputConstraint > | aikido::constraint::dart::detail::createBoxConstraint (std::shared_ptr< const statespace::dart::RJoint< N >> _stateSpace, std::unique_ptr< common::RNG > _rng) |
template<class OutputConstraint > | |
std::unique_ptr< OutputConstraint > | aikido::constraint::dart::detail::createBoxConstraint (std::shared_ptr< const statespace::dart::SE2Joint > _stateSpace, std::unique_ptr< common::RNG > _rng) |
template<class OutputConstraint > | |
std::unique_ptr< OutputConstraint > | aikido::constraint::dart::detail::createBoxConstraint (std::shared_ptr< const statespace::dart::WeldJoint > _stateSpace, std::unique_ptr< common::RNG >) |
template<class Space > | |
std::unique_ptr< Differentiable > | aikido::constraint::dart::createDifferentiableBoundsFor (std::shared_ptr< Space > _stateSpace) |
Create differentiable bounds that can be applied to the given StateSpace. More... | |
template<class Space > | |
std::unique_ptr< Projectable > | aikido::constraint::dart::createProjectableBoundsFor (std::shared_ptr< Space > _stateSpace) |
Create a Projectable that can be used to project a state from the given StateSpace back within bounds set on the StateSpace. More... | |
template<class Space > | |
std::unique_ptr< Testable > | aikido::constraint::dart::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 the StateSpace. More... | |
template<class Space > | |
std::unique_ptr< Sampleable > | aikido::constraint::dart::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 bounds define on the StateSpace. More... | |