pax_global_header00006660000000000000000000000064125602272360014517gustar00rootroot0000000000000052 comment=24cf74908542c7891366e698f9beac1ee776d52f ros-eigen-stl-containers-0.1.4/000077500000000000000000000000001256022723600163545ustar00rootroot00000000000000ros-eigen-stl-containers-0.1.4/CMakeLists.txt000066400000000000000000000003711256022723600211150ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(eigen_stl_containers) find_package(catkin REQUIRED) catkin_package( INCLUDE_DIRS include DEPENDS Eigen) install(DIRECTORY include/ DESTINATION include FILES_MATCHING PATTERN "*.h") ros-eigen-stl-containers-0.1.4/include/000077500000000000000000000000001256022723600177775ustar00rootroot00000000000000ros-eigen-stl-containers-0.1.4/include/eigen_stl_containers/000077500000000000000000000000001256022723600241755ustar00rootroot00000000000000ros-eigen-stl-containers-0.1.4/include/eigen_stl_containers/eigen_stl_containers.h000066400000000000000000000040131256022723600305420ustar00rootroot00000000000000/********************************************************************* * 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. *********************************************************************/ /* Author: Ioan Sucan */ #ifndef EIGEN_STL_CONTAINERS_EIGEN_STL_CONTAINERS_ #define EIGEN_STL_CONTAINERS_EIGEN_STL_CONTAINERS_ #include "eigen_stl_containers/eigen_stl_vector_container.h" #include "eigen_stl_containers/eigen_stl_map_container.h" #endif ros-eigen-stl-containers-0.1.4/include/eigen_stl_containers/eigen_stl_map_container.h000066400000000000000000000053551256022723600312260ustar00rootroot00000000000000/********************************************************************* * 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. *********************************************************************/ /* Author: Ioan Sucan */ #ifndef EIGEN_STL_CONTAINERS_EIGEN_STL_MAP_CONTAINER_ #define EIGEN_STL_CONTAINERS_EIGEN_STL_MAP_CONTAINER_ #include #include #include #include namespace EigenSTL { typedef std::map, Eigen::aligned_allocator > > map_string_Vector3d; typedef std::map, Eigen::aligned_allocator > > map_string_Vector3f; typedef std::map, Eigen::aligned_allocator > > map_string_Affine3d; typedef std::map, Eigen::aligned_allocator > > map_string_Affine3f; } #endif ros-eigen-stl-containers-0.1.4/include/eigen_stl_containers/eigen_stl_vector_container.h000066400000000000000000000051331256022723600317450ustar00rootroot00000000000000/********************************************************************* * 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. *********************************************************************/ /* Author: Ioan Sucan */ #ifndef EIGEN_STL_CONTAINERS_EIGEN_STL_VECTOR_CONTAINER_ #define EIGEN_STL_CONTAINERS_EIGEN_STL_VECTOR_CONTAINER_ #include #include #include #include /** \brief Typedef's for STL containers of Eigen types with proper memory alignment. */ namespace EigenSTL { typedef std::vector > vector_Vector3f; typedef std::vector > vector_Vector3d; typedef std::vector > vector_Vector4f; typedef std::vector > vector_Affine3d; typedef std::vector > vector_Affine3f; } #endif ros-eigen-stl-containers-0.1.4/package.xml000066400000000000000000000010151256022723600204660ustar00rootroot00000000000000 eigen_stl_containers 0.1.4 This package provides a set of typedef's that allow using Eigen datatypes in STL containers Ioan Sucan Ioan Sucan BSD http://eigen.tuxfamily.org/dox/TopicUnalignedArrayAssert.html catkin eigen