Namespaces | Classes | Typedefs | Enumerations | Functions
shapes Namespace Reference

Definition of various shapes. No properties such as position are included. These are simply the descriptions and dimensions of shapes. More...

Namespaces

namespace  detail

Classes

class  Box
 Definition of a box Aligned with the XYZ axes. More...
class  Cone
 Definition of a cone Tip is on positive z axis. Center of base is on negative z axis. Origin is halway between tip and center of base. More...
class  Cylinder
 Definition of a cylinder Length is along z axis. Origin is at center of mass. More...
class  Mesh
 Definition of a triangle mesh By convention the "center" of the shape is at the origin. For a mesh this implies that the AABB of the mesh is centered at the origin. Some methods may not work with arbitrary meshes whose AABB is not centered at the origin. More...
class  OcTree
 Representation of an octomap::OcTree as a Shape. More...
class  Plane
 Definition of a plane with equation ax + by + cz + d = 0. More...
class  Shape
 A basic definition of a shape. Shapes are considered centered at origin. More...
class  Sphere
 Definition of a sphere. More...

Typedefs

typedef boost::shared_ptr
< const Shape
ShapeConstPtr
 Shared pointer to a const Shape.
typedef boost::variant
< shape_msgs::SolidPrimitive,
shape_msgs::Mesh,
shape_msgs::Plane > 
ShapeMsg
 Type that can hold any of the desired shape message types.
typedef boost::shared_ptr< ShapeShapePtr
 Shared pointer to a Shape.

Enumerations

enum  ShapeType {
  UNKNOWN_SHAPE, SPHERE, CYLINDER, CONE,
  BOX, PLANE, MESH, OCTREE
}
 A list of known shape types. More...

Functions

void computeShapeBoundingSphere (const Shape *shape, Eigen::Vector3d &center, double &radius)
 Compute a sphere bounding a shape.
Eigen::Vector3d computeShapeExtents (const ShapeMsg &shape_msg)
 Compute the extents of a shape.
Eigen::Vector3d computeShapeExtents (const Shape *shape)
 Compute the extents of a shape.
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.
bool constructMsgFromShape (const Shape *shape, ShapeMsg &shape_msg)
 Construct the message that corresponds to the shape. Return false on failure.
ShapeconstructShapeFromMsg (const shape_msgs::SolidPrimitive &shape_msg)
 Construct the shape that corresponds to the message. Return NULL on failure.
ShapeconstructShapeFromMsg (const shape_msgs::Plane &shape_msg)
 Construct the shape that corresponds to the message. Return NULL on failure.
ShapeconstructShapeFromMsg (const shape_msgs::Mesh &shape_msg)
 Construct the shape that corresponds to the message. Return NULL on failure.
ShapeconstructShapeFromMsg (const ShapeMsg &shape_msg)
 Construct the shape that corresponds to the message. Return NULL on failure.
ShapeconstructShapeFromText (std::istream &in)
 Construct a shape from plain text description.
MeshcreateMeshFromAsset (const aiScene *scene, const Eigen::Vector3d &scale, const std::string &assimp_hint=std::string())
 Load a mesh from an assimp datastructure.
MeshcreateMeshFromAsset (const aiScene *scene, const std::string &assimp_hint=std::string())
 Load a mesh from an assimp datastructure.
MeshcreateMeshFromBinary (const char *buffer, std::size_t size, const std::string &assimp_hint=std::string())
 Load a mesh from a binary stream that contains a mesh that can be loaded by assimp.
MeshcreateMeshFromBinary (const char *buffer, std::size_t size, const Eigen::Vector3d &scale, const std::string &assimp_hint=std::string())
 Load a mesh from a resource that contains a mesh that can be loaded by assimp.
MeshcreateMeshFromResource (const std::string &resource)
 Load a mesh from a resource that contains a mesh that can be loaded by assimp.
MeshcreateMeshFromResource (const std::string &resource, const Eigen::Vector3d &scale)
 Load a mesh from a resource that contains a mesh that can be loaded by assimp.
MeshcreateMeshFromShape (const Shape *shape)
 Construct a mesh from a primitive shape that is NOT already a mesh. This call allocates a new object.
MeshcreateMeshFromShape (const Box &box)
 Construct a mesh from a box.
MeshcreateMeshFromShape (const Sphere &sphere)
 Construct a mesh from a sphere.
MeshcreateMeshFromShape (const Cylinder &cylinder)
 Construct a mesh from a cylinder.
MeshcreateMeshFromShape (const Cone &cone)
 Construct a mesh from a cone.
MeshcreateMeshFromVertices (const EigenSTL::vector_Vector3d &vertices, const std::vector< unsigned int > &triangles)
 Load a mesh from a set of vertices. Triangles are constructed using index values from the triangles vector. Triangle k has vertices at index values triangles[3k], triangles[3k+1], triangles[3k+2].
MeshcreateMeshFromVertices (const EigenSTL::vector_Vector3d &source)
 Load a mesh from a set of vertices. Every 3 vertices are considered a triangle. Repeating vertices are identified and the set of triangle indices is constructed. The normal at each triangle is also computed.
void saveAsText (const Shape *shape, std::ostream &out)
 Save all the information about this shape as plain text.
const std::string & shapeStringName (const Shape *shape)
 Get the string name of the shape.
void writeSTLBinary (const Mesh *mesh, std::vector< char > &buffer)
 Write the mesh to a buffer in STL format.

Detailed Description

Definition of various shapes. No properties such as position are included. These are simply the descriptions and dimensions of shapes.


Typedef Documentation

typedef boost::shared_ptr<const Shape> shapes::ShapeConstPtr

Shared pointer to a const Shape.

Definition at line 271 of file shapes.h.

typedef boost::variant<shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane> shapes::ShapeMsg

Type that can hold any of the desired shape message types.

Definition at line 49 of file shape_messages.h.

typedef boost::shared_ptr<Shape> shapes::ShapePtr

Shared pointer to a Shape.

Definition at line 268 of file shapes.h.


Enumeration Type Documentation

A list of known shape types.

Enumerator:
UNKNOWN_SHAPE 
SPHERE 
CYLINDER 
CONE 
BOX 
PLANE 
MESH 
OCTREE 

Definition at line 58 of file shapes.h.


Function Documentation

void shapes::computeShapeBoundingSphere ( const Shape *  shape,
Eigen::Vector3d &  center,
double &  radius 
)

Compute a sphere bounding a shape.

Definition at line 304 of file shape_operations.cpp.

Eigen::Vector3d shapes::computeShapeExtents ( const ShapeMsg &  shape_msg)

Compute the extents of a shape.

Definition at line 245 of file shape_operations.cpp.

Eigen::Vector3d shapes::computeShapeExtents ( const Shape *  shape)

Compute the extents of a shape.

Definition at line 250 of file shape_operations.cpp.

bool shapes::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.

Definition at line 192 of file shape_operations.cpp.

bool shapes::constructMsgFromShape ( const Shape *  shape,
ShapeMsg &  shape_msg 
)

Construct the message that corresponds to the shape. Return false on failure.

Definition at line 374 of file shape_operations.cpp.

Shape * shapes::constructShapeFromMsg ( const shape_msgs::SolidPrimitive &  shape_msg)

Construct the shape that corresponds to the message. Return NULL on failure.

Definition at line 85 of file shape_operations.cpp.

Shape * shapes::constructShapeFromMsg ( const shape_msgs::Plane &  shape_msg)

Construct the shape that corresponds to the message. Return NULL on failure.

Definition at line 56 of file shape_operations.cpp.

Shape * shapes::constructShapeFromMsg ( const shape_msgs::Mesh &  shape_msg)

Construct the shape that corresponds to the message. Return NULL on failure.

Definition at line 61 of file shape_operations.cpp.

Shape * shapes::constructShapeFromMsg ( const ShapeMsg &  shape_msg)

Construct the shape that corresponds to the message. Return NULL on failure.

Definition at line 150 of file shape_operations.cpp.

Shape * shapes::constructShapeFromText ( std::istream &  in)

Construct a shape from plain text description.

Definition at line 519 of file shape_operations.cpp.

Mesh * shapes::createMeshFromAsset ( const aiScene *  scene,
const Eigen::Vector3d &  scale,
const std::string &  assimp_hint = std::string() 
)

Load a mesh from an assimp datastructure.

Definition at line 343 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromAsset ( const aiScene *  scene,
const std::string &  assimp_hint = std::string() 
)

Load a mesh from an assimp datastructure.

Definition at line 337 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromBinary ( const char *  buffer,
std::size_t  size,
const std::string &  assimp_hint = std::string() 
)

Load a mesh from a binary stream that contains a mesh that can be loaded by assimp.

Definition at line 211 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromBinary ( const char *  buffer,
std::size_t  size,
const Eigen::Vector3d &  scale,
const std::string &  assimp_hint = std::string() 
)

Load a mesh from a resource that contains a mesh that can be loaded by assimp.

Definition at line 218 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromResource ( const std::string &  resource)

Load a mesh from a resource that contains a mesh that can be loaded by assimp.

Definition at line 205 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromResource ( const std::string &  resource,
const Eigen::Vector3d &  scale 
)

Load a mesh from a resource that contains a mesh that can be loaded by assimp.

Definition at line 278 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromShape ( const Shape *  shape)

Construct a mesh from a primitive shape that is NOT already a mesh. This call allocates a new object.

Definition at line 367 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromShape ( const Box &  box)

Construct a mesh from a box.

Definition at line 385 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromShape ( const Sphere &  sphere)

Construct a mesh from a sphere.

Definition at line 443 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromShape ( const Cylinder &  cylinder)

Construct a mesh from a cylinder.

Definition at line 509 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromShape ( const Cone &  cone)

Construct a mesh from a cone.

Definition at line 580 of file mesh_operations.cpp.

Mesh * shapes::createMeshFromVertices ( const EigenSTL::vector_Vector3d vertices,
const std::vector< unsigned int > &  triangles 
)

Load a mesh from a set of vertices. Triangles are constructed using index values from the triangles vector. Triangle k has vertices at index values triangles[3k], triangles[3k+1], triangles[3k+2].

Definition at line 112 of file mesh_operations.cpp.

Load a mesh from a set of vertices. Every 3 vertices are considered a triangle. Repeating vertices are identified and the set of triangle indices is constructed. The normal at each triangle is also computed.

Definition at line 130 of file mesh_operations.cpp.

void shapes::saveAsText ( const Shape *  shape,
std::ostream &  out 
)

Save all the information about this shape as plain text.

Definition at line 461 of file shape_operations.cpp.

const std::string & shapes::shapeStringName ( const Shape *  shape)

Get the string name of the shape.

Definition at line 589 of file shape_operations.cpp.

void shapes::writeSTLBinary ( const Mesh *  mesh,
std::vector< char > &  buffer 
)

Write the mesh to a buffer in STL format.

Definition at line 665 of file mesh_operations.cpp.



geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Thu Jun 6 2019 20:13:53