Skip to content

Commit

Permalink
Merge pull request #32 from davetcoleman/merge_shape_msgs
Browse files Browse the repository at this point in the history
Merge shape_tools package into geometric shapes
  • Loading branch information
mikeferguson committed Apr 22, 2015
2 parents a1babc3 + 115d86e commit 8655161
Show file tree
Hide file tree
Showing 9 changed files with 470 additions and 20 deletions.
11 changes: 6 additions & 5 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -34,15 +34,15 @@ else()
endif()

find_package(octomap REQUIRED)
find_package(catkin COMPONENTS cmake_modules shape_msgs resource_retriever shape_tools random_numbers eigen_stl_containers)
find_package(catkin COMPONENTS cmake_modules visualization_msgs shape_msgs resource_retriever random_numbers eigen_stl_containers)
find_package(console_bridge REQUIRED)

find_package(Eigen REQUIRED)

catkin_package(
INCLUDE_DIRS include ${OCTOMAP_INCLUDE_DIRS}
LIBRARIES ${PROJECT_NAME} ${OCTOMAP_LIBRARIES}
CATKIN_DEPENDS shape_tools shape_msgs random_numbers eigen_stl_containers visualization_msgs
CATKIN_DEPENDS shape_msgs random_numbers eigen_stl_containers visualization_msgs
DEPENDS Eigen console_bridge
)

Expand All @@ -61,7 +61,9 @@ add_library(${PROJECT_NAME}
src/shape_operations.cpp
src/mesh_operations.cpp
src/bodies.cpp
src/body_operations.cpp)
src/body_operations.cpp
src/shape_to_marker.cpp
src/shape_extents.cpp)
target_link_libraries(${PROJECT_NAME} ${ASSIMP_LIBRARIES} ${QHULL_LIBRARIES} ${catkin_LIBRARIES} ${console_bridge_LIBRARIES} ${Boost_LIBRARIES})


Expand All @@ -76,5 +78,4 @@ install(TARGETS ${PROJECT_NAME}

install(DIRECTORY include/
DESTINATION include
FILES_MATCHING PATTERN "*.h")

FILES_MATCHING PATTERN "*.h")
6 changes: 4 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
geometric_shapes
================

This package contains generic definitions of geometric shapes and bodies. Shapes represent only the form of an object.
This package contains generic definitions of geometric shapes and bodies, as well as tools for operating on shape messages.
Shapes represent only the form of an object.
Bodies are shapes at a particular pose. Routines such as point containment and ray intersections are provided.

Supported shapes:
Expand All @@ -12,7 +13,8 @@ Supported shapes:
- mesh

Note: Bodies for meshes compute the convex hull of those meshes in order to provide the point containment / ray intersection routines.

Note: [shape_tools](https://github.com/ros-planning/shape_tools) package was recently merged into this package

## Build Status

hydro-devel branch: [![Build Status](https://travis-ci.org/ros-planning/geometric_shapes.png?branch=hydro-devel)](https://travis-ci.org/ros-planning/geometric_shapes)
52 changes: 52 additions & 0 deletions include/geometric_shapes/shape_extents.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2012, Willow Garage, Inc.
* All rights reserved.
*
* 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 Willow Garage 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 GEOMETRIC_SHAPES_SHAPE_EXTENTS_
#define GEOMETRIC_SHAPES_SHAPE_EXTENTS_

#include <shape_msgs/SolidPrimitive.h>
#include <shape_msgs/Mesh.h>

namespace geometric_shapes
{

/** \brief Get the dimensions of an axis-aligned bounding box for the shape described by \e shape_msg */
void getShapeExtents(const shape_msgs::SolidPrimitive& shape_msg, double& x_extent, double& y_extent, double& z_extent);

/** \brief Get the dimensions of an axis-aligned bounding box for the shape described by \e shape_msg */
void getShapeExtents(const shape_msgs::Mesh& shape_msg, double& x_extent, double& y_extent, double& z_extent);

}

#endif
60 changes: 60 additions & 0 deletions include/geometric_shapes/shape_to_marker.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2012, Willow Garage, Inc.
* All rights reserved.
*
* 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 Willow Garage 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 GEOMETRIC_SHAPES_SHAPE_TO_MARKER_
#define GEOMETRIC_SHAPES_SHAPE_TO_MARKER_

#include <shape_msgs/Mesh.h>
#include <shape_msgs/SolidPrimitive.h>
#include <visualization_msgs/Marker.h>

namespace geometric_shapes
{

/** \brief Convert a shape_msgs::Mesh \e shape_msg to a
visualization_msgs::Marker \e marker. The corresponding marker
will be constructed as a LINE_LIST (if \e use_mesh_triangle_list
is false) or as a TRIANGLE_LIST (if \e use_mesh_triangle_list is
true). On incorrect input, this function throws a
std::runtime_error. */
void constructMarkerFromShape(const shape_msgs::Mesh &shape_msg, visualization_msgs::Marker &marker, bool use_mesh_triangle_list = true);

/** \brief Convert a shape_msgs::SolidPrimitive \e shape_msg to a
visualization_msgs::Marker \e marker. On incorrect input, this
function throws a std::runtime_error. */
void constructMarkerFromShape(const shape_msgs::SolidPrimitive &shape_msg, visualization_msgs::Marker &marker);

}

#endif
99 changes: 99 additions & 0 deletions include/geometric_shapes/solid_primitive_dims.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2012, Willow Garage, Inc.
* All rights reserved.
*
* 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 Willow Garage 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 GEOMETRIC_SHAPES_SOLID_PRIMITIVE_DIMS_
#define GEOMETRIC_SHAPES_SOLID_PRIMITIVE_DIMS_

#include <shape_msgs/SolidPrimitive.h>

namespace geometric_shapes
{

/** \brief The number of dimensions of a particular shape */
template<int>
struct SolidPrimitiveDimCount
{
enum { value = 0 };
};

template<>
struct SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::SPHERE>
{
enum
{
value = static_cast<int>(shape_msgs::SolidPrimitive::SPHERE_RADIUS) + 1
};
};

template<>
struct SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>
{
enum
{
value = (static_cast<int>(shape_msgs::SolidPrimitive::BOX_X) >= static_cast<int>(shape_msgs::SolidPrimitive::BOX_Y) &&
static_cast<int>(shape_msgs::SolidPrimitive::BOX_X) >= static_cast<int>(shape_msgs::SolidPrimitive::BOX_Z)) ?
static_cast<int>(shape_msgs::SolidPrimitive::BOX_X) :
(((static_cast<int>(shape_msgs::SolidPrimitive::BOX_Y) >= static_cast<int>(shape_msgs::SolidPrimitive::BOX_X) &&
static_cast<int>(shape_msgs::SolidPrimitive::BOX_Y) >= static_cast<int>(shape_msgs::SolidPrimitive::BOX_Z))) ?
static_cast<int>(shape_msgs::SolidPrimitive::BOX_Y) :
((static_cast<int>(shape_msgs::SolidPrimitive::BOX_Z) >= static_cast<int>(shape_msgs::SolidPrimitive::BOX_X) &&
static_cast<int>(shape_msgs::SolidPrimitive::BOX_Z) >= static_cast<int>(shape_msgs::SolidPrimitive::BOX_Y)) ?
static_cast<int>(shape_msgs::SolidPrimitive::BOX_Z) : 0)) + 1
};
};

template<>
struct SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::CONE>
{
enum
{
value = (static_cast<int>(shape_msgs::SolidPrimitive::CONE_RADIUS) >= static_cast<int>(shape_msgs::SolidPrimitive::CONE_HEIGHT) ?
static_cast<int>(shape_msgs::SolidPrimitive::CONE_RADIUS) : static_cast<int>(shape_msgs::SolidPrimitive::CONE_HEIGHT)) + 1
};
};

template<>
struct SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::CYLINDER>
{
enum
{
value = (static_cast<int>(shape_msgs::SolidPrimitive::CYLINDER_RADIUS) >= static_cast<int>(shape_msgs::SolidPrimitive::CYLINDER_HEIGHT) ?
static_cast<int>(shape_msgs::SolidPrimitive::CYLINDER_RADIUS) : static_cast<int>(shape_msgs::SolidPrimitive::CYLINDER_HEIGHT)) + 1
};
};


}

#endif
6 changes: 4 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,9 @@
<version>0.4.1</version>
<description>This package contains generic definitions of geometric shapes and bodies.</description>
<author email="isucan@google.com">Ioan Sucan</author>
<author email="gjones@willowgarage.edu">Gil Jones</author>
<maintainer email="isucan@google.com">Ioan Sucan</maintainer>
<maintainer email="dave@dav.ee">Dave Coleman</maintainer>

<license>BSD</license>
<url>http://ros.org/wiki/geometric_shapes</url>
Expand All @@ -12,7 +14,7 @@

<build_depend>boost</build_depend>
<build_depend>shape_msgs</build_depend>
<build_depend>shape_tools</build_depend>
<build_depend>visualization_msgs</build_depend>
<build_depend>octomap</build_depend>
<build_depend>assimp-dev</build_depend>
<build_depend>eigen</build_depend>
Expand All @@ -27,7 +29,7 @@

<run_depend>boost</run_depend>
<run_depend>shape_msgs</run_depend>
<run_depend>shape_tools</run_depend>
<run_depend>visualization_msgs</run_depend>
<run_depend>octomap</run_depend>
<run_depend>assimp</run_depend>
<run_depend>eigen</run_depend>
Expand Down
Loading

0 comments on commit 8655161

Please sign in to comment.