Go to the documentation of this file.
40 #include <console_bridge/console.h>
41 #include <Eigen/Geometry>
97 result.reset(
new shapes::Box(dims[0], dims[1], dims[2]));
114 vertexList.reserve(3 * mesh->getTriangles().size());
115 for (
const auto& triangle : mesh->getTriangles())
116 vertexList.push_back(scaledVertices[triangle]);
134 const auto& pose = body->
getPose();
135 msg.pose.position.x = pose.translation().x();
136 msg.pose.position.y = pose.translation().y();
137 msg.pose.position.z = pose.translation().z();
140 Eigen::Quaterniond quat(pose.linear().matrix());
141 msg.pose.orientation.x = quat.x();
142 msg.pose.orientation.y = quat.y();
143 msg.pose.orientation.z = quat.z();
144 msg.pose.orientation.w = quat.w();
151 mergedSphere.
center = Eigen::Vector3d(0.0, 0.0, 0.0);
152 mergedSphere.
radius = 0.0;
156 mergedSphere = spheres[0];
157 for (
unsigned int i = 1; i < spheres.size(); ++i)
159 if (spheres[i].radius <= 0.0)
161 Eigen::Vector3d diff = spheres[i].
center - mergedSphere.
center;
162 double d = diff.norm();
163 if (
d + mergedSphere.
radius <= spheres[i].radius)
165 mergedSphere.
center = spheres[i].center;
166 mergedSphere.
radius = spheres[i].radius;
168 else if (
d + spheres[i].radius > mergedSphere.
radius)
170 Eigen::Vector3d delta = mergedSphere.
center - spheres[i].center;
171 mergedSphere.
radius = (delta.norm() + spheres[i].radius + mergedSphere.
radius) / 2.0;
172 mergedSphere.
center = delta.normalized() * (mergedSphere.
radius - spheres[i].radius) + spheres[i].center;
180 template <
typename T>
190 Eigen::Quaterniond q(pose.orientation.w, pose.orientation.x, pose.orientation.y, pose.orientation.z);
191 if (fabs(q.squaredNorm() - 1.0) > 1e-3)
194 q = Eigen::Quaterniond(1.0, 0.0, 0.0, 0.0);
196 Eigen::Isometry3d af(Eigen::Translation3d(pose.position.x, pose.position.y, pose.position.z) * q);
224 Eigen::Vector3d sum(0.0, 0.0, 0.0);
227 unsigned int vertex_count = 0;
235 for (
unsigned int j = 0; j < conv->
getScaledVertices().size(); j++, vertex_count++)
241 sphere.
center = sum / (double)vertex_count;
243 double max_dist_squared = 0.0;
254 if (dist > max_dist_squared)
256 max_dist_squared = dist;
260 sphere.
radius = sqrt(max_dist_squared);
265 for (
const auto& box : boxes)
266 mergedBox.extend(box);
271 for (
const auto& box : boxes)
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
Type that can hold any of the desired shape message types.
void setPoseDirty(const Eigen::Isometry3d &pose)
Set the pose of the body.
void setDimensionsDirty(const shapes::Shape *shape)
Set the dimensions of the body (from corresponding shape).
void constructMarkerFromBody(const bodies::Body *body, visualization_msgs::Marker &msg)
Construct a Marker message that corresponds to this (scaled and padded) body.
std::vector< double > getScaledDimensions() const override
Get the dimensions associated to this body (scaled and padded)
void mergeBoundingBoxesApprox(const std::vector< OBB > &boxes, OBB &mergedBox)
Compute an approximate oriented bounding box to enclose a set of bounding boxes.
Definition of a cylinder Length is along z axis. Origin is at center of mass.
A basic definition of a shape. Shapes are considered centered at origin.
void mergeBoundingBoxes(const std::vector< AABB > &boxes, AABB &mergedBox)
Compute an axis-aligned bounding box to enclose a set of bounding boxes.
A body is a shape + its pose. Point inclusion, ray intersection can be tested, volumes and bounding s...
OBB * extendApprox(const OBB &box)
Add the other OBB to this one and compute an approximate enclosing OBB.
Body * constructBodyFromMsgHelper(const T &shape_msg, const geometry_msgs::Pose &pose)
Definition of a sphere that bounds another object.
std::shared_ptr< Shape > ShapePtr
Shared pointer to a Shape.
Definition of a box Aligned with the XYZ axes.
void computeBoundingSphere(const std::vector< const Body * > &bodies, BoundingSphere &mergedSphere)
Compute the bounding sphere for a set of bodies and store the resulting sphere in mergedSphere.
Represents an oriented bounding box.
Body * constructBodyFromMsg(const shape_msgs::Mesh &shape, const geometry_msgs::Pose &pose)
Create a body from a given shape.
Body * createEmptyBodyFromShapeType(const shapes::ShapeType &shapeType)
Create a body from a given shape.
Mesh * createMeshFromVertices(const EigenSTL::vector_Vector3d &vertices, const std::vector< unsigned int > &triangles)
Load a mesh from a set of vertices.
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
#define ASSERT_ISOMETRY(transform)
Assert that the given transform is an isometry.
ShapeType
A list of known shape types.
shapes::ShapeType getType() const
Get the type of shape this body represents.
std::vector< double > getScaledDimensions() const override
Get the dimensions associated to this body (scaled and padded)
ShapeType type
The type of the shape.
const Eigen::Isometry3d & getPose() const
Retrieve the pose of the body.
shapes::ShapeConstPtr constructShapeFromBody(const bodies::Body *body)
Get a shape that corresponds to this (scaled and padded) body.
virtual void updateInternalData()=0
This function is called every time a change to the body is made, so that intermediate values stored f...
bool constructMarkerFromShape(const Shape *shape, visualization_msgs::Marker &mk, bool use_mesh_triangle_list=false)
Construct the marker that corresponds to the shape. Return false on failure.
Shape * constructShapeFromMsg(const shape_msgs::SolidPrimitive &shape_msg)
Construct the shape that corresponds to the message. Return NULL on failure.
void setDimensions(const shapes::Shape *shape)
Set the dimensions of the body (from corresponding shape)
std::vector< double > getScaledDimensions() const override
Get the dimensions associated to this body (scaled and padded)
This set of classes allows quickly detecting whether a given point is inside an object or not....
void mergeBoundingSpheres(const std::vector< BoundingSphere > &spheres, BoundingSphere &mergedSphere)
Compute a bounding sphere to enclose a set of bounding spheres.
std::shared_ptr< const Shape > ShapeConstPtr
Shared pointer to a const Shape.
const EigenSTL::vector_Vector3d & getScaledVertices() const
Definition of a cylinder.
Definition of a convex mesh. Convex hull is computed for a given shape::Mesh.
Represents an axis-aligned bounding box.
Body * createBodyFromShape(const shapes::Shape *shape)
Create a body from a given shape.
geometric_shapes
Author(s): Ioan Sucan
, Gil Jones
autogenerated on Tue Aug 13 2024 02:40:57