Aikido
SO3Angular.hpp
Go to the documentation of this file.
1 #ifndef AIKIDO_DISTANCE_GEODESICDISTANCEMETRIC_HPP_
2 #define AIKIDO_DISTANCE_GEODESICDISTANCEMETRIC_HPP_
3 
6 
7 namespace aikido {
8 namespace distance {
9 
11 class SO3Angular : public DistanceMetric
12 {
13 public:
16  explicit SO3Angular(std::shared_ptr<const statespace::SO3> _space);
17 
18  // Documentation inherited
20 
24  double distance(
25  const statespace::StateSpace::State* _state1,
26  const statespace::StateSpace::State* _state2) const override;
27 
28 private:
29  std::shared_ptr<const statespace::SO3> mStateSpace;
30 };
31 
32 } // namespace distance
33 } // namespace aikido
34 
35 #endif
aikido
Format of serialized trajectory in YAML.
Definition: algorithm.hpp:4
aikido::statespace::ConstStateSpacePtr
std::shared_ptr< const StateSpace > ConstStateSpacePtr
Definition: StateSpace.hpp:15
aikido::distance::SO3Angular
Implements a distance metric on SO(3)
Definition: SO3Angular.hpp:11
aikido::distance::SO3Angular::SO3Angular
SO3Angular(std::shared_ptr< const statespace::SO3 > _space)
Constructor.
aikido::distance::SO3Angular::mStateSpace
std::shared_ptr< const statespace::SO3 > mStateSpace
Definition: SO3Angular.hpp:29
aikido::distance::SO3Angular::distance
double distance(const statespace::StateSpace::State *_state1, const statespace::StateSpace::State *_state2) const override
Computes distance (in radians) between the two states.
SO3.hpp
DistanceMetric.hpp
aikido::distance::DistanceMetric
Implements a distance metric defined on a StateSpace.
Definition: DistanceMetric.hpp:13
aikido::statespace::StateSpace::State
Definition: StateSpace.hpp:167
aikido::distance::SO3Angular::getStateSpace
statespace::ConstStateSpacePtr getStateSpace() const override
Get the StateSpace associated with this metric.