30 #ifndef TRANSFORM_UTIL_TRANSFORM_H_ 31 #define TRANSFORM_UTIL_TRANSFORM_H_ 33 #include <boost/shared_ptr.hpp> 62 const tf::Vector3& v_in, tf::Vector3& v_out)
const = 0;
79 tf::Vector3 vector = offset - origin;
85 tf::Vector3 cross = tf::Vector3(1, 0, 0).cross(vector);
86 double w = vector.length() + tf::Vector3(1, 0, 0).dot(vector);
87 return tf::Quaternion(cross.x(), cross.y(), cross.z(), w).normalized();
159 tf::Vector3 operator()(
const tf::Vector3& v)
const;
168 tf::Vector3
operator*(
const tf::Vector3& v)
const;
201 tf::Vector3 GetOrigin()
const;
239 virtual void Transform(
const tf::Vector3& v_in, tf::Vector3& v_out)
const;
240 virtual TransformImplPtr
Inverse()
const;
268 virtual void Transform(
const tf::Vector3& v_in, tf::Vector3& v_out)
const;
275 virtual TransformImplPtr
Inverse()
const;
282 #endif // TRANSFORM_UTIL_TRANSFORM_H_
TFSIMD_FORCE_INLINE Vector3 operator*(const Matrix3x3 &m, const Vector3 &v)