22 #include <gazebo/common/common.hh> 23 #include <ignition/math/Vector3.hh> 24 #include <ignition/math/Quaternion.hh> 65 Face(
int i1,
int i2,
int i3);
85 public:
static Polyhedron makeCylinder(
double r,
91 public:
Volume ComputeFullVolume();
98 public:
Volume SubmergedVolume(
const ignition::math::Vector3d &x,
99 const ignition::math::Quaterniond &q,
109 private:
static Volume tetrahedronVolume(
const ignition::math::Vector3d& v1,
110 const ignition::math::Vector3d& v2,
111 const ignition::math::Vector3d& v3,
112 const ignition::math::Vector3d& p =
113 ignition::math::Vector3d({0., 0., 0.}));
123 private:
static Volume clipTriangle(
const ignition::math::Vector3d& v1,
124 const ignition::math::Vector3d& v2,
125 const ignition::math::Vector3d& v3,
129 const ignition::math::Vector3d& p =
130 ignition::math::Vector3d({0., 0., 0.}));
133 private: std::vector<ignition::math::Vector3d>
vertices;
139 private:
const double EPSILON = 1e-6;
ignition::math::Vector3d normal
Vector3 normal to plane.
float offset
Offset w.r.t. normal.
std::vector< Face > faces
Object faces.
Plane()
Initializes plane at z=0.
Submerged volume calculation using polyhedron based on: Exact Buoyancy for Polyhedra by Eric Catto...
Store vertex index for a triangular face.
ignition::math::Vector3d centroid
Vector3 representing volume centroid.
std::vector< ignition::math::Vector3d > vertices
Object vertices.
Represents output volume with centroid.
Represents a plane as a normal and offset.
double volume
Submerged volume of shape.