Aikido
|
Implements a distance metric on SO(3) More...
#include <aikido/distance/SO3Angular.hpp>
Public Member Functions | |
SO3Angular (std::shared_ptr< const statespace::SO3 > _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 distance (in radians) between the two states. More... | |
![]() | |
virtual | ~DistanceMetric ()=default |
Destructor. More... | |
Private Attributes | |
std::shared_ptr< const statespace::SO3 > | mStateSpace |
Implements a distance metric on SO(3)
|
explicit |
Constructor.
_space | The SO3 this distance metric operates on |
|
overridevirtual |
Computes distance (in radians) between the two states.
_state1 | The first state (type SO3::State) |
_state2 | The second state (type SO3::State) |
Implements aikido::distance::DistanceMetric.
|
overridevirtual |
Get the StateSpace associated with this metric.
Implements aikido::distance::DistanceMetric.
|
private |