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