Drake
Drake C++ Documentation
hopf_coordinate.h File Reference

Detailed Description

Hopf coordinates parametrizes SO(3) locally as the Cartesian product of a one-sphere and a two-sphere S¹ x S².

Computationally, each rotation in the Hopf coordinates can be written as (θ, φ, ψ), in which ψ parametrizes the circle S¹ and has a range of 2π, and θ, φ represent the spherical coordinates for S², with the range of π and 2π respectively.

#include <cmath>
#include <Eigen/Dense>
#include <Eigen/Geometry>
#include "drake/common/drake_assert.h"
#include "drake/common/eigen_types.h"
Include dependency graph for hopf_coordinate.h:

Namespaces

 drake
 
 drake::math
 

Functions

template<typename T >
const Eigen::Quaternion< T > HopfCoordinateToQuaternion (const T &theta, const T &phi, const T &psi)
 Transforms Hopf coordinates to a quaternion w, x, y, z as w = cos(θ/2)cos(ψ/2) x = cos(θ/2)sin(ψ/2) y = sin(θ/2)cos(φ+ψ/2) z = sin(θ/2)sin(φ+ψ/2) The user can refer to equation 5 of Generating Uniform Incremental Grids on SO(3) Using the Hopf Fibration by Anna Yershova, Steven LaValle and Julie Mitchell, 2008. More...
 
template<typename T >
Vector3< T > QuaternionToHopfCoordinate (const Eigen::Quaternion< T > &quaternion)
 Convert a unit-length quaternion (w, x, y, z) (with the requirement w >= 0) to Hopf coordinate as ψ = 2*atan2(x, w) φ = mod(atan2(z, y) - ψ/2, 2pi) θ = 2*atan2(√(y²+z²), √(w²+x²)) ψ is in the range of [-pi, pi]. More...