Program Listing for File Pose6D.h
↰ Return to documentation for file (include/octomap/math/Pose6D.h
)
/*
* OctoMap - An Efficient Probabilistic 3D Mapping Framework Based on Octrees
* https://octomap.github.io/
*
* Copyright (c) 2009-2013, K.M. Wurm and A. Hornung, University of Freiburg
* All rights reserved.
* License: New BSD
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the University of Freiburg nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#ifndef OCTOMATH_POSE6D_H
#define OCTOMATH_POSE6D_H
#include "Vector3.h"
#include "Quaternion.h"
namespace octomath {
class Pose6D {
public:
Pose6D();
~Pose6D();
Pose6D(const Vector3& trans, const Quaternion& rot);
Pose6D(float x, float y, float z, double roll, double pitch, double yaw);
Pose6D(const Pose6D& other);
Pose6D& operator= (const Pose6D& other);
bool operator==(const Pose6D& other) const;
bool operator!=(const Pose6D& other) const;
inline Vector3& trans() { return translation; }
inline Quaternion& rot() { return rotation; }
const Vector3& trans() const { return translation; }
const Quaternion& rot() const { return rotation; }
inline float& x() { return translation(0); }
inline float& y() { return translation(1); }
inline float& z() { return translation(2); }
inline const float& x() const { return translation(0); }
inline const float& y() const { return translation(1); }
inline const float& z() const { return translation(2); }
inline double roll() const {return (rotation.toEuler())(0); }
inline double pitch() const {return (rotation.toEuler())(1); }
inline double yaw() const {return (rotation.toEuler())(2); }
Vector3 transform (const Vector3 &v) const;
Pose6D inv() const;
Pose6D& inv_IP();
Pose6D operator* (const Pose6D &p) const;
const Pose6D& operator*= (const Pose6D &p);
double distance(const Pose6D &other) const;
double transLength() const;
std::ostream& write(std::ostream &s) const;
std::istream& read(std::istream &s);
std::ostream& writeBinary(std::ostream &s) const;
std::istream& readBinary(std::istream &s);
protected:
Vector3 translation;
Quaternion rotation;
};
std::ostream& operator<<(std::ostream& s, const Pose6D& p);
}
#endif