Return pointer to cached basis
parent
87ba9384e0
commit
d6ffef89e6
|
@ -58,7 +58,7 @@ Unit3 Unit3::Random(boost::mt19937 & rng) {
|
||||||
}
|
}
|
||||||
|
|
||||||
/* ************************************************************************* */
|
/* ************************************************************************* */
|
||||||
Matrix Unit3::basis() const {
|
const Matrix& Unit3::basis() const {
|
||||||
|
|
||||||
// Return cached version if exists
|
// Return cached version if exists
|
||||||
if (B_.rows() == 3)
|
if (B_.rows() == 3)
|
||||||
|
|
|
@ -84,7 +84,7 @@ public:
|
||||||
* It is a 3*2 matrix [b1 b2] composed of two orthogonal directions
|
* It is a 3*2 matrix [b1 b2] composed of two orthogonal directions
|
||||||
* tangent to the sphere at the current direction.
|
* tangent to the sphere at the current direction.
|
||||||
*/
|
*/
|
||||||
Matrix basis() const;
|
const Matrix& basis() const;
|
||||||
|
|
||||||
/// Return skew-symmetric associated with 3D point on unit sphere
|
/// Return skew-symmetric associated with 3D point on unit sphere
|
||||||
Matrix skew() const;
|
Matrix skew() const;
|
||||||
|
|
Loading…
Reference in New Issue