├── .gitignore ├── collada_parser ├── collada_parser_plugin_description.xml ├── mainpage.dox ├── package.xml ├── include │ └── collada_parser │ │ ├── collada_parser.h │ │ └── collada_parser_plugin.h ├── src │ └── collada_parser_plugin.cpp ├── CMakeLists.txt └── CHANGELOG.rst ├── README.md └── collada_urdf ├── package.xml ├── test └── test_collada_urdf.cpp ├── include └── collada_urdf │ └── collada_urdf.h ├── src ├── urdf_to_collada.cpp ├── collada_to_urdf.cpp └── collada_urdf.cpp ├── CMakeLists.txt └── CHANGELOG.rst /.gitignore: -------------------------------------------------------------------------------- 1 | .*.sw? 2 | -------------------------------------------------------------------------------- /collada_parser/collada_parser_plugin_description.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | Parse models as URDF from Collada files. 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /collada_parser/mainpage.dox: -------------------------------------------------------------------------------- 1 | /** 2 | \mainpage 3 | \htmlinclude manifest.html 4 | 5 | \b collada_parser is ... 6 | 7 | 10 | 11 | 12 | \section codeapi Code API 13 | 14 | 24 | 25 | 26 | */ 27 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Collada URDF 2 | 3 | This contains packages for converting from collada files to URDF. 4 | See the ROS wiki for API documentation and tutorials. 5 | 6 | * [`collada_urdf`](http://wiki.ros.org/collada_urdf) 7 | * [`collada_parser`](http://wiki.ros.org/collada_parser) 8 | 9 | This was originally part of the [`ros/robot_model`](https://github.com/ros/robot_model) repository. 10 | It has been moved to this repo as described by [`ros/robot_model#195`](https://github.com/ros/robot_model/issues/195) 11 | 12 | ## Linking issue with Raspbian 13 | 14 | If you are using a Raspberry Pi with Raspbian you might encounter a linking problem with Assimp that looks like: 15 | ```bash 16 | ~/ros_catkin_ws/devel_isolated/collada_urdf/lib/libcollada_urdf.so: undefined reference to `typeinfo for Assimp::IOSystem' 17 | collect2: error: ld returned 1 exit status 18 | ``` 19 | 20 | A work-around consists of compiling and installing Assimp latest version: 21 | ```bash 22 | mkdir -p $HOME/libraries/assimp-3.3.1/build_release 23 | cd $HOME/libraries/assimp-3.3.1/ 24 | wget https://github.com/assimp/assimp/archive/v3.3.1.zip 25 | unzip v3.3.1.zip 26 | rm v3.3.1.zip 27 | mv v3.3.1 src 28 | cd build_release 29 | cmake ../src -DCMAKE_BUILD_TYPE=Release -DASSIMP_BUILD_TESTS=False 30 | make -j3 31 | 32 | sudo make -j3 install 33 | ``` 34 | 35 | Make sure you reconfigure the catkin workspace (or just delete the build files) so that the newest Assimp version is found before compiling again. 36 | 37 | -------------------------------------------------------------------------------- /collada_parser/package.xml: -------------------------------------------------------------------------------- 1 | 2 | collada_parser 3 | 1.12.13 4 | 5 | This package contains a C++ parser for the Collada robot 6 | description format. The parser reads a Collada XML robot 7 | description, and creates a C++ URDF model. Although it is possible 8 | to directly use this parser when working with Collada robot 9 | descriptions, the preferred user API is found in the urdf package. 10 | 11 | 12 | Rosen Diankov 13 | Kei Okada 14 | Ioan Sucan 15 | Jackie Kay 16 | Chris Lalancette 17 | Shane Loretz 18 | 19 | BSD 20 | 21 | http://ros.org/wiki/collada_parser 22 | https://github.com/ros/collada_urdf 23 | https://github.com/ros/collada_urdf/issues 24 | 25 | catkin 26 | 27 | urdf 28 | urdf_parser_plugin 29 | 30 | class_loader 31 | collada-dom 32 | liburdfdom-headers-dev 33 | rosconsole 34 | urdf 35 | urdf_parser_plugin 36 | 37 | class_loader 38 | collada-dom 39 | rosconsole 40 | urdf_parser_plugin 41 | 42 | 43 | 44 | 45 | 46 | 47 | 48 | -------------------------------------------------------------------------------- /collada_urdf/package.xml: -------------------------------------------------------------------------------- 1 | 2 | collada_urdf 3 | 1.12.13 4 | 5 | This package contains a tool to convert Unified Robot Description Format (URDF) documents into COLLAborative Design Activity (COLLADA) documents. 6 | 7 | Implements robot-specific COLLADA extensions as defined by 8 | http://openrave.programmingvision.com/index.php/Started:COLLADA 9 | 10 | 11 | Tim Field 12 | Rosen Diankov 13 | Ioan Sucan 14 | Jackie Kay 15 | Chris Lalancette 16 | Shane Loretz 17 | 18 | BSD 19 | 20 | http://ros.org/wiki/collada_urdf 21 | https://github.com/ros/collada_urdf 22 | https://github.com/ros/collada_urdf/issues 23 | 24 | catkin 25 | 26 | liburdfdom-headers-dev 27 | 28 | angles 29 | assimp-dev 30 | cmake_modules 31 | collada-dom 32 | collada_parser 33 | eigen 34 | geometric_shapes 35 | liburdfdom-dev 36 | liburdfdom-headers-dev 37 | resource_retriever 38 | rosconsole 39 | urdf 40 | 41 | assimp 42 | collada-dom 43 | collada_parser 44 | geometric_shapes 45 | liburdfdom-dev 46 | resource_retriever 47 | rosconsole 48 | urdf 49 | 50 | 51 | -------------------------------------------------------------------------------- /collada_parser/include/collada_parser/collada_parser.h: -------------------------------------------------------------------------------- 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: Wim Meeussen */ 36 | 37 | #ifndef COLLADA_PARSER_COLLADA_PARSER_H 38 | #define COLLADA_PARSER_COLLADA_PARSER_H 39 | 40 | #include 41 | 42 | #include 43 | 44 | namespace urdf { 45 | 46 | /// \brief Load Model from string 47 | urdf::ModelInterfaceSharedPtr parseCollada(const std::string& xml_string); 48 | 49 | } 50 | 51 | #endif 52 | -------------------------------------------------------------------------------- /collada_parser/src/collada_parser_plugin.cpp: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2013, 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 | #include "collada_parser/collada_parser_plugin.h" 38 | #include "collada_parser/collada_parser.h" 39 | #include 40 | 41 | urdf::ModelInterfaceSharedPtr urdf::ColladaURDFParser::parse(const std::string &xml_string) 42 | { 43 | return urdf::parseCollada(xml_string); 44 | } 45 | 46 | CLASS_LOADER_REGISTER_CLASS(urdf::ColladaURDFParser, urdf::URDFParser) 47 | -------------------------------------------------------------------------------- /collada_parser/include/collada_parser/collada_parser_plugin.h: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2013, 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 COLLADA_PARSER_COLLADA_PARSER_PLUGIN_H 38 | #define COLLADA_PARSER_COLLADA_PARSER_PLUGIN_H 39 | 40 | #include 41 | 42 | #include 43 | 44 | namespace urdf 45 | { 46 | 47 | class ColladaURDFParser : public URDFParser 48 | { 49 | public: 50 | 51 | virtual urdf::ModelInterfaceSharedPtr parse(const std::string& xml_string); 52 | }; 53 | 54 | } 55 | 56 | #endif 57 | -------------------------------------------------------------------------------- /collada_parser/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(collada_parser) 3 | 4 | find_package(Boost REQUIRED system) 5 | 6 | find_package(catkin REQUIRED COMPONENTS class_loader rosconsole urdf urdf_parser_plugin) 7 | find_package(urdfdom_headers REQUIRED) 8 | 9 | add_compile_options(-std=c++11) 10 | 11 | include_directories(include ${Boost_INCLUDE_DIR} ${catkin_INCLUDE_DIRS} ${urdfdom_headers_INCLUDE_DIRS}) 12 | 13 | set(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake-extensions/) 14 | find_package(PkgConfig) 15 | find_package(COLLADA_DOM 2.4 REQUIRED COMPONENTS 1.5) 16 | if(COLLADA_DOM_FOUND) 17 | include_directories(${COLLADA_DOM_INCLUDE_DIRS}) 18 | link_directories(${COLLADA_DOM_LIBRARY_DIRS}) 19 | endif() 20 | 21 | catkin_package( 22 | LIBRARIES ${PROJECT_NAME} 23 | INCLUDE_DIRS include 24 | CATKIN_DEPENDS class_loader rosconsole urdf urdf_parser_plugin 25 | DEPENDS COLLADA_DOM 26 | ) 27 | 28 | # necessary for collada reader to create the temporary dae files due 29 | # to limitations in the URDF geometry 30 | include (CheckFunctionExists) 31 | check_function_exists(mkstemps HAVE_MKSTEMPS) 32 | if(HAVE_MKSTEMPS) 33 | add_definitions("-DHAVE_MKSTEMPS") 34 | endif() 35 | 36 | # build the parser lib 37 | add_library(${PROJECT_NAME} src/collada_parser.cpp) 38 | target_link_libraries(${PROJECT_NAME} 39 | ${COLLADA_DOM_LIBRARIES} ${Boost_LIBRARIES} ${catkin_LIBRARIES} 40 | ) 41 | 42 | # build the plugin for the parser 43 | add_library(${PROJECT_NAME}_plugin src/collada_parser_plugin.cpp) 44 | target_link_libraries(${PROJECT_NAME}_plugin 45 | ${PROJECT_NAME} ${Boost_LIBRARIES} ${catkin_LIBRARIES} 46 | ) 47 | 48 | set_target_properties(${PROJECT_NAME} 49 | PROPERTIES COMPILER_FLAGS "${COLLADA_DOM_CFLAGS_OTHER}" 50 | ) 51 | if(APPLE) 52 | set_target_properties(${PROJECT_NAME} 53 | PROPERTIES LINK_FLAGS 54 | "${COLLADA_DOM_LDFLAGS_OTHER} -undefined dynamic_lookup" 55 | ) 56 | else() 57 | set_target_properties(${PROJECT_NAME} 58 | PROPERTIES LINK_FLAGS "${COLLADA_DOM_LDFLAGS_OTHER}" 59 | ) 60 | endif() 61 | 62 | install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_plugin 63 | DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}) 64 | 65 | install(DIRECTORY include/${PROJECT_NAME}/ 66 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) 67 | 68 | install(FILES collada_parser_plugin_description.xml 69 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 70 | -------------------------------------------------------------------------------- /collada_urdf/test/test_collada_urdf.cpp: -------------------------------------------------------------------------------- 1 | // Copyright (c) 2010, Willow Garage, Inc. 2 | // All rights reserved. 3 | // 4 | // Redistribution and use in source and binary forms, with or without 5 | // modification, are permitted provided that the following conditions are met: 6 | // 7 | // * Redistributions of source code must retain the above copyright 8 | // notice, this list of conditions and the following disclaimer. 9 | // * Redistributions in binary form must reproduce the above copyright 10 | // notice, this list of conditions and the following disclaimer in the 11 | // documentation and/or other materials provided with the distribution. 12 | // * Neither the name of Willow Garage, Inc. nor the names of its 13 | // contributors may be used to endorse or promote products derived from 14 | // this software without specific prior written permission. 15 | // 16 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 17 | // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 18 | // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 19 | // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 20 | // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 21 | // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 22 | // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 23 | // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 24 | // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 25 | // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 26 | // POSSIBILITY OF SUCH DAMAGE. 27 | 28 | /* Author: Tim Field */ 29 | 30 | #include "collada_urdf/collada_urdf.h" 31 | 32 | #include 33 | 34 | TEST(collada_urdf, collada_from_urdf_file_works) 35 | { 36 | urdf::Model robot_model; 37 | 38 | ASSERT_TRUE(robot_model.initFile("pr2.urdf")); 39 | ASSERT_TRUE(collada_urdf::WriteUrdfModelToColladaFile(robot_model, "pr2.dae")); 40 | } 41 | 42 | TEST(collada_urdf, collada_output_dir_does_not_exist) 43 | { 44 | urdf::Model robot_model; 45 | 46 | ASSERT_TRUE(robot_model.initFile("pr2.urdf")); 47 | ASSERT_FALSE(collada_urdf::WriteUrdfModelToColladaFile(robot_model, "a/very/long/directory/path/that/should/not/exist/pr2.dae")); 48 | } 49 | 50 | int main(int argc, char **argv) 51 | { 52 | testing::InitGoogleTest(&argc, argv); 53 | return RUN_ALL_TESTS(); 54 | } 55 | -------------------------------------------------------------------------------- /collada_urdf/include/collada_urdf/collada_urdf.h: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2010, 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 | * * Redstributions 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 | /* Authors: Tim Field */ 36 | 37 | #ifndef COLLADA_URDF_COLLADA_URDF_H 38 | #define COLLADA_URDF_COLLADA_URDF_H 39 | 40 | #include 41 | #include 42 | 43 | #include "urdf/model.h" 44 | 45 | namespace collada_urdf { 46 | 47 | class ColladaUrdfException : public std::runtime_error 48 | { 49 | public: 50 | ColladaUrdfException(std::string const& what); 51 | }; 52 | 53 | /** Write a COLLADA DOM to a file 54 | * \param robot_model The URDF robot model 55 | * \param file The filename to write the document to 56 | * \return true on success, false on failure 57 | */ 58 | bool WriteUrdfModelToColladaFile(urdf::Model const& robot_model, std::string const& file); 59 | 60 | } 61 | 62 | #endif 63 | -------------------------------------------------------------------------------- /collada_urdf/src/urdf_to_collada.cpp: -------------------------------------------------------------------------------- 1 | /********************************************************************* 2 | * Software License Agreement (BSD License) 3 | * 4 | * Copyright (c) 2010, 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 | * * Redstributions 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: Tim Field */ 36 | 37 | #include "collada_urdf/collada_urdf.h" 38 | 39 | int main(int argc, char** argv) 40 | { 41 | if (argc != 3) { 42 | std::cerr << "Usage: urdf_to_collada input.urdf output.dae" << std::endl; 43 | return -1; 44 | } 45 | 46 | std::string input_filename(argv[1]); 47 | std::string output_filename(argv[2]); 48 | 49 | urdf::Model robot_model; 50 | if (!robot_model.initFile(input_filename)) { 51 | std::cerr << "failed to open urdf file " << input_filename << std::endl; 52 | return -2; 53 | } 54 | 55 | collada_urdf::WriteUrdfModelToColladaFile(robot_model, output_filename); 56 | std::cout << std::endl << "Document successfully written to " << output_filename << std::endl; 57 | 58 | return 0; 59 | } 60 | -------------------------------------------------------------------------------- /collada_urdf/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 3.0.2) 2 | project(collada_urdf) 3 | 4 | find_package(catkin REQUIRED COMPONENTS angles cmake_modules collada_parser geometric_shapes resource_retriever rosconsole urdf) 5 | 6 | find_package(urdfdom_headers REQUIRED) 7 | 8 | include(CheckCXXCompilerFlag) 9 | check_cxx_compiler_flag(-std=c++11 HAS_STD_CPP11_FLAG) 10 | if(HAS_STD_CPP11_FLAG) 11 | add_compile_options(-std=c++11) 12 | endif() 13 | 14 | include_directories(include) 15 | 16 | find_package(assimp QUIET) 17 | if ( NOT ASSIMP_FOUND ) 18 | find_package(Assimp QUIET) 19 | if ( NOT ASSIMP_FOUND ) 20 | find_package(PkgConfig REQUIRED) 21 | pkg_check_modules(ASSIMP assimp) 22 | endif() 23 | endif() 24 | if( ASSIMP_FOUND ) 25 | if( NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.1150" ) 26 | add_definitions(-DASSIMP_UNIFIED_HEADER_NAMES) 27 | endif() 28 | if( NOT ${ASSIMP_VERSION} VERSION_LESS "2.0.885" ) 29 | add_definitions(-DASSIMP_EXPORT_API) 30 | endif() 31 | include_directories(${ASSIMP_INCLUDE_DIRS}) 32 | link_directories(${ASSIMP_LIBRARY_DIRS}) 33 | else() 34 | message(STATUS "could not find assimp (perhaps available thorugh ROS package?), so assuming assimp v2") 35 | set(ASSIMP_LIBRARIES assimp) 36 | set(ASSIMP_LIBRARY_DIRS) 37 | set(ASSIMP_CXX_FLAGS) 38 | set(ASSIMP_CFLAGS_OTHER) 39 | set(ASSIMP_LINK_FLAGS) 40 | set(ASSIMP_INCLUDE_DIRS) 41 | endif() 42 | 43 | # Note: assimp 3.1 overwrites CMake Boost variables, so we need to check for 44 | # Boost after assimp. 45 | find_package(Boost REQUIRED COMPONENTS system filesystem program_options) 46 | include_directories(${Boost_INCLUDE_DIR}) 47 | 48 | find_package(Eigen3 REQUIRED) 49 | 50 | find_package(COLLADA_DOM 2.3 COMPONENTS 1.5) 51 | if( COLLADA_DOM_FOUND ) 52 | include_directories(${COLLADA_DOM_INCLUDE_DIRS}) 53 | link_directories(${COLLADA_DOM_LIBRARY_DIRS}) 54 | endif() 55 | 56 | catkin_package( 57 | LIBRARIES ${PROJECT_NAME} 58 | INCLUDE_DIRS include 59 | CATKIN_DEPENDS collada_parser geometric_shapes resource_retriever rosconsole urdf 60 | DEPENDS ASSIMP COLLADA_DOM urdfdom_headers 61 | ) 62 | 63 | include_directories(${catkin_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS}) 64 | link_directories(${catkin_LIBRARY_DIRS}) 65 | 66 | add_library(${PROJECT_NAME} src/collada_urdf.cpp) 67 | target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${COLLADA_DOM_LIBRARIES} 68 | ${Boost_LIBRARIES} ${ASSIMP_LIBRARIES}) 69 | set_target_properties(${PROJECT_NAME} PROPERTIES COMPILER_FLAGS "${ASSIMP_CXX_FLAGS} ${ASSIMP_CFLAGS_OTHER}") 70 | set_target_properties(${PROJECT_NAME} PROPERTIES LINK_FLAGS "${ASSIMP_LINK_FLAGS}") 71 | 72 | add_executable(urdf_to_collada src/urdf_to_collada.cpp) 73 | target_link_libraries(urdf_to_collada ${catkin_LIBRARIES} ${COLLADA_DOM_LIBRARIES} 74 | ${Boost_LIBRARIES} ${PROJECT_NAME}) 75 | 76 | add_executable(collada_to_urdf src/collada_to_urdf.cpp) 77 | target_link_libraries(collada_to_urdf ${ASSIMP_LIBRARIES} ${catkin_LIBRARIES} ${COLLADA_DOM_LIBRARIES} ${Boost_LIBRARIES}) 78 | set_target_properties(collada_to_urdf PROPERTIES COMPILER_FLAGS "${ASSIMP_CXX_FLAGS} ${ASSIMP_CFLAGS_OTHER}") 79 | set_target_properties(collada_to_urdf PROPERTIES LINK_FLAGS "${ASSIMP_LINK_FLAGS}") 80 | 81 | if(CATKIN_ENABLE_TESTING) 82 | catkin_add_gtest(test_collada_urdf test/test_collada_urdf.cpp WORKING_DIRECTORY ${PROJECT_SOURCE_DIR}/test) 83 | target_link_libraries(test_collada_urdf ${PROJECT_NAME} ${catkin_LIBRARIES} ${COLLADA_DOM_LIBRARIES} 84 | ${Boost_LIBRARIES}) 85 | endif() 86 | 87 | install(TARGETS ${PROJECT_NAME} urdf_to_collada collada_to_urdf 88 | LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} 89 | RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}) 90 | 91 | install(DIRECTORY include/${PROJECT_NAME}/ 92 | DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}) 93 | -------------------------------------------------------------------------------- /collada_parser/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package collada_parser 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.12.13 (2020-07-14) 6 | -------------------- 7 | * Update to newer CMake to get rid of CMP0048 warning (`#38 `_) 8 | * Contributors: Chris Lalancette 9 | 10 | 1.12.12 (2018-05-08) 11 | -------------------- 12 | * add exec_depend to package.xml of collada_parser for loading by pluginlib (`#27 `_) 13 | * Contributors: Yohei Kakiuchi 14 | 15 | 1.12.11 (2018-04-17) 16 | -------------------- 17 | * Collada cleanup dependencies (`#26 `_) 18 | * update links now that this is in its own repo 19 | * Make CMakeLists.txt depend on collada-dom version 2.4. (`#11 `_) 20 | * Contributors: Chris Lalancette, Mikael Arguedas 21 | 22 | 1.12.10 (2017-05-04) 23 | -------------------- 24 | * Moved collada_parser and collada_urdf to new repository 25 | 26 | 1.12.9 (2017-04-26) 27 | ------------------- 28 | 29 | 1.12.8 (2017-03-27) 30 | ------------------- 31 | * add Chris and Shane as maintainers (`#184 `_) 32 | * fix missed mandatory -std=c++11 flag (`#181 `_) 33 | collada_parser,kdl_parser,urdf: add c++11 flag, 34 | collada_parser: replace typeof with ansi __typeof\_\_ 35 | builded/tested on gentoo 36 | Thanks den4ix for the contribution! 37 | * Contributors: Denis Romanchuk, William Woodall 38 | 39 | 1.12.7 (2017-01-26) 40 | ------------------- 41 | 42 | 1.12.6 (2017-01-04) 43 | ------------------- 44 | * Now using ``urdf::*ShredPtr`` instead of ``boost::shared_ptr`` (`#144 `_) 45 | * Contributors: Jochen Sprickerhof 46 | 47 | 1.12.5 (2016-10-27) 48 | ------------------- 49 | 50 | 1.12.4 (2016-08-23) 51 | ------------------- 52 | 53 | 1.12.3 (2016-06-10) 54 | ------------------- 55 | 56 | 1.12.2 (2016-04-12) 57 | ------------------- 58 | 59 | 1.12.1 (2016-04-10) 60 | ------------------- 61 | 62 | 1.11.8 (2015-09-11) 63 | ------------------- 64 | 65 | 1.11.7 (2015-04-22) 66 | ------------------- 67 | 68 | 1.11.6 (2014-11-30) 69 | ------------------- 70 | * fix rotation of joint axis when oriantation between parent link and child link is differ 71 | * Contributors: YoheiKakiuchi 72 | 73 | 1.11.5 (2014-07-24) 74 | ------------------- 75 | 76 | 1.11.4 (2014-07-07) 77 | ------------------- 78 | * collada_parser: add extract actuators, fix for using nominal torque 79 | * moving to new dependency for urdfdom and urdfdom_headers. https://github.com/ros/rosdistro/issues/4633 80 | * Contributors: Tully Foote, YoheiKakiuchi 81 | 82 | 1.11.3 (2014-06-24) 83 | ------------------- 84 | * update usage of urdfdom_headers for indigo/trusty 85 | * Contributors: William Woodall 86 | 87 | 1.11.2 (2014-03-22) 88 | ------------------- 89 | 90 | 1.11.1 (2014-03-20) 91 | ------------------- 92 | * remove visual and collision if there is no vertices 93 | * do not use visual and collision group 94 | * fix debug message 95 | * fix problem of root coordinates 96 | * Contributors: YoheiKakiuchi 97 | 98 | 1.11.0 (2014-02-21) 99 | ------------------- 100 | * fix, joint axis should be rotated depend on local coords 101 | * fix overwriting velocity limit 102 | * Contributors: YoheiKakiuchi 103 | 104 | 1.10.18 (2013-12-04) 105 | -------------------- 106 | * add DEPENDS for kdl_parser 107 | * Contributors: Ioan Sucan 108 | 109 | 1.10.16 (2013-11-18) 110 | -------------------- 111 | * fix for using collada_parser_plugin 112 | 113 | 1.10.15 (2013-08-17) 114 | -------------------- 115 | -------------------------------------------------------------------------------- /collada_urdf/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package collada_urdf 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.12.13 (2020-07-14) 6 | -------------------- 7 | * Update to newer CMake to get rid of CMP0048 warning (`#38 `_) 8 | * Enable to output transmission_interface instead of pr2_mechanism_model (`#35 `_) 9 | * Contributors: Chris Lalancette, Shun Hasegawa 10 | 11 | 1.12.12 (2018-05-08) 12 | -------------------- 13 | 14 | 1.12.11 (2018-04-17) 15 | -------------------- 16 | * Collada cleanup dependencies (`#26 `_) 17 | * update links now that this is in its own repo 18 | * Switch to using Eigen for Quaternion and Matrix. (`#21 `_) 19 | * add relicensing comment (`#19 `_) 20 | * remove unused tinyxml from cmakelists (`#15 `_) 21 | * Contributors: Chris Lalancette, Mikael Arguedas, Rosen Diankov 22 | 23 | 1.12.10 (2017-05-04) 24 | -------------------- 25 | * Moved collada_parser and collada_urdf to new repository 26 | 27 | 1.12.9 (2017-04-26) 28 | ------------------- 29 | 30 | 1.12.8 (2017-03-27) 31 | ------------------- 32 | * Remove old gazebo settings. 33 | Based on an initial patch from YoheiKakiuchi, just totally 34 | remove old Gazebo 1.0 settings, as they are never used and 35 | almost certainly will never be used. 36 | * add Chris and Shane as maintainers (`#184 `_) 37 | * Do a few cleanup tasks in collada_urdf (`#183 `_) 38 | * Style cleanup within collada_urdf. 39 | No functional change, just style. 40 | * Make sure to quit out of urdf_to_collada when invalid file is found. 41 | Otherwise, we'll just end up segfaulting later on. 42 | * Re-enable one of the collada-urdf tests. 43 | In point of fact, we delete the rest of the tests because 44 | they don't make much sense anymore. Just enable this one 45 | for now; we'll enable further ones in the future. 46 | * Add in another test for collada_urdf. 47 | * remove divide by 2 when writing boxes to collada format (`#133 `_) 48 | * Contributors: Chris Lalancette, Jackie Kay, William Woodall 49 | 50 | 1.12.7 (2017-01-26) 51 | ------------------- 52 | 53 | 1.12.6 (2017-01-04) 54 | ------------------- 55 | * Now using ``urdf::*ShredPtr`` instead of ``boost::shared_ptr`` (`#144 `_) 56 | * Contributors: Jochen Sprickerhof 57 | 58 | 1.12.5 (2016-10-27) 59 | ------------------- 60 | 61 | 1.12.4 (2016-08-23) 62 | ------------------- 63 | * Use the C++11 standard (`#145 `_) 64 | * Contributors: William Woodall 65 | 66 | 1.12.3 (2016-06-10) 67 | ------------------- 68 | 69 | 1.12.2 (2016-04-12) 70 | ------------------- 71 | 72 | 1.12.1 (2016-04-10) 73 | ------------------- 74 | 75 | 1.11.8 (2015-09-11) 76 | ------------------- 77 | * Removed pcre hack for newer released collada-dom. 78 | * Contributors: Kei Okada 79 | 80 | 1.11.7 (2015-04-22) 81 | ------------------- 82 | * Fixed `#89 `_ 83 | Accomplished by loading libpcrecpp before collada-dom. 84 | * Contributors: Kei Okada, William Woodall 85 | 86 | 1.11.6 (2014-11-30) 87 | ------------------- 88 | 89 | 1.11.5 (2014-07-24) 90 | ------------------- 91 | 92 | 1.11.4 (2014-07-07) 93 | ------------------- 94 | * moving to new dependency for urdfdom and urdfdom_headers. https://github.com/ros/rosdistro/issues/4633 95 | * Fix clash with assimp 3.1 in CMake. 96 | * Contributors: Benjamin Chrétien, Tully Foote 97 | 98 | 1.11.3 (2014-06-24) 99 | ------------------- 100 | * Merge pull request `#69 `_ from YoheiKakiuchi/indigo-devel-store-original-mesh-name 101 | storing original mesh file name and location 102 | * storing original mesh file name and location 103 | * Contributors: Ioan A Sucan, YoheiKakiuchi 104 | 105 | 1.11.2 (2014-03-22) 106 | ------------------- 107 | * use new urdfdom_headers API 108 | * Contributors: Ioan Sucan 109 | 110 | 1.11.1 (2014-03-20) 111 | ------------------- 112 | * Use assimp-dev dep for building 113 | * Contributors: Scott K Logan 114 | 115 | 1.11.0 (2014-02-21) 116 | ------------------- 117 | * Use VERSION_LESS instead of STRLESS 118 | The version comparison routines were added in cmake 2.8.0 119 | * Fix export API detection (for assimp < 2.0.885) 120 | It looks like this API was added in Assimp 2.0.885: 121 | https://github.com/assimp/assimp/commit/ae23c03bd9a0b5f1227dc0042fd98f7206c770a8 122 | * Invert Assimp version detect logic for greater accuracy 123 | * Updated Assimp defines to be more flexible 124 | This commit is a follow-up to 85b20197671e142044e471df603debd0faf08baf 125 | Why was export.h removed from assimp < 3.0.0? 126 | * Better feature detection for assimp version 127 | The unified headers were introduced in Assimp 2.0.1150, so checking for Assimp 3.0.0 is not quite the best solution. 128 | See https://github.com/assimp/assimp/commit/6fa251c2f2e7a142bb861227dce0c26362927fbc 129 | * Contributors: Scott K Logan 130 | 131 | 1.10.18 (2013-12-04) 132 | -------------------- 133 | * add DEPENDS for kdl_parser 134 | * Contributors: Ioan Sucan 135 | 136 | 1.10.16 (2013-11-18) 137 | -------------------- 138 | * check for CATKIN_ENABLE_TESTING 139 | * fix for compiling collada_to_urdf, add dependency to tf 140 | * add collada_to_urdf.cpp for converting collada file to urdf file 141 | 142 | 1.10.15 (2013-08-17) 143 | -------------------- 144 | * fix `#30 `_ 145 | -------------------------------------------------------------------------------- /collada_urdf/src/collada_to_urdf.cpp: -------------------------------------------------------------------------------- 1 | /* Author: Yohei Kakiuchi */ 2 | 3 | #include 4 | #include 5 | #include 6 | #include 7 | 8 | #include 9 | #include 10 | 11 | #include 12 | #include 13 | 14 | #if defined(ASSIMP_UNIFIED_HEADER_NAMES) 15 | #include 16 | #include 17 | #include 18 | #include 19 | #include 20 | #include 21 | #else 22 | #include 23 | #if defined(ASSIMP_EXPORT_API) 24 | #include 25 | #endif 26 | #include 27 | #include 28 | #endif 29 | 30 | #include 31 | #include 32 | #include 33 | 34 | #include 35 | 36 | #undef GAZEBO_1_3 37 | 38 | #define GAZEBO_1_3 39 | 40 | using namespace urdf; 41 | using namespace std; 42 | 43 | bool use_simple_visual = false; 44 | bool use_simple_collision = false; 45 | bool add_gazebo_description = false; 46 | bool use_transmission_interface = false; 47 | bool use_assimp_export = false; 48 | bool use_same_collision_as_visual = true; 49 | bool rotate_inertia_frame = true; 50 | bool export_collision_mesh = false; 51 | 52 | string mesh_dir = "/tmp"; 53 | string arobot_name = ""; 54 | string output_file = ""; 55 | string mesh_prefix = ""; 56 | 57 | #define PRINT_ORIGIN(os, origin) \ 58 | os << "xyz: " << origin.position.x << " " << origin.position.y << " " << origin.position.z << " "; \ 59 | { double r,p,y; origin.rotation.getRPY(r, p, y); \ 60 | os << "rpy: " << r << " " << p << " " << y; } 61 | 62 | #define PRINT_ORIGIN_XML(os, origin) \ 63 | os << "xyz=\"" << origin.position.x << " " << origin.position.y << " " << origin.position.z << "\""; \ 64 | { double h___r, h___p, h___y; \ 65 | origin.rotation.getRPY(h___r, h___p, h___y); \ 66 | os << " rpy=\"" << h___r << " " << h___p << " " << h___y << "\""; } 67 | 68 | #define PRINT_GEOM(os, geometry) \ 69 | if ( geometry->type == urdf::Geometry::MESH ) { os << "geom: name: " << ((urdf::Mesh *)geometry.get())->filename; } 70 | 71 | void assimp_file_export(std::string fname, std::string ofname, 72 | std::string mesh_type = "collada") { 73 | #if defined(ASSIMP_EXPORT_API) 74 | if (fname.find("file://") == 0) { 75 | fname.erase(0, strlen("file://")); 76 | } 77 | Assimp::Importer importer; 78 | /* 79 | { // ignore UP_DIRECTION tag in collada 80 | bool existing; 81 | importer.SetPropertyBool(AI_CONFIG_IMPORT_COLLADA_IGNORE_UP_DIRECTION, true, &existing); 82 | if(existing) { 83 | fprintf(stderr, ";; OverWrite : Ignore UP_DIRECTION", existing); 84 | } 85 | } 86 | */ 87 | const aiScene* scene = importer.ReadFile(fname.c_str(), 88 | aiProcess_Triangulate | 89 | aiProcess_GenNormals | 90 | aiProcess_JoinIdenticalVertices | 91 | aiProcess_SplitLargeMeshes | 92 | aiProcess_OptimizeMeshes | 93 | aiProcess_SortByPType); 94 | 95 | if (!scene) { 96 | std::string str( importer.GetErrorString() ); 97 | std::cerr << ";; " << str << std::endl; 98 | return; 99 | } 100 | 101 | Assimp::Exporter aexpt; 102 | aiReturn ret = aexpt.Export(scene, mesh_type, ofname); 103 | if ( ret != AI_SUCCESS ) { 104 | std::string str( "assimp error" ); 105 | std::cerr << ";; " << str << std::endl; 106 | } 107 | #endif 108 | } 109 | 110 | // assimp bounding box calculation 111 | void assimp_calc_bbox(string fname, float &minx, float &miny, float &minz, 112 | float &maxx, float &maxy, float &maxz) { 113 | 114 | if (fname.find("file://") == 0) { 115 | fname.erase(0, strlen("file://")); 116 | } 117 | 118 | Assimp::Importer importer; 119 | const aiScene* scene = importer.ReadFile(fname.c_str(), 120 | aiProcess_Triangulate | 121 | aiProcess_JoinIdenticalVertices | 122 | aiProcess_SortByPType); // aiProcess_GenNormals 123 | // aiProcess_GenSmoothNormals 124 | // aiProcess_SplitLargeMeshes 125 | if (!scene) { 126 | std::string str( importer.GetErrorString() ); 127 | std::cerr << ";; " << str << std::endl; 128 | return; 129 | } 130 | 131 | aiNode *node = scene->mRootNode; 132 | 133 | bool found = false; 134 | if(node->mNumMeshes > 0 && node->mMeshes != NULL) { 135 | std::cerr << "Root node has meshes " << node->mMeshes << std::endl;; 136 | found = true; 137 | } else { 138 | for (unsigned int i=0; i < node->mNumChildren; ++i) { 139 | if(node->mChildren[i]->mNumMeshes > 0 && node->mChildren[i]->mMeshes != NULL) { 140 | std::cerr << "Child " << i << " has meshes" << std::endl; 141 | node = node->mChildren[i]; 142 | found = true; 143 | break; 144 | } 145 | } 146 | } 147 | if(found == false) { 148 | std::cerr << "Can't find meshes in file" << std::endl; 149 | return; 150 | } 151 | 152 | aiMatrix4x4 transform = node->mTransformation; 153 | 154 | // copy vertices 155 | maxx = maxy = maxz = -100000000.0; 156 | minx = miny = minz = 100000000.0; 157 | 158 | std::cerr << ";; num meshes: " << node->mNumMeshes << std::endl; 159 | for (unsigned int m = 0; m < node->mNumMeshes; m++) { 160 | aiMesh *a = scene->mMeshes[node->mMeshes[m]]; 161 | std::cerr << ";; num vertices: " << a->mNumVertices << std::endl; 162 | 163 | for (unsigned int i = 0 ; i < a->mNumVertices ; ++i) { 164 | aiVector3D p; 165 | p.x = a->mVertices[i].x; 166 | p.y = a->mVertices[i].y; 167 | p.z = a->mVertices[i].z; 168 | p *= transform; 169 | 170 | if ( maxx < p.x ) { 171 | maxx = p.x; 172 | } 173 | if ( maxy < p.y ) { 174 | maxy = p.y; 175 | } 176 | if ( maxz < p.z ) { 177 | maxz = p.z; 178 | } 179 | if ( minx > p.x ) { 180 | minx = p.x; 181 | } 182 | if ( miny > p.y ) { 183 | miny = p.y; 184 | } 185 | if ( minz > p.z ) { 186 | minz = p.z; 187 | } 188 | } 189 | } 190 | } 191 | 192 | void addChildLinkNamesXML(urdf::LinkConstSharedPtr link, ofstream& os) 193 | { 194 | os << " name << "\">" << endl; 195 | if ( !!link->visual ) { 196 | os << " " << endl; 197 | 198 | if (!use_simple_visual) { 199 | os << " visual->origin); 201 | os << "/>" << endl; 202 | os << " " << endl; 203 | if ( link->visual->geometry->type == urdf::Geometry::MESH ) { 204 | std::string ifname (((urdf::Mesh *)link->visual->geometry.get())->filename); 205 | if (ifname.find("file://") == 0) { 206 | ifname.erase(0, strlen("file://")); 207 | } 208 | std::string ofname (mesh_dir + "/" + link->name + "_mesh.dae"); 209 | 210 | if (use_assimp_export) { 211 | // using collada export 212 | assimp_file_export (ifname, ofname); 213 | } else { 214 | // copy to ofname 215 | std::ofstream tmp_os; 216 | tmp_os.open(ofname.c_str()); 217 | std::ifstream is; 218 | is.open(ifname.c_str()); 219 | std::string buf; 220 | while(is && getline(is, buf)) tmp_os << buf << std::endl; 221 | is.close(); 222 | tmp_os.close(); 223 | } 224 | if (mesh_prefix != "") { 225 | os << " name + "_mesh.dae" << "\" scale=\"1 1 1\" />" << endl; 226 | } else { 227 | os << " " << endl; 228 | } 229 | } 230 | os << " " << endl; 231 | } else { 232 | // simple visual 233 | float ax,ay,az,bx,by,bz; 234 | if ( link->visual->geometry->type == urdf::Geometry::MESH ) { 235 | assimp_calc_bbox(((urdf::Mesh *)link->visual->geometry.get())->filename, 236 | ax, ay, az, bx, by, bz); 237 | } 238 | os << " visual->origin; 240 | 241 | pp.position.x += ( ax + bx ) / 2 ; 242 | pp.position.y += ( ay + by ) / 2 ; 243 | pp.position.z += ( az + bz ) / 2 ; 244 | PRINT_ORIGIN_XML(os, pp); 245 | os << "/>" << endl; 246 | 247 | os << " " << endl; 248 | os << " " << endl; 249 | os << " " << endl; 250 | } 251 | os << " " << endl; 252 | } 253 | if ( !!link->collision ) { 254 | os << " " << endl; 255 | if (!use_simple_collision) { 256 | os << " collision->origin); 258 | os << "/>" << endl; 259 | os << " " << endl; 260 | 261 | if ( link->visual->geometry->type == urdf::Geometry::MESH ) { 262 | std::string ifname; 263 | if (use_same_collision_as_visual) { 264 | ifname.assign (((urdf::Mesh *)link->visual->geometry.get())->filename); 265 | } else { 266 | ifname.assign (((urdf::Mesh *)link->collision->geometry.get())->filename); 267 | } 268 | if (ifname.find("file://") == 0) { 269 | ifname.erase(0, strlen("file://")); 270 | } 271 | std::string oofname; 272 | if (export_collision_mesh) { 273 | oofname = link->name + "_mesh.stl"; 274 | } else { 275 | oofname = link->name + "_mesh.dae"; 276 | } 277 | std::string ofname = (mesh_dir + "/" + oofname); 278 | 279 | if (use_assimp_export) { 280 | // using collada export 281 | if (export_collision_mesh) { 282 | assimp_file_export (ifname, ofname, "stl"); 283 | } else { 284 | assimp_file_export (ifname, ofname); 285 | } 286 | } else { 287 | // copy to ofname 288 | std::ofstream tmp_os; 289 | tmp_os.open(ofname.c_str()); 290 | std::ifstream is; 291 | is.open(ifname.c_str()); 292 | std::string buf; 293 | while(is && getline(is, buf)) tmp_os << buf << std::endl; 294 | is.close(); 295 | tmp_os.close(); 296 | } 297 | if (mesh_prefix != "") { 298 | os << " " << endl; 303 | } 304 | os << " " << endl; 305 | } else { 306 | // simple collision 307 | float ax,ay,az,bx,by,bz; 308 | if ( link->visual->geometry->type == urdf::Geometry::MESH ) { 309 | assimp_calc_bbox(std::string ( ((urdf::Mesh *)link->visual->geometry.get())->filename ), 310 | ax, ay, az, bx, by, bz); 311 | } 312 | os << " visual->origin; 314 | pp.position.x += ( ax + bx ) / 2 ; 315 | pp.position.y += ( ay + by ) / 2 ; 316 | pp.position.z += ( az + bz ) / 2 ; 317 | PRINT_ORIGIN_XML(os, pp); 318 | os << "/>" << endl; 319 | 320 | os << " " << endl; 321 | os << " " << endl; 322 | os << " " << endl; 323 | } 324 | os << " " << endl; 325 | } 326 | if ( !!link->inertial ) { 327 | if (!rotate_inertia_frame) { 328 | os << " " << endl; 329 | os << " inertial->mass << "\" />" << endl; 330 | os << " inertial->origin); 332 | os << "/>" << endl; 333 | os << " inertial->ixx << "\" "; 334 | os << "ixy=\"" << link->inertial->ixy << "\" "; 335 | os << "ixz=\"" << link->inertial->ixz << "\" "; 336 | os << "iyy=\"" << link->inertial->iyy << "\" "; 337 | os << "iyz=\"" << link->inertial->iyz << "\" "; 338 | os << "izz=\"" << link->inertial->izz << "\"/>" << endl; 339 | os << " " << endl; 340 | } else { 341 | // rotation should be identity 342 | os << " " << endl; 343 | os << " inertial->mass << "\" />" << endl; 344 | os << " inertial->origin.rotation.w, 347 | link->inertial->origin.rotation.x, 348 | link->inertial->origin.rotation.y, 349 | link->inertial->origin.rotation.z); 350 | Eigen::Matrix3d mat(qt); 351 | Eigen::Matrix3d tmat(mat.transpose()); 352 | Eigen::Matrix3d imat; 353 | imat(0, 0) = link->inertial->ixx; 354 | imat(0, 1) = link->inertial->ixy; 355 | imat(0, 2) = link->inertial->ixz; 356 | imat(1, 0) = link->inertial->ixy; 357 | imat(1, 1) = link->inertial->iyy; 358 | imat(1, 2) = link->inertial->iyz; 359 | imat(2, 0) = link->inertial->ixz; 360 | imat(2, 1) = link->inertial->iyz; 361 | imat(2, 2) = link->inertial->izz; 362 | 363 | #define DEBUG_MAT(mat) \ 364 | cout << "#2f((" << mat(0, 0) << " " << mat(0, 1) << " " << mat(0, 2) << ")"; \ 365 | cout << "(" << mat(1, 0) << " " << mat(1, 1) << " " << mat(1, 2) << ")"; \ 366 | cout << "(" << mat(2, 0) << " " << mat(2, 1) << " " << mat(2, 2) << "))" << endl; 367 | 368 | #if DEBUG 369 | DEBUG_MAT(mat); 370 | DEBUG_MAT(tmat); 371 | DEBUG_MAT(imat); 372 | #endif 373 | 374 | imat = ( mat * imat * tmat ); 375 | 376 | #if DEBUG 377 | DEBUG_MAT(imat); 378 | #endif 379 | 380 | urdf::Pose t_pose (link->inertial->origin); 381 | t_pose.rotation.clear(); 382 | 383 | PRINT_ORIGIN_XML(os, t_pose); 384 | os << "/>" << endl; 385 | 386 | os << " " << endl; 392 | os << " " << endl; 393 | } 394 | } 395 | os << " " << endl; 396 | 397 | #ifdef GAZEBO_1_3 398 | if ( add_gazebo_description ) { 399 | os << " name << "\">" << endl; 400 | os << " 0.9" << endl; 401 | os << " 0.9" << endl; 402 | os << " " << endl; 403 | } 404 | #endif 405 | 406 | for (std::vector::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++) 407 | addChildLinkNamesXML(*child, os); 408 | } 409 | 410 | void addChildJointNamesXML(urdf::LinkConstSharedPtr link, ofstream& os) 411 | { 412 | double r, p, y; 413 | for (std::vector::const_iterator child = link->child_links.begin(); child != link->child_links.end(); child++){ 414 | (*child)->parent_joint->parent_to_joint_origin_transform.rotation.getRPY(r,p,y); 415 | std::string jtype; 416 | if ( (*child)->parent_joint->type == urdf::Joint::UNKNOWN ) { 417 | jtype = std::string("unknown"); 418 | } else if ( (*child)->parent_joint->type == urdf::Joint::REVOLUTE ) { 419 | jtype = std::string("revolute"); 420 | } else if ( (*child)->parent_joint->type == urdf::Joint::CONTINUOUS ) { 421 | jtype = std::string("continuous"); 422 | } else if ( (*child)->parent_joint->type == urdf::Joint::PRISMATIC ) { 423 | jtype = std::string("prismatic"); 424 | } else if ( (*child)->parent_joint->type == urdf::Joint::FLOATING ) { 425 | jtype = std::string("floating"); 426 | } else if ( (*child)->parent_joint->type == urdf::Joint::PLANAR ) { 427 | jtype = std::string("planar"); 428 | } else if ( (*child)->parent_joint->type == urdf::Joint::FIXED ) { 429 | jtype = std::string("fixed"); 430 | } else { 431 | ///error 432 | } 433 | 434 | os << " parent_joint->name << "\" type=\"" << jtype << "\">" << endl; 435 | os << " name << "\"/>" << endl; 436 | os << " name << "\"/>" << endl; 437 | os << " parent_joint->parent_to_joint_origin_transform.position.x << " "; 438 | os << (*child)->parent_joint->parent_to_joint_origin_transform.position.y << " "; 439 | os << (*child)->parent_joint->parent_to_joint_origin_transform.position.z; 440 | os << "\" rpy=\"" << r << " " << p << " " << y << " " << "\"/>" << endl; 441 | os << " parent_joint->axis.x << " "; 442 | os << (*child)->parent_joint->axis.y << " " << (*child)->parent_joint->axis.z << "\"/>" << endl; 443 | { 444 | urdf::JointSharedPtr jt((*child)->parent_joint); 445 | 446 | if ( !!jt->limits ) { 447 | os << " limits->lower << "\""; 449 | os << " upper=\"" << jt->limits->upper << "\""; 450 | if (jt->limits->effort == 0.0) { 451 | os << " effort=\"100\""; 452 | } else { 453 | os << " effort=\"" << jt->limits->effort << "\""; 454 | } 455 | os << " velocity=\"" << jt->limits->velocity << "\""; 456 | os << " />" << endl; 457 | } 458 | if ( !!jt->dynamics ) { 459 | os << " dynamics->damping << "\""; 461 | os << " friction=\"" << jt->dynamics->friction << "\""; 462 | os << " />" << endl; 463 | } else { 464 | os << " " << endl; 468 | } 469 | #ifdef GAZEBO_1_3 470 | #if 0 471 | os << " " << endl; 477 | #endif 478 | #endif 479 | } 480 | 481 | os << " " << endl; 482 | 483 | if ( add_gazebo_description ) { 484 | if ( !use_transmission_interface ) { 485 | os << " parent_joint->name << "_trans\" >" << endl; 487 | os << " parent_joint->name << "_motor\" />" << endl; 488 | os << " parent_joint->name << "\" />" << endl; 489 | os << " 1" << endl; 490 | //os << " 1" << endl; 491 | //os << " 90000" << endl; 492 | os << " " << endl; 493 | } else { 494 | os << " parent_joint->name << "_trans\">" << endl; 495 | os << " transmission_interface/SimpleTransmission" << endl; 496 | os << " parent_joint->name << "\">" << endl; 497 | os << " hardware_interface/EffortJointInterface" << endl; 498 | os << " " << endl; 499 | os << " parent_joint->name << "_motor\">" << endl; 500 | os << " hardware_interface/EffortJointInterface" << endl; 501 | os << " 1" << endl; 502 | os << " " << endl; 503 | os << " " << endl; 504 | } 505 | #ifdef GAZEBO_1_3 506 | os << " parent_joint->name << "\">" << endl; 507 | os << " 0.4" << endl; 508 | os << " " << endl; 509 | #endif 510 | } 511 | addChildJointNamesXML(*child, os); 512 | } 513 | } 514 | 515 | void printTreeXML(urdf::LinkConstSharedPtr link, string name, string file) 516 | { 517 | std::ofstream os; 518 | os.open(file.c_str()); 519 | os << "" << endl; 520 | os << "" << endl; 522 | 523 | addChildLinkNamesXML(link, os); 524 | 525 | addChildJointNamesXML(link, os); 526 | 527 | os << "" << endl; 528 | os.close(); 529 | } 530 | 531 | namespace po = boost::program_options; 532 | // using namespace std; 533 | 534 | int main(int argc, char** argv) 535 | { 536 | string inputfile; 537 | 538 | po::options_description desc("Usage: collada_to_urdf input.dae [options]\n Options for collada_to_urdf"); 539 | desc.add_options() 540 | ("help", "produce help message") 541 | ("simple_visual,V", "use bounding box for visual") 542 | ("simple_collision,C", "use bounding box for collision") 543 | ("export_collision_mesh", "export collision mesh as STL") 544 | ("add_gazebo_description,G", "add description for using on gazebo") 545 | ("use_transmission_interface,T", "use transmission_interface as transmission") 546 | ("use_assimp_export,A", "use assimp library for exporting mesh") 547 | ("use_collision,U", "use collision geometry (default collision is the same as visual)") 548 | ("original_inertia_rotation,R", "does not rotate inertia frame") 549 | ("robot_name,N", po::value< vector >(), "output robot name") 550 | ("mesh_output_dir", po::value< vector >(), "directory for outputing") 551 | ("mesh_prefix", po::value< vector >(), "prefix of mesh files") 552 | ("output_file,O", po::value< vector >(), "output file") 553 | ("input_file", po::value< vector >(), "input file") 554 | ; 555 | 556 | po::positional_options_description p; 557 | p.add("input_file", -1); 558 | 559 | po::variables_map vm; 560 | try { 561 | po::store(po::command_line_parser(argc, argv). 562 | options(desc).positional(p).run(), vm); 563 | po::notify(vm); 564 | } 565 | catch (po::error e) { 566 | cerr << ";; option parse error / " << e.what() << endl; 567 | return 1; 568 | } 569 | 570 | if (vm.count("help")) { 571 | cout << desc << "\n"; 572 | return 1; 573 | } 574 | if (vm.count("simple_visual")) { 575 | use_simple_visual = true; 576 | cerr << ";; Using simple_visual" << endl; 577 | } 578 | if (vm.count("simple_collision")) { 579 | use_simple_collision = true; 580 | cerr << ";; Using simple_collision" << endl; 581 | } 582 | if (vm.count("add_gazebo_description")) { 583 | add_gazebo_description = true; 584 | cerr << ";; Adding gazebo description" << endl; 585 | } 586 | if (vm.count("use_transmission_interface")) { 587 | use_transmission_interface = true; 588 | cerr << ";; Using transmission_interface as transmission" << endl; 589 | } 590 | if (vm.count("use_assimp_export")) { 591 | #if defined(ASSIMP_EXPORT_API) 592 | use_assimp_export = true; 593 | #endif 594 | cerr << ";; Use assimp export" << endl; 595 | } 596 | if (vm.count("original_inertia_rotation")) { 597 | rotate_inertia_frame = false; 598 | cerr << ";; Does not rotate inertia frame" << endl; 599 | } 600 | if (vm.count("export_collision_mesh")) { 601 | export_collision_mesh = true; 602 | cerr << ";; erxport collision mesh as STL" << endl; 603 | } 604 | if (vm.count("output_file")) { 605 | vector aa = vm["output_file"].as< vector >(); 606 | cerr << ";; output file is: " 607 | << aa[0] << endl; 608 | output_file = aa[0]; 609 | } 610 | if (vm.count("robot_name")) { 611 | vector aa = vm["robot_name"].as< vector >(); 612 | cerr << ";; robot_name is: " 613 | << aa[0] << endl; 614 | arobot_name = aa[0]; 615 | } 616 | if (vm.count("mesh_prefix")) { 617 | vector aa = vm["mesh_prefix"].as< vector >(); 618 | cerr << ";; mesh_prefix is: " 619 | << aa[0] << endl; 620 | mesh_prefix = aa[0]; 621 | } 622 | if (vm.count("mesh_output_dir")) { 623 | vector aa = vm["mesh_output_dir"].as< vector >(); 624 | cerr << ";; Mesh output directory is: " 625 | << aa[0] << endl; 626 | mesh_dir = aa[0]; 627 | // check directory existence 628 | boost::filesystem::path mpath( mesh_dir ); 629 | try { 630 | if ( ! boost::filesystem::is_directory(mpath) ) { 631 | boost::filesystem::create_directory ( mpath ); 632 | } 633 | } 634 | catch ( boost::filesystem::filesystem_error e ) { 635 | cerr << ";; mesh output directory error / " << e.what() << endl; 636 | return 1; 637 | } 638 | } 639 | if (vm.count("input_file")) { 640 | vector aa = vm["input_file"].as< vector >(); 641 | cerr << ";; Input file is: " 642 | << aa[0] << endl; 643 | inputfile = aa[0]; 644 | } 645 | 646 | if(inputfile == "") { 647 | cerr << desc << endl; 648 | return 1; 649 | } 650 | 651 | std::string xml_string; 652 | std::fstream xml_file(inputfile.c_str(), std::fstream::in); 653 | while ( xml_file.good() ) 654 | { 655 | std::string line; 656 | std::getline( xml_file, line); 657 | xml_string += (line + "\n"); 658 | } 659 | xml_file.close(); 660 | 661 | urdf::ModelInterfaceSharedPtr robot; 662 | if( xml_string.find("getName(); 679 | } 680 | if (output_file == "") { 681 | output_file = arobot_name + ".urdf"; 682 | } 683 | printTreeXML (robot->getRoot(), arobot_name, output_file); 684 | 685 | return 0; 686 | } 687 | -------------------------------------------------------------------------------- /collada_urdf/src/collada_urdf.cpp: -------------------------------------------------------------------------------- 1 | // -*- coding: utf-8 -*- 2 | /********************************************************************* 3 | * Software License Agreement (BSD License) 4 | * 5 | * Copyright (c) 2010, Willow Garage, Inc., University of Tokyo 6 | * All rights reserved. 7 | * 8 | * Redistribution and use in source and binary forms, with or without 9 | * modification, are permitted provided that the following conditions 10 | * are met: 11 | * 12 | * * Redstributions of source code must retain the above copyright 13 | * notice, this list of conditions and the following disclaimer. 14 | * * Redistributions in binary form must reproduce the above 15 | * copyright notice, this list of conditions and the following 16 | * disclaimer in the documentation and/or other materials provided 17 | * with the distribution. 18 | * * Neither the name of the Willow Garage nor the names of its 19 | * contributors may be used to endorse or promote products derived 20 | * from this software without specific prior written permission. 21 | * 22 | * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 23 | * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 24 | * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 25 | * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 26 | * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 27 | * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 28 | * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 29 | * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 30 | * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 31 | * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 32 | * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 33 | * POSSIBILITY OF SUCH DAMAGE. 34 | *********************************************************************/ 35 | 36 | /* Authors: Rosen Diankov, Tim Field */ 37 | 38 | #include "collada_urdf/collada_urdf.h" 39 | 40 | #include 41 | #include 42 | #include 43 | #include 44 | 45 | #ifndef _WIN32 46 | #pragma GCC diagnostic push 47 | #pragma GCC diagnostic ignored "-Wdeprecated-declarations" 48 | #include 49 | #include 50 | #include 51 | #include 52 | #include 53 | #include 54 | #include 55 | #include 56 | #include 57 | #pragma GCC diagnostic pop 58 | #endif 59 | 60 | #include 61 | #include 62 | #include 63 | #include 64 | #include 65 | 66 | #include 67 | #include 68 | #include 69 | #include 70 | #include 71 | #include 72 | 73 | #if defined(ASSIMP_UNIFIED_HEADER_NAMES) 74 | #include 75 | #include 76 | #include 77 | #include 78 | #include 79 | #include 80 | #include 81 | #else 82 | #include 83 | #include 84 | #include 85 | #include 86 | #include 87 | #include 88 | #endif 89 | 90 | #include 91 | #include 92 | 93 | #define FOREACH(it, v) for(decltype((v).begin()) it = (v).begin(); it != (v).end(); (it)++) 94 | #define FOREACHC FOREACH 95 | 96 | using namespace std; 97 | 98 | namespace ColladaDOM150 { } 99 | 100 | namespace collada_urdf { 101 | 102 | using namespace ColladaDOM150; 103 | 104 | /// ResourceIOStream is copied from rviz (BSD, Willow Garage) 105 | class ResourceIOStream : public Assimp::IOStream 106 | { 107 | public: 108 | ResourceIOStream(const resource_retriever::MemoryResource& res) 109 | : res_(res) 110 | , pos_(res.data.get()) 111 | { 112 | } 113 | 114 | ~ResourceIOStream() 115 | { 116 | } 117 | 118 | size_t Read(void* buffer, size_t size, size_t count) 119 | { 120 | size_t to_read = size * count; 121 | if (pos_ + to_read > res_.data.get() + res_.size) 122 | { 123 | to_read = res_.size - (pos_ - res_.data.get()); 124 | } 125 | 126 | memcpy(buffer, pos_, to_read); 127 | pos_ += to_read; 128 | 129 | return to_read; 130 | } 131 | 132 | size_t Write( const void* buffer, size_t size, size_t count) { 133 | ROS_BREAK(); return 0; 134 | } 135 | 136 | aiReturn Seek( size_t offset, aiOrigin origin) 137 | { 138 | uint8_t* new_pos = 0; 139 | switch (origin) 140 | { 141 | case aiOrigin_SET: 142 | new_pos = res_.data.get() + offset; 143 | break; 144 | case aiOrigin_CUR: 145 | new_pos = pos_ + offset; // TODO is this right? can offset really not be negative 146 | break; 147 | case aiOrigin_END: 148 | new_pos = res_.data.get() + res_.size - offset; // TODO is this right? 149 | break; 150 | default: 151 | ROS_BREAK(); 152 | } 153 | 154 | if (new_pos < res_.data.get() || new_pos > res_.data.get() + res_.size) 155 | { 156 | return aiReturn_FAILURE; 157 | } 158 | 159 | pos_ = new_pos; 160 | return aiReturn_SUCCESS; 161 | } 162 | 163 | size_t Tell() const 164 | { 165 | return pos_ - res_.data.get(); 166 | } 167 | 168 | size_t FileSize() const 169 | { 170 | return res_.size; 171 | } 172 | 173 | void Flush() { 174 | } 175 | 176 | private: 177 | resource_retriever::MemoryResource res_; 178 | uint8_t* pos_; 179 | }; 180 | 181 | namespace mathextra { 182 | 183 | // code from MagicSoftware by Dave Eberly 184 | const double g_fEpsilon = 1e-15; 185 | //=========================================================================== 186 | 187 | 188 | #define distinctRoots 0 // roots r0 < r1 < r2 189 | #define singleRoot 1 // root r0 190 | #define floatRoot01 2 // roots r0 = r1 < r2 191 | #define floatRoot12 4 // roots r0 < r1 = r2 192 | #define tripleRoot 6 // roots r0 = r1 = r2 193 | 194 | 195 | template 196 | void Tridiagonal3 (S* mat, T* diag, T* subd) 197 | { 198 | T a, b, c, d, e, f, ell, q; 199 | 200 | a = mat[0*3+0]; 201 | b = mat[0*3+1]; 202 | c = mat[0*3+2]; 203 | d = mat[1*3+1]; 204 | e = mat[1*3+2]; 205 | f = mat[2*3+2]; 206 | 207 | subd[2] = 0.0; 208 | diag[0] = a; 209 | if ( fabs(c) >= g_fEpsilon ) { 210 | ell = (T)sqrt(b*b+c*c); 211 | b /= ell; 212 | c /= ell; 213 | q = 2*b*e+c*(f-d); 214 | diag[1] = d+c*q; 215 | diag[2] = f-c*q; 216 | subd[0] = ell; 217 | subd[1] = e-b*q; 218 | mat[0*3+0] = (S)1; mat[0*3+1] = (S)0; mat[0*3+2] = (T)0; 219 | mat[1*3+0] = (S)0; mat[1*3+1] = b; mat[1*3+2] = c; 220 | mat[2*3+0] = (S)0; mat[2*3+1] = c; mat[2*3+2] = -b; 221 | } 222 | else { 223 | diag[1] = d; 224 | diag[2] = f; 225 | subd[0] = b; 226 | subd[1] = e; 227 | mat[0*3+0] = (S)1; mat[0*3+1] = (S)0; mat[0*3+2] = (S)0; 228 | mat[1*3+0] = (S)0; mat[1*3+1] = (S)1; mat[1*3+2] = (S)0; 229 | mat[2*3+0] = (S)0; mat[2*3+1] = (S)0; mat[2*3+2] = (S)1; 230 | } 231 | } 232 | 233 | int CubicRoots (double c0, double c1, double c2, double *r0, double *r1, double *r2) 234 | { 235 | // polynomial is L^3-c2*L^2+c1*L-c0 236 | 237 | int maxiter = 50; 238 | double discr, temp, pval, pdval, b0, b1; 239 | int i; 240 | 241 | // find local extrema (if any) of p'(L) = 3*L^2-2*c2*L+c1 242 | discr = c2*c2-3*c1; 243 | if ( discr >= 0.0 ) { 244 | discr = (double)sqrt(discr); 245 | temp = (c2+discr)/3; 246 | pval = temp*(temp*(temp-c2)+c1)-c0; 247 | if ( pval >= 0.0 ) { 248 | // double root occurs before the positive local maximum 249 | (*r0) = (c2-discr)/3 - 1; // initial guess for Newton's methods 250 | pval = 2*g_fEpsilon; 251 | for (i = 0; i < maxiter && fabs(pval) > g_fEpsilon; i++) { 252 | pval = (*r0)*((*r0)*((*r0)-c2)+c1)-c0; 253 | pdval = (*r0)*(3*(*r0)-2*c2)+c1; 254 | (*r0) -= pval/pdval; 255 | } 256 | 257 | // Other two roots are solutions to quadratic equation 258 | // L^2 + ((*r0)-c2)*L + [(*r0)*((*r0)-c2)+c1] = 0. 259 | b1 = (*r0)-c2; 260 | b0 = (*r0)*((*r0)-c2)+c1; 261 | discr = b1*b1-4*b0; 262 | if ( discr < -g_fEpsilon ) 263 | { 264 | // single root r0 265 | return singleRoot; 266 | } 267 | else 268 | { 269 | int result = distinctRoots; 270 | 271 | // roots r0 <= r1 <= r2 272 | discr = sqrt(fabs(discr)); 273 | (*r1) = 0.5f*(-b1-discr); 274 | (*r2) = 0.5f*(-b1+discr); 275 | 276 | if ( fabs((*r0)-(*r1)) <= g_fEpsilon ) 277 | { 278 | (*r0) = (*r1); 279 | result |= floatRoot01; 280 | } 281 | if ( fabs((*r1)-(*r2)) <= g_fEpsilon ) 282 | { 283 | (*r1) = (*r2); 284 | result |= floatRoot12; 285 | } 286 | return result; 287 | } 288 | } 289 | else { 290 | // double root occurs after the negative local minimum 291 | (*r2) = temp + 1; // initial guess for Newton's method 292 | pval = 2*g_fEpsilon; 293 | for (i = 0; i < maxiter && fabs(pval) > g_fEpsilon; i++) { 294 | pval = (*r2)*((*r2)*((*r2)-c2)+c1)-c0; 295 | pdval = (*r2)*(3*(*r2)-2*c2)+c1; 296 | (*r2) -= pval/pdval; 297 | } 298 | 299 | // Other two roots are solutions to quadratic equation 300 | // L^2 + (r2-c2)*L + [r2*(r2-c2)+c1] = 0. 301 | b1 = (*r2)-c2; 302 | b0 = (*r2)*((*r2)-c2)+c1; 303 | discr = b1*b1-4*b0; 304 | if ( discr < -g_fEpsilon ) 305 | { 306 | // single root 307 | (*r0) = (*r2); 308 | return singleRoot; 309 | } 310 | else 311 | { 312 | int result = distinctRoots; 313 | 314 | // roots r0 <= r1 <= r2 315 | discr = sqrt(fabs(discr)); 316 | (*r0) = 0.5f*(-b1-discr); 317 | (*r1) = 0.5f*(-b1+discr); 318 | 319 | if ( fabs((*r0)-(*r1)) <= g_fEpsilon ) 320 | { 321 | (*r0) = (*r1); 322 | result |= floatRoot01; 323 | } 324 | if ( fabs((*r1)-(*r2)) <= g_fEpsilon ) 325 | { 326 | (*r1) = (*r2); 327 | result |= floatRoot12; 328 | } 329 | return result; 330 | } 331 | } 332 | } 333 | else { 334 | // p(L) has one double root 335 | (*r0) = c0; 336 | pval = 2*g_fEpsilon; 337 | for (i = 0; i < maxiter && fabs(pval) > g_fEpsilon; i++) { 338 | pval = (*r0)*((*r0)*((*r0)-c2)+c1)-c0; 339 | pdval = (*r0)*(3*(*r0)-2*c2)+c1; 340 | (*r0) -= pval/pdval; 341 | } 342 | return singleRoot; 343 | } 344 | } 345 | 346 | //---------------------------------------------------------------------------- 347 | template 348 | bool _QLAlgorithm3 (T* m_aafEntry, T* afDiag, T* afSubDiag) 349 | { 350 | // QL iteration with implicit shifting to reduce matrix from tridiagonal 351 | // to diagonal 352 | 353 | for (int i0 = 0; i0 < 3; i0++) 354 | { 355 | const int iMaxIter = 32; 356 | int iIter; 357 | for (iIter = 0; iIter < iMaxIter; iIter++) 358 | { 359 | int i1; 360 | for (i1 = i0; i1 <= 1; i1++) 361 | { 362 | T fSum = fabs(afDiag[i1]) + 363 | fabs(afDiag[i1+1]); 364 | if ( fabs(afSubDiag[i1]) + fSum == fSum ) 365 | break; 366 | } 367 | if ( i1 == i0 ) 368 | break; 369 | 370 | T fTmp0 = (afDiag[i0+1]-afDiag[i0])/(2.0f*afSubDiag[i0]); 371 | T fTmp1 = sqrt(fTmp0*fTmp0+1.0f); 372 | if ( fTmp0 < 0.0f ) 373 | fTmp0 = afDiag[i1]-afDiag[i0]+afSubDiag[i0]/(fTmp0-fTmp1); 374 | else 375 | fTmp0 = afDiag[i1]-afDiag[i0]+afSubDiag[i0]/(fTmp0+fTmp1); 376 | T fSin = 1.0f; 377 | T fCos = 1.0f; 378 | T fTmp2 = 0.0f; 379 | for (int i2 = i1-1; i2 >= i0; i2--) 380 | { 381 | T fTmp3 = fSin*afSubDiag[i2]; 382 | T fTmp4 = fCos*afSubDiag[i2]; 383 | if ( fabs(fTmp3) >= fabs(fTmp0) ) 384 | { 385 | fCos = fTmp0/fTmp3; 386 | fTmp1 = sqrt(fCos*fCos+1.0f); 387 | afSubDiag[i2+1] = fTmp3*fTmp1; 388 | fSin = 1.0f/fTmp1; 389 | fCos *= fSin; 390 | } 391 | else 392 | { 393 | fSin = fTmp3/fTmp0; 394 | fTmp1 = sqrt(fSin*fSin+1.0f); 395 | afSubDiag[i2+1] = fTmp0*fTmp1; 396 | fCos = 1.0f/fTmp1; 397 | fSin *= fCos; 398 | } 399 | fTmp0 = afDiag[i2+1]-fTmp2; 400 | fTmp1 = (afDiag[i2]-fTmp0)*fSin+2.0f*fTmp4*fCos; 401 | fTmp2 = fSin*fTmp1; 402 | afDiag[i2+1] = fTmp0+fTmp2; 403 | fTmp0 = fCos*fTmp1-fTmp4; 404 | 405 | for (int iRow = 0; iRow < 3; iRow++) 406 | { 407 | fTmp3 = m_aafEntry[iRow*3+i2+1]; 408 | m_aafEntry[iRow*3+i2+1] = fSin*m_aafEntry[iRow*3+i2] + 409 | fCos*fTmp3; 410 | m_aafEntry[iRow*3+i2] = fCos*m_aafEntry[iRow*3+i2] - 411 | fSin*fTmp3; 412 | } 413 | } 414 | afDiag[i0] -= fTmp2; 415 | afSubDiag[i0] = fTmp0; 416 | afSubDiag[i1] = 0.0f; 417 | } 418 | 419 | if ( iIter == iMaxIter ) 420 | { 421 | // should not get here under normal circumstances 422 | return false; 423 | } 424 | } 425 | 426 | return true; 427 | } 428 | 429 | bool QLAlgorithm3 (float* m_aafEntry, float* afDiag, float* afSubDiag) 430 | { 431 | return _QLAlgorithm3(m_aafEntry, afDiag, afSubDiag); 432 | } 433 | 434 | bool QLAlgorithm3 (double* m_aafEntry, double* afDiag, double* afSubDiag) 435 | { 436 | return _QLAlgorithm3(m_aafEntry, afDiag, afSubDiag); 437 | } 438 | 439 | void EigenSymmetric3(const double* fmat, double* afEigenvalue, double* fevecs) 440 | { 441 | double afSubDiag[3]; 442 | 443 | memcpy(fevecs, fmat, sizeof(double)*9); 444 | Tridiagonal3(fevecs, afEigenvalue,afSubDiag); 445 | QLAlgorithm3(fevecs, afEigenvalue,afSubDiag); 446 | 447 | // make eigenvectors form a right--handed system 448 | double fDet = fevecs[0*3+0] * (fevecs[1*3+1] * fevecs[2*3+2] - fevecs[1*3+2] * fevecs[2*3+1]) + 449 | fevecs[0*3+1] * (fevecs[1*3+2] * fevecs[2*3+0] - fevecs[1*3+0] * fevecs[2*3+2]) + 450 | fevecs[0*3+2] * (fevecs[1*3+0] * fevecs[2*3+1] - fevecs[1*3+1] * fevecs[2*3+0]); 451 | if ( fDet < 0.0f ) 452 | { 453 | fevecs[0*3+2] = -fevecs[0*3+2]; 454 | fevecs[1*3+2] = -fevecs[1*3+2]; 455 | fevecs[2*3+2] = -fevecs[2*3+2]; 456 | } 457 | } 458 | /* end of MAGIC code */ 459 | 460 | } // end namespace geometry 461 | 462 | /// ResourceIOSystem is copied from rviz (BSD, Willow Garage) 463 | class ResourceIOSystem : public Assimp::IOSystem 464 | { 465 | public: 466 | ResourceIOSystem() 467 | { 468 | } 469 | 470 | ~ResourceIOSystem() 471 | { 472 | } 473 | 474 | // Check whether a specific file exists 475 | bool Exists(const char* file) const 476 | { 477 | // Ugly -- two retrievals where there should be one (Exists + Open) 478 | // resource_retriever needs a way of checking for existence 479 | // TODO: cache this 480 | resource_retriever::MemoryResource res; 481 | try { 482 | res = retriever_.get(file); 483 | } 484 | catch (resource_retriever::Exception& e) { 485 | return false; 486 | } 487 | 488 | return true; 489 | } 490 | 491 | // Get the path delimiter character we'd like to see 492 | char getOsSeparator() const 493 | { 494 | return '/'; 495 | } 496 | 497 | // ... and finally a method to open a custom stream 498 | Assimp::IOStream* Open(const char* file, const char* mode) 499 | { 500 | ROS_ASSERT(mode == std::string("r") || mode == std::string("rb")); 501 | 502 | // Ugly -- two retrievals where there should be one (Exists + Open) 503 | // resource_retriever needs a way of checking for existence 504 | resource_retriever::MemoryResource res; 505 | try { 506 | res = retriever_.get(file); 507 | } 508 | catch (resource_retriever::Exception& e) { 509 | return 0; 510 | } 511 | 512 | return new ResourceIOStream(res); 513 | } 514 | 515 | void Close(Assimp::IOStream* stream) { 516 | delete stream; 517 | } 518 | 519 | private: 520 | mutable resource_retriever::Retriever retriever_; 521 | }; 522 | 523 | class Triangle 524 | { 525 | public: 526 | Triangle(const urdf::Vector3 &_p1, const urdf::Vector3 &_p2, const urdf::Vector3 &_p3) : 527 | p1(_p1), p2(_p2), p3(_p3) 528 | {} 529 | Triangle() { this->clear(); }; 530 | urdf::Vector3 p1, p2, p3; 531 | 532 | void clear() { p1.clear(); p2.clear(); p3.clear(); }; 533 | }; 534 | 535 | /// \brief Implements writing urdf::Model objects to a COLLADA DOM. 536 | // Portions of this code are taken verbatim from OpenRAVE (https://github.com/rdiankov/openrave, commits 87410293, ca3473f7, d844de2a) and relicensed as BSD by the original author (rdiankov) 537 | class ColladaWriter : public daeErrorHandler 538 | { 539 | private: 540 | struct SCENE 541 | { 542 | domVisual_sceneRef vscene; 543 | domKinematics_sceneRef kscene; 544 | domPhysics_sceneRef pscene; 545 | domInstance_with_extraRef viscene; 546 | domInstance_kinematics_sceneRef kiscene; 547 | domInstance_with_extraRef piscene; 548 | }; 549 | 550 | typedef std::map< urdf::LinkConstSharedPtr, urdf::Pose > MAPLINKPOSES; 551 | struct LINKOUTPUT 552 | { 553 | list > listusedlinks; 554 | list > listprocesseddofs; 555 | daeElementRef plink; 556 | domNodeRef pnode; 557 | MAPLINKPOSES _maplinkposes; 558 | }; 559 | 560 | struct physics_model_output 561 | { 562 | domPhysics_modelRef pmodel; 563 | std::vector vrigidbodysids; ///< same ordering as the physics indices 564 | }; 565 | 566 | struct kinematics_model_output 567 | { 568 | struct axis_output 569 | { 570 | //axis_output(const string& sid, KinBody::JointConstPtr pjoint, int iaxis) : sid(sid), pjoint(pjoint), iaxis(iaxis) {} 571 | axis_output() : iaxis(0) { 572 | } 573 | string sid, nodesid; 574 | urdf::JointConstSharedPtr pjoint; 575 | int iaxis; 576 | string jointnodesid; 577 | }; 578 | domKinematics_modelRef kmodel; 579 | std::vector vaxissids; 580 | std::vector vlinksids; 581 | MAPLINKPOSES _maplinkposes; 582 | }; 583 | 584 | struct axis_sids 585 | { 586 | axis_sids(const string& axissid, const string& valuesid, const string& jointnodesid) : axissid(axissid), valuesid(valuesid), jointnodesid(jointnodesid) { 587 | } 588 | string axissid, valuesid, jointnodesid; 589 | }; 590 | 591 | struct instance_kinematics_model_output 592 | { 593 | domInstance_kinematics_modelRef ikm; 594 | std::vector vaxissids; 595 | boost::shared_ptr kmout; 596 | std::vector > vkinematicsbindings; 597 | }; 598 | 599 | struct instance_articulated_system_output 600 | { 601 | domInstance_articulated_systemRef ias; 602 | std::vector vaxissids; 603 | std::vector vlinksids; 604 | std::vector > vkinematicsbindings; 605 | }; 606 | 607 | struct instance_physics_model_output 608 | { 609 | domInstance_physics_modelRef ipm; 610 | boost::shared_ptr pmout; 611 | }; 612 | 613 | struct kinbody_models 614 | { 615 | std::string uri, kinematicsgeometryhash; 616 | boost::shared_ptr kmout; 617 | boost::shared_ptr pmout; 618 | }; 619 | 620 | public: 621 | ColladaWriter(const urdf::Model& robot, int writeoptions) : _writeoptions(writeoptions), _robot(robot), _dom(NULL) { 622 | daeErrorHandler::setErrorHandler(this); 623 | _importer.SetIOHandler(new ResourceIOSystem()); 624 | } 625 | virtual ~ColladaWriter() { 626 | } 627 | 628 | daeDocument* doc() { 629 | return _doc; 630 | } 631 | 632 | bool convert() 633 | { 634 | try { 635 | const char* documentName = "urdf_snapshot"; 636 | daeInt error = _collada.getDatabase()->insertDocument(documentName, &_doc ); // also creates a collada root 637 | if (error != DAE_OK || _doc == NULL) { 638 | throw ColladaUrdfException("Failed to create document"); 639 | } 640 | _dom = daeSafeCast(_doc->getDomRoot()); 641 | _dom->setAttribute("xmlns:math","http://www.w3.org/1998/Math/MathML"); 642 | 643 | //create the required asset tag 644 | domAssetRef asset = daeSafeCast( _dom->add( COLLADA_ELEMENT_ASSET ) ); 645 | { 646 | // facet becomes owned by locale, so no need to explicitly delete 647 | boost::posix_time::time_facet* facet = new boost::posix_time::time_facet("%Y-%m-%dT%H:%M:%s"); 648 | std::stringstream ss; 649 | ss.imbue(std::locale(ss.getloc(), facet)); 650 | ss << boost::posix_time::second_clock::local_time(); 651 | 652 | domAsset::domCreatedRef created = daeSafeCast( asset->add( COLLADA_ELEMENT_CREATED ) ); 653 | created->setValue(ss.str().c_str()); 654 | domAsset::domModifiedRef modified = daeSafeCast( asset->add( COLLADA_ELEMENT_MODIFIED ) ); 655 | modified->setValue(ss.str().c_str()); 656 | 657 | domAsset::domContributorRef contrib = daeSafeCast( asset->add( COLLADA_TYPE_CONTRIBUTOR ) ); 658 | domAsset::domContributor::domAuthoring_toolRef authoringtool = daeSafeCast( contrib->add( COLLADA_ELEMENT_AUTHORING_TOOL ) ); 659 | authoringtool->setValue("URDF Collada Writer"); 660 | 661 | domAsset::domUnitRef units = daeSafeCast( asset->add( COLLADA_ELEMENT_UNIT ) ); 662 | units->setMeter(1); 663 | units->setName("meter"); 664 | 665 | domAsset::domUp_axisRef zup = daeSafeCast( asset->add( COLLADA_ELEMENT_UP_AXIS ) ); 666 | zup->setValue(UP_AXIS_Z_UP); 667 | } 668 | 669 | _globalscene = _dom->getScene(); 670 | if( !_globalscene ) { 671 | _globalscene = daeSafeCast( _dom->add( COLLADA_ELEMENT_SCENE ) ); 672 | } 673 | 674 | _visualScenesLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_VISUAL_SCENES)); 675 | _visualScenesLib->setId("vscenes"); 676 | _geometriesLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_GEOMETRIES)); 677 | _geometriesLib->setId("geometries"); 678 | _effectsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_EFFECTS)); 679 | _effectsLib->setId("effects"); 680 | _materialsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_MATERIALS)); 681 | _materialsLib->setId("materials"); 682 | _kinematicsModelsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_MODELS)); 683 | _kinematicsModelsLib->setId("kmodels"); 684 | _articulatedSystemsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_ARTICULATED_SYSTEMS)); 685 | _articulatedSystemsLib->setId("asystems"); 686 | _kinematicsScenesLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_KINEMATICS_SCENES)); 687 | _kinematicsScenesLib->setId("kscenes"); 688 | _physicsScenesLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_PHYSICS_SCENES)); 689 | _physicsScenesLib->setId("pscenes"); 690 | _physicsModelsLib = daeSafeCast(_dom->add(COLLADA_ELEMENT_LIBRARY_PHYSICS_MODELS)); 691 | _physicsModelsLib->setId("pmodels"); 692 | domExtraRef pextra_library_sensors = daeSafeCast(_dom->add(COLLADA_ELEMENT_EXTRA)); 693 | pextra_library_sensors->setId("sensors"); 694 | pextra_library_sensors->setType("library_sensors"); 695 | _sensorsLib = daeSafeCast(pextra_library_sensors->add(COLLADA_ELEMENT_TECHNIQUE)); 696 | _sensorsLib->setProfile("OpenRAVE"); ///< documented profile on robot extensions 697 | 698 | _CreateScene(); 699 | _WritePhysics(); 700 | _WriteRobot(); 701 | _WriteBindingsInstance_kinematics_scene(); 702 | return true; 703 | } 704 | catch (ColladaUrdfException ex) { 705 | ROS_ERROR("Error converting: %s", ex.what()); 706 | return false; 707 | } 708 | } 709 | 710 | bool writeTo(string const& file) { 711 | try { 712 | daeString uri = _doc->getDocumentURI()->getURI(); 713 | _collada.writeTo(uri, file); 714 | } catch (ColladaUrdfException ex) { 715 | return false; 716 | } 717 | return true; 718 | } 719 | 720 | protected: 721 | virtual void handleError(daeString msg) { 722 | throw ColladaUrdfException(msg); 723 | } 724 | virtual void handleWarning(daeString msg) { 725 | std::cerr << "COLLADA DOM warning: " << msg << std::endl; 726 | } 727 | 728 | void _CreateScene() 729 | { 730 | // Create visual scene 731 | _scene.vscene = daeSafeCast(_visualScenesLib->add(COLLADA_ELEMENT_VISUAL_SCENE)); 732 | _scene.vscene->setId("vscene"); 733 | _scene.vscene->setName("URDF Visual Scene"); 734 | 735 | // Create kinematics scene 736 | _scene.kscene = daeSafeCast(_kinematicsScenesLib->add(COLLADA_ELEMENT_KINEMATICS_SCENE)); 737 | _scene.kscene->setId("kscene"); 738 | _scene.kscene->setName("URDF Kinematics Scene"); 739 | 740 | // Create physic scene 741 | _scene.pscene = daeSafeCast(_physicsScenesLib->add(COLLADA_ELEMENT_PHYSICS_SCENE)); 742 | _scene.pscene->setId("pscene"); 743 | _scene.pscene->setName("URDF Physics Scene"); 744 | 745 | // Create instance visual scene 746 | _scene.viscene = daeSafeCast(_globalscene->add( COLLADA_ELEMENT_INSTANCE_VISUAL_SCENE )); 747 | _scene.viscene->setUrl( (string("#") + string(_scene.vscene->getID())).c_str() ); 748 | 749 | // Create instance kinematics scene 750 | _scene.kiscene = daeSafeCast(_globalscene->add( COLLADA_ELEMENT_INSTANCE_KINEMATICS_SCENE )); 751 | _scene.kiscene->setUrl( (string("#") + string(_scene.kscene->getID())).c_str() ); 752 | 753 | // Create instance physics scene 754 | _scene.piscene = daeSafeCast(_globalscene->add( COLLADA_ELEMENT_INSTANCE_PHYSICS_SCENE )); 755 | _scene.piscene->setUrl( (string("#") + string(_scene.pscene->getID())).c_str() ); 756 | } 757 | 758 | void _WritePhysics() { 759 | domPhysics_scene::domTechnique_commonRef common = daeSafeCast(_scene.pscene->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 760 | // Create gravity 761 | domTargetable_float3Ref g = daeSafeCast(common->add(COLLADA_ELEMENT_GRAVITY)); 762 | g->getValue().set3 (0,0,0); 763 | } 764 | 765 | /// \brief Write kinematic body in a given scene 766 | void _WriteRobot(int id = 0) 767 | { 768 | ROS_DEBUG_STREAM(str(boost::format("writing robot as instance_articulated_system (%d) %s\n")%id%_robot.getName())); 769 | string asid = _ComputeId(str(boost::format("robot%d")%id)); 770 | string askid = _ComputeId(str(boost::format("%s_kinematics")%asid)); 771 | string asmid = _ComputeId(str(boost::format("%s_motion")%asid)); 772 | string iassid = _ComputeId(str(boost::format("%s_inst")%asmid)); 773 | 774 | domInstance_articulated_systemRef ias = daeSafeCast(_scene.kscene->add(COLLADA_ELEMENT_INSTANCE_ARTICULATED_SYSTEM)); 775 | ias->setSid(iassid.c_str()); 776 | ias->setUrl((string("#")+asmid).c_str()); 777 | ias->setName(_robot.getName().c_str()); 778 | 779 | _iasout.reset(new instance_articulated_system_output()); 780 | _iasout->ias = ias; 781 | 782 | // motion info 783 | domArticulated_systemRef articulated_system_motion = daeSafeCast(_articulatedSystemsLib->add(COLLADA_ELEMENT_ARTICULATED_SYSTEM)); 784 | articulated_system_motion->setId(asmid.c_str()); 785 | domMotionRef motion = daeSafeCast(articulated_system_motion->add(COLLADA_ELEMENT_MOTION)); 786 | domMotion_techniqueRef mt = daeSafeCast(motion->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 787 | domInstance_articulated_systemRef ias_motion = daeSafeCast(motion->add(COLLADA_ELEMENT_INSTANCE_ARTICULATED_SYSTEM)); 788 | ias_motion->setUrl(str(boost::format("#%s")%askid).c_str()); 789 | 790 | // kinematics info 791 | domArticulated_systemRef articulated_system_kinematics = daeSafeCast(_articulatedSystemsLib->add(COLLADA_ELEMENT_ARTICULATED_SYSTEM)); 792 | articulated_system_kinematics->setId(askid.c_str()); 793 | domKinematicsRef kinematics = daeSafeCast(articulated_system_kinematics->add(COLLADA_ELEMENT_KINEMATICS)); 794 | domKinematics_techniqueRef kt = daeSafeCast(kinematics->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 795 | 796 | _WriteInstance_kinematics_model(kinematics,askid,id); 797 | 798 | for(size_t idof = 0; idof < _ikmout->vaxissids.size(); ++idof) { 799 | string axis_infosid = _ComputeId(str(boost::format("axis_info_inst%d")%idof)); 800 | urdf::JointConstSharedPtr pjoint = _ikmout->kmout->vaxissids.at(idof).pjoint; 801 | BOOST_ASSERT(_mapjointindices[pjoint] == (int)idof); 802 | //int iaxis = _ikmout->kmout->vaxissids.at(idof).iaxis; 803 | 804 | // Kinematics axis info 805 | domKinematics_axis_infoRef kai = daeSafeCast(kt->add(COLLADA_ELEMENT_AXIS_INFO)); 806 | kai->setAxis(str(boost::format("%s/%s")%_ikmout->kmout->kmodel->getID()%_ikmout->kmout->vaxissids.at(idof).sid).c_str()); 807 | kai->setSid(axis_infosid.c_str()); 808 | bool bactive = !pjoint->mimic; 809 | double flower=0, fupper=0; 810 | if( pjoint->type != urdf::Joint::CONTINUOUS ) { 811 | if( !!pjoint->limits ) { 812 | flower = pjoint->limits->lower; 813 | fupper = pjoint->limits->upper; 814 | } 815 | if( !!pjoint->safety ) { 816 | flower = pjoint->safety->soft_lower_limit; 817 | fupper = pjoint->safety->soft_upper_limit; 818 | } 819 | if( flower == fupper ) { 820 | bactive = false; 821 | } 822 | double fmult = 1.0; 823 | if( pjoint->type != urdf::Joint::PRISMATIC ) { 824 | fmult = 180.0/M_PI; 825 | } 826 | domKinematics_limitsRef plimits = daeSafeCast(kai->add(COLLADA_ELEMENT_LIMITS)); 827 | daeSafeCast(plimits->add(COLLADA_ELEMENT_MIN)->add(COLLADA_ELEMENT_FLOAT))->setValue(flower*fmult); 828 | daeSafeCast(plimits->add(COLLADA_ELEMENT_MAX)->add(COLLADA_ELEMENT_FLOAT))->setValue(fupper*fmult); 829 | } 830 | 831 | domCommon_bool_or_paramRef active = daeSafeCast(kai->add(COLLADA_ELEMENT_ACTIVE)); 832 | daeSafeCast(active->add(COLLADA_ELEMENT_BOOL))->setValue(bactive); 833 | domCommon_bool_or_paramRef locked = daeSafeCast(kai->add(COLLADA_ELEMENT_LOCKED)); 834 | daeSafeCast(locked->add(COLLADA_ELEMENT_BOOL))->setValue(false); 835 | 836 | // Motion axis info 837 | domMotion_axis_infoRef mai = daeSafeCast(mt->add(COLLADA_ELEMENT_AXIS_INFO)); 838 | mai->setAxis(str(boost::format("%s/%s")%askid%axis_infosid).c_str()); 839 | if( !!pjoint->limits ) { 840 | domCommon_float_or_paramRef speed = daeSafeCast(mai->add(COLLADA_ELEMENT_SPEED)); 841 | daeSafeCast(speed->add(COLLADA_ELEMENT_FLOAT))->setValue(pjoint->limits->velocity); 842 | domCommon_float_or_paramRef accel = daeSafeCast(mai->add(COLLADA_ELEMENT_ACCELERATION)); 843 | daeSafeCast(accel->add(COLLADA_ELEMENT_FLOAT))->setValue(pjoint->limits->effort); 844 | } 845 | } 846 | 847 | // write the bindings 848 | string asmsym = _ComputeId(str(boost::format("%s_%s")%asmid%_ikmout->ikm->getSid())); 849 | string assym = _ComputeId(str(boost::format("%s_%s")%_scene.kscene->getID()%_ikmout->ikm->getSid())); 850 | FOREACH(it, _ikmout->vkinematicsbindings) { 851 | domKinematics_newparamRef abm = daeSafeCast(ias_motion->add(COLLADA_ELEMENT_NEWPARAM)); 852 | abm->setSid(asmsym.c_str()); 853 | daeSafeCast(abm->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format("%s/%s")%askid%it->first).c_str()); 854 | domKinematics_bindRef ab = daeSafeCast(ias->add(COLLADA_ELEMENT_BIND)); 855 | ab->setSymbol(assym.c_str()); 856 | daeSafeCast(ab->add(COLLADA_ELEMENT_PARAM))->setRef(str(boost::format("%s/%s")%asmid%asmsym).c_str()); 857 | _iasout->vkinematicsbindings.push_back(make_pair(string(ab->getSymbol()), it->second)); 858 | } 859 | for(size_t idof = 0; idof < _ikmout->vaxissids.size(); ++idof) { 860 | const axis_sids& kas = _ikmout->vaxissids.at(idof); 861 | domKinematics_newparamRef abm = daeSafeCast(ias_motion->add(COLLADA_ELEMENT_NEWPARAM)); 862 | abm->setSid(_ComputeId(str(boost::format("%s_%s")%asmid%kas.axissid)).c_str()); 863 | daeSafeCast(abm->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format("%s/%s")%askid%kas.axissid).c_str()); 864 | domKinematics_bindRef ab = daeSafeCast(ias->add(COLLADA_ELEMENT_BIND)); 865 | ab->setSymbol(str(boost::format("%s_%s")%assym%kas.axissid).c_str()); 866 | daeSafeCast(ab->add(COLLADA_ELEMENT_PARAM))->setRef(str(boost::format("%s/%s_%s")%asmid%asmid%kas.axissid).c_str()); 867 | string valuesid; 868 | if( kas.valuesid.size() > 0 ) { 869 | domKinematics_newparamRef abmvalue = daeSafeCast(ias_motion->add(COLLADA_ELEMENT_NEWPARAM)); 870 | abmvalue->setSid(_ComputeId(str(boost::format("%s_%s")%asmid%kas.valuesid)).c_str()); 871 | daeSafeCast(abmvalue->add(COLLADA_ELEMENT_SIDREF))->setValue(str(boost::format("%s/%s")%askid%kas.valuesid).c_str()); 872 | domKinematics_bindRef abvalue = daeSafeCast(ias->add(COLLADA_ELEMENT_BIND)); 873 | valuesid = _ComputeId(str(boost::format("%s_%s")%assym%kas.valuesid)); 874 | abvalue->setSymbol(valuesid.c_str()); 875 | daeSafeCast(abvalue->add(COLLADA_ELEMENT_PARAM))->setRef(str(boost::format("%s/%s_%s")%asmid%asmid%kas.valuesid).c_str()); 876 | } 877 | _iasout->vaxissids.push_back(axis_sids(ab->getSymbol(),valuesid,kas.jointnodesid)); 878 | } 879 | 880 | boost::shared_ptr ipmout = _WriteInstance_physics_model(id,_scene.pscene,_scene.pscene->getID(), _ikmout->kmout->_maplinkposes); 881 | } 882 | 883 | /// \brief Write kinematic body in a given scene 884 | virtual void _WriteInstance_kinematics_model(daeElementRef parent, const string& sidscope, int id) 885 | { 886 | ROS_DEBUG_STREAM(str(boost::format("writing instance_kinematics_model %s\n")%_robot.getName())); 887 | boost::shared_ptr kmout = WriteKinematics_model(id); 888 | 889 | _ikmout.reset(new instance_kinematics_model_output()); 890 | _ikmout->kmout = kmout; 891 | _ikmout->ikm = daeSafeCast(parent->add(COLLADA_ELEMENT_INSTANCE_KINEMATICS_MODEL)); 892 | 893 | string symscope, refscope; 894 | if( sidscope.size() > 0 ) { 895 | symscope = sidscope+string("_"); 896 | refscope = sidscope+string("/"); 897 | } 898 | string ikmsid = _ComputeId(str(boost::format("%s_inst")%kmout->kmodel->getID())); 899 | _ikmout->ikm->setUrl(str(boost::format("#%s")%kmout->kmodel->getID()).c_str()); 900 | _ikmout->ikm->setSid(ikmsid.c_str()); 901 | 902 | domKinematics_newparamRef kbind = daeSafeCast(_ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM)); 903 | kbind->setSid(_ComputeId(symscope+ikmsid).c_str()); 904 | daeSafeCast(kbind->add(COLLADA_ELEMENT_SIDREF))->setValue((refscope+ikmsid).c_str()); 905 | _ikmout->vkinematicsbindings.push_back(make_pair(string(kbind->getSid()), str(boost::format("visual%d/node%d")%id%_maplinkindices[_robot.getRoot()]))); 906 | 907 | _ikmout->vaxissids.reserve(kmout->vaxissids.size()); 908 | int i = 0; 909 | FOREACH(it,kmout->vaxissids) { 910 | domKinematics_newparamRef kbind = daeSafeCast(_ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM)); 911 | string ref = it->sid; 912 | size_t index = ref.find("/"); 913 | while(index != string::npos) { 914 | ref[index] = '.'; 915 | index = ref.find("/",index+1); 916 | } 917 | string sid = _ComputeId(symscope+ikmsid+"_"+ref); 918 | kbind->setSid(sid.c_str()); 919 | daeSafeCast(kbind->add(COLLADA_ELEMENT_SIDREF))->setValue((refscope+ikmsid+"/"+it->sid).c_str()); 920 | double value=0; 921 | double flower=0, fupper=0; 922 | if( !!it->pjoint->limits ) { 923 | flower = it->pjoint->limits->lower; 924 | fupper = it->pjoint->limits->upper; 925 | } 926 | if( flower > 0 || fupper < 0 ) { 927 | value = 0.5*(flower+fupper); 928 | } 929 | domKinematics_newparamRef pvalueparam = daeSafeCast(_ikmout->ikm->add(COLLADA_ELEMENT_NEWPARAM)); 930 | pvalueparam->setSid((sid+string("_value")).c_str()); 931 | daeSafeCast(pvalueparam->add(COLLADA_ELEMENT_FLOAT))->setValue(value); 932 | _ikmout->vaxissids.push_back(axis_sids(sid,pvalueparam->getSid(),kmout->vaxissids.at(i).jointnodesid)); 933 | ++i; 934 | } 935 | } 936 | 937 | virtual boost::shared_ptr WriteKinematics_model(int id) 938 | { 939 | domKinematics_modelRef kmodel = daeSafeCast(_kinematicsModelsLib->add(COLLADA_ELEMENT_KINEMATICS_MODEL)); 940 | string kmodelid = _ComputeKinematics_modelId(id); 941 | kmodel->setId(kmodelid.c_str()); 942 | kmodel->setName(_robot.getName().c_str()); 943 | 944 | domKinematics_model_techniqueRef ktec = daeSafeCast(kmodel->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 945 | 946 | // Create root node for the visual scene 947 | domNodeRef pnoderoot = daeSafeCast(_scene.vscene->add(COLLADA_ELEMENT_NODE)); 948 | string bodyid = _ComputeId(str(boost::format("visual%d")%id)); 949 | pnoderoot->setId(bodyid.c_str()); 950 | pnoderoot->setSid(bodyid.c_str()); 951 | pnoderoot->setName(_robot.getName().c_str()); 952 | 953 | // Declare all the joints 954 | _mapjointindices.clear(); 955 | int index = 0; 956 | FOREACHC(itj, _robot.joints_) { 957 | _mapjointindices[itj->second] = index++; 958 | } 959 | _maplinkindices.clear(); 960 | index = 0; 961 | FOREACHC(itj, _robot.links_) { 962 | _maplinkindices[itj->second] = index++; 963 | } 964 | _mapmaterialindices.clear(); 965 | index = 0; 966 | FOREACHC(itj, _robot.materials_) { 967 | _mapmaterialindices[itj->second] = index++; 968 | } 969 | 970 | double lmin, lmax; 971 | vector vdomjoints(_robot.joints_.size()); 972 | boost::shared_ptr kmout(new kinematics_model_output()); 973 | kmout->kmodel = kmodel; 974 | kmout->vaxissids.resize(_robot.joints_.size()); 975 | kmout->vlinksids.resize(_robot.links_.size()); 976 | 977 | FOREACHC(itjoint, _robot.joints_) { 978 | urdf::JointSharedPtr pjoint = itjoint->second; 979 | int index = _mapjointindices[itjoint->second]; 980 | domJointRef pdomjoint = daeSafeCast(ktec->add(COLLADA_ELEMENT_JOINT)); 981 | string jointid = _ComputeId(pjoint->name); //str(boost::format("joint%d")%index); 982 | pdomjoint->setSid(jointid.c_str() ); 983 | pdomjoint->setName(pjoint->name.c_str()); 984 | domAxis_constraintRef axis; 985 | if( !!pjoint->limits ) { 986 | lmin = pjoint->limits->lower; 987 | lmax = pjoint->limits->upper; 988 | } 989 | else { 990 | lmin = lmax = 0; 991 | } 992 | 993 | double fmult = 1.0; 994 | switch(pjoint->type) { 995 | case urdf::Joint::REVOLUTE: 996 | case urdf::Joint::CONTINUOUS: 997 | axis = daeSafeCast(pdomjoint->add(COLLADA_ELEMENT_REVOLUTE)); 998 | fmult = 180.0f/M_PI; 999 | lmin *= fmult; 1000 | lmax *= fmult; 1001 | break; 1002 | case urdf::Joint::PRISMATIC: 1003 | axis = daeSafeCast(pdomjoint->add(COLLADA_ELEMENT_PRISMATIC)); 1004 | break; 1005 | case urdf::Joint::FIXED: 1006 | axis = daeSafeCast(pdomjoint->add(COLLADA_ELEMENT_REVOLUTE)); 1007 | lmin = 0; 1008 | lmax = 0; 1009 | fmult = 0; 1010 | break; 1011 | default: 1012 | ROS_WARN_STREAM(str(boost::format("unsupported joint type specified %d")%(int)pjoint->type)); 1013 | break; 1014 | } 1015 | 1016 | if( !axis ) { 1017 | continue; 1018 | } 1019 | 1020 | int ia = 0; 1021 | string axisid = _ComputeId(str(boost::format("axis%d")%ia)); 1022 | axis->setSid(axisid.c_str()); 1023 | kmout->vaxissids.at(index).pjoint = pjoint; 1024 | kmout->vaxissids.at(index).sid = jointid+string("/")+axisid; 1025 | kmout->vaxissids.at(index).iaxis = ia; 1026 | domAxisRef paxis = daeSafeCast(axis->add(COLLADA_ELEMENT_AXIS)); 1027 | paxis->getValue().setCount(3); 1028 | paxis->getValue()[0] = pjoint->axis.x; 1029 | paxis->getValue()[1] = pjoint->axis.y; 1030 | paxis->getValue()[2] = pjoint->axis.z; 1031 | if( pjoint->type != urdf::Joint::CONTINUOUS ) { 1032 | domJoint_limitsRef plimits = daeSafeCast(axis->add(COLLADA_TYPE_LIMITS)); 1033 | daeSafeCast(plimits->add(COLLADA_ELEMENT_MIN))->getValue() = lmin; 1034 | daeSafeCast(plimits->add(COLLADA_ELEMENT_MAX))->getValue() = lmax; 1035 | } 1036 | vdomjoints.at(index) = pdomjoint; 1037 | } 1038 | 1039 | LINKOUTPUT childinfo = _WriteLink(_robot.getRoot(), ktec, pnoderoot, kmodel->getID()); 1040 | FOREACHC(itused, childinfo.listusedlinks) { 1041 | kmout->vlinksids.at(itused->first) = itused->second; 1042 | } 1043 | FOREACH(itprocessed,childinfo.listprocesseddofs) { 1044 | kmout->vaxissids.at(itprocessed->first).jointnodesid = itprocessed->second; 1045 | } 1046 | kmout->_maplinkposes = childinfo._maplinkposes; 1047 | 1048 | // create the formulas for all mimic joints 1049 | FOREACHC(itjoint, _robot.joints_) { 1050 | string jointsid = _ComputeId(itjoint->second->name); 1051 | urdf::JointSharedPtr pjoint = itjoint->second; 1052 | if( !pjoint->mimic ) { 1053 | continue; 1054 | } 1055 | 1056 | domFormulaRef pf = daeSafeCast(ktec->add(COLLADA_ELEMENT_FORMULA)); 1057 | string formulaid = _ComputeId(str(boost::format("%s_formula")%jointsid)); 1058 | pf->setSid(formulaid.c_str()); 1059 | domCommon_float_or_paramRef ptarget = daeSafeCast(pf->add(COLLADA_ELEMENT_TARGET)); 1060 | string targetjointid = str(boost::format("%s/%s")%kmodel->getID()%jointsid); 1061 | daeSafeCast(ptarget->add(COLLADA_TYPE_PARAM))->setValue(targetjointid.c_str()); 1062 | 1063 | domTechniqueRef pftec = daeSafeCast(pf->add(COLLADA_ELEMENT_TECHNIQUE)); 1064 | pftec->setProfile("OpenRAVE"); 1065 | // save position equation 1066 | { 1067 | daeElementRef poselt = pftec->add("equation"); 1068 | poselt->setAttribute("type","position"); 1069 | // create a const0*joint+const1 formula 1070 | // a x b 1071 | daeElementRef pmath_math = poselt->add("math"); 1072 | daeElementRef pmath_apply = pmath_math->add("apply"); 1073 | { 1074 | daeElementRef pmath_plus = pmath_apply->add("plus"); 1075 | daeElementRef pmath_apply1 = pmath_apply->add("apply"); 1076 | { 1077 | daeElementRef pmath_times = pmath_apply1->add("times"); 1078 | daeElementRef pmath_const0 = pmath_apply1->add("cn"); 1079 | pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier)); 1080 | daeElementRef pmath_symb = pmath_apply1->add("csymbol"); 1081 | pmath_symb->setAttribute("encoding","COLLADA"); 1082 | pmath_symb->setCharData(str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name))); 1083 | } 1084 | daeElementRef pmath_const1 = pmath_apply->add("cn"); 1085 | pmath_const1->setCharData(str(boost::format("%f")%pjoint->mimic->offset)); 1086 | } 1087 | } 1088 | // save first partial derivative 1089 | { 1090 | daeElementRef derivelt = pftec->add("equation"); 1091 | derivelt->setAttribute("type","first_partial"); 1092 | derivelt->setAttribute("target",str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name)).c_str()); 1093 | daeElementRef pmath_const0 = derivelt->add("cn"); 1094 | pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier)); 1095 | } 1096 | // save second partial derivative 1097 | { 1098 | daeElementRef derivelt = pftec->add("equation"); 1099 | derivelt->setAttribute("type","second_partial"); 1100 | derivelt->setAttribute("target",str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name)).c_str()); 1101 | daeElementRef pmath_const0 = derivelt->add("cn"); 1102 | pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier)); 1103 | } 1104 | 1105 | { 1106 | domFormula_techniqueRef pfcommontec = daeSafeCast(pf->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 1107 | // create a const0*joint+const1 formula 1108 | // a x b 1109 | daeElementRef pmath_math = pfcommontec->add("math"); 1110 | daeElementRef pmath_apply = pmath_math->add("apply"); 1111 | { 1112 | daeElementRef pmath_plus = pmath_apply->add("plus"); 1113 | daeElementRef pmath_apply1 = pmath_apply->add("apply"); 1114 | { 1115 | daeElementRef pmath_times = pmath_apply1->add("times"); 1116 | daeElementRef pmath_const0 = pmath_apply1->add("cn"); 1117 | pmath_const0->setCharData(str(boost::format("%f")%pjoint->mimic->multiplier)); 1118 | daeElementRef pmath_symb = pmath_apply1->add("csymbol"); 1119 | pmath_symb->setAttribute("encoding","COLLADA"); 1120 | pmath_symb->setCharData(str(boost::format("%s/%s")%kmodel->getID()%_ComputeId(pjoint->mimic->joint_name))); 1121 | } 1122 | daeElementRef pmath_const1 = pmath_apply->add("cn"); 1123 | pmath_const1->setCharData(str(boost::format("%f")%pjoint->mimic->offset)); 1124 | } 1125 | } 1126 | } 1127 | 1128 | return kmout; 1129 | } 1130 | 1131 | /// \brief Write link of a kinematic body 1132 | /// 1133 | /// \param link Link to write 1134 | /// \param pkinparent Kinbody parent 1135 | /// \param pnodeparent Node parent 1136 | /// \param strModelUri 1137 | virtual LINKOUTPUT _WriteLink(urdf::LinkConstSharedPtr plink, daeElementRef pkinparent, domNodeRef pnodeparent, const string& strModelUri) 1138 | { 1139 | LINKOUTPUT out; 1140 | int linkindex = _maplinkindices[plink]; 1141 | string linksid = _ComputeId(plink->name); 1142 | domLinkRef pdomlink = daeSafeCast(pkinparent->add(COLLADA_ELEMENT_LINK)); 1143 | pdomlink->setName(plink->name.c_str()); 1144 | pdomlink->setSid(linksid.c_str()); 1145 | 1146 | domNodeRef pnode = daeSafeCast(pnodeparent->add(COLLADA_ELEMENT_NODE)); 1147 | string nodeid = _ComputeId(str(boost::format("v%s_node%d")%strModelUri%linkindex)); 1148 | pnode->setId( nodeid.c_str() ); 1149 | string nodesid = _ComputeId(str(boost::format("node%d")%linkindex)); 1150 | pnode->setSid(nodesid.c_str()); 1151 | pnode->setName(plink->name.c_str()); 1152 | 1153 | urdf::GeometrySharedPtr geometry; 1154 | urdf::MaterialSharedPtr material; 1155 | urdf::Pose geometry_origin; 1156 | if( !!plink->visual ) { 1157 | geometry = plink->visual->geometry; 1158 | material = plink->visual->material; 1159 | geometry_origin = plink->visual->origin; 1160 | } 1161 | else if( !!plink->collision ) { 1162 | geometry = plink->collision->geometry; 1163 | geometry_origin = plink->collision->origin; 1164 | } 1165 | 1166 | urdf::Pose geometry_origin_inv = _poseInverse(geometry_origin); 1167 | 1168 | if( !!geometry ) { 1169 | bool write_visual = false; 1170 | if ( !!plink->visual ) { 1171 | if (plink->visual_array.size() > 1) { 1172 | int igeom = 0; 1173 | for (std::vector::const_iterator it = plink->visual_array.begin(); 1174 | it != plink->visual_array.end(); it++) { 1175 | // geom 1176 | string geomid = _ComputeId(str(boost::format("g%s_%s_geom%d")%strModelUri%linksid%igeom)); 1177 | igeom++; 1178 | domGeometryRef pdomgeom; 1179 | if ( it != plink->visual_array.begin() ) { 1180 | urdf::Pose org_trans = _poseMult(geometry_origin_inv, (*it)->origin); 1181 | pdomgeom = _WriteGeometry((*it)->geometry, geomid, &org_trans); 1182 | } 1183 | else { 1184 | pdomgeom = _WriteGeometry((*it)->geometry, geomid); 1185 | } 1186 | domInstance_geometryRef pinstgeom = daeSafeCast(pnode->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY)); 1187 | pinstgeom->setUrl((string("#") + geomid).c_str()); 1188 | // material 1189 | _WriteMaterial(pdomgeom->getID(), (*it)->material); 1190 | domBind_materialRef pmat = daeSafeCast(pinstgeom->add(COLLADA_ELEMENT_BIND_MATERIAL)); 1191 | domBind_material::domTechnique_commonRef pmattec = daeSafeCast(pmat->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 1192 | domInstance_materialRef pinstmat = daeSafeCast(pmattec->add(COLLADA_ELEMENT_INSTANCE_MATERIAL)); 1193 | pinstmat->setTarget(xsAnyURI(*pdomgeom, string("#")+geomid+string("_mat"))); 1194 | pinstmat->setSymbol("mat0"); 1195 | write_visual = true; 1196 | } 1197 | } 1198 | } 1199 | if (!write_visual) { 1200 | // just 1 visual 1201 | int igeom = 0; 1202 | string geomid = _ComputeId(str(boost::format("g%s_%s_geom%d")%strModelUri%linksid%igeom)); 1203 | domGeometryRef pdomgeom = _WriteGeometry(geometry, geomid); 1204 | domInstance_geometryRef pinstgeom = daeSafeCast(pnode->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY)); 1205 | pinstgeom->setUrl((string("#")+geomid).c_str()); 1206 | 1207 | // material 1208 | _WriteMaterial(pdomgeom->getID(), material); 1209 | domBind_materialRef pmat = daeSafeCast(pinstgeom->add(COLLADA_ELEMENT_BIND_MATERIAL)); 1210 | domBind_material::domTechnique_commonRef pmattec = daeSafeCast(pmat->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 1211 | domInstance_materialRef pinstmat = daeSafeCast(pmattec->add(COLLADA_ELEMENT_INSTANCE_MATERIAL)); 1212 | pinstmat->setTarget(xsAnyURI(*pdomgeom, string("#")+geomid+string("_mat"))); 1213 | pinstmat->setSymbol("mat0"); 1214 | } 1215 | } 1216 | 1217 | _WriteTransformation(pnode, geometry_origin); 1218 | 1219 | // process all children 1220 | FOREACHC(itjoint, plink->child_joints) { 1221 | urdf::JointSharedPtr pjoint = *itjoint; 1222 | int index = _mapjointindices[pjoint]; 1223 | 1224 | // 1225 | domLink::domAttachment_fullRef attachment_full = daeSafeCast(pdomlink->add(COLLADA_ELEMENT_ATTACHMENT_FULL)); 1226 | string jointid = str(boost::format("%s/%s")%strModelUri%_ComputeId(pjoint->name)); 1227 | attachment_full->setJoint(jointid.c_str()); 1228 | 1229 | LINKOUTPUT childinfo = _WriteLink(_robot.getLink(pjoint->child_link_name), attachment_full, pnode, strModelUri); 1230 | FOREACH(itused,childinfo.listusedlinks) { 1231 | out.listusedlinks.push_back(make_pair(itused->first,linksid+string("/")+itused->second)); 1232 | } 1233 | FOREACH(itprocessed,childinfo.listprocesseddofs) { 1234 | out.listprocesseddofs.push_back(make_pair(itprocessed->first,nodesid+string("/")+itprocessed->second)); 1235 | } 1236 | FOREACH(itlinkpos,childinfo._maplinkposes) { 1237 | out._maplinkposes[itlinkpos->first] = _poseMult(pjoint->parent_to_joint_origin_transform,itlinkpos->second); 1238 | } 1239 | // rotate/translate elements 1240 | string jointnodesid = _ComputeId(str(boost::format("node_%s_axis0")%pjoint->name)); 1241 | switch(pjoint->type) { 1242 | case urdf::Joint::REVOLUTE: 1243 | case urdf::Joint::CONTINUOUS: 1244 | case urdf::Joint::FIXED: { 1245 | domRotateRef protate = daeSafeCast(childinfo.pnode->add(COLLADA_ELEMENT_ROTATE,0)); 1246 | protate->setSid(jointnodesid.c_str()); 1247 | protate->getValue().setCount(4); 1248 | protate->getValue()[0] = pjoint->axis.x; 1249 | protate->getValue()[1] = pjoint->axis.y; 1250 | protate->getValue()[2] = pjoint->axis.z; 1251 | protate->getValue()[3] = 0; 1252 | break; 1253 | } 1254 | case urdf::Joint::PRISMATIC: { 1255 | domTranslateRef ptrans = daeSafeCast(childinfo.pnode->add(COLLADA_ELEMENT_TRANSLATE,0)); 1256 | ptrans->setSid(jointnodesid.c_str()); 1257 | ptrans->getValue().setCount(3); 1258 | ptrans->getValue()[0] = 0; 1259 | ptrans->getValue()[1] = 0; 1260 | ptrans->getValue()[2] = 0; 1261 | break; 1262 | } 1263 | default: 1264 | ROS_WARN_STREAM(str(boost::format("unsupported joint type specified %d")%(int)pjoint->type)); 1265 | break; 1266 | } 1267 | 1268 | _WriteTransformation(attachment_full, pjoint->parent_to_joint_origin_transform); 1269 | _WriteTransformation(childinfo.pnode, pjoint->parent_to_joint_origin_transform); 1270 | _WriteTransformation(childinfo.pnode, geometry_origin_inv); // have to do multiply by inverse since geometry transformation is not part of hierarchy 1271 | out.listprocesseddofs.push_back(make_pair(index,string(childinfo.pnode->getSid())+string("/")+jointnodesid)); 1272 | // 1273 | } 1274 | 1275 | out._maplinkposes[plink] = urdf::Pose(); 1276 | out.listusedlinks.push_back(make_pair(linkindex,linksid)); 1277 | out.plink = pdomlink; 1278 | out.pnode = pnode; 1279 | return out; 1280 | } 1281 | 1282 | domGeometryRef _WriteGeometry(urdf::GeometrySharedPtr geometry, const std::string& geometry_id, urdf::Pose *org_trans = NULL) 1283 | { 1284 | domGeometryRef cgeometry = daeSafeCast(_geometriesLib->add(COLLADA_ELEMENT_GEOMETRY)); 1285 | cgeometry->setId(geometry_id.c_str()); 1286 | switch (geometry->type) { 1287 | case urdf::Geometry::MESH: { 1288 | urdf::Mesh* urdf_mesh = (urdf::Mesh*) geometry.get(); 1289 | cgeometry->setName(urdf_mesh->filename.c_str()); 1290 | _loadMesh(urdf_mesh->filename, cgeometry, urdf_mesh->scale, org_trans); 1291 | break; 1292 | } 1293 | case urdf::Geometry::SPHERE: { 1294 | shapes::Sphere sphere(static_cast(geometry.get())->radius); 1295 | boost::scoped_ptr mesh(shapes::createMeshFromShape(sphere)); 1296 | _loadVertices(mesh.get(), cgeometry); 1297 | break; 1298 | } 1299 | case urdf::Geometry::BOX: { 1300 | shapes::Box box(static_cast(geometry.get())->dim.x, 1301 | static_cast(geometry.get())->dim.y, 1302 | static_cast(geometry.get())->dim.z); 1303 | boost::scoped_ptr mesh(shapes::createMeshFromShape(box)); 1304 | _loadVertices(mesh.get(), cgeometry); 1305 | break; 1306 | } 1307 | case urdf::Geometry::CYLINDER: { 1308 | shapes::Cylinder cyl(static_cast(geometry.get())->radius, 1309 | static_cast(geometry.get())->length); 1310 | boost::scoped_ptr mesh(shapes::createMeshFromShape(cyl)); 1311 | _loadVertices(mesh.get(), cgeometry); 1312 | break; 1313 | } 1314 | default: { 1315 | throw ColladaUrdfException(str(boost::format("undefined geometry type %d, name %s")%(int)geometry->type%geometry_id)); 1316 | } 1317 | } 1318 | return cgeometry; 1319 | } 1320 | 1321 | void _WriteMaterial(const string& geometry_id, urdf::MaterialSharedPtr material) 1322 | { 1323 | string effid = geometry_id+string("_eff"); 1324 | string matid = geometry_id+string("_mat"); 1325 | domMaterialRef pdommat = daeSafeCast(_materialsLib->add(COLLADA_ELEMENT_MATERIAL)); 1326 | pdommat->setId(matid.c_str()); 1327 | domInstance_effectRef pdominsteff = daeSafeCast(pdommat->add(COLLADA_ELEMENT_INSTANCE_EFFECT)); 1328 | pdominsteff->setUrl((string("#")+effid).c_str()); 1329 | 1330 | urdf::Color ambient, diffuse; 1331 | ambient.init("0.1 0.1 0.1 0"); 1332 | diffuse.init("1 1 1 0"); 1333 | 1334 | if( !!material ) { 1335 | ambient.r = diffuse.r = material->color.r; 1336 | ambient.g = diffuse.g = material->color.g; 1337 | ambient.b = diffuse.b = material->color.b; 1338 | ambient.a = diffuse.a = material->color.a; 1339 | } 1340 | 1341 | domEffectRef effect = _WriteEffect(geometry_id, ambient, diffuse); 1342 | 1343 | // 1344 | domMaterialRef dommaterial = daeSafeCast(_materialsLib->add(COLLADA_ELEMENT_MATERIAL)); 1345 | string material_id = geometry_id + string("_mat"); 1346 | dommaterial->setId(material_id.c_str()); 1347 | { 1348 | // 1349 | domInstance_effectRef instance_effect = daeSafeCast(dommaterial->add(COLLADA_ELEMENT_INSTANCE_EFFECT)); 1350 | string effect_id(effect->getId()); 1351 | instance_effect->setUrl((string("#") + effect_id).c_str()); 1352 | } 1353 | // 1354 | 1355 | domEffectRef pdomeff = _WriteEffect(effid, ambient, diffuse); 1356 | } 1357 | 1358 | boost::shared_ptr _WriteInstance_physics_model(int id, daeElementRef parent, const string& sidscope, const MAPLINKPOSES& maplinkposes) 1359 | { 1360 | boost::shared_ptr pmout = WritePhysics_model(id, maplinkposes); 1361 | boost::shared_ptr ipmout(new instance_physics_model_output()); 1362 | ipmout->pmout = pmout; 1363 | ipmout->ipm = daeSafeCast(parent->add(COLLADA_ELEMENT_INSTANCE_PHYSICS_MODEL)); 1364 | string bodyid = _ComputeId(str(boost::format("visual%d")%id)); 1365 | ipmout->ipm->setParent(xsAnyURI(*ipmout->ipm,string("#")+bodyid)); 1366 | string symscope, refscope; 1367 | if( sidscope.size() > 0 ) { 1368 | symscope = sidscope+string("_"); 1369 | refscope = sidscope+string("/"); 1370 | } 1371 | string ipmsid = str(boost::format("%s_inst")%pmout->pmodel->getID()); 1372 | ipmout->ipm->setUrl(str(boost::format("#%s")%pmout->pmodel->getID()).c_str()); 1373 | ipmout->ipm->setSid(ipmsid.c_str()); 1374 | 1375 | string kmodelid = _ComputeKinematics_modelId(id); 1376 | for(size_t i = 0; i < pmout->vrigidbodysids.size(); ++i) { 1377 | domInstance_rigid_bodyRef pirb = daeSafeCast(ipmout->ipm->add(COLLADA_ELEMENT_INSTANCE_RIGID_BODY)); 1378 | pirb->setBody(pmout->vrigidbodysids[i].c_str()); 1379 | pirb->setTarget(xsAnyURI(*pirb,str(boost::format("#v%s_node%d")%kmodelid%i))); 1380 | } 1381 | 1382 | return ipmout; 1383 | } 1384 | 1385 | boost::shared_ptr WritePhysics_model(int id, const MAPLINKPOSES& maplinkposes) 1386 | { 1387 | boost::shared_ptr pmout(new physics_model_output()); 1388 | pmout->pmodel = daeSafeCast(_physicsModelsLib->add(COLLADA_ELEMENT_PHYSICS_MODEL)); 1389 | string pmodelid = str(boost::format("pmodel%d")%id); 1390 | pmout->pmodel->setId(pmodelid.c_str()); 1391 | pmout->pmodel->setName(_robot.getName().c_str()); 1392 | FOREACHC(itlink,_robot.links_) { 1393 | domRigid_bodyRef rigid_body = daeSafeCast(pmout->pmodel->add(COLLADA_ELEMENT_RIGID_BODY)); 1394 | string rigidsid = str(boost::format("rigid%d")%_maplinkindices[itlink->second]); 1395 | pmout->vrigidbodysids.push_back(rigidsid); 1396 | rigid_body->setSid(rigidsid.c_str()); 1397 | rigid_body->setName(itlink->second->name.c_str()); 1398 | domRigid_body::domTechnique_commonRef ptec = daeSafeCast(rigid_body->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 1399 | urdf::InertialSharedPtr inertial = itlink->second->inertial; 1400 | if( !!inertial ) { 1401 | daeSafeCast(ptec->add(COLLADA_ELEMENT_DYNAMIC))->setValue(xsBoolean(true)); //!!inertial)); 1402 | domTargetable_floatRef mass = daeSafeCast(ptec->add(COLLADA_ELEMENT_MASS)); 1403 | mass->setValue(inertial->mass); 1404 | double fCovariance[9] = { inertial->ixx, inertial->ixy, inertial->ixz, inertial->ixy, inertial->iyy, inertial->iyz, inertial->ixz, inertial->iyz, inertial->izz}; 1405 | double eigenvalues[3], eigenvectors[9]; 1406 | mathextra::EigenSymmetric3(fCovariance,eigenvalues,eigenvectors); 1407 | boost::array minertiaframe; 1408 | for(int j = 0; j < 3; ++j) { 1409 | minertiaframe[4*0+j] = eigenvectors[3*j]; 1410 | minertiaframe[4*1+j] = eigenvectors[3*j+1]; 1411 | minertiaframe[4*2+j] = eigenvectors[3*j+2]; 1412 | } 1413 | urdf::Pose tinertiaframe; 1414 | tinertiaframe.rotation = _quatFromMatrix(minertiaframe); 1415 | tinertiaframe = _poseMult(inertial->origin,tinertiaframe); 1416 | 1417 | domTargetable_float3Ref pinertia = daeSafeCast(ptec->add(COLLADA_ELEMENT_INERTIA)); 1418 | pinertia->getValue().setCount(3); 1419 | pinertia->getValue()[0] = eigenvalues[0]; 1420 | pinertia->getValue()[1] = eigenvalues[1]; 1421 | pinertia->getValue()[2] = eigenvalues[2]; 1422 | urdf::Pose posemassframe = _poseMult(maplinkposes.find(itlink->second)->second,tinertiaframe); 1423 | _WriteTransformation(ptec->add(COLLADA_ELEMENT_MASS_FRAME), posemassframe); 1424 | 1425 | // // create a shape for every geometry 1426 | // int igeom = 0; 1427 | // FOREACHC(itgeom, (*itlink)->GetGeometries()) { 1428 | // domRigid_body::domTechnique_common::domShapeRef pdomshape = daeSafeCast(ptec->add(COLLADA_ELEMENT_SHAPE)); 1429 | // // there is a weird bug here where _WriteTranformation will fail to create rotate/translate elements in instance_geometry is created first... (is this part of the spec?) 1430 | // _WriteTransformation(pdomshape,tbaseinv*(*itlink)->GetTransform()*itgeom->GetTransform()); 1431 | // domInstance_geometryRef pinstgeom = daeSafeCast(pdomshape->add(COLLADA_ELEMENT_INSTANCE_GEOMETRY)); 1432 | // pinstgeom->setUrl(xsAnyURI(*pinstgeom,string("#")+_GetGeometryId(*itlink,igeom))); 1433 | // ++igeom; 1434 | // } 1435 | } 1436 | } 1437 | return pmout; 1438 | } 1439 | 1440 | void _loadVertices(const shapes::Mesh *mesh, domGeometryRef pdomgeom) { 1441 | 1442 | // convert the mesh into an STL binary (in memory) 1443 | std::vector buffer; 1444 | shapes::writeSTLBinary(mesh, buffer); 1445 | 1446 | // Create an instance of the Importer class 1447 | Assimp::Importer importer; 1448 | 1449 | // And have it read the given file with some postprocessing 1450 | const aiScene* scene = importer.ReadFileFromMemory(reinterpret_cast(&buffer[0]), buffer.size(), 1451 | aiProcess_Triangulate | 1452 | aiProcess_JoinIdenticalVertices | 1453 | aiProcess_SortByPType | 1454 | aiProcess_OptimizeGraph | 1455 | aiProcess_OptimizeMeshes, "stl"); 1456 | 1457 | // Note: we do this mesh -> STL -> assimp mesh because the aiScene::aiScene symbol is hidden by default 1458 | 1459 | domMeshRef pdommesh = daeSafeCast(pdomgeom->add(COLLADA_ELEMENT_MESH)); 1460 | domSourceRef pvertsource = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_SOURCE)); 1461 | domAccessorRef pacc; 1462 | domFloat_arrayRef parray; 1463 | { 1464 | pvertsource->setId(str(boost::format("%s_positions")%pdomgeom->getID()).c_str()); 1465 | 1466 | parray = daeSafeCast(pvertsource->add(COLLADA_ELEMENT_FLOAT_ARRAY)); 1467 | parray->setId(str(boost::format("%s_positions-array")%pdomgeom->getID()).c_str()); 1468 | parray->setDigits(6); // 6 decimal places 1469 | 1470 | domSource::domTechnique_commonRef psourcetec = daeSafeCast(pvertsource->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 1471 | pacc = daeSafeCast(psourcetec->add(COLLADA_ELEMENT_ACCESSOR)); 1472 | pacc->setSource(xsAnyURI(*parray, std::string("#")+string(parray->getID()))); 1473 | pacc->setStride(3); 1474 | 1475 | domParamRef px = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); 1476 | px->setName("X"); px->setType("float"); 1477 | domParamRef py = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); 1478 | py->setName("Y"); py->setType("float"); 1479 | domParamRef pz = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); 1480 | pz->setName("Z"); pz->setType("float"); 1481 | } 1482 | domVerticesRef pverts = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_VERTICES)); 1483 | { 1484 | pverts->setId("vertices"); 1485 | domInput_localRef pvertinput = daeSafeCast(pverts->add(COLLADA_ELEMENT_INPUT)); 1486 | pvertinput->setSemantic("POSITION"); 1487 | pvertinput->setSource(domUrifragment(*pvertsource, std::string("#")+std::string(pvertsource->getID()))); 1488 | } 1489 | _buildAiMesh(scene,scene->mRootNode,pdommesh,parray, pdomgeom->getID(), urdf::Vector3(1,1,1)); 1490 | pacc->setCount(parray->getCount()); 1491 | } 1492 | 1493 | void _loadMesh(std::string const& filename, domGeometryRef pdomgeom, const urdf::Vector3& scale, urdf::Pose *org_trans) 1494 | { 1495 | const aiScene* scene = _importer.ReadFile(filename, aiProcess_SortByPType|aiProcess_Triangulate); //|aiProcess_GenNormals|aiProcess_GenUVCoords|aiProcess_FlipUVs); 1496 | if( !scene ) { 1497 | ROS_WARN("failed to load resource %s",filename.c_str()); 1498 | return; 1499 | } 1500 | if( !scene->mRootNode ) { 1501 | ROS_WARN("resource %s has no data",filename.c_str()); 1502 | return; 1503 | } 1504 | if (!scene->HasMeshes()) { 1505 | ROS_WARN_STREAM(str(boost::format("No meshes found in file %s")%filename)); 1506 | return; 1507 | } 1508 | domMeshRef pdommesh = daeSafeCast(pdomgeom->add(COLLADA_ELEMENT_MESH)); 1509 | domSourceRef pvertsource = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_SOURCE)); 1510 | domAccessorRef pacc; 1511 | domFloat_arrayRef parray; 1512 | { 1513 | pvertsource->setId(str(boost::format("%s_positions")%pdomgeom->getID()).c_str()); 1514 | 1515 | parray = daeSafeCast(pvertsource->add(COLLADA_ELEMENT_FLOAT_ARRAY)); 1516 | parray->setId(str(boost::format("%s_positions-array")%pdomgeom->getID()).c_str()); 1517 | parray->setDigits(6); // 6 decimal places 1518 | 1519 | domSource::domTechnique_commonRef psourcetec = daeSafeCast(pvertsource->add(COLLADA_ELEMENT_TECHNIQUE_COMMON)); 1520 | pacc = daeSafeCast(psourcetec->add(COLLADA_ELEMENT_ACCESSOR)); 1521 | pacc->setSource(xsAnyURI(*parray, string("#")+string(parray->getID()))); 1522 | pacc->setStride(3); 1523 | 1524 | domParamRef px = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); 1525 | px->setName("X"); px->setType("float"); 1526 | domParamRef py = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); 1527 | py->setName("Y"); py->setType("float"); 1528 | domParamRef pz = daeSafeCast(pacc->add(COLLADA_ELEMENT_PARAM)); 1529 | pz->setName("Z"); pz->setType("float"); 1530 | } 1531 | domVerticesRef pverts = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_VERTICES)); 1532 | { 1533 | pverts->setId("vertices"); 1534 | domInput_localRef pvertinput = daeSafeCast(pverts->add(COLLADA_ELEMENT_INPUT)); 1535 | pvertinput->setSemantic("POSITION"); 1536 | pvertinput->setSource(domUrifragment(*pvertsource, string("#")+string(pvertsource->getID()))); 1537 | } 1538 | _buildAiMesh(scene,scene->mRootNode,pdommesh,parray, pdomgeom->getID(),scale,org_trans); 1539 | pacc->setCount(parray->getCount()); 1540 | } 1541 | 1542 | void _buildAiMesh(const aiScene* scene, aiNode* node, domMeshRef pdommesh, domFloat_arrayRef parray, const string& geomid, const urdf::Vector3& scale, urdf::Pose *org_trans = NULL) 1543 | { 1544 | if( !node ) { 1545 | return; 1546 | } 1547 | aiMatrix4x4 transform = node->mTransformation; 1548 | aiNode *pnode = node->mParent; 1549 | while (pnode) { 1550 | // Don't convert to y-up orientation, which is what the root node in 1551 | // Assimp does 1552 | if (pnode->mParent != NULL) { 1553 | transform = pnode->mTransformation * transform; 1554 | } 1555 | pnode = pnode->mParent; 1556 | } 1557 | 1558 | { 1559 | uint32_t vertexOffset = parray->getCount(); 1560 | uint32_t nTotalVertices=0; 1561 | for (uint32_t i = 0; i < node->mNumMeshes; i++) { 1562 | aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]]; 1563 | nTotalVertices += input_mesh->mNumVertices; 1564 | } 1565 | 1566 | parray->getValue().grow(parray->getCount()+nTotalVertices*3); 1567 | parray->setCount(parray->getCount()+nTotalVertices); 1568 | 1569 | for (uint32_t i = 0; i < node->mNumMeshes; i++) { 1570 | aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]]; 1571 | for (uint32_t j = 0; j < input_mesh->mNumVertices; j++) { 1572 | aiVector3D p = input_mesh->mVertices[j]; 1573 | p *= transform; 1574 | if (org_trans) { 1575 | urdf::Vector3 vv; 1576 | vv.x = p.x*scale.x; 1577 | vv.y = p.y*scale.y; 1578 | vv.z = p.z*scale.z; 1579 | urdf::Vector3 nv = _poseMult(*org_trans, vv); 1580 | parray->getValue().append(nv.x); 1581 | parray->getValue().append(nv.y); 1582 | parray->getValue().append(nv.z); 1583 | } 1584 | else { 1585 | parray->getValue().append(p.x*scale.x); 1586 | parray->getValue().append(p.y*scale.y); 1587 | parray->getValue().append(p.z*scale.z); 1588 | } 1589 | } 1590 | } 1591 | 1592 | // in order to save space, separate triangles from poly lists 1593 | 1594 | vector triangleindices, otherindices; 1595 | int nNumOtherPrimitives = 0; 1596 | for (uint32_t i = 0; i < node->mNumMeshes; i++) { 1597 | aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]]; 1598 | uint32_t indexCount = 0, otherIndexCount = 0; 1599 | for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) { 1600 | aiFace& face = input_mesh->mFaces[j]; 1601 | if( face.mNumIndices == 3 ) { 1602 | indexCount += face.mNumIndices; 1603 | } 1604 | else { 1605 | otherIndexCount += face.mNumIndices; 1606 | } 1607 | } 1608 | triangleindices.reserve(triangleindices.size()+indexCount); 1609 | otherindices.reserve(otherindices.size()+otherIndexCount); 1610 | for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) { 1611 | aiFace& face = input_mesh->mFaces[j]; 1612 | if( face.mNumIndices == 3 ) { 1613 | triangleindices.push_back(vertexOffset+face.mIndices[0]); 1614 | triangleindices.push_back(vertexOffset+face.mIndices[1]); 1615 | triangleindices.push_back(vertexOffset+face.mIndices[2]); 1616 | } 1617 | else { 1618 | for (uint32_t k = 0; k < face.mNumIndices; ++k) { 1619 | otherindices.push_back(face.mIndices[k]+vertexOffset); 1620 | } 1621 | nNumOtherPrimitives++; 1622 | } 1623 | } 1624 | vertexOffset += input_mesh->mNumVertices; 1625 | } 1626 | 1627 | if( triangleindices.size() > 0 ) { 1628 | domTrianglesRef ptris = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_TRIANGLES)); 1629 | ptris->setCount(triangleindices.size()/3); 1630 | ptris->setMaterial("mat0"); 1631 | domInput_local_offsetRef pvertoffset = daeSafeCast(ptris->add(COLLADA_ELEMENT_INPUT)); 1632 | pvertoffset->setSemantic("VERTEX"); 1633 | pvertoffset->setOffset(0); 1634 | pvertoffset->setSource(domUrifragment(*pdommesh->getVertices(), str(boost::format("#%s/vertices")%geomid))); 1635 | domPRef pindices = daeSafeCast(ptris->add(COLLADA_ELEMENT_P)); 1636 | pindices->getValue().setCount(triangleindices.size()); 1637 | for(size_t ind = 0; ind < triangleindices.size(); ++ind) { 1638 | pindices->getValue()[ind] = triangleindices[ind]; 1639 | } 1640 | } 1641 | 1642 | if( nNumOtherPrimitives > 0 ) { 1643 | domPolylistRef ptris = daeSafeCast(pdommesh->add(COLLADA_ELEMENT_POLYLIST)); 1644 | ptris->setCount(nNumOtherPrimitives); 1645 | ptris->setMaterial("mat0"); 1646 | domInput_local_offsetRef pvertoffset = daeSafeCast(ptris->add(COLLADA_ELEMENT_INPUT)); 1647 | pvertoffset->setSemantic("VERTEX"); 1648 | pvertoffset->setSource(domUrifragment(*pdommesh->getVertices(), str(boost::format("#%s/vertices")%geomid))); 1649 | domPRef pindices = daeSafeCast(ptris->add(COLLADA_ELEMENT_P)); 1650 | pindices->getValue().setCount(otherindices.size()); 1651 | for(size_t ind = 0; ind < otherindices.size(); ++ind) { 1652 | pindices->getValue()[ind] = otherindices[ind]; 1653 | } 1654 | 1655 | domPolylist::domVcountRef pcount = daeSafeCast(ptris->add(COLLADA_ELEMENT_VCOUNT)); 1656 | pcount->getValue().setCount(nNumOtherPrimitives); 1657 | uint32_t offset = 0; 1658 | for (uint32_t i = 0; i < node->mNumMeshes; i++) { 1659 | aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]]; 1660 | for (uint32_t j = 0; j < input_mesh->mNumFaces; j++) { 1661 | aiFace& face = input_mesh->mFaces[j]; 1662 | if( face.mNumIndices > 3 ) { 1663 | pcount->getValue()[offset++] = face.mNumIndices; 1664 | } 1665 | } 1666 | } 1667 | } 1668 | } 1669 | 1670 | for (uint32_t i=0; i < node->mNumChildren; ++i) { 1671 | _buildAiMesh(scene, node->mChildren[i], pdommesh,parray,geomid,scale,org_trans); 1672 | } 1673 | } 1674 | 1675 | 1676 | domEffectRef _WriteEffect(std::string const& effect_id, urdf::Color const& color_ambient, urdf::Color const& color_diffuse) 1677 | { 1678 | // 1679 | domEffectRef effect = daeSafeCast(_effectsLib->add(COLLADA_ELEMENT_EFFECT)); 1680 | effect->setId(effect_id.c_str()); 1681 | { 1682 | // 1683 | domProfile_commonRef profile = daeSafeCast(effect->add(COLLADA_ELEMENT_PROFILE_COMMON)); 1684 | { 1685 | // 1686 | domProfile_common::domTechniqueRef technique = daeSafeCast(profile->add(COLLADA_ELEMENT_TECHNIQUE)); 1687 | { 1688 | // 1689 | domProfile_common::domTechnique::domPhongRef phong = daeSafeCast(technique->add(COLLADA_ELEMENT_PHONG)); 1690 | { 1691 | // 1692 | domFx_common_color_or_textureRef ambient = daeSafeCast(phong->add(COLLADA_ELEMENT_AMBIENT)); 1693 | { 1694 | // r g b a 1695 | domFx_common_color_or_texture::domColorRef ambient_color = daeSafeCast(ambient->add(COLLADA_ELEMENT_COLOR)); 1696 | ambient_color->getValue().setCount(4); 1697 | ambient_color->getValue()[0] = color_ambient.r; 1698 | ambient_color->getValue()[1] = color_ambient.g; 1699 | ambient_color->getValue()[2] = color_ambient.b; 1700 | ambient_color->getValue()[3] = color_ambient.a; 1701 | // 1702 | } 1703 | // 1704 | 1705 | // 1706 | domFx_common_color_or_textureRef diffuse = daeSafeCast(phong->add(COLLADA_ELEMENT_DIFFUSE)); 1707 | { 1708 | // r g b a 1709 | domFx_common_color_or_texture::domColorRef diffuse_color = daeSafeCast(diffuse->add(COLLADA_ELEMENT_COLOR)); 1710 | diffuse_color->getValue().setCount(4); 1711 | diffuse_color->getValue()[0] = color_diffuse.r; 1712 | diffuse_color->getValue()[1] = color_diffuse.g; 1713 | diffuse_color->getValue()[2] = color_diffuse.b; 1714 | diffuse_color->getValue()[3] = color_diffuse.a; 1715 | // 1716 | } 1717 | // 1718 | } 1719 | // 1720 | } 1721 | // 1722 | } 1723 | // 1724 | } 1725 | // 1726 | 1727 | return effect; 1728 | } 1729 | 1730 | /// \brief Write transformation 1731 | /// \param pelt Element to transform 1732 | /// \param t Transform to write 1733 | void _WriteTransformation(daeElementRef pelt, const urdf::Pose& t) 1734 | { 1735 | domRotateRef prot = daeSafeCast(pelt->add(COLLADA_ELEMENT_ROTATE,0)); 1736 | domTranslateRef ptrans = daeSafeCast(pelt->add(COLLADA_ELEMENT_TRANSLATE,0)); 1737 | ptrans->getValue().setCount(3); 1738 | ptrans->getValue()[0] = t.position.x; 1739 | ptrans->getValue()[1] = t.position.y; 1740 | ptrans->getValue()[2] = t.position.z; 1741 | 1742 | prot->getValue().setCount(4); 1743 | // extract axis from quaternion 1744 | double sinang = t.rotation.x*t.rotation.x+t.rotation.y*t.rotation.y+t.rotation.z*t.rotation.z; 1745 | if( std::fabs(sinang) < 1e-10 ) { 1746 | prot->getValue()[0] = 1; 1747 | prot->getValue()[1] = 0; 1748 | prot->getValue()[2] = 0; 1749 | prot->getValue()[3] = 0; 1750 | } 1751 | else { 1752 | urdf::Rotation quat; 1753 | if( t.rotation.w < 0 ) { 1754 | quat.x = -t.rotation.x; 1755 | quat.y = -t.rotation.y; 1756 | quat.z = -t.rotation.z; 1757 | quat.w = -t.rotation.w; 1758 | } 1759 | else { 1760 | quat = t.rotation; 1761 | } 1762 | sinang = std::sqrt(sinang); 1763 | prot->getValue()[0] = quat.x/sinang; 1764 | prot->getValue()[1] = quat.y/sinang; 1765 | prot->getValue()[2] = quat.z/sinang; 1766 | prot->getValue()[3] = angles::to_degrees(2.0*std::atan2(sinang,quat.w)); 1767 | } 1768 | } 1769 | 1770 | // binding in instance_kinematics_scene 1771 | void _WriteBindingsInstance_kinematics_scene() 1772 | { 1773 | FOREACHC(it, _iasout->vkinematicsbindings) { 1774 | domBind_kinematics_modelRef pmodelbind = daeSafeCast(_scene.kiscene->add(COLLADA_ELEMENT_BIND_KINEMATICS_MODEL)); 1775 | pmodelbind->setNode(it->second.c_str()); 1776 | daeSafeCast(pmodelbind->add(COLLADA_ELEMENT_PARAM))->setValue(it->first.c_str()); 1777 | } 1778 | FOREACHC(it, _iasout->vaxissids) { 1779 | domBind_joint_axisRef pjointbind = daeSafeCast(_scene.kiscene->add(COLLADA_ELEMENT_BIND_JOINT_AXIS)); 1780 | pjointbind->setTarget(it->jointnodesid.c_str()); 1781 | daeSafeCast(pjointbind->add(COLLADA_ELEMENT_AXIS)->add(COLLADA_TYPE_PARAM))->setValue(it->axissid.c_str()); 1782 | daeSafeCast(pjointbind->add(COLLADA_ELEMENT_VALUE)->add(COLLADA_TYPE_PARAM))->setValue(it->valuesid.c_str()); 1783 | } 1784 | } 1785 | 1786 | private: 1787 | static urdf::Vector3 _poseMult(const urdf::Pose& p, const urdf::Vector3& v) 1788 | { 1789 | double ww = 2 * p.rotation.x * p.rotation.x; 1790 | double wx = 2 * p.rotation.x * p.rotation.y; 1791 | double wy = 2 * p.rotation.x * p.rotation.z; 1792 | double wz = 2 * p.rotation.x * p.rotation.w; 1793 | double xx = 2 * p.rotation.y * p.rotation.y; 1794 | double xy = 2 * p.rotation.y * p.rotation.z; 1795 | double xz = 2 * p.rotation.y * p.rotation.w; 1796 | double yy = 2 * p.rotation.z * p.rotation.z; 1797 | double yz = 2 * p.rotation.z * p.rotation.w; 1798 | urdf::Vector3 vnew; 1799 | vnew.x = (1-xx-yy) * v.x + (wx-yz) * v.y + (wy+xz)*v.z + p.position.x; 1800 | vnew.y = (wx+yz) * v.x + (1-ww-yy) * v.y + (xy-wz)*v.z + p.position.y; 1801 | vnew.z = (wy-xz) * v.x + (xy+wz) * v.y + (1-ww-xx)*v.z + p.position.z; 1802 | return vnew; 1803 | } 1804 | 1805 | static urdf::Pose _poseInverse(const urdf::Pose& p) 1806 | { 1807 | urdf::Pose pinv; 1808 | pinv.rotation.x = -p.rotation.x; 1809 | pinv.rotation.y = -p.rotation.y; 1810 | pinv.rotation.z = -p.rotation.z; 1811 | pinv.rotation.w = p.rotation.w; 1812 | urdf::Vector3 t = _poseMult(pinv,p.position); 1813 | pinv.position.x = -t.x; 1814 | pinv.position.y = -t.y; 1815 | pinv.position.z = -t.z; 1816 | return pinv; 1817 | } 1818 | 1819 | static urdf::Rotation _quatMult(const urdf::Rotation& quat0, const urdf::Rotation& quat1) 1820 | { 1821 | urdf::Rotation q; 1822 | q.x = quat0.w*quat1.x + quat0.x*quat1.w + quat0.y*quat1.z - quat0.z*quat1.y; 1823 | q.y = quat0.w*quat1.y + quat0.y*quat1.w + quat0.z*quat1.x - quat0.x*quat1.z; 1824 | q.z = quat0.w*quat1.z + quat0.z*quat1.w + quat0.x*quat1.y - quat0.y*quat1.x; 1825 | q.w = quat0.w*quat1.w - quat0.x*quat1.x - quat0.y*quat1.y - quat0.z*quat1.z; 1826 | double fnorm = std::sqrt(q.x*q.x+q.y*q.y+q.z*q.z+q.w*q.w); 1827 | // don't touch the divides 1828 | q.x /= fnorm; 1829 | q.y /= fnorm; 1830 | q.z /= fnorm; 1831 | q.w /= fnorm; 1832 | return q; 1833 | } 1834 | 1835 | static urdf::Pose _poseMult(const urdf::Pose& p0, const urdf::Pose& p1) 1836 | { 1837 | urdf::Pose p; 1838 | p.position = _poseMult(p0,p1.position); 1839 | p.rotation = _quatMult(p0.rotation,p1.rotation); 1840 | return p; 1841 | } 1842 | 1843 | static urdf::Rotation _quatFromMatrix(const boost::array& mat) 1844 | { 1845 | urdf::Rotation rot; 1846 | double tr = mat[4*0+0] + mat[4*1+1] + mat[4*2+2]; 1847 | if (tr >= 0) { 1848 | rot.w = tr + 1; 1849 | rot.x = (mat[4*2+1] - mat[4*1+2]); 1850 | rot.y = (mat[4*0+2] - mat[4*2+0]); 1851 | rot.z = (mat[4*1+0] - mat[4*0+1]); 1852 | } 1853 | else { 1854 | // find the largest diagonal element and jump to the appropriate case 1855 | if (mat[4*1+1] > mat[4*0+0]) { 1856 | if (mat[4*2+2] > mat[4*1+1]) { 1857 | rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1; 1858 | rot.x = (mat[4*2+0] + mat[4*0+2]); 1859 | rot.y = (mat[4*1+2] + mat[4*2+1]); 1860 | rot.w = (mat[4*1+0] - mat[4*0+1]); 1861 | } 1862 | else { 1863 | rot.y = (mat[4*1+1] - (mat[4*2+2] + mat[4*0+0])) + 1; 1864 | rot.z = (mat[4*1+2] + mat[4*2+1]); 1865 | rot.x = (mat[4*0+1] + mat[4*1+0]); 1866 | rot.w = (mat[4*0+2] - mat[4*2+0]); 1867 | } 1868 | } 1869 | else if (mat[4*2+2] > mat[4*0+0]) { 1870 | rot.z = (mat[4*2+2] - (mat[4*0+0] + mat[4*1+1])) + 1; 1871 | rot.x = (mat[4*2+0] + mat[4*0+2]); 1872 | rot.y = (mat[4*1+2] + mat[4*2+1]); 1873 | rot.w = (mat[4*1+0] - mat[4*0+1]); 1874 | } 1875 | else { 1876 | rot.x = (mat[4*0+0] - (mat[4*1+1] + mat[4*2+2])) + 1; 1877 | rot.y = (mat[4*0+1] + mat[4*1+0]); 1878 | rot.z = (mat[4*2+0] + mat[4*0+2]); 1879 | rot.w = (mat[4*2+1] - mat[4*1+2]); 1880 | } 1881 | } 1882 | double fnorm = std::sqrt(rot.x*rot.x+rot.y*rot.y+rot.z*rot.z+rot.w*rot.w); 1883 | // don't touch the divides 1884 | rot.x /= fnorm; 1885 | rot.y /= fnorm; 1886 | rot.z /= fnorm; 1887 | rot.w /= fnorm; 1888 | return rot; 1889 | } 1890 | 1891 | static std::string _ComputeKinematics_modelId(int id) 1892 | { 1893 | return _ComputeId(str(boost::format("kmodel%d")%id)); 1894 | } 1895 | 1896 | /// \brief computes a collada-compliant sid from the urdf name 1897 | static std::string _ComputeId(const std::string& name) 1898 | { 1899 | std::string newname = name; 1900 | for(size_t i = 0; i < newname.size(); ++i) { 1901 | if( newname[i] == '/' || newname[i] == ' ' || newname[i] == '.' ) { 1902 | newname[i] = '_'; 1903 | } 1904 | } 1905 | return newname; 1906 | } 1907 | 1908 | int _writeoptions; 1909 | 1910 | const urdf::Model& _robot; 1911 | DAE _collada; 1912 | domCOLLADA* _dom; 1913 | daeDocument *_doc; 1914 | domCOLLADA::domSceneRef _globalscene; 1915 | 1916 | domLibrary_visual_scenesRef _visualScenesLib; 1917 | domLibrary_kinematics_scenesRef _kinematicsScenesLib; 1918 | domLibrary_kinematics_modelsRef _kinematicsModelsLib; 1919 | domLibrary_articulated_systemsRef _articulatedSystemsLib; 1920 | domLibrary_physics_scenesRef _physicsScenesLib; 1921 | domLibrary_physics_modelsRef _physicsModelsLib; 1922 | domLibrary_materialsRef _materialsLib; 1923 | domLibrary_effectsRef _effectsLib; 1924 | domLibrary_geometriesRef _geometriesLib; 1925 | domTechniqueRef _sensorsLib; ///< custom sensors library 1926 | SCENE _scene; 1927 | 1928 | boost::shared_ptr _ikmout; 1929 | boost::shared_ptr _iasout; 1930 | std::map< urdf::JointConstSharedPtr, int > _mapjointindices; 1931 | std::map< urdf::LinkConstSharedPtr, int > _maplinkindices; 1932 | std::map< urdf::MaterialConstSharedPtr, int > _mapmaterialindices; 1933 | Assimp::Importer _importer; 1934 | }; 1935 | 1936 | 1937 | ColladaUrdfException::ColladaUrdfException(std::string const& what) 1938 | : std::runtime_error(what) 1939 | { 1940 | } 1941 | 1942 | bool WriteUrdfModelToColladaFile(urdf::Model const& robot_model, string const& file) { 1943 | ColladaWriter writer(robot_model, 0); 1944 | if ( ! writer.convert() ) { 1945 | std::cerr << std::endl << "Error converting document" << std::endl; 1946 | return -1; 1947 | } 1948 | return writer.writeTo(file); 1949 | } 1950 | 1951 | } 1952 | --------------------------------------------------------------------------------