shape_operations.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #ifndef GEOMETRIC_SHAPES_SHAPE_OPERATIONS_
38 #define GEOMETRIC_SHAPES_SHAPE_OPERATIONS_
39 
43 #include <visualization_msgs/Marker.h>
44 #include <iostream>
45 
46 namespace shapes
47 {
49 Shape* constructShapeFromMsg(const shape_msgs::SolidPrimitive& shape_msg);
50 
52 Shape* constructShapeFromMsg(const shape_msgs::Plane& shape_msg);
53 
55 Shape* constructShapeFromMsg(const shape_msgs::Mesh& shape_msg);
56 
58 Shape* constructShapeFromMsg(const ShapeMsg& shape_msg);
59 
61 bool constructMsgFromShape(const Shape* shape, ShapeMsg& shape_msg);
62 
64 bool constructMarkerFromShape(const Shape* shape, visualization_msgs::Marker& mk, bool use_mesh_triangle_list = false);
65 
67 Eigen::Vector3d computeShapeExtents(const ShapeMsg& shape_msg);
68 
70 Eigen::Vector3d computeShapeExtents(const Shape* shape);
71 
73 void computeShapeBoundingSphere(const Shape* shape, Eigen::Vector3d& center, double& radius);
74 
76 const std::string& shapeStringName(const Shape* shape);
77 
79 void saveAsText(const Shape* shape, std::ostream& out);
80 
82 Shape* constructShapeFromText(std::istream& in);
83 } // namespace shapes
84 
85 #endif
shapes::ShapeMsg
boost::variant< shape_msgs::SolidPrimitive, shape_msgs::Mesh, shape_msgs::Plane > ShapeMsg
Type that can hold any of the desired shape message types.
Definition: shape_messages.h:84
shapes
Definition of various shapes. No properties such as position are included. These are simply the descr...
Definition: mesh_operations.h:47
shapes::computeShapeExtents
Eigen::Vector3d computeShapeExtents(const ShapeMsg &shape_msg)
Compute the extents of a shape.
Definition: shape_operations.cpp:257
mesh_operations.h
shape_messages.h
shapes::constructMarkerFromShape
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.
Definition: shape_operations.cpp:207
shapes::constructShapeFromMsg
Shape * constructShapeFromMsg(const shape_msgs::SolidPrimitive &shape_msg)
Construct the shape that corresponds to the message. Return NULL on failure.
Definition: shape_operations.cpp:116
shapes::shapeStringName
const std::string & shapeStringName(const Shape *shape)
Get the string name of the shape.
Definition: shape_operations.cpp:579
shapes::constructMsgFromShape
bool constructMsgFromShape(const Shape *shape, ShapeMsg &shape_msg)
Construct the message that corresponds to the shape. Return false on failure.
Definition: shape_operations.cpp:378
shapes::saveAsText
void saveAsText(const Shape *shape, std::ostream &out)
Save all the information about this shape as plain text.
Definition: shape_operations.cpp:460
shapes.h
shapes::computeShapeBoundingSphere
void computeShapeBoundingSphere(const Shape *shape, Eigen::Vector3d &center, double &radius)
Compute a sphere bounding a shape.
Definition: shape_operations.cpp:312
shapes::constructShapeFromText
Shape * constructShapeFromText(std::istream &in)
Construct a shape from plain text description.
Definition: shape_operations.cpp:514


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Sun Oct 1 2023 02:40:16