pax_global_header00006660000000000000000000000064131231602100014477gustar00rootroot0000000000000052 comment=0c0951c29cffde2659e150d08758d7f5d25943f5 ros-eigen-stl-containers-0.1.8/000077500000000000000000000000001312316021000163405ustar00rootroot00000000000000ros-eigen-stl-containers-0.1.8/CHANGELOG.rst000066400000000000000000000033571312316021000203710ustar00rootroot00000000000000^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Changelog for package eigen_stl_containers ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 0.1.8 (2017-03-10) ------------------ * Fix it up so we can correctly find Eigen everywhere. * Contributors: Chris Lalancette, Kei Okada 0.1.7 (2017-03-01) ------------------ * install headers to CATKIN_PACKAGE_INCLUDE_DESTINATION (`#4 `_) * Added more typedefs for std::vectors of Eigen types (`#8 `_) * Contributors: Michael Görner, Victor Lamoine 0.1.6 (2016-09-28) ------------------ * Fixed exporting of eigen3 depends (`#6 `_) * Contributors: Kei Okada 0.1.5 (2016-03-23) ------------------ * Merge pull request `#3 `_ from scpeters/patch-1 add links to repository and issue tracker * add links to repository and issue tracker * Added tag 0.1.4 for changeset 27d05d1c09b5 * Contributors: Ioan Sucan, Steven Peters, William Woodall 0.1.4 (2013-03-13) ------------------ * properly export includes and depends for catkin * Added tag 0.1.3 for changeset 93304e48d411 * Contributors: Ioan Sucan 0.1.3 (2012-12-15) ------------------ * Added tag 0.1.2 for changeset a0b26dabeaec * Contributors: Ioan Sucan 0.1.2 (2012-10-18) ------------------ * bump version * Added tag 0.1.2 for changeset 17cd6bd5aedd * switching to package.xml * Added tag 0.1.1 for changeset 7647a299476f * Contributors: Ioan Sucan 0.1.1 (2012-09-19) ------------------ * add more typedefs * Added tag 0.1.0 for changeset 14f67f1013f4 * Contributors: Ioan Sucan 0.1.0 (2012-08-12) ------------------ * add vector types * Contributors: Ioan Sucan ros-eigen-stl-containers-0.1.8/CMakeLists.txt000066400000000000000000000022611312316021000211010ustar00rootroot00000000000000cmake_minimum_required(VERSION 2.8.3) project(eigen_stl_containers) find_package(catkin REQUIRED) # We don't build anything here, but in order to export the right # build flags in catkin_package(), we still have to find Eigen3 here. Note # that this is somewhat complicated because of our need to support Ubuntu # all the way back to saucy. First we look for the Eigen3 cmake module # provided by the libeigen3-dev on newer Ubuntu. If that fails, then we # fall-back to the version provided by cmake_modules, which is a stand-in. find_package(Eigen3 QUIET) if(NOT EIGEN3_FOUND) # saucy does not have Eigen3, but have Eigen instead find_package(cmake_modules REQUIRED) find_package(Eigen REQUIRED) set(EIGEN3_INCLUDE_DIRS ${EIGEN_INCLUDE_DIRS}) endif() # Note that eigen 3.2 (on Ubuntu Wily) only provides EIGEN3_INCLUDE_DIR, # not EIGEN3_INCLUDE_DIRS, so we have to set the latter from the former. if(NOT EIGEN3_INCLUDE_DIRS) set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) endif() catkin_package( INCLUDE_DIRS include ${EIGEN3_INCLUDE_DIRS}) install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} FILES_MATCHING PATTERN "*.h") ros-eigen-stl-containers-0.1.8/include/000077500000000000000000000000001312316021000177635ustar00rootroot00000000000000ros-eigen-stl-containers-0.1.8/include/eigen_stl_containers/000077500000000000000000000000001312316021000241615ustar00rootroot00000000000000ros-eigen-stl-containers-0.1.8/include/eigen_stl_containers/eigen_stl_containers.h000066400000000000000000000040131312316021000305260ustar00rootroot00000000000000/********************************************************************* * 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.8/include/eigen_stl_containers/eigen_stl_map_container.h000066400000000000000000000053551312316021000312120ustar00rootroot00000000000000/********************************************************************* * 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.8/include/eigen_stl_containers/eigen_stl_vector_container.h000066400000000000000000000056151312316021000317360ustar00rootroot00000000000000/********************************************************************* * 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_Vector4d; typedef std::vector > vector_Affine3f; typedef std::vector > vector_Affine3d; typedef std::vector > vector_Isometry3f; typedef std::vector > vector_Isometry3d; } #endif ros-eigen-stl-containers-0.1.8/package.xml000066400000000000000000000015221312316021000204550ustar00rootroot00000000000000 eigen_stl_containers 0.1.8 This package provides a set of typedef's that allow using Eigen datatypes in STL containers Ioan Sucan Chris Lalancette Shane Loretz BSD http://eigen.tuxfamily.org/dox/TopicUnalignedArrayAssert.html https://github.com/ros/eigen_stl_containers/issues https://github.com/ros/eigen_stl_containers catkin cmake_modules eigen eigen