| 
    Aikido
    
   | 
 
Implements a Euclidean distance metric. More...
#include <aikido/distance/RnEuclidean.hpp>
  
Public Member Functions | |
| REuclidean (std::shared_ptr< const statespace::R< N >> _space) | |
| Constructor.  More... | |
| statespace::ConstStateSpacePtr | getStateSpace () const override | 
| Get the StateSpace associated with this metric.  More... | |
| double | distance (const statespace::StateSpace::State *_state1, const statespace::StateSpace::State *_state2) const override | 
| Computes Euclidean distance between two states.  More... | |
  Public Member Functions inherited from aikido::distance::DistanceMetric | |
| virtual | ~DistanceMetric ()=default | 
| Destructor.  More... | |
Private Attributes | |
| std::shared_ptr< const statespace::R< N > > | mStateSpace | 
Implements a Euclidean distance metric.
      
  | 
  explicit | 
Constructor.
| _space | The Rn this metric operates on | 
      
  | 
  overridevirtual | 
Computes Euclidean distance between two states.
| _state1 | The first state (type Rn::State) | 
| _state2 | The second state (type Rn::State) | 
Implements aikido::distance::DistanceMetric.
      
  | 
  overridevirtual | 
Get the StateSpace associated with this metric.
Implements aikido::distance::DistanceMetric.
      
  | 
  private |