From 4a91c0445e29aa7895e128d2e9146186d0d90bf8 Mon Sep 17 00:00:00 2001 From: Markus Neuner Date: Wed, 23 Jan 2013 13:17:52 +0100 Subject: [PATCH 2/2] Added Microsoft-specific dllexport and dllimport storage-class attributes to export and import functions, data, and objects to or from the OROCOS-KDL shared libraries (DLL). The macros and preprocessor defintions that contain the KDL_EXPORT define, which contains '__declspec(dllexport)' or '__declspec(dllimport)' on windows and nothing on unix are automatically generated with the CMake function GENERATE_EXPORT_HEADER() and the accompanying ADD_COMPILER_EXPORT_FLAGS() function. It generates a 'kdl_export.hpp' in the binary directory that is suitable for preprocessor inclusion which contains EXPORT macros (SOMELIB_EXPORT, SOMELIB_NO_EXPORT, SOMELIB_DEPRECATED, SOMELIB_DEPRECATED_EXPORT and SOMELIB_DEPRECATED_NO_EXPORT) to be used in the OROCOS-KDL library classes. The resulting hjeader file is included and installed with other headers in the library. EXPORTS: All classes and relevant functions in '/orocos_kdl/src/*.hpp', some constants in '/orocos_kdl/src/utilities/utility.h' and the models in '/orocos_kdl/models/models.hpp' (if enabled) are exported. The GENERATE_EXPORT_HEADER function is available since CMake version 2.8.6 and above. To use the functionality with CMake versions below 2.8.6 (the currently minumum required CMake version of OROCOS-KDL is 2.4.6) the following files were added: * /orocos_kdl/config/GenerateExportHeader.cmake * /orocos_kdl/config/exportheader.cmake.in * /orocos_kdl/config/CMakeParseArguments.cmake FIX: In addions some fixes were applied to convenience the nmake compiler (missing math.h include and/or missing '#define _USE_MATH_DEFINES', non constant array length initialization, undefined uint typedef, ambiguous function calls because of 'using namespace KDL;' e.g. sin, cos, sqrt) * /orocos_kdl/examples/geometry.cpp * /orocos_kdl/examples/trajectory_example.cpp * /orocos_kdl/models/puma560.cpp * /orocos_kdl/tests/framestest.cpp * /orocos_kdl/tests/kinfamtest.cpp * /orocos_kdl/tests/solvertest.cpp TESTED: Tested that everything compiles (orocos-kdl, orocos-models-kdl, examples, demos, tests) and that all test succeed and the examples work with the following compilers: * WINDOWS: nmake version 10.00.30319.01 (MSVC 2010) compiled from command line * WINDOWS: Visual Studio Express 2010 * WINDOWS: QtCreator 2.6.1 * LINUX: gcc version 4.7.2 (Latest Debian unstable as of 2012-12-28) --- orocos_kdl/CMakeLists.txt | 9 +- .../cmakemoduleslegacy/CMakeParseArguments.cmake | 195 ++++++++++ .../cmakemoduleslegacy/GenerateExportHeader.cmake | 408 +++++++++++++++++++++ orocos_kdl/config/cmakemoduleslegacy/ReadMe.txt | 1 + .../cmakemoduleslegacy/exportheader.cmake.in | 35 ++ orocos_kdl/examples/CMakeLists.txt | 2 +- orocos_kdl/examples/geometry.cpp | 3 + orocos_kdl/examples/trajectory_example.cpp | 3 + orocos_kdl/models/CMakeLists.txt | 11 +- orocos_kdl/models/models.hpp | 10 +- orocos_kdl/models/puma560.cpp | 3 + orocos_kdl/src/CMakeLists.txt | 13 +- orocos_kdl/src/articulatedbodyinertia.hpp | 19 +- orocos_kdl/src/chain.hpp | 3 +- orocos_kdl/src/chaindynparam.hpp | 3 +- orocos_kdl/src/chainfksolver.hpp | 10 +- orocos_kdl/src/chainfksolverpos_recursive.hpp | 3 +- orocos_kdl/src/chainfksolvervel_recursive.hpp | 3 +- orocos_kdl/src/chainidsolver.hpp | 3 +- .../src/chainidsolver_recursive_newton_euler.hpp | 3 +- orocos_kdl/src/chainidsolver_vereshchagin.hpp | 3 +- orocos_kdl/src/chainiksolver.hpp | 7 +- orocos_kdl/src/chainiksolverpos_lma.hpp | 3 +- orocos_kdl/src/chainiksolverpos_nr.hpp | 3 +- orocos_kdl/src/chainiksolverpos_nr_jl.hpp | 3 +- orocos_kdl/src/chainiksolvervel_pinv.hpp | 3 +- orocos_kdl/src/chainiksolvervel_pinv_givens.hpp | 3 +- orocos_kdl/src/chainiksolvervel_pinv_nso.hpp | 3 +- orocos_kdl/src/chainiksolvervel_wdls.hpp | 3 +- orocos_kdl/src/chainjnttojacsolver.hpp | 3 +- orocos_kdl/src/frameacc.hpp | 113 +++--- orocos_kdl/src/frameacc_io.hpp | 9 +- orocos_kdl/src/frames.hpp | 157 ++++---- orocos_kdl/src/frames_io.hpp | 33 +- orocos_kdl/src/framevel.hpp | 151 ++++---- orocos_kdl/src/framevel_io.hpp | 9 +- orocos_kdl/src/jacobian.hpp | 13 +- orocos_kdl/src/jntarray.hpp | 19 +- orocos_kdl/src/jntarrayacc.hpp | 31 +- orocos_kdl/src/jntarrayvel.hpp | 23 +- orocos_kdl/src/jntspaceinertiamatrix.hpp | 19 +- orocos_kdl/src/joint.hpp | 4 +- orocos_kdl/src/kinfam_io.hpp | 38 +- orocos_kdl/src/path.hpp | 7 +- orocos_kdl/src/path_circle.hpp | 4 +- orocos_kdl/src/path_composite.hpp | 3 +- orocos_kdl/src/path_cyclic_closed.hpp | 3 +- orocos_kdl/src/path_line.hpp | 3 +- orocos_kdl/src/path_point.hpp | 4 +- orocos_kdl/src/path_roundedcomposite.hpp | 3 +- orocos_kdl/src/rigidbodyinertia.hpp | 14 +- orocos_kdl/src/rotational_interpolation.hpp | 3 +- orocos_kdl/src/rotational_interpolation_sa.hpp | 3 +- orocos_kdl/src/rotationalinertia.hpp | 17 +- orocos_kdl/src/segment.hpp | 3 +- orocos_kdl/src/stiffness.hpp | 4 +- orocos_kdl/src/trajectory.hpp | 6 +- orocos_kdl/src/trajectory_composite.hpp | 4 +- orocos_kdl/src/trajectory_segment.hpp | 3 +- orocos_kdl/src/trajectory_stationary.hpp | 3 +- orocos_kdl/src/tree.hpp | 5 +- orocos_kdl/src/treefksolver.hpp | 7 +- orocos_kdl/src/treefksolverpos_recursive.hpp | 3 +- orocos_kdl/src/treeiksolver.hpp | 3 +- orocos_kdl/src/treeiksolverpos_nr_jl.hpp | 3 +- orocos_kdl/src/treeiksolverpos_online.hpp | 3 +- orocos_kdl/src/treeiksolvervel_wdls.hpp | 3 +- orocos_kdl/src/treejnttojacsolver.hpp | 3 +- orocos_kdl/src/utilities/utility.h | 9 +- orocos_kdl/src/velocityprofile.hpp | 4 +- orocos_kdl/src/velocityprofile_dirac.hpp | 4 +- orocos_kdl/src/velocityprofile_rect.hpp | 4 +- orocos_kdl/src/velocityprofile_spline.hpp | 3 +- orocos_kdl/src/velocityprofile_trap.hpp | 7 +- orocos_kdl/src/velocityprofile_traphalf.hpp | 6 +- orocos_kdl/tests/CMakeLists.txt | 2 +- orocos_kdl/tests/framestest.cpp | 55 +-- orocos_kdl/tests/kinfamtest.cpp | 4 + orocos_kdl/tests/solvertest.cpp | 4 +- 79 files changed, 1165 insertions(+), 447 deletions(-) create mode 100644 orocos_kdl/config/cmakemoduleslegacy/CMakeParseArguments.cmake create mode 100644 orocos_kdl/config/cmakemoduleslegacy/GenerateExportHeader.cmake create mode 100644 orocos_kdl/config/cmakemoduleslegacy/ReadMe.txt create mode 100644 orocos_kdl/config/cmakemoduleslegacy/exportheader.cmake.in diff --git a/orocos_kdl/CMakeLists.txt b/orocos_kdl/CMakeLists.txt index 902a064..37dca90 100644 --- a/orocos_kdl/CMakeLists.txt +++ b/orocos_kdl/CMakeLists.txt @@ -52,13 +52,20 @@ INCLUDE_DIRECTORIES(${EIGEN_INCLUDE_DIRS}) INCLUDE (${PROJ_SOURCE_DIR}/config/DependentOption.cmake) +# Add required modules that are not available in older CMake versions +IF("${CMAKE_VERSION}" VERSION_LESS "2.8.6") + SET(CMAKE_MODULE_PATH "${CMAKE_MODULE_PATH}" "${CMAKE_CURRENT_SOURCE_DIR}/config/cmakemoduleslegacy") +ENDIF("${CMAKE_VERSION}" VERSION_LESS "2.8.6") + OPTION(ENABLE_TESTS OFF "Enable building of tests") IF( ENABLE_TESTS ) # If not in standard paths, set CMAKE_xxx_PATH's in environment, eg. # export CMAKE_INCLUDE_PATH=/opt/local/include # export CMAKE_LIBRARY_PATH=/opt/local/lib FIND_LIBRARY(CPPUNIT cppunit) - SET(CPPUNIT ${CPPUNIT} "dl") + IF( NOT MSVC ) + SET(CPPUNIT ${CPPUNIT} "dl") + ENDIF( NOT MSVC ) FIND_PATH(CPPUNIT_HEADERS cppunit/TestRunner.h) IF ( CPPUNIT AND CPPUNIT_HEADERS) MESSAGE("-- Looking for Cppunit - found") diff --git a/orocos_kdl/config/cmakemoduleslegacy/CMakeParseArguments.cmake b/orocos_kdl/config/cmakemoduleslegacy/CMakeParseArguments.cmake new file mode 100644 index 0000000..f5a03fe --- /dev/null +++ b/orocos_kdl/config/cmakemoduleslegacy/CMakeParseArguments.cmake @@ -0,0 +1,195 @@ +# CMAKE_PARSE_ARGUMENTS( args...) +# +# CMAKE_PARSE_ARGUMENTS() is intended to be used in macros or functions for +# parsing the arguments given to that macro or function. +# It processes the arguments and defines a set of variables which hold the +# values of the respective options. +# +# The argument contains all options for the respective macro, +# i.e. keywords which can be used when calling the macro without any value +# following, like e.g. the OPTIONAL keyword of the install() command. +# +# The argument contains all keywords for this macro +# which are followed by one value, like e.g. DESTINATION keyword of the +# install() command. +# +# The argument contains all keywords for this macro +# which can be followed by more than one value, like e.g. the TARGETS or +# FILES keywords of the install() command. +# +# When done, CMAKE_PARSE_ARGUMENTS() will have defined for each of the +# keywords listed in , and +# a variable composed of the given +# followed by "_" and the name of the respective keyword. +# These variables will then hold the respective value from the argument list. +# For the keywords this will be TRUE or FALSE. +# +# All remaining arguments are collected in a variable +# _UNPARSED_ARGUMENTS, this can be checked afterwards to see whether +# your macro was called with unrecognized parameters. +# +# As an example here a my_install() macro, which takes similar arguments as the +# real install() command: +# +# function(MY_INSTALL) +# set(options OPTIONAL FAST) +# set(oneValueArgs DESTINATION RENAME) +# set(multiValueArgs TARGETS CONFIGURATIONS) +# cmake_parse_arguments(MY_INSTALL "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN} ) +# ... +# +# Assume my_install() has been called like this: +# my_install(TARGETS foo bar DESTINATION bin OPTIONAL blub) +# +# After the cmake_parse_arguments() call the macro will have set the following +# variables: +# MY_INSTALL_OPTIONAL = TRUE +# MY_INSTALL_FAST = FALSE (this option was not used when calling my_install() +# MY_INSTALL_DESTINATION = "bin" +# MY_INSTALL_RENAME = "" (was not used) +# MY_INSTALL_TARGETS = "foo;bar" +# MY_INSTALL_CONFIGURATIONS = "" (was not used) +# MY_INSTALL_UNPARSED_ARGUMENTS = "blub" (no value expected after "OPTIONAL" +# +# You can the continue and process these variables. +# +# Keywords terminate lists of values, e.g. if directly after a one_value_keyword +# another recognized keyword follows, this is interpreted as the beginning of +# the new option. +# E.g. my_install(TARGETS foo DESTINATION OPTIONAL) would result in +# MY_INSTALL_DESTINATION set to "OPTIONAL", but MY_INSTALL_DESTINATION would +# be empty and MY_INSTALL_OPTIONAL would be set to TRUE therefor. + +#============================================================================= +# Copyright 2010 Alexander Neundorf +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of CMake, substitute the full +# License text for the above reference.) +# CMake - Cross Platform Makefile Generator +# Copyright 2000-2011 Kitware, Inc., Insight Software Consortium +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the names of Kitware, Inc., the Insight Software Consortium, +# nor the names of their contributors may be used to endorse or promote +# products derived from this software without specific prior written +# permission. + +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +# HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +# +# ------------------------------------------------------------------------------ +# +# The above copyright and license notice applies to distributions of +# CMake in source and binary form. Some source files contain additional +# notices of original copyright by their contributors; see each source +# for details. Third-party software packages supplied with CMake under +# compatible licenses provide their own copyright notices documented in +# corresponding subdirectories. +# +# ------------------------------------------------------------------------------ +# +# CMake was initially developed by Kitware with the following sponsorship: +# +# * National Library of Medicine at the National Institutes of Health +# as part of the Insight Segmentation and Registration Toolkit (ITK). +# +# * US National Labs (Los Alamos, Livermore, Sandia) ASC Parallel +# Visualization Initiative. +# +# * National Alliance for Medical Image Computing (NAMIC) is funded by the +# National Institutes of Health through the NIH Roadmap for Medical Research, +# Grant U54 EB005149. +# +# * Kitware, Inc. +# + + +if(__CMAKE_PARSE_ARGUMENTS_INCLUDED) + return() +endif() +set(__CMAKE_PARSE_ARGUMENTS_INCLUDED TRUE) + + +function(CMAKE_PARSE_ARGUMENTS prefix _optionNames _singleArgNames _multiArgNames) + # first set all result variables to empty/FALSE + foreach(arg_name ${_singleArgNames} ${_multiArgNames}) + set(${prefix}_${arg_name}) + endforeach(arg_name) + + foreach(option ${_optionNames}) + set(${prefix}_${option} FALSE) + endforeach(option) + + set(${prefix}_UNPARSED_ARGUMENTS) + + set(insideValues FALSE) + set(currentArgName) + + # now iterate over all arguments and fill the result variables + foreach(currentArg ${ARGN}) + list(FIND _optionNames "${currentArg}" optionIndex) # ... then this marks the end of the arguments belonging to this keyword + list(FIND _singleArgNames "${currentArg}" singleArgIndex) # ... then this marks the end of the arguments belonging to this keyword + list(FIND _multiArgNames "${currentArg}" multiArgIndex) # ... then this marks the end of the arguments belonging to this keyword + + if(${optionIndex} EQUAL -1 AND ${singleArgIndex} EQUAL -1 AND ${multiArgIndex} EQUAL -1) + if(insideValues) + if("${insideValues}" STREQUAL "SINGLE") + set(${prefix}_${currentArgName} ${currentArg}) + set(insideValues FALSE) + elseif("${insideValues}" STREQUAL "MULTI") + list(APPEND ${prefix}_${currentArgName} ${currentArg}) + endif() + else(insideValues) + list(APPEND ${prefix}_UNPARSED_ARGUMENTS ${currentArg}) + endif(insideValues) + else() + if(NOT ${optionIndex} EQUAL -1) + set(${prefix}_${currentArg} TRUE) + set(insideValues FALSE) + elseif(NOT ${singleArgIndex} EQUAL -1) + set(currentArgName ${currentArg}) + set(${prefix}_${currentArgName}) + set(insideValues "SINGLE") + elseif(NOT ${multiArgIndex} EQUAL -1) + set(currentArgName ${currentArg}) + set(${prefix}_${currentArgName}) + set(insideValues "MULTI") + endif() + endif() + + endforeach(currentArg) + + # propagate the result variables to the caller: + foreach(arg_name ${_singleArgNames} ${_multiArgNames} ${_optionNames}) + set(${prefix}_${arg_name} ${${prefix}_${arg_name}} PARENT_SCOPE) + endforeach(arg_name) + set(${prefix}_UNPARSED_ARGUMENTS ${${prefix}_UNPARSED_ARGUMENTS} PARENT_SCOPE) + +endfunction(CMAKE_PARSE_ARGUMENTS _options _singleArgs _multiArgs) diff --git a/orocos_kdl/config/cmakemoduleslegacy/GenerateExportHeader.cmake b/orocos_kdl/config/cmakemoduleslegacy/GenerateExportHeader.cmake new file mode 100644 index 0000000..96044c6 --- /dev/null +++ b/orocos_kdl/config/cmakemoduleslegacy/GenerateExportHeader.cmake @@ -0,0 +1,408 @@ +# - Function for generation of export macros for libraries +# This module provides the function GENERATE_EXPORT_HEADER() and the +# accompanying ADD_COMPILER_EXPORT_FLAGS() function. +# +# The GENERATE_EXPORT_HEADER function can be used to generate a file suitable +# for preprocessor inclusion which contains EXPORT macros to be used in +# library classes. +# +# GENERATE_EXPORT_HEADER( LIBRARY_TARGET +# [BASE_NAME ] +# [EXPORT_MACRO_NAME ] +# [EXPORT_FILE_NAME ] +# [DEPRECATED_MACRO_NAME ] +# [NO_EXPORT_MACRO_NAME ] +# [STATIC_DEFINE ] +# [NO_DEPRECATED_MACRO_NAME ] +# [DEFINE_NO_DEPRECATED] +# [PREFIX_NAME ] +# ) +# +# ADD_COMPILER_EXPORT_FLAGS( [] ) +# +# By default GENERATE_EXPORT_HEADER() generates macro names in a file name +# determined by the name of the library. The ADD_COMPILER_EXPORT_FLAGS function +# adds -fvisibility=hidden to CMAKE_CXX_FLAGS if supported, and is a no-op on +# Windows which does not need extra compiler flags for exporting support. You +# may optionally pass a single argument to ADD_COMPILER_EXPORT_FLAGS that will +# be populated with the required CXX_FLAGS required to enable visibility support +# for the compiler/architecture in use. +# +# This means that in the simplest case, users of these functions will be +# equivalent to: +# +# add_compiler_export_flags() +# add_library(somelib someclass.cpp) +# generate_export_header(somelib) +# install(TARGETS somelib DESTINATION ${LIBRARY_INSTALL_DIR}) +# install(FILES +# someclass.h +# ${PROJECT_BINARY_DIR}/somelib_export.h DESTINATION ${INCLUDE_INSTALL_DIR} +# ) +# +# And in the ABI header files: +# +# #include "somelib_export.h" +# class SOMELIB_EXPORT SomeClass { +# ... +# }; +# +# The CMake fragment will generate a file in the ${CMAKE_CURRENT_BUILD_DIR} +# called somelib_export.h containing the macros SOMELIB_EXPORT, SOMELIB_NO_EXPORT, +# SOMELIB_DEPRECATED, SOMELIB_DEPRECATED_EXPORT and SOMELIB_DEPRECATED_NO_EXPORT. +# The resulting file should be installed with other headers in the library. +# +# The BASE_NAME argument can be used to override the file name and the names +# used for the macros +# +# add_library(somelib someclass.cpp) +# generate_export_header(somelib +# BASE_NAME other_name +# ) +# +# Generates a file called other_name_export.h containing the macros +# OTHER_NAME_EXPORT, OTHER_NAME_NO_EXPORT and OTHER_NAME_DEPRECATED etc. +# +# The BASE_NAME may be overridden by specifiying other options in the function. +# For example: +# +# add_library(somelib someclass.cpp) +# generate_export_header(somelib +# EXPORT_MACRO_NAME OTHER_NAME_EXPORT +# ) +# +# creates the macro OTHER_NAME_EXPORT instead of SOMELIB_EXPORT, but other macros +# and the generated file name is as default. +# +# add_library(somelib someclass.cpp) +# generate_export_header(somelib +# DEPRECATED_MACRO_NAME KDE_DEPRECATED +# ) +# +# creates the macro KDE_DEPRECATED instead of SOMELIB_DEPRECATED. +# +# If LIBRARY_TARGET is a static library, macros are defined without values. +# +# If the same sources are used to create both a shared and a static library, the +# uppercased symbol ${BASE_NAME}_STATIC_DEFINE should be used when building the +# static library +# +# add_library(shared_variant SHARED ${lib_SRCS}) +# add_library(static_variant ${lib_SRCS}) +# generate_export_header(shared_variant BASE_NAME libshared_and_static) +# set_target_properties(static_variant PROPERTIES +# COMPILE_FLAGS -DLIBSHARED_AND_STATIC_STATIC_DEFINE) +# +# This will cause the export macros to expand to nothing when building the +# static library. +# +# If DEFINE_NO_DEPRECATED is specified, then a macro ${BASE_NAME}_NO_DEPRECATED +# will be defined +# This macro can be used to remove deprecated code from preprocessor output. +# +# option(EXCLUDE_DEPRECATED "Exclude deprecated parts of the library" FALSE) +# if (EXCLUDE_DEPRECATED) +# set(NO_BUILD_DEPRECATED DEFINE_NO_DEPRECATED) +# endif() +# generate_export_header(somelib ${NO_BUILD_DEPRECATED}) +# +# And then in somelib: +# +# class SOMELIB_EXPORT SomeClass +# { +# public: +# #ifndef SOMELIB_NO_DEPRECATED +# SOMELIB_DEPRECATED void oldMethod(); +# #endif +# }; +# +# #ifndef SOMELIB_NO_DEPRECATED +# void SomeClass::oldMethod() { } +# #endif +# +# If PREFIX_NAME is specified, the argument will be used as a prefix to all +# generated macros. +# +# For example: +# +# generate_export_header(somelib PREFIX_NAME VTK_) +# +# Generates the macros VTK_SOMELIB_EXPORT etc. + +#============================================================================= +# Copyright 2011 Stephen Kelly +# +# Distributed under the OSI-approved BSD License (the "License"); +# see accompanying file Copyright.txt for details. +# +# This software is distributed WITHOUT ANY WARRANTY; without even the +# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +# See the License for more information. +#============================================================================= +# (To distribute this file outside of CMake, substitute the full +# License text for the above reference.) +# CMake - Cross Platform Makefile Generator +# Copyright 2000-2011 Kitware, Inc., Insight Software Consortium +# All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# * Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# +# * Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in the +# documentation and/or other materials provided with the distribution. +# +# * Neither the names of Kitware, Inc., the Insight Software Consortium, +# nor the names of their contributors may be used to endorse or promote +# products derived from this software without specific prior written +# permission. + +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +# A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +# HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +# SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +# LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +# DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +# THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +# (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +# OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +# +# ------------------------------------------------------------------------------ +# +# The above copyright and license notice applies to distributions of +# CMake in source and binary form. Some source files contain additional +# notices of original copyright by their contributors; see each source +# for details. Third-party software packages supplied with CMake under +# compatible licenses provide their own copyright notices documented in +# corresponding subdirectories. +# +# ------------------------------------------------------------------------------ +# +# CMake was initially developed by Kitware with the following sponsorship: +# +# * National Library of Medicine at the National Institutes of Health +# as part of the Insight Segmentation and Registration Toolkit (ITK). +# +# * US National Labs (Los Alamos, Livermore, Sandia) ASC Parallel +# Visualization Initiative. +# +# * National Alliance for Medical Image Computing (NAMIC) is funded by the +# National Institutes of Health through the NIH Roadmap for Medical Research, +# Grant U54 EB005149. +# +# * Kitware, Inc. +# + +include(CMakeParseArguments) +include(CheckCXXCompilerFlag) + +# TODO: Install this macro separately? +macro(_check_cxx_compiler_attribute _ATTRIBUTE _RESULT) + check_cxx_source_compiles("${_ATTRIBUTE} int somefunc() { return 0; } + int main() { return somefunc();}" ${_RESULT} + ) +endmacro() + +macro(_test_compiler_hidden_visibility) + + if(CMAKE_COMPILER_IS_GNUCXX AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS "4.2") + set(GCC_TOO_OLD TRUE) + message(WARNING "GCC version older than 4.2") + elseif(CMAKE_COMPILER_IS_GNUC AND CMAKE_C_COMPILER_VERSION VERSION_LESS "4.2") + set(GCC_TOO_OLD TRUE) + message(WARNING "GCC version older than 4.2") + elseif(CMAKE_CXX_COMPILER_ID MATCHES Intel AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS "12.0") + set(_INTEL_TOO_OLD TRUE) + message(WARNING "Intel compiler older than 12.0") + endif() + + + # Exclude XL here because it misinterprets -fvisibility=hidden even though + # the check_cxx_compiler_flag passes + # http://www.cdash.org/CDash/testDetails.php?test=109109951&build=1419259 + if(NOT GCC_TOO_OLD + AND NOT _INTEL_TOO_OLD + AND NOT WIN32 + AND NOT CYGWIN + AND NOT "${CMAKE_CXX_COMPILER_ID}" MATCHES XL + AND NOT "${CMAKE_CXX_COMPILER_ID}" MATCHES PGI + AND NOT "${CMAKE_CXX_COMPILER_ID}" MATCHES Watcom) + check_cxx_compiler_flag(-fvisibility=hidden COMPILER_HAS_HIDDEN_VISIBILITY) + check_cxx_compiler_flag(-fvisibility-inlines-hidden + COMPILER_HAS_HIDDEN_INLINE_VISIBILITY) + option(USE_COMPILER_HIDDEN_VISIBILITY + "Use HIDDEN visibility support if available." ON) + mark_as_advanced(USE_COMPILER_HIDDEN_VISIBILITY) + endif() +endmacro() + +macro(_test_compiler_has_deprecated) + if("${CMAKE_CXX_COMPILER_ID}" MATCHES Borland + OR "${CMAKE_CXX_COMPILER_ID}" MATCHES HP + OR GCC_TOO_OLD + OR "${CMAKE_CXX_COMPILER_ID}" MATCHES PGI + OR "${CMAKE_CXX_COMPILER_ID}" MATCHES Watcom) + set(COMPILER_HAS_DEPRECATED "" CACHE INTERNAL + "Compiler support for a deprecated attribute") + else() + _check_cxx_compiler_attribute("__attribute__((__deprecated__))" + COMPILER_HAS_DEPRECATED_ATTR) + if(COMPILER_HAS_DEPRECATED_ATTR) + set(COMPILER_HAS_DEPRECATED "${COMPILER_HAS_DEPRECATED_ATTR}" + CACHE INTERNAL "Compiler support for a deprecated attribute") + else() + _check_cxx_compiler_attribute("__declspec(deprecated)" + COMPILER_HAS_DEPRECATED) + endif() + endif() +endmacro() + +get_filename_component(_GENERATE_EXPORT_HEADER_MODULE_DIR + "${CMAKE_CURRENT_LIST_FILE}" PATH) + +macro(_DO_SET_MACRO_VALUES TARGET_LIBRARY) + set(DEFINE_DEPRECATED) + set(DEFINE_EXPORT) + set(DEFINE_IMPORT) + set(DEFINE_NO_EXPORT) + + if (COMPILER_HAS_DEPRECATED_ATTR) + set(DEFINE_DEPRECATED "__attribute__ ((__deprecated__))") + elseif(COMPILER_HAS_DEPRECATED) + set(DEFINE_DEPRECATED "__declspec(deprecated)") + endif() + + get_property(type TARGET ${TARGET_LIBRARY} PROPERTY TYPE) + + if(NOT ${type} STREQUAL "STATIC_LIBRARY") + if(WIN32) + set(DEFINE_EXPORT "__declspec(dllexport)") + set(DEFINE_IMPORT "__declspec(dllimport)") + elseif(COMPILER_HAS_HIDDEN_VISIBILITY AND USE_COMPILER_HIDDEN_VISIBILITY) + set(DEFINE_EXPORT "__attribute__((visibility(\"default\")))") + set(DEFINE_IMPORT "__attribute__((visibility(\"default\")))") + set(DEFINE_NO_EXPORT "__attribute__((visibility(\"hidden\")))") + endif() + endif() +endmacro() + +macro(_DO_GENERATE_EXPORT_HEADER TARGET_LIBRARY) + # Option overrides + set(options DEFINE_NO_DEPRECATED) + set(oneValueArgs PREFIX_NAME BASE_NAME EXPORT_MACRO_NAME EXPORT_FILE_NAME + DEPRECATED_MACRO_NAME NO_EXPORT_MACRO_NAME STATIC_DEFINE + NO_DEPRECATED_MACRO_NAME) + set(multiValueArgs) + + cmake_parse_arguments(_GEH "${options}" "${oneValueArgs}" "${multiValueArgs}" + ${ARGN}) + + set(BASE_NAME "${TARGET_LIBRARY}") + + if(_GEH_BASE_NAME) + set(BASE_NAME ${_GEH_BASE_NAME}) + endif() + + string(TOUPPER ${BASE_NAME} BASE_NAME_UPPER) + string(TOLOWER ${BASE_NAME} BASE_NAME_LOWER) + + # Default options + set(EXPORT_MACRO_NAME "${_GEH_PREFIX_NAME}${BASE_NAME_UPPER}_EXPORT") + set(NO_EXPORT_MACRO_NAME "${_GEH_PREFIX_NAME}${BASE_NAME_UPPER}_NO_EXPORT") + set(EXPORT_FILE_NAME "${CMAKE_CURRENT_BINARY_DIR}/${BASE_NAME_LOWER}_export.h") + set(DEPRECATED_MACRO_NAME "${_GEH_PREFIX_NAME}${BASE_NAME_UPPER}_DEPRECATED") + set(STATIC_DEFINE "${_GEH_PREFIX_NAME}${BASE_NAME_UPPER}_STATIC_DEFINE") + set(NO_DEPRECATED_MACRO_NAME + "${_GEH_PREFIX_NAME}${BASE_NAME_UPPER}_NO_DEPRECATED") + + if(_GEH_UNPARSED_ARGUMENTS) + message(FATAL_ERROR "Unknown keywords given to GENERATE_EXPORT_HEADER(): \"${_GEH_UNPARSED_ARGUMENTS}\"") + endif() + + if(_GEH_EXPORT_MACRO_NAME) + set(EXPORT_MACRO_NAME ${_GEH_PREFIX_NAME}${_GEH_EXPORT_MACRO_NAME}) + endif() + if(_GEH_EXPORT_FILE_NAME) + if(IS_ABSOLUTE ${_GEH_EXPORT_FILE_NAME}) + set(EXPORT_FILE_NAME ${_GEH_EXPORT_FILE_NAME}) + else() + set(EXPORT_FILE_NAME "${CMAKE_CURRENT_BINARY_DIR}/${_GEH_EXPORT_FILE_NAME}") + endif() + endif() + if(_GEH_DEPRECATED_MACRO_NAME) + set(DEPRECATED_MACRO_NAME ${_GEH_PREFIX_NAME}${_GEH_DEPRECATED_MACRO_NAME}) + endif() + if(_GEH_NO_EXPORT_MACRO_NAME) + set(NO_EXPORT_MACRO_NAME ${_GEH_PREFIX_NAME}${_GEH_NO_EXPORT_MACRO_NAME}) + endif() + if(_GEH_STATIC_DEFINE) + set(STATIC_DEFINE ${_GEH_PREFIX_NAME}${_GEH_STATIC_DEFINE}) + endif() + + if(_GEH_DEFINE_NO_DEPRECATED) + set(DEFINE_NO_DEPRECATED TRUE) + endif() + + if(_GEH_NO_DEPRECATED_MACRO_NAME) + set(NO_DEPRECATED_MACRO_NAME + ${_GEH_PREFIX_NAME}${_GEH_NO_DEPRECATED_MACRO_NAME}) + endif() + + set(INCLUDE_GUARD_NAME "${EXPORT_MACRO_NAME}_H") + + get_target_property(EXPORT_IMPORT_CONDITION ${TARGET_LIBRARY} DEFINE_SYMBOL) + + if(NOT EXPORT_IMPORT_CONDITION) + set(EXPORT_IMPORT_CONDITION ${TARGET_LIBRARY}_EXPORTS) + endif() + + configure_file("${_GENERATE_EXPORT_HEADER_MODULE_DIR}/exportheader.cmake.in" + "${EXPORT_FILE_NAME}" @ONLY) +endmacro() + +function(GENERATE_EXPORT_HEADER TARGET_LIBRARY) + get_property(type TARGET ${TARGET_LIBRARY} PROPERTY TYPE) + if(${type} STREQUAL "MODULE") + message(WARNING "This macro should not be used with libraries of type MODULE") + return() + endif() + if(NOT ${type} STREQUAL "STATIC_LIBRARY" AND NOT ${type} STREQUAL "SHARED_LIBRARY") + message(WARNING "This macro can only be used with libraries") + return() + endif() + _test_compiler_hidden_visibility() + _test_compiler_has_deprecated() + _do_set_macro_values(${TARGET_LIBRARY}) + _do_generate_export_header(${TARGET_LIBRARY} ${ARGN}) +endfunction() + +function(add_compiler_export_flags) + + _test_compiler_hidden_visibility() + _test_compiler_has_deprecated() + + if(NOT (USE_COMPILER_HIDDEN_VISIBILITY AND COMPILER_HAS_HIDDEN_VISIBILITY)) + # Just return if there are no flags to add. + return() + endif() + + set (EXTRA_FLAGS "-fvisibility=hidden") + + if(COMPILER_HAS_HIDDEN_INLINE_VISIBILITY) + set (EXTRA_FLAGS "${EXTRA_FLAGS} -fvisibility-inlines-hidden") + endif() + + # Either return the extra flags needed in the supplied argument, or to the + # CMAKE_CXX_FLAGS if no argument is supplied. + if(ARGV0) + set(${ARGV0} "${EXTRA_FLAGS}" PARENT_SCOPE) + else() + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${EXTRA_FLAGS}" PARENT_SCOPE) + endif() +endfunction() diff --git a/orocos_kdl/config/cmakemoduleslegacy/ReadMe.txt b/orocos_kdl/config/cmakemoduleslegacy/ReadMe.txt new file mode 100644 index 0000000..9b019cd --- /dev/null +++ b/orocos_kdl/config/cmakemoduleslegacy/ReadMe.txt @@ -0,0 +1 @@ +Contains CMake modules that are only needed by certain older versions of CMake. \ No newline at end of file diff --git a/orocos_kdl/config/cmakemoduleslegacy/exportheader.cmake.in b/orocos_kdl/config/cmakemoduleslegacy/exportheader.cmake.in new file mode 100644 index 0000000..80a879d --- /dev/null +++ b/orocos_kdl/config/cmakemoduleslegacy/exportheader.cmake.in @@ -0,0 +1,35 @@ + +#ifndef @INCLUDE_GUARD_NAME@ +#define @INCLUDE_GUARD_NAME@ + +#ifdef @STATIC_DEFINE@ +# define @EXPORT_MACRO_NAME@ +# define @NO_EXPORT_MACRO_NAME@ +#else +# ifndef @EXPORT_MACRO_NAME@ +# ifdef @EXPORT_IMPORT_CONDITION@ + /* We are building this library */ +# define @EXPORT_MACRO_NAME@ @DEFINE_EXPORT@ +# else + /* We are using this library */ +# define @EXPORT_MACRO_NAME@ @DEFINE_IMPORT@ +# endif +# endif + +# ifndef @NO_EXPORT_MACRO_NAME@ +# define @NO_EXPORT_MACRO_NAME@ @DEFINE_NO_EXPORT@ +# endif +#endif + +#ifndef @DEPRECATED_MACRO_NAME@ +# define @DEPRECATED_MACRO_NAME@ @DEFINE_DEPRECATED@ +# define @DEPRECATED_MACRO_NAME@_EXPORT @EXPORT_MACRO_NAME@ @DEFINE_DEPRECATED@ +# define @DEPRECATED_MACRO_NAME@_NO_EXPORT @NO_EXPORT_MACRO_NAME@ @DEFINE_DEPRECATED@ +#endif + +#cmakedefine01 DEFINE_NO_DEPRECATED +#if DEFINE_NO_DEPRECATED +# define @NO_DEPRECATED_MACRO_NAME@ +#endif + +#endif diff --git a/orocos_kdl/examples/CMakeLists.txt b/orocos_kdl/examples/CMakeLists.txt index 616a760..b2d69ce 100644 --- a/orocos_kdl/examples/CMakeLists.txt +++ b/orocos_kdl/examples/CMakeLists.txt @@ -1,5 +1,5 @@ IF(ENABLE_EXAMPLES) -INCLUDE_DIRECTORIES(${PROJ_SOURCE_DIR}/src ${PROJ_SOURCE_DIR}/models) +INCLUDE_DIRECTORIES(${PROJ_SOURCE_DIR}/src ${PROJ_SOURCE_DIR}/models ${PROJ_BINARY_DIR}/src ${PROJ_BINARY_DIR}/models) add_executable(geometry geometry.cpp ) TARGET_LINK_LIBRARIES(geometry orocos-kdl) diff --git a/orocos_kdl/examples/geometry.cpp b/orocos_kdl/examples/geometry.cpp index 141ff04..99f44ff 100644 --- a/orocos_kdl/examples/geometry.cpp +++ b/orocos_kdl/examples/geometry.cpp @@ -1,6 +1,9 @@ #include #include +#define _USE_MATH_DEFINES // For MSVC +#include + int main() { diff --git a/orocos_kdl/examples/trajectory_example.cpp b/orocos_kdl/examples/trajectory_example.cpp index 99908fe..7995c72 100644 --- a/orocos_kdl/examples/trajectory_example.cpp +++ b/orocos_kdl/examples/trajectory_example.cpp @@ -21,6 +21,9 @@ #include #include +#define _USE_MATH_DEFINES // For MSVC +#include + int main(int argc,char* argv[]) { using namespace KDL; // Create the trajectory: diff --git a/orocos_kdl/models/CMakeLists.txt b/orocos_kdl/models/CMakeLists.txt index de8a567..b4be7ed 100644 --- a/orocos_kdl/models/CMakeLists.txt +++ b/orocos_kdl/models/CMakeLists.txt @@ -1,18 +1,23 @@ OPTION(BUILD_MODELS "Build models for some well known robots" FALSE) IF(BUILD_MODELS) - + INCLUDE(GenerateExportHeader) + ADD_COMPILER_EXPORT_FLAGS() ADD_LIBRARY(orocos-kdl-models SHARED puma560.cpp kukaLWR_DHnew.cpp) - INCLUDE_DIRECTORIES(${PROJ_SOURCE_DIR}/src) + INCLUDE_DIRECTORIES(${PROJ_SOURCE_DIR}/src ${PROJ_BINARY_DIR}/src ${CMAKE_CURRENT_BINARY_DIR}) SET_TARGET_PROPERTIES( orocos-kdl-models PROPERTIES SOVERSION "${KDL_VERSION_MAJOR}.${KDL_VERSION_MINOR}" VERSION "${KDL_VERSION}" COMPILE_FLAGS "${CMAKE_CXX_FLAGS_ADD} ${KDL_CFLAGS}" - INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib") + INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib" + DEFINE_SYMBOL OROCOS_KDL_MODELS_EXPORTS + LINKER_LANGUAGE CXX) + GENERATE_EXPORT_HEADER(orocos-kdl-models BASE_NAME KDL_MODELS EXPORT_FILE_NAME kdl_models_export.hpp) TARGET_LINK_LIBRARIES(orocos-kdl-models orocos-kdl) INSTALL_TARGETS( /lib orocos-kdl-models) INSTALL_FILES( /include/kdl FILES models.hpp) + INSTALL_FILES( /include/kdl FILES ${CMAKE_CURRENT_BINARY_DIR}/kdl_models_export.hpp) ENDIF(BUILD_MODELS) INCLUDE(CMakeDependentOption) diff --git a/orocos_kdl/models/models.hpp b/orocos_kdl/models/models.hpp index 90ed895..ab0519d 100644 --- a/orocos_kdl/models/models.hpp +++ b/orocos_kdl/models/models.hpp @@ -22,14 +22,16 @@ #ifndef MODELS_HPP #define MODELS_HPP +#include + namespace KDL{ class Chain; -Chain Puma560(); -Chain KukaLWR(); -Chain KukaLWRsegment(); -Chain KukaLWR_DHnew(); +KDL_MODELS_EXPORT Chain Puma560(); +KDL_MODELS_EXPORT Chain KukaLWR(); +KDL_MODELS_EXPORT Chain KukaLWRsegment(); +KDL_MODELS_EXPORT Chain KukaLWR_DHnew(); } #endif \ No newline at end of file diff --git a/orocos_kdl/models/puma560.cpp b/orocos_kdl/models/puma560.cpp index 6074428..b084ac6 100644 --- a/orocos_kdl/models/puma560.cpp +++ b/orocos_kdl/models/puma560.cpp @@ -22,6 +22,9 @@ #include #include "models.hpp" +#define _USE_MATH_DEFINES // For MSVC +#include + namespace KDL{ Chain Puma560(){ Chain puma560; diff --git a/orocos_kdl/src/CMakeLists.txt b/orocos_kdl/src/CMakeLists.txt index 813d918..6760cf9 100644 --- a/orocos_kdl/src/CMakeLists.txt +++ b/orocos_kdl/src/CMakeLists.txt @@ -1,21 +1,32 @@ + +INCLUDE(GenerateExportHeader) + FILE( GLOB KDL_SRCS [^.]*.cpp ) FILE( GLOB KDL_HPPS [^.]*.hpp [^.]*.inl) FILE( GLOB UTIL_SRCS utilities/[^.]*.cpp utilities/[^.]*.cxx) FILE( GLOB UTIL_HPPS utilities/[^.]*.h utilities/[^.]*.hpp) +ADD_COMPILER_EXPORT_FLAGS() + ADD_LIBRARY(orocos-kdl SHARED ${KDL_SRCS} ${UTIL_SRCS}) SET_TARGET_PROPERTIES( orocos-kdl PROPERTIES SOVERSION "${KDL_VERSION_MAJOR}.${KDL_VERSION_MINOR}" VERSION "${KDL_VERSION}" COMPILE_FLAGS "${CMAKE_CXX_FLAGS_ADD} ${KDL_CFLAGS}" - INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib") + INSTALL_NAME_DIR "${CMAKE_INSTALL_PREFIX}/lib" + DEFINE_SYMBOL OROCOS_KDL_EXPORTS + LINKER_LANGUAGE CXX) +GENERATE_EXPORT_HEADER(orocos-kdl BASE_NAME KDL EXPORT_FILE_NAME kdl_export.hpp) +INCLUDE_DIRECTORIES(${CMAKE_CURRENT_BINARY_DIR}) + INSTALL_TARGETS( /lib orocos-kdl) # CMake 2.2: INSTALL_FILES( /include/kdl FILES ${KDL_HPPS}) INSTALL_FILES( /include/kdl/utilities FILES ${UTIL_HPPS}) +INSTALL_FILES( /include/kdl FILES ${CMAKE_CURRENT_BINARY_DIR}/kdl_export.hpp) # Orocos convention: CONFIGURE_FILE( kdl.pc.in ${CMAKE_CURRENT_BINARY_DIR}/orocos-kdl.pc @ONLY) diff --git a/orocos_kdl/src/articulatedbodyinertia.hpp b/orocos_kdl/src/articulatedbodyinertia.hpp index e2524a7..3e2504a 100644 --- a/orocos_kdl/src/articulatedbodyinertia.hpp +++ b/orocos_kdl/src/articulatedbodyinertia.hpp @@ -26,6 +26,7 @@ #include "rotationalinertia.hpp" #include "rigidbodyinertia.hpp" +#include "kdl_export.hpp" #include @@ -37,7 +38,7 @@ namespace KDL { * The inertia is defined in a certain reference point and a certain reference base. * The reference point does not have to coincide with the origin of the reference frame. */ - class ArticulatedBodyInertia{ + class KDL_EXPORT ArticulatedBodyInertia{ public: /** @@ -72,32 +73,32 @@ namespace KDL { /** * Scalar product: I_new = double * I_old */ - friend ArticulatedBodyInertia operator*(double a,const ArticulatedBodyInertia& I); + KDL_EXPORT friend ArticulatedBodyInertia operator*(double a,const ArticulatedBodyInertia& I); /** * addition I: I_new = I_old1 + I_old2, make sure that I_old1 * and I_old2 are expressed in the same reference frame/point, * otherwise the result is worth nothing */ - friend ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& Ia,const ArticulatedBodyInertia& Ib); - friend ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& Ia,const RigidBodyInertia& Ib); - friend ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& Ia,const ArticulatedBodyInertia& Ib); - friend ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& Ia,const RigidBodyInertia& Ib); + KDL_EXPORT friend ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& Ia,const ArticulatedBodyInertia& Ib); + KDL_EXPORT friend ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& Ia,const RigidBodyInertia& Ib); + KDL_EXPORT friend ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& Ia,const ArticulatedBodyInertia& Ib); + KDL_EXPORT friend ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& Ia,const RigidBodyInertia& Ib); /** * calculate spatial momentum: h = I*v * make sure that the twist v and the inertia are expressed in the same reference frame/point */ - friend Wrench operator*(const ArticulatedBodyInertia& I,const Twist& t); + KDL_EXPORT friend Wrench operator*(const ArticulatedBodyInertia& I,const Twist& t); /** * Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b. */ - friend ArticulatedBodyInertia operator*(const Frame& T,const ArticulatedBodyInertia& I); + KDL_EXPORT friend ArticulatedBodyInertia operator*(const Frame& T,const ArticulatedBodyInertia& I); /** * Reference frame orientation change Ia = R_a_b*Ib with R_a_b * the rotation of b expressed in a */ - friend ArticulatedBodyInertia operator*(const Rotation& R,const ArticulatedBodyInertia& I); + KDL_EXPORT friend ArticulatedBodyInertia operator*(const Rotation& R,const ArticulatedBodyInertia& I); /** * Reference point change with v the vector from the old to diff --git a/orocos_kdl/src/chain.hpp b/orocos_kdl/src/chain.hpp index 5dcb862..bfc0bcc 100644 --- a/orocos_kdl/src/chain.hpp +++ b/orocos_kdl/src/chain.hpp @@ -23,6 +23,7 @@ #define KDL_CHAIN_HPP #include "segment.hpp" +#include "kdl_export.hpp" #include namespace KDL { @@ -32,7 +33,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class Chain { + class KDL_EXPORT Chain { private: int nrOfJoints; int nrOfSegments; diff --git a/orocos_kdl/src/chaindynparam.hpp b/orocos_kdl/src/chaindynparam.hpp index bac007c..5d24a5d 100644 --- a/orocos_kdl/src/chaindynparam.hpp +++ b/orocos_kdl/src/chaindynparam.hpp @@ -25,6 +25,7 @@ #include "chainidsolver_recursive_newton_euler.hpp" #include "articulatedbodyinertia.hpp" #include "jntspaceinertiamatrix.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -43,7 +44,7 @@ namespace KDL { * (expressed in the segments reference frame) and the dynamical * parameters of the segments. */ - class ChainDynParam + class KDL_EXPORT ChainDynParam { public: ChainDynParam(const Chain& chain, Vector _grav); diff --git a/orocos_kdl/src/chainfksolver.hpp b/orocos_kdl/src/chainfksolver.hpp index fa6f625..baebb92 100644 --- a/orocos_kdl/src/chainfksolver.hpp +++ b/orocos_kdl/src/chainfksolver.hpp @@ -28,6 +28,7 @@ #include "jntarray.hpp" #include "jntarrayvel.hpp" #include "jntarrayacc.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -38,8 +39,7 @@ namespace KDL { * @ingroup KinematicFamily */ - //Forward definition - class ChainFkSolverPos { + class KDL_EXPORT ChainFkSolverPos { public: /** * Calculate forward position kinematics for a KDL::Chain, @@ -60,7 +60,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class ChainFkSolverVel { + class KDL_EXPORT ChainFkSolverVel { public: /** * Calculate forward position and velocity kinematics, from @@ -83,7 +83,7 @@ namespace KDL { * @ingroup KinematicFamily */ - class ChainFkSolverAcc { + class KDL_EXPORT ChainFkSolverAcc { public: /** * Calculate forward position, velocity and accelaration @@ -98,7 +98,7 @@ namespace KDL { */ virtual int JntToCart(const JntArrayAcc& q_in, FrameAcc& out,int segmentNr=-1)=0; - virtual ~ChainFkSolverAcc()=0; + virtual ~ChainFkSolverAcc(){}; }; diff --git a/orocos_kdl/src/chainfksolverpos_recursive.hpp b/orocos_kdl/src/chainfksolverpos_recursive.hpp index 72cdab0..8d8ecf8 100644 --- a/orocos_kdl/src/chainfksolverpos_recursive.hpp +++ b/orocos_kdl/src/chainfksolverpos_recursive.hpp @@ -23,6 +23,7 @@ #define KDLCHAINFKSOLVERPOS_RECURSIVE_HPP #include "chainfksolver.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -33,7 +34,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class ChainFkSolverPos_recursive : public ChainFkSolverPos + class KDL_EXPORT ChainFkSolverPos_recursive : public ChainFkSolverPos { public: ChainFkSolverPos_recursive(const Chain& chain); diff --git a/orocos_kdl/src/chainfksolvervel_recursive.hpp b/orocos_kdl/src/chainfksolvervel_recursive.hpp index b6b58b8..26787a9 100644 --- a/orocos_kdl/src/chainfksolvervel_recursive.hpp +++ b/orocos_kdl/src/chainfksolvervel_recursive.hpp @@ -23,6 +23,7 @@ #define KDL_CHAIN_FKSOLVERVEL_RECURSIVE_HPP #include "chainfksolver.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -34,7 +35,7 @@ namespace KDL * * @ingroup KinematicFamily */ - class ChainFkSolverVel_recursive : public ChainFkSolverVel + class KDL_EXPORT ChainFkSolverVel_recursive : public ChainFkSolverVel { public: ChainFkSolverVel_recursive(const Chain& chain); diff --git a/orocos_kdl/src/chainidsolver.hpp b/orocos_kdl/src/chainidsolver.hpp index b7f4636..925fe69 100644 --- a/orocos_kdl/src/chainidsolver.hpp +++ b/orocos_kdl/src/chainidsolver.hpp @@ -25,6 +25,7 @@ #include "chain.hpp" #include "frames.hpp" #include "jntarray.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -36,7 +37,7 @@ namespace KDL * dynamics solver for a KDL::Chain. * */ - class ChainIdSolver + class KDL_EXPORT ChainIdSolver { public: /** diff --git a/orocos_kdl/src/chainidsolver_recursive_newton_euler.hpp b/orocos_kdl/src/chainidsolver_recursive_newton_euler.hpp index 3140cd2..89aae85 100644 --- a/orocos_kdl/src/chainidsolver_recursive_newton_euler.hpp +++ b/orocos_kdl/src/chainidsolver_recursive_newton_euler.hpp @@ -23,6 +23,7 @@ #define KDL_CHAIN_IKSOLVER_RECURSIVE_NEWTON_EULER_HPP #include "chainidsolver.hpp" +#include "kdl_export.hpp" namespace KDL{ /** @@ -37,7 +38,7 @@ namespace KDL{ * (expressed in the segments reference frame) and the dynamical * parameters of the segments. */ - class ChainIdSolver_RNE : public ChainIdSolver{ + class KDL_EXPORT ChainIdSolver_RNE : public ChainIdSolver{ public: /** * Constructor for the solver, it will allocate all the necessary memory diff --git a/orocos_kdl/src/chainidsolver_vereshchagin.hpp b/orocos_kdl/src/chainidsolver_vereshchagin.hpp index 9038b25..84a9a31 100644 --- a/orocos_kdl/src/chainidsolver_vereshchagin.hpp +++ b/orocos_kdl/src/chainidsolver_vereshchagin.hpp @@ -25,6 +25,7 @@ #include "chainidsolver.hpp" #include "frames.hpp" #include "articulatedbodyinertia.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -40,7 +41,7 @@ typedef Eigen::Matrix Vector6d; typedef Eigen::Matrix Matrix6d; typedef Eigen::Matrix Matrix6Xd; -class ChainIdSolver_Vereshchagin +class KDL_EXPORT ChainIdSolver_Vereshchagin { public: /** diff --git a/orocos_kdl/src/chainiksolver.hpp b/orocos_kdl/src/chainiksolver.hpp index 4daed84..2bb1572 100644 --- a/orocos_kdl/src/chainiksolver.hpp +++ b/orocos_kdl/src/chainiksolver.hpp @@ -29,6 +29,7 @@ #include "jntarray.hpp" #include "jntarrayvel.hpp" #include "jntarrayacc.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -38,7 +39,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class ChainIkSolverPos { + class KDL_EXPORT ChainIkSolverPos { public: /** * Calculate inverse position kinematics, from cartesian @@ -61,7 +62,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class ChainIkSolverVel { + class KDL_EXPORT ChainIkSolverVel { public: /** * Calculate inverse velocity kinematics, from joint positions @@ -97,7 +98,7 @@ namespace KDL { * @ingroup KinematicFamily */ - class ChainIkSolverAcc { + class KDL_EXPORT ChainIkSolverAcc { public: /** * Calculate inverse acceleration kinematics from joint diff --git a/orocos_kdl/src/chainiksolverpos_lma.hpp b/orocos_kdl/src/chainiksolverpos_lma.hpp index 842a9c0..06bc00e 100644 --- a/orocos_kdl/src/chainiksolverpos_lma.hpp +++ b/orocos_kdl/src/chainiksolverpos_lma.hpp @@ -33,6 +33,7 @@ #include "chainiksolver.hpp" #include "chain.hpp" +#include "kdl_export.hpp" #include namespace KDL @@ -61,7 +62,7 @@ namespace KDL * \ingroup KinematicFamily */ -class ChainIkSolverPos_LMA : public KDL::ChainIkSolverPos +class KDL_EXPORT ChainIkSolverPos_LMA : public KDL::ChainIkSolverPos { private: typedef double ScalarType; diff --git a/orocos_kdl/src/chainiksolverpos_nr.hpp b/orocos_kdl/src/chainiksolverpos_nr.hpp index f49ff9a..ed0dfb6 100644 --- a/orocos_kdl/src/chainiksolverpos_nr.hpp +++ b/orocos_kdl/src/chainiksolverpos_nr.hpp @@ -24,6 +24,7 @@ #include "chainiksolver.hpp" #include "chainfksolver.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -35,7 +36,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class ChainIkSolverPos_NR : public ChainIkSolverPos + class KDL_EXPORT ChainIkSolverPos_NR : public ChainIkSolverPos { public: /** diff --git a/orocos_kdl/src/chainiksolverpos_nr_jl.hpp b/orocos_kdl/src/chainiksolverpos_nr_jl.hpp index 9d42945..a3cee5c 100644 --- a/orocos_kdl/src/chainiksolverpos_nr_jl.hpp +++ b/orocos_kdl/src/chainiksolverpos_nr_jl.hpp @@ -26,6 +26,7 @@ #include "chainiksolver.hpp" #include "chainfksolver.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -37,7 +38,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class ChainIkSolverPos_NR_JL : public ChainIkSolverPos + class KDL_EXPORT ChainIkSolverPos_NR_JL : public ChainIkSolverPos { public: /** diff --git a/orocos_kdl/src/chainiksolvervel_pinv.hpp b/orocos_kdl/src/chainiksolvervel_pinv.hpp index 37b4c77..f998360 100644 --- a/orocos_kdl/src/chainiksolvervel_pinv.hpp +++ b/orocos_kdl/src/chainiksolvervel_pinv.hpp @@ -25,6 +25,7 @@ #include "chainiksolver.hpp" #include "chainjnttojacsolver.hpp" #include "utilities/svd_HH.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -37,7 +38,7 @@ namespace KDL * * @ingroup KinematicFamily */ - class ChainIkSolverVel_pinv : public ChainIkSolverVel + class KDL_EXPORT ChainIkSolverVel_pinv : public ChainIkSolverVel { public: /** diff --git a/orocos_kdl/src/chainiksolvervel_pinv_givens.hpp b/orocos_kdl/src/chainiksolvervel_pinv_givens.hpp index 04b1e0b..9e2a668 100644 --- a/orocos_kdl/src/chainiksolvervel_pinv_givens.hpp +++ b/orocos_kdl/src/chainiksolvervel_pinv_givens.hpp @@ -5,6 +5,7 @@ #include "chainiksolver.hpp" #include "chainjnttojacsolver.hpp" +#include "kdl_export.hpp" #include @@ -21,7 +22,7 @@ namespace KDL * * @ingroup KinematicFamily */ - class ChainIkSolverVel_pinv_givens : public ChainIkSolverVel + class KDL_EXPORT ChainIkSolverVel_pinv_givens : public ChainIkSolverVel { public: /** diff --git a/orocos_kdl/src/chainiksolvervel_pinv_nso.hpp b/orocos_kdl/src/chainiksolvervel_pinv_nso.hpp index 8577024..709a90d 100644 --- a/orocos_kdl/src/chainiksolvervel_pinv_nso.hpp +++ b/orocos_kdl/src/chainiksolvervel_pinv_nso.hpp @@ -25,6 +25,7 @@ #include "chainiksolver.hpp" #include "chainjnttojacsolver.hpp" #include "utilities/svd_HH.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -43,7 +44,7 @@ namespace KDL * * @ingroup KinematicFamily */ - class ChainIkSolverVel_pinv_nso : public ChainIkSolverVel + class KDL_EXPORT ChainIkSolverVel_pinv_nso : public ChainIkSolverVel { public: /** diff --git a/orocos_kdl/src/chainiksolvervel_wdls.hpp b/orocos_kdl/src/chainiksolvervel_wdls.hpp index 176e811..fa43850 100644 --- a/orocos_kdl/src/chainiksolvervel_wdls.hpp +++ b/orocos_kdl/src/chainiksolvervel_wdls.hpp @@ -24,6 +24,7 @@ #include "chainiksolver.hpp" #include "chainjnttojacsolver.hpp" +#include "kdl_export.hpp" #include namespace KDL @@ -60,7 +61,7 @@ namespace KDL * * @ingroup KinematicFamily */ - class ChainIkSolverVel_wdls : public ChainIkSolverVel + class KDL_EXPORT ChainIkSolverVel_wdls : public ChainIkSolverVel { public: /** diff --git a/orocos_kdl/src/chainjnttojacsolver.hpp b/orocos_kdl/src/chainjnttojacsolver.hpp index 18e2ca5..2b92729 100644 --- a/orocos_kdl/src/chainjnttojacsolver.hpp +++ b/orocos_kdl/src/chainjnttojacsolver.hpp @@ -26,6 +26,7 @@ #include "jacobian.hpp" #include "jntarray.hpp" #include "chain.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -37,7 +38,7 @@ namespace KDL * */ - class ChainJntToJacSolver + class KDL_EXPORT ChainJntToJacSolver { public: explicit ChainJntToJacSolver(const Chain& chain); diff --git a/orocos_kdl/src/frameacc.hpp b/orocos_kdl/src/frameacc.hpp index 5d5279b..9e8e8c9 100644 --- a/orocos_kdl/src/frameacc.hpp +++ b/orocos_kdl/src/frameacc.hpp @@ -32,8 +32,7 @@ #include "utilities/rall2d.h" #include "frames.hpp" - - +#include "kdl_export.hpp" namespace KDL { @@ -41,7 +40,7 @@ class TwistAcc; typedef Rall2d doubleAcc; -class VectorAcc +class KDL_EXPORT VectorAcc { public: Vector p; //!< position vector @@ -60,37 +59,37 @@ public: IMETHOD static VectorAcc Zero(); IMETHOD void ReverseSign(); IMETHOD doubleAcc Norm(); - IMETHOD friend VectorAcc operator + (const VectorAcc& r1,const VectorAcc& r2); - IMETHOD friend VectorAcc operator - (const VectorAcc& r1,const VectorAcc& r2); - IMETHOD friend VectorAcc operator + (const Vector& r1,const VectorAcc& r2); - IMETHOD friend VectorAcc operator - (const Vector& r1,const VectorAcc& r2); - IMETHOD friend VectorAcc operator + (const VectorAcc& r1,const Vector& r2); - IMETHOD friend VectorAcc operator - (const VectorAcc& r1,const Vector& r2); - IMETHOD friend VectorAcc operator * (const VectorAcc& r1,const VectorAcc& r2); - IMETHOD friend VectorAcc operator * (const VectorAcc& r1,const Vector& r2); - IMETHOD friend VectorAcc operator * (const Vector& r1,const VectorAcc& r2); - IMETHOD friend VectorAcc operator * (const VectorAcc& r1,double r2); - IMETHOD friend VectorAcc operator * (double r1,const VectorAcc& r2); - IMETHOD friend VectorAcc operator * (const doubleAcc& r1,const VectorAcc& r2); - IMETHOD friend VectorAcc operator * (const VectorAcc& r2,const doubleAcc& r1); - IMETHOD friend VectorAcc operator*(const Rotation& R,const VectorAcc& x); - - IMETHOD friend VectorAcc operator / (const VectorAcc& r1,double r2); - IMETHOD friend VectorAcc operator / (const VectorAcc& r2,const doubleAcc& r1); - - - IMETHOD friend bool Equal(const VectorAcc& r1,const VectorAcc& r2,double eps=epsilon); - IMETHOD friend bool Equal(const Vector& r1,const VectorAcc& r2,double eps=epsilon); - IMETHOD friend bool Equal(const VectorAcc& r1,const Vector& r2,double eps=epsilon); - IMETHOD friend VectorAcc operator - (const VectorAcc& r); - IMETHOD friend doubleAcc dot(const VectorAcc& lhs,const VectorAcc& rhs); - IMETHOD friend doubleAcc dot(const VectorAcc& lhs,const Vector& rhs); - IMETHOD friend doubleAcc dot(const Vector& lhs,const VectorAcc& rhs); + KDL_EXPORT IMETHOD friend VectorAcc operator + (const VectorAcc& r1,const VectorAcc& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator - (const VectorAcc& r1,const VectorAcc& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator + (const Vector& r1,const VectorAcc& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator - (const Vector& r1,const VectorAcc& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator + (const VectorAcc& r1,const Vector& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator - (const VectorAcc& r1,const Vector& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator * (const VectorAcc& r1,const VectorAcc& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator * (const VectorAcc& r1,const Vector& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator * (const Vector& r1,const VectorAcc& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator * (const VectorAcc& r1,double r2); + KDL_EXPORT IMETHOD friend VectorAcc operator * (double r1,const VectorAcc& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator * (const doubleAcc& r1,const VectorAcc& r2); + KDL_EXPORT IMETHOD friend VectorAcc operator * (const VectorAcc& r2,const doubleAcc& r1); + KDL_EXPORT IMETHOD friend VectorAcc operator*(const Rotation& R,const VectorAcc& x); + + KDL_EXPORT IMETHOD friend VectorAcc operator / (const VectorAcc& r1,double r2); + KDL_EXPORT IMETHOD friend VectorAcc operator / (const VectorAcc& r2,const doubleAcc& r1); + + + KDL_EXPORT IMETHOD friend bool Equal(const VectorAcc& r1,const VectorAcc& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const Vector& r1,const VectorAcc& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const VectorAcc& r1,const Vector& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend VectorAcc operator - (const VectorAcc& r); + KDL_EXPORT IMETHOD friend doubleAcc dot(const VectorAcc& lhs,const VectorAcc& rhs); + KDL_EXPORT IMETHOD friend doubleAcc dot(const VectorAcc& lhs,const Vector& rhs); + KDL_EXPORT IMETHOD friend doubleAcc dot(const Vector& lhs,const VectorAcc& rhs); }; -class RotationAcc +class KDL_EXPORT RotationAcc { public: Rotation R; //!< rotation matrix @@ -130,12 +129,12 @@ public: // rotvec is normalized. // rotation around a constant vector ! - IMETHOD friend RotationAcc operator* (const RotationAcc& r1,const RotationAcc& r2); - IMETHOD friend RotationAcc operator* (const Rotation& r1,const RotationAcc& r2); - IMETHOD friend RotationAcc operator* (const RotationAcc& r1,const Rotation& r2); - IMETHOD friend bool Equal(const RotationAcc& r1,const RotationAcc& r2,double eps=epsilon); - IMETHOD friend bool Equal(const Rotation& r1,const RotationAcc& r2,double eps=epsilon); - IMETHOD friend bool Equal(const RotationAcc& r1,const Rotation& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend RotationAcc operator* (const RotationAcc& r1,const RotationAcc& r2); + KDL_EXPORT IMETHOD friend RotationAcc operator* (const Rotation& r1,const RotationAcc& r2); + KDL_EXPORT IMETHOD friend RotationAcc operator* (const RotationAcc& r1,const Rotation& r2); + KDL_EXPORT IMETHOD friend bool Equal(const RotationAcc& r1,const RotationAcc& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const Rotation& r1,const RotationAcc& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const RotationAcc& r1,const Rotation& r2,double eps=epsilon); IMETHOD TwistAcc Inverse(const TwistAcc& arg) const; IMETHOD TwistAcc Inverse(const Twist& arg) const; IMETHOD TwistAcc operator * (const TwistAcc& arg) const; @@ -145,7 +144,7 @@ public: -class FrameAcc +class KDL_EXPORT FrameAcc { public: RotationAcc M; //!< Rotation,angular velocity, and angular acceleration of frame. @@ -168,12 +167,12 @@ public: IMETHOD Frame GetFrame() const; IMETHOD Twist GetTwist() const; IMETHOD Twist GetAccTwist() const; - IMETHOD friend FrameAcc operator * (const FrameAcc& f1,const FrameAcc& f2); - IMETHOD friend FrameAcc operator * (const Frame& f1,const FrameAcc& f2); - IMETHOD friend FrameAcc operator * (const FrameAcc& f1,const Frame& f2); - IMETHOD friend bool Equal(const FrameAcc& r1,const FrameAcc& r2,double eps=epsilon); - IMETHOD friend bool Equal(const Frame& r1,const FrameAcc& r2,double eps=epsilon); - IMETHOD friend bool Equal(const FrameAcc& r1,const Frame& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend FrameAcc operator * (const FrameAcc& f1,const FrameAcc& f2); + KDL_EXPORT IMETHOD friend FrameAcc operator * (const Frame& f1,const FrameAcc& f2); + KDL_EXPORT IMETHOD friend FrameAcc operator * (const FrameAcc& f1,const Frame& f2); + KDL_EXPORT IMETHOD friend bool Equal(const FrameAcc& r1,const FrameAcc& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const Frame& r1,const FrameAcc& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const FrameAcc& r1,const Frame& r2,double eps=epsilon); IMETHOD TwistAcc Inverse(const TwistAcc& arg) const; IMETHOD TwistAcc Inverse(const Twist& arg) const; @@ -189,7 +188,7 @@ public: //very similar to Wrench class. -class TwistAcc +class KDL_EXPORT TwistAcc { public: VectorAcc vel; //!< translational velocity and its 1st and 2nd derivative @@ -202,19 +201,19 @@ public: IMETHOD TwistAcc& operator-=(const TwistAcc& arg); IMETHOD TwistAcc& operator+=(const TwistAcc& arg); - IMETHOD friend TwistAcc operator*(const TwistAcc& lhs,double rhs); - IMETHOD friend TwistAcc operator*(double lhs,const TwistAcc& rhs); - IMETHOD friend TwistAcc operator/(const TwistAcc& lhs,double rhs); + KDL_EXPORT IMETHOD friend TwistAcc operator*(const TwistAcc& lhs,double rhs); + KDL_EXPORT IMETHOD friend TwistAcc operator*(double lhs,const TwistAcc& rhs); + KDL_EXPORT IMETHOD friend TwistAcc operator/(const TwistAcc& lhs,double rhs); - IMETHOD friend TwistAcc operator*(const TwistAcc& lhs,const doubleAcc& rhs); - IMETHOD friend TwistAcc operator*(const doubleAcc& lhs,const TwistAcc& rhs); - IMETHOD friend TwistAcc operator/(const TwistAcc& lhs,const doubleAcc& rhs); + KDL_EXPORT IMETHOD friend TwistAcc operator*(const TwistAcc& lhs,const doubleAcc& rhs); + KDL_EXPORT IMETHOD friend TwistAcc operator*(const doubleAcc& lhs,const TwistAcc& rhs); + KDL_EXPORT IMETHOD friend TwistAcc operator/(const TwistAcc& lhs,const doubleAcc& rhs); - IMETHOD friend TwistAcc operator+(const TwistAcc& lhs,const TwistAcc& rhs); - IMETHOD friend TwistAcc operator-(const TwistAcc& lhs,const TwistAcc& rhs); - IMETHOD friend TwistAcc operator-(const TwistAcc& arg); + KDL_EXPORT IMETHOD friend TwistAcc operator+(const TwistAcc& lhs,const TwistAcc& rhs); + KDL_EXPORT IMETHOD friend TwistAcc operator-(const TwistAcc& lhs,const TwistAcc& rhs); + KDL_EXPORT IMETHOD friend TwistAcc operator-(const TwistAcc& arg); - IMETHOD friend void SetToZero(TwistAcc& v); + KDL_EXPORT IMETHOD friend void SetToZero(TwistAcc& v); static IMETHOD TwistAcc Zero(); @@ -227,9 +226,9 @@ public: // the new point. // Complexity : 6M+6A - IMETHOD friend bool Equal(const TwistAcc& a,const TwistAcc& b,double eps=epsilon); - IMETHOD friend bool Equal(const Twist& a,const TwistAcc& b,double eps=epsilon); - IMETHOD friend bool Equal(const TwistAcc& a,const Twist& b,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const TwistAcc& a,const TwistAcc& b,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const Twist& a,const TwistAcc& b,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const TwistAcc& a,const Twist& b,double eps=epsilon); IMETHOD Twist GetTwist() const; diff --git a/orocos_kdl/src/frameacc_io.hpp b/orocos_kdl/src/frameacc_io.hpp index ee74fc7..ca229fd 100644 --- a/orocos_kdl/src/frameacc_io.hpp +++ b/orocos_kdl/src/frameacc_io.hpp @@ -24,28 +24,29 @@ #include "frames_io.hpp" #include "frameacc.hpp" +#include "kdl_export.hpp" namespace KDL { // Output... -inline std::ostream& operator << (std::ostream& os,const VectorAcc& r) { +KDL_EXPORT inline std::ostream& operator << (std::ostream& os,const VectorAcc& r) { os << "{" << r.p << "," << r.v << "," << r.dv << "}" << std::endl; return os; } -inline std::ostream& operator << (std::ostream& os,const RotationAcc& r) { +KDL_EXPORT inline std::ostream& operator << (std::ostream& os,const RotationAcc& r) { os << "{" << std::endl << r.R << "," << std::endl << r.w << "," << std::endl << r.dw << std::endl << "}" << std::endl; return os; } -inline std::ostream& operator << (std::ostream& os,const FrameAcc& r) { +KDL_EXPORT inline std::ostream& operator << (std::ostream& os,const FrameAcc& r) { os << "{" << std::endl << r.M << "," << std::endl << r.p << "}" << std::endl; return os; } -inline std::ostream& operator << (std::ostream& os,const TwistAcc& r) { +KDL_EXPORT inline std::ostream& operator << (std::ostream& os,const TwistAcc& r) { os << "{" << std::endl << r.vel << "," << std::endl << r.rot << std::endl << "}" << std::endl; return os; } diff --git a/orocos_kdl/src/frames.hpp b/orocos_kdl/src/frames.hpp index d6fcab4..2552706 100644 --- a/orocos_kdl/src/frames.hpp +++ b/orocos_kdl/src/frames.hpp @@ -127,6 +127,7 @@ #include "utilities/kdl-config.h" #include "utilities/utility.h" +#include "kdl_export.hpp" ///////////////////////////////////////////////////////////// @@ -148,7 +149,7 @@ class Frame2; /** * \brief A concrete implementation of a 3 dimensional vector class */ -class Vector +class KDL_EXPORT Vector { public: double data[3]; @@ -201,21 +202,21 @@ public: inline Vector& operator +=(const Vector& arg); //! Scalar multiplication is defined - inline friend Vector operator*(const Vector& lhs,double rhs); + KDL_EXPORT inline friend Vector operator*(const Vector& lhs,double rhs); //! Scalar multiplication is defined - inline friend Vector operator*(double lhs,const Vector& rhs); + KDL_EXPORT inline friend Vector operator*(double lhs,const Vector& rhs); //! Scalar division is defined - inline friend Vector operator/(const Vector& lhs,double rhs); - inline friend Vector operator+(const Vector& lhs,const Vector& rhs); - inline friend Vector operator-(const Vector& lhs,const Vector& rhs); - inline friend Vector operator*(const Vector& lhs,const Vector& rhs); - inline friend Vector operator-(const Vector& arg); - inline friend double dot(const Vector& lhs,const Vector& rhs); + KDL_EXPORT inline friend Vector operator/(const Vector& lhs,double rhs); + KDL_EXPORT inline friend Vector operator+(const Vector& lhs,const Vector& rhs); + KDL_EXPORT inline friend Vector operator-(const Vector& lhs,const Vector& rhs); + KDL_EXPORT inline friend Vector operator*(const Vector& lhs,const Vector& rhs); + KDL_EXPORT inline friend Vector operator-(const Vector& arg); + KDL_EXPORT inline friend double dot(const Vector& lhs,const Vector& rhs); //! To have a uniform operator to put an element to zero, for scalar values //! and for objects. - inline friend void SetToZero(Vector& v); + KDL_EXPORT inline friend void SetToZero(Vector& v); //! @return a zero vector inline static Vector Zero(); @@ -244,12 +245,12 @@ public: //! do not use operator == because the definition of Equal(.,.) is slightly //! different. It compares whether the 2 arguments are equal in an eps-interval - inline friend bool Equal(const Vector& a,const Vector& b,double eps=epsilon); + KDL_EXPORT inline friend bool Equal(const Vector& a,const Vector& b,double eps=epsilon); //! The literal equality operator==(), also identical. - inline friend bool operator==(const Vector& a,const Vector& b); + KDL_EXPORT inline friend bool operator==(const Vector& a,const Vector& b); //! The literal inequality operator!=(). - inline friend bool operator!=(const Vector& a,const Vector& b); + KDL_EXPORT inline friend bool operator!=(const Vector& a,const Vector& b); friend class Rotation; friend class Frame; @@ -289,7 +290,7 @@ public: \par type Concrete implementation */ -class Rotation +class KDL_EXPORT Rotation { public: double data[9]; @@ -316,7 +317,7 @@ public: //! Access to elements 0..2,0..2, bounds are checked when NDEBUG is not set inline double operator() (int i,int j) const; - friend Rotation operator *(const Rotation& lhs,const Rotation& rhs); + KDL_EXPORT friend Rotation operator *(const Rotation& lhs,const Rotation& rhs); //! Sets the value of *this to its inverse. inline void SetInverse(); @@ -535,12 +536,12 @@ public: //! do not use operator == because the definition of Equal(.,.) is slightly //! different. It compares whether the 2 arguments are equal in an eps-interval - friend bool Equal(const Rotation& a,const Rotation& b,double eps); + KDL_EXPORT friend bool Equal(const Rotation& a,const Rotation& b,double eps); //! The literal equality operator==(), also identical. - friend bool operator==(const Rotation& a,const Rotation& b); + KDL_EXPORT friend bool operator==(const Rotation& a,const Rotation& b); //! The literal inequality operator!=() - friend bool operator!=(const Rotation& a,const Rotation& b); + KDL_EXPORT friend bool operator!=(const Rotation& a,const Rotation& b); friend class Frame; }; @@ -558,7 +559,7 @@ public: Frame.M contains columns that represent the axes of frame B wrt frame A Frame.p contains the origin of frame B expressed in frame A. */ -class Frame { +class KDL_EXPORT Frame { public: Vector p; //!< origine of the Frame Rotation M; //!< Orientation of the Frame @@ -625,7 +626,7 @@ public: inline Twist operator * (const Twist& arg) const; //! Composition of two frames. - inline friend Frame operator *(const Frame& lhs,const Frame& rhs); + KDL_EXPORT inline friend Frame operator *(const Frame& lhs,const Frame& rhs); //! @return the identity transformation Frame(Rotation::Identity(),Vector::Zero()). inline static Frame Identity(); @@ -694,12 +695,12 @@ public: //! do not use operator == because the definition of Equal(.,.) is slightly //! different. It compares whether the 2 arguments are equal in an eps-interval - inline friend bool Equal(const Frame& a,const Frame& b,double eps=epsilon); + KDL_EXPORT inline friend bool Equal(const Frame& a,const Frame& b,double eps=epsilon); //! The literal equality operator==(), also identical. - inline friend bool operator==(const Frame& a,const Frame& b); + KDL_EXPORT inline friend bool operator==(const Frame& a,const Frame& b); //! The literal inequality operator!=(). - inline friend bool operator!=(const Frame& a,const Frame& b); + KDL_EXPORT inline friend bool operator!=(const Frame& a,const Frame& b); }; /** @@ -708,7 +709,7 @@ public: * This class represents a twist. A twist is the combination of translational * velocity and rotational velocity applied at one point. */ -class Twist { +class KDL_EXPORT Twist { public: Vector vel; //!< The velocity of that point Vector rot; //!< The rotational velocity of that point. @@ -738,19 +739,19 @@ public: return this->operator() ( index ); } - inline friend Twist operator*(const Twist& lhs,double rhs); - inline friend Twist operator*(double lhs,const Twist& rhs); - inline friend Twist operator/(const Twist& lhs,double rhs); - inline friend Twist operator+(const Twist& lhs,const Twist& rhs); - inline friend Twist operator-(const Twist& lhs,const Twist& rhs); - inline friend Twist operator-(const Twist& arg); - inline friend double dot(const Twist& lhs,const Wrench& rhs); - inline friend double dot(const Wrench& rhs,const Twist& lhs); - inline friend void SetToZero(Twist& v); + KDL_EXPORT inline friend Twist operator*(const Twist& lhs,double rhs); + KDL_EXPORT inline friend Twist operator*(double lhs,const Twist& rhs); + KDL_EXPORT inline friend Twist operator/(const Twist& lhs,double rhs); + KDL_EXPORT inline friend Twist operator+(const Twist& lhs,const Twist& rhs); + KDL_EXPORT inline friend Twist operator-(const Twist& lhs,const Twist& rhs); + KDL_EXPORT inline friend Twist operator-(const Twist& arg); + KDL_EXPORT inline friend double dot(const Twist& lhs,const Wrench& rhs); + KDL_EXPORT inline friend double dot(const Wrench& rhs,const Twist& lhs); + KDL_EXPORT inline friend void SetToZero(Twist& v); /// Spatial cross product for 6d motion vectors, beware all of them have to be expressed in the same reference frame/point - inline friend Twist operator*(const Twist& lhs,const Twist& rhs); + KDL_EXPORT inline friend Twist operator*(const Twist& lhs,const Twist& rhs); /// Spatial cross product for 6d force vectors, beware all of them have to be expressed in the same reference frame/point - inline friend Wrench operator*(const Twist& lhs,const Wrench& rhs); + KDL_EXPORT inline friend Wrench operator*(const Twist& lhs,const Wrench& rhs); //! @return a zero Twist : Twist(Vector::Zero(),Vector::Zero()) static inline Twist Zero(); @@ -769,12 +770,12 @@ public: //! do not use operator == because the definition of Equal(.,.) is slightly //! different. It compares whether the 2 arguments are equal in an eps-interval - inline friend bool Equal(const Twist& a,const Twist& b,double eps=epsilon); + KDL_EXPORT inline friend bool Equal(const Twist& a,const Twist& b,double eps=epsilon); //! The literal equality operator==(), also identical. - inline friend bool operator==(const Twist& a,const Twist& b); + KDL_EXPORT inline friend bool operator==(const Twist& a,const Twist& b); //! The literal inequality operator!=(). - inline friend bool operator!=(const Twist& a,const Twist& b); + KDL_EXPORT inline friend bool operator!=(const Twist& a,const Twist& b); // = Friends friend class Rotation; @@ -866,7 +867,7 @@ public: * * This class represents a Wrench. A Wrench is the force and torque applied at a point */ -class Wrench +class KDL_EXPORT Wrench { public: Vector force; //!< Force that is applied at the origin of the current ref frame @@ -899,21 +900,21 @@ public: } //! Scalar multiplication - inline friend Wrench operator*(const Wrench& lhs,double rhs); + KDL_EXPORT inline friend Wrench operator*(const Wrench& lhs,double rhs); //! Scalar multiplication - inline friend Wrench operator*(double lhs,const Wrench& rhs); + KDL_EXPORT inline friend Wrench operator*(double lhs,const Wrench& rhs); //! Scalar division - inline friend Wrench operator/(const Wrench& lhs,double rhs); + KDL_EXPORT inline friend Wrench operator/(const Wrench& lhs,double rhs); - inline friend Wrench operator+(const Wrench& lhs,const Wrench& rhs); - inline friend Wrench operator-(const Wrench& lhs,const Wrench& rhs); + KDL_EXPORT inline friend Wrench operator+(const Wrench& lhs,const Wrench& rhs); + KDL_EXPORT inline friend Wrench operator-(const Wrench& lhs,const Wrench& rhs); //! An unary - operator - inline friend Wrench operator-(const Wrench& arg); + KDL_EXPORT inline friend Wrench operator-(const Wrench& arg); //! Sets the Wrench to Zero, to have a uniform function that sets an object or //! double to zero. - inline friend void SetToZero(Wrench& v); + KDL_EXPORT inline friend void SetToZero(Wrench& v); //! @return a zero Wrench static inline Wrench Zero(); @@ -932,12 +933,12 @@ public: //! do not use operator == because the definition of Equal(.,.) is slightly //! different. It compares whether the 2 arguments are equal in an eps-interval - inline friend bool Equal(const Wrench& a,const Wrench& b,double eps=epsilon); + KDL_EXPORT inline friend bool Equal(const Wrench& a,const Wrench& b,double eps=epsilon); //! The literal equality operator==(), also identical. - inline friend bool operator==(const Wrench& a,const Wrench& b); + KDL_EXPORT inline friend bool operator==(const Wrench& a,const Wrench& b); //! The literal inequality operator!=(). - inline friend bool operator!=(const Wrench& a,const Wrench& b); + KDL_EXPORT inline friend bool operator!=(const Wrench& a,const Wrench& b); friend class Rotation; friend class Frame; @@ -947,7 +948,7 @@ public: //! 2D version of Vector -class Vector2 +class KDL_EXPORT Vector2 { double data[2]; public: @@ -986,14 +987,14 @@ public: inline Vector2& operator +=(const Vector2& arg); - inline friend Vector2 operator*(const Vector2& lhs,double rhs); - inline friend Vector2 operator*(double lhs,const Vector2& rhs); - inline friend Vector2 operator/(const Vector2& lhs,double rhs); - inline friend Vector2 operator+(const Vector2& lhs,const Vector2& rhs); - inline friend Vector2 operator-(const Vector2& lhs,const Vector2& rhs); - inline friend Vector2 operator*(const Vector2& lhs,const Vector2& rhs); - inline friend Vector2 operator-(const Vector2& arg); - inline friend void SetToZero(Vector2& v); + KDL_EXPORT inline friend Vector2 operator*(const Vector2& lhs,double rhs); + KDL_EXPORT inline friend Vector2 operator*(double lhs,const Vector2& rhs); + KDL_EXPORT inline friend Vector2 operator/(const Vector2& lhs,double rhs); + KDL_EXPORT inline friend Vector2 operator+(const Vector2& lhs,const Vector2& rhs); + KDL_EXPORT inline friend Vector2 operator-(const Vector2& lhs,const Vector2& rhs); + KDL_EXPORT inline friend Vector2 operator*(const Vector2& lhs,const Vector2& rhs); + KDL_EXPORT inline friend Vector2 operator-(const Vector2& arg); + KDL_EXPORT inline friend void SetToZero(Vector2& v); //! @return a zero 2D vector. inline static Vector2 Zero(); @@ -1025,20 +1026,20 @@ public: //! do not use operator == because the definition of Equal(.,.) is slightly //! different. It compares whether the 2 arguments are equal in an eps-interval - inline friend bool Equal(const Vector2& a,const Vector2& b,double eps=epsilon); + KDL_EXPORT inline friend bool Equal(const Vector2& a,const Vector2& b,double eps=epsilon); //! The literal equality operator==(), also identical. - inline friend bool operator==(const Vector2& a,const Vector2& b); + KDL_EXPORT inline friend bool operator==(const Vector2& a,const Vector2& b); //! The literal inequality operator!=(). - inline friend bool operator!=(const Vector2& a,const Vector2& b); + KDL_EXPORT inline friend bool operator!=(const Vector2& a,const Vector2& b); - friend class Rotation2; + KDL_EXPORT friend class Rotation2; }; //! A 2D Rotation class, for conventions see Rotation. For further documentation //! of the methods see Rotation class. -class Rotation2 +class KDL_EXPORT Rotation2 { double s,c; //! c,s represent cos(angle), sin(angle), this also represents first col. of rot matrix @@ -1056,7 +1057,7 @@ public: //! Access to elements 0..1,0..1, bounds are checked when NDEBUG is not set inline double operator() (int i,int j) const; - inline friend Rotation2 operator *(const Rotation2& lhs,const Rotation2& rhs); + KDL_EXPORT inline friend Rotation2 operator *(const Rotation2& lhs,const Rotation2& rhs); inline void SetInverse(); inline Rotation2 Inverse() const; @@ -1077,12 +1078,12 @@ public: //! do not use operator == because the definition of Equal(.,.) is slightly //! different. It compares whether the 2 arguments are equal in an eps-interval - inline friend bool Equal(const Rotation2& a,const Rotation2& b,double eps=epsilon); + KDL_EXPORT inline friend bool Equal(const Rotation2& a,const Rotation2& b,double eps=epsilon); }; //! A 2D frame class, for further documentation see the Frames class //! for methods with unchanged semantics. -class Frame2 +class KDL_EXPORT Frame2 { public: Vector2 p; //!< origine of the Frame @@ -1110,7 +1111,7 @@ public: inline Vector2 Inverse(const Vector2& arg) const; inline Frame2& operator = (const Frame2& arg); inline Vector2 operator * (const Vector2& arg); - inline friend Frame2 operator *(const Frame2& lhs,const Frame2& rhs); + KDL_EXPORT inline friend Frame2 operator *(const Frame2& lhs,const Frame2& rhs); inline void SetIdentity(); inline void Integrate(const Twist& t_this,double frequency); inline static Frame2 Identity() { @@ -1118,7 +1119,7 @@ public: tmp.SetIdentity(); return tmp; } - inline friend bool Equal(const Frame2& a,const Frame2& b,double eps=epsilon); + KDL_EXPORT inline friend bool Equal(const Frame2& a,const Frame2& b,double eps=epsilon); }; /** @@ -1131,7 +1132,7 @@ public: * \param dt [optional][obsolete] time interval over which the numerical differentiation takes place. * \return the difference (b-a) expressed to the frame w. */ -IMETHOD Vector diff(const Vector& p_w_a,const Vector& p_w_b,double dt=1); +KDL_EXPORT IMETHOD Vector diff(const Vector& p_w_a,const Vector& p_w_b,double dt=1); /** @@ -1161,7 +1162,7 @@ IMETHOD Vector diff(const Vector& p_w_a,const Vector& p_w_b,double dt=1); * \warning - For angles equal to \f$ \pi \f$, The negative of the * return value is equally valid. */ -IMETHOD Vector diff(const Rotation& R_a_b1,const Rotation& R_a_b2,double dt=1); +KDL_EXPORT IMETHOD Vector diff(const Rotation& R_a_b1,const Rotation& R_a_b2,double dt=1); /** * determines the rotation axis necessary to rotate the frame b1 to the same orientation as frame b2 and the vector @@ -1171,19 +1172,19 @@ IMETHOD Vector diff(const Rotation& R_a_b1,const Rotation& R_a_b2,double dt=1); * \warning The result is not a Twist! * see diff() for Rotation and Vector arguments for further detail on the semantics. */ -IMETHOD Twist diff(const Frame& F_a_b1,const Frame& F_a_b2,double dt=1); +KDL_EXPORT IMETHOD Twist diff(const Frame& F_a_b1,const Frame& F_a_b2,double dt=1); /** * determines the difference between two twists i.e. the difference between * the underlying velocity vectors and rotational velocity vectors. */ -IMETHOD Twist diff(const Twist& a,const Twist& b,double dt=1); +KDL_EXPORT IMETHOD Twist diff(const Twist& a,const Twist& b,double dt=1); /** * determines the difference between two wrenches i.e. the difference between * the underlying torque vectors and force vectors. */ -IMETHOD Wrench diff(const Wrench& W_a_p1,const Wrench& W_a_p2,double dt=1); +KDL_EXPORT IMETHOD Wrench diff(const Wrench& W_a_p1,const Wrench& W_a_p2,double dt=1); /** * \brief adds vector da to vector a. @@ -1192,7 +1193,7 @@ IMETHOD Wrench diff(const Wrench& W_a_p1,const Wrench& W_a_p2,double dt=1); * \param p_w_da vector da expressed to some frame w. * \returns the vector resulting from the displacement of vector a by vector da, expressed in the frame w. */ -IMETHOD Vector addDelta(const Vector& p_w_a,const Vector& p_w_da,double dt=1); +KDL_EXPORT IMETHOD Vector addDelta(const Vector& p_w_a,const Vector& p_w_da,double dt=1); /** * returns the rotation matrix resulting from the rotation of frame a by the axis and angle @@ -1206,7 +1207,7 @@ IMETHOD Vector addDelta(const Vector& p_w_a,const Vector& p_w_da,double dt=1); * specified with da. The resulting rotation matrix is expressed with respect to * frame w. */ -IMETHOD Rotation addDelta(const Rotation& R_w_a,const Vector& da_w,double dt=1); +KDL_EXPORT IMETHOD Rotation addDelta(const Rotation& R_w_a,const Vector& da_w,double dt=1); /** * returns the frame resulting from the rotation of frame a by the axis and angle @@ -1218,7 +1219,7 @@ IMETHOD Rotation addDelta(const Rotation& R_w_a,const Vector& da_w,double dt=1); * \returns the frame resulting from the rotation of frame a by the axis and angle * specified with da.rot, and the translation of the origin da_w.vel . The resulting frame is expressed with respect to frame w. */ -IMETHOD Frame addDelta(const Frame& F_w_a,const Twist& da_w,double dt=1); +KDL_EXPORT IMETHOD Frame addDelta(const Frame& F_w_a,const Twist& da_w,double dt=1); /** * \brief adds the twist da to the twist a. @@ -1227,7 +1228,7 @@ IMETHOD Frame addDelta(const Frame& F_w_a,const Twist& da_w,double dt=1); * \param da a twist difference wrt some frame * \returns The twist (a+da) wrt the corresponding frame. */ -IMETHOD Twist addDelta(const Twist& a,const Twist&da,double dt=1); +KDL_EXPORT IMETHOD Twist addDelta(const Twist& a,const Twist&da,double dt=1); /** @@ -1238,7 +1239,7 @@ IMETHOD Twist addDelta(const Twist& a,const Twist&da,double dt=1); * \param da a wrench difference wrt some frame * \returns the wrench (a+da) wrt the corresponding frame. */ -IMETHOD Wrench addDelta(const Wrench& a,const Wrench&da,double dt=1); +KDL_EXPORT IMETHOD Wrench addDelta(const Wrench& a,const Wrench&da,double dt=1); #ifdef KDL_INLINE // #include "vector.inl" diff --git a/orocos_kdl/src/frames_io.hpp b/orocos_kdl/src/frames_io.hpp index a358d27..88a6645 100644 --- a/orocos_kdl/src/frames_io.hpp +++ b/orocos_kdl/src/frames_io.hpp @@ -80,6 +80,7 @@ #include "frames.hpp" #include "jntarray.hpp" #include "jacobian.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -88,25 +89,25 @@ namespace KDL { // I/O to C++ stream. - std::ostream& operator << (std::ostream& os,const Vector& v); - std::ostream& operator << (std::ostream& os,const Rotation& R); - std::ostream& operator << (std::ostream& os,const Frame& T); - std::ostream& operator << (std::ostream& os,const Twist& T); - std::ostream& operator << (std::ostream& os,const Wrench& T); - std::ostream& operator << (std::ostream& os,const Vector2& v); - std::ostream& operator << (std::ostream& os,const Rotation2& R); - std::ostream& operator << (std::ostream& os,const Frame2& T); + KDL_EXPORT std::ostream& operator << (std::ostream& os,const Vector& v); + KDL_EXPORT std::ostream& operator << (std::ostream& os,const Rotation& R); + KDL_EXPORT std::ostream& operator << (std::ostream& os,const Frame& T); + KDL_EXPORT std::ostream& operator << (std::ostream& os,const Twist& T); + KDL_EXPORT std::ostream& operator << (std::ostream& os,const Wrench& T); + KDL_EXPORT std::ostream& operator << (std::ostream& os,const Vector2& v); + KDL_EXPORT std::ostream& operator << (std::ostream& os,const Rotation2& R); + KDL_EXPORT std::ostream& operator << (std::ostream& os,const Frame2& T); - std::istream& operator >> (std::istream& is,Vector& v); - std::istream& operator >> (std::istream& is,Rotation& R); - std::istream& operator >> (std::istream& is,Frame& T); - std::istream& operator >> (std::istream& os,Twist& T); - std::istream& operator >> (std::istream& os,Wrench& T); - std::istream& operator >> (std::istream& is,Vector2& v); - std::istream& operator >> (std::istream& is,Rotation2& R); - std::istream& operator >> (std::istream& is,Frame2& T); + KDL_EXPORT std::istream& operator >> (std::istream& is,Vector& v); + KDL_EXPORT std::istream& operator >> (std::istream& is,Rotation& R); + KDL_EXPORT std::istream& operator >> (std::istream& is,Frame& T); + KDL_EXPORT std::istream& operator >> (std::istream& os,Twist& T); + KDL_EXPORT std::istream& operator >> (std::istream& os,Wrench& T); + KDL_EXPORT std::istream& operator >> (std::istream& is,Vector2& v); + KDL_EXPORT std::istream& operator >> (std::istream& is,Rotation2& R); + KDL_EXPORT std::istream& operator >> (std::istream& is,Frame2& T); } // namespace Frame diff --git a/orocos_kdl/src/framevel.hpp b/orocos_kdl/src/framevel.hpp index 1310a10..b1c74f3 100644 --- a/orocos_kdl/src/framevel.hpp +++ b/orocos_kdl/src/framevel.hpp @@ -28,26 +28,25 @@ #include "utilities/traits.h" #include "frames.hpp" - - +#include "kdl_export.hpp" namespace KDL { typedef Rall1d doubleVel; -IMETHOD doubleVel diff(const doubleVel& a,const doubleVel& b,double dt=1.0) { +KDL_EXPORT IMETHOD doubleVel diff(const doubleVel& a,const doubleVel& b,double dt=1.0) { return doubleVel((b.t-a.t)/dt,(b.grad-a.grad)/dt); } -IMETHOD doubleVel addDelta(const doubleVel& a,const doubleVel&da,double dt=1.0) { +KDL_EXPORT IMETHOD doubleVel addDelta(const doubleVel& a,const doubleVel&da,double dt=1.0) { return doubleVel(a.t+da.t*dt,a.grad+da.grad*dt); } -IMETHOD void random(doubleVel& F) { +KDL_EXPORT IMETHOD void random(doubleVel& F) { random(F.t); random(F.grad); } -IMETHOD void posrandom(doubleVel& F) { +KDL_EXPORT IMETHOD void posrandom(doubleVel& F) { posrandom(F.t); posrandom(F.grad); } @@ -67,7 +66,7 @@ class VectorVel; class FrameVel; class RotationVel; -class VectorVel +class KDL_EXPORT VectorVel // = TITLE // An VectorVel is a Vector and its first derivative // = CLASS TYPE @@ -91,38 +90,38 @@ public: IMETHOD static VectorVel Zero(); IMETHOD void ReverseSign(); IMETHOD doubleVel Norm() const; - IMETHOD friend VectorVel operator + (const VectorVel& r1,const VectorVel& r2); - IMETHOD friend VectorVel operator - (const VectorVel& r1,const VectorVel& r2); - IMETHOD friend VectorVel operator + (const Vector& r1,const VectorVel& r2); - IMETHOD friend VectorVel operator - (const Vector& r1,const VectorVel& r2); - IMETHOD friend VectorVel operator + (const VectorVel& r1,const Vector& r2); - IMETHOD friend VectorVel operator - (const VectorVel& r1,const Vector& r2); - IMETHOD friend VectorVel operator * (const VectorVel& r1,const VectorVel& r2); - IMETHOD friend VectorVel operator * (const VectorVel& r1,const Vector& r2); - IMETHOD friend VectorVel operator * (const Vector& r1,const VectorVel& r2); - IMETHOD friend VectorVel operator * (const VectorVel& r1,double r2); - IMETHOD friend VectorVel operator * (double r1,const VectorVel& r2); - IMETHOD friend VectorVel operator * (const doubleVel& r1,const VectorVel& r2); - IMETHOD friend VectorVel operator * (const VectorVel& r2,const doubleVel& r1); - IMETHOD friend VectorVel operator*(const Rotation& R,const VectorVel& x); - - IMETHOD friend VectorVel operator / (const VectorVel& r1,double r2); - IMETHOD friend VectorVel operator / (const VectorVel& r2,const doubleVel& r1); - IMETHOD friend void SetToZero(VectorVel& v); - - - IMETHOD friend bool Equal(const VectorVel& r1,const VectorVel& r2,double eps=epsilon); - IMETHOD friend bool Equal(const Vector& r1,const VectorVel& r2,double eps=epsilon); - IMETHOD friend bool Equal(const VectorVel& r1,const Vector& r2,double eps=epsilon); - IMETHOD friend VectorVel operator - (const VectorVel& r); - IMETHOD friend doubleVel dot(const VectorVel& lhs,const VectorVel& rhs); - IMETHOD friend doubleVel dot(const VectorVel& lhs,const Vector& rhs); - IMETHOD friend doubleVel dot(const Vector& lhs,const VectorVel& rhs); + KDL_EXPORT IMETHOD friend VectorVel operator + (const VectorVel& r1,const VectorVel& r2); + KDL_EXPORT IMETHOD friend VectorVel operator - (const VectorVel& r1,const VectorVel& r2); + KDL_EXPORT IMETHOD friend VectorVel operator + (const Vector& r1,const VectorVel& r2); + KDL_EXPORT IMETHOD friend VectorVel operator - (const Vector& r1,const VectorVel& r2); + KDL_EXPORT IMETHOD friend VectorVel operator + (const VectorVel& r1,const Vector& r2); + KDL_EXPORT IMETHOD friend VectorVel operator - (const VectorVel& r1,const Vector& r2); + KDL_EXPORT IMETHOD friend VectorVel operator * (const VectorVel& r1,const VectorVel& r2); + KDL_EXPORT IMETHOD friend VectorVel operator * (const VectorVel& r1,const Vector& r2); + KDL_EXPORT IMETHOD friend VectorVel operator * (const Vector& r1,const VectorVel& r2); + KDL_EXPORT IMETHOD friend VectorVel operator * (const VectorVel& r1,double r2); + KDL_EXPORT IMETHOD friend VectorVel operator * (double r1,const VectorVel& r2); + KDL_EXPORT IMETHOD friend VectorVel operator * (const doubleVel& r1,const VectorVel& r2); + KDL_EXPORT IMETHOD friend VectorVel operator * (const VectorVel& r2,const doubleVel& r1); + KDL_EXPORT IMETHOD friend VectorVel operator*(const Rotation& R,const VectorVel& x); + + KDL_EXPORT IMETHOD friend VectorVel operator / (const VectorVel& r1,double r2); + KDL_EXPORT IMETHOD friend VectorVel operator / (const VectorVel& r2,const doubleVel& r1); + KDL_EXPORT IMETHOD friend void SetToZero(VectorVel& v); + + + KDL_EXPORT IMETHOD friend bool Equal(const VectorVel& r1,const VectorVel& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const Vector& r1,const VectorVel& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const VectorVel& r1,const Vector& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend VectorVel operator - (const VectorVel& r); + KDL_EXPORT IMETHOD friend doubleVel dot(const VectorVel& lhs,const VectorVel& rhs); + KDL_EXPORT IMETHOD friend doubleVel dot(const VectorVel& lhs,const Vector& rhs); + KDL_EXPORT IMETHOD friend doubleVel dot(const Vector& lhs,const VectorVel& rhs); }; -class RotationVel +class KDL_EXPORT RotationVel // = TITLE // An RotationVel is a Rotation and its first derivative, a rotation vector // = CLASS TYPE @@ -164,12 +163,12 @@ public: IMETHOD static RotationVel Rot2(const Vector& rotvec,const doubleVel& angle); // rotvec is normalized. // rotation around a constant vector ! - IMETHOD friend RotationVel operator* (const RotationVel& r1,const RotationVel& r2); - IMETHOD friend RotationVel operator* (const Rotation& r1,const RotationVel& r2); - IMETHOD friend RotationVel operator* (const RotationVel& r1,const Rotation& r2); - IMETHOD friend bool Equal(const RotationVel& r1,const RotationVel& r2,double eps=epsilon); - IMETHOD friend bool Equal(const Rotation& r1,const RotationVel& r2,double eps=epsilon); - IMETHOD friend bool Equal(const RotationVel& r1,const Rotation& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend RotationVel operator* (const RotationVel& r1,const RotationVel& r2); + KDL_EXPORT IMETHOD friend RotationVel operator* (const Rotation& r1,const RotationVel& r2); + KDL_EXPORT IMETHOD friend RotationVel operator* (const RotationVel& r1,const Rotation& r2); + KDL_EXPORT IMETHOD friend bool Equal(const RotationVel& r1,const RotationVel& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const Rotation& r1,const RotationVel& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const RotationVel& r1,const Rotation& r2,double eps=epsilon); IMETHOD TwistVel Inverse(const TwistVel& arg) const; IMETHOD TwistVel Inverse(const Twist& arg) const; @@ -180,7 +179,7 @@ public: -class FrameVel +class KDL_EXPORT FrameVel // = TITLE // An FrameVel is a Frame and its first derivative, a Twist vector // = CLASS TYPE @@ -218,12 +217,12 @@ public: IMETHOD VectorVel Inverse(const Vector& arg) const; IMETHOD Frame GetFrame() const; IMETHOD Twist GetTwist() const; - IMETHOD friend FrameVel operator * (const FrameVel& f1,const FrameVel& f2); - IMETHOD friend FrameVel operator * (const Frame& f1,const FrameVel& f2); - IMETHOD friend FrameVel operator * (const FrameVel& f1,const Frame& f2); - IMETHOD friend bool Equal(const FrameVel& r1,const FrameVel& r2,double eps=epsilon); - IMETHOD friend bool Equal(const Frame& r1,const FrameVel& r2,double eps=epsilon); - IMETHOD friend bool Equal(const FrameVel& r1,const Frame& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend FrameVel operator * (const FrameVel& f1,const FrameVel& f2); + KDL_EXPORT IMETHOD friend FrameVel operator * (const Frame& f1,const FrameVel& f2); + KDL_EXPORT IMETHOD friend FrameVel operator * (const FrameVel& f1,const Frame& f2); + KDL_EXPORT IMETHOD friend bool Equal(const FrameVel& r1,const FrameVel& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const Frame& r1,const FrameVel& r2,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const FrameVel& r1,const Frame& r2,double eps=epsilon); IMETHOD TwistVel Inverse(const TwistVel& arg) const; IMETHOD TwistVel Inverse(const Twist& arg) const; @@ -236,7 +235,7 @@ public: //very similar to Wrench class. -class TwistVel +class KDL_EXPORT TwistVel // = TITLE // This class represents a TwistVel. This is a velocity and rotational velocity together { @@ -262,18 +261,18 @@ public: IMETHOD TwistVel& operator+=(const TwistVel& arg); // = External operators - IMETHOD friend TwistVel operator*(const TwistVel& lhs,double rhs); - IMETHOD friend TwistVel operator*(double lhs,const TwistVel& rhs); - IMETHOD friend TwistVel operator/(const TwistVel& lhs,double rhs); + KDL_EXPORT IMETHOD friend TwistVel operator*(const TwistVel& lhs,double rhs); + KDL_EXPORT IMETHOD friend TwistVel operator*(double lhs,const TwistVel& rhs); + KDL_EXPORT IMETHOD friend TwistVel operator/(const TwistVel& lhs,double rhs); - IMETHOD friend TwistVel operator*(const TwistVel& lhs,const doubleVel& rhs); - IMETHOD friend TwistVel operator*(const doubleVel& lhs,const TwistVel& rhs); - IMETHOD friend TwistVel operator/(const TwistVel& lhs,const doubleVel& rhs); + KDL_EXPORT IMETHOD friend TwistVel operator*(const TwistVel& lhs,const doubleVel& rhs); + KDL_EXPORT IMETHOD friend TwistVel operator*(const doubleVel& lhs,const TwistVel& rhs); + KDL_EXPORT IMETHOD friend TwistVel operator/(const TwistVel& lhs,const doubleVel& rhs); - IMETHOD friend TwistVel operator+(const TwistVel& lhs,const TwistVel& rhs); - IMETHOD friend TwistVel operator-(const TwistVel& lhs,const TwistVel& rhs); - IMETHOD friend TwistVel operator-(const TwistVel& arg); - IMETHOD friend void SetToZero(TwistVel& v); + KDL_EXPORT IMETHOD friend TwistVel operator+(const TwistVel& lhs,const TwistVel& rhs); + KDL_EXPORT IMETHOD friend TwistVel operator-(const TwistVel& lhs,const TwistVel& rhs); + KDL_EXPORT IMETHOD friend TwistVel operator-(const TwistVel& arg); + KDL_EXPORT IMETHOD friend void SetToZero(TwistVel& v); // = Zero @@ -293,9 +292,9 @@ public: // = Equality operators // do not use operator == because the definition of Equal(.,.) is slightly // different. It compares whether the 2 arguments are equal in an eps-interval - IMETHOD friend bool Equal(const TwistVel& a,const TwistVel& b,double eps=epsilon); - IMETHOD friend bool Equal(const Twist& a,const TwistVel& b,double eps=epsilon); - IMETHOD friend bool Equal(const TwistVel& a,const Twist& b,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const TwistVel& a,const TwistVel& b,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const Twist& a,const TwistVel& b,double eps=epsilon); + KDL_EXPORT IMETHOD friend bool Equal(const TwistVel& a,const Twist& b,double eps=epsilon); // = Conversion to other entities IMETHOD Twist GetTwist() const; @@ -306,65 +305,65 @@ public: }; -IMETHOD VectorVel diff(const VectorVel& a,const VectorVel& b,double dt=1.0) { +KDL_EXPORT IMETHOD VectorVel diff(const VectorVel& a,const VectorVel& b,double dt=1.0) { return VectorVel(diff(a.p,b.p,dt),diff(a.v,b.v,dt)); } -IMETHOD VectorVel addDelta(const VectorVel& a,const VectorVel&da,double dt=1.0) { +KDL_EXPORT IMETHOD VectorVel addDelta(const VectorVel& a,const VectorVel&da,double dt=1.0) { return VectorVel(addDelta(a.p,da.p,dt),addDelta(a.v,da.v,dt)); } -IMETHOD VectorVel diff(const RotationVel& a,const RotationVel& b,double dt = 1.0) { +KDL_EXPORT IMETHOD VectorVel diff(const RotationVel& a,const RotationVel& b,double dt = 1.0) { return VectorVel(diff(a.R,b.R,dt),diff(a.w,b.w,dt)); } -IMETHOD RotationVel addDelta(const RotationVel& a,const VectorVel&da,double dt=1.0) { +KDL_EXPORT IMETHOD RotationVel addDelta(const RotationVel& a,const VectorVel&da,double dt=1.0) { return RotationVel(addDelta(a.R,da.p,dt),addDelta(a.w,da.v,dt)); } -IMETHOD TwistVel diff(const FrameVel& a,const FrameVel& b,double dt=1.0) { +KDL_EXPORT IMETHOD TwistVel diff(const FrameVel& a,const FrameVel& b,double dt=1.0) { return TwistVel(diff(a.M,b.M,dt),diff(a.p,b.p,dt)); } -IMETHOD FrameVel addDelta(const FrameVel& a,const TwistVel& da,double dt=1.0) { +KDL_EXPORT IMETHOD FrameVel addDelta(const FrameVel& a,const TwistVel& da,double dt=1.0) { return FrameVel( addDelta(a.M,da.rot,dt), addDelta(a.p,da.vel,dt) ); } -IMETHOD void random(VectorVel& a) { +KDL_EXPORT IMETHOD void random(VectorVel& a) { random(a.p); random(a.v); } -IMETHOD void random(TwistVel& a) { +KDL_EXPORT IMETHOD void random(TwistVel& a) { random(a.vel); random(a.rot); } -IMETHOD void random(RotationVel& R) { +KDL_EXPORT IMETHOD void random(RotationVel& R) { random(R.R); random(R.w); } -IMETHOD void random(FrameVel& F) { +KDL_EXPORT IMETHOD void random(FrameVel& F) { random(F.M); random(F.p); } -IMETHOD void posrandom(VectorVel& a) { +KDL_EXPORT IMETHOD void posrandom(VectorVel& a) { posrandom(a.p); posrandom(a.v); } -IMETHOD void posrandom(TwistVel& a) { +KDL_EXPORT IMETHOD void posrandom(TwistVel& a) { posrandom(a.vel); posrandom(a.rot); } -IMETHOD void posrandom(RotationVel& R) { +KDL_EXPORT IMETHOD void posrandom(RotationVel& R) { posrandom(R.R); posrandom(R.w); } -IMETHOD void posrandom(FrameVel& F) { +KDL_EXPORT IMETHOD void posrandom(FrameVel& F) { posrandom(F.M); posrandom(F.p); } diff --git a/orocos_kdl/src/framevel_io.hpp b/orocos_kdl/src/framevel_io.hpp index 2124c13..0cbb87e 100644 --- a/orocos_kdl/src/framevel_io.hpp +++ b/orocos_kdl/src/framevel_io.hpp @@ -23,27 +23,28 @@ #include "framevel_io.hpp" #include "frames_io.hpp" +#include "kdl_export.hpp" namespace KDL { // Output... -inline std::ostream& operator << (std::ostream& os,const VectorVel& r) { +KDL_EXPORT inline std::ostream& operator << (std::ostream& os,const VectorVel& r) { os << "{" << r.p << "," << r.v << "}" << std::endl; return os; } -inline std::ostream& operator << (std::ostream& os,const RotationVel& r) { +KDL_EXPORT inline std::ostream& operator << (std::ostream& os,const RotationVel& r) { os << "{" << std::endl << r.R << "," < namespace KDL { - class Jacobian + class KDL_EXPORT Jacobian { public: Eigen::Matrix data; @@ -44,7 +45,7 @@ namespace KDL bool operator ==(const Jacobian& arg)const; bool operator !=(const Jacobian& arg)const; - friend bool Equal(const Jacobian& a,const Jacobian& b,double eps=epsilon); + KDL_EXPORT friend bool Equal(const Jacobian& a,const Jacobian& b,double eps=epsilon); ~Jacobian(); @@ -54,11 +55,11 @@ namespace KDL unsigned int rows()const; unsigned int columns()const; - friend void SetToZero(Jacobian& jac); + KDL_EXPORT friend void SetToZero(Jacobian& jac); - friend bool changeRefPoint(const Jacobian& src1, const Vector& base_AB, Jacobian& dest); - friend bool changeBase(const Jacobian& src1, const Rotation& rot, Jacobian& dest); - friend bool changeRefFrame(const Jacobian& src1,const Frame& frame, Jacobian& dest); + KDL_EXPORT friend bool changeRefPoint(const Jacobian& src1, const Vector& base_AB, Jacobian& dest); + KDL_EXPORT friend bool changeBase(const Jacobian& src1, const Rotation& rot, Jacobian& dest); + KDL_EXPORT friend bool changeRefFrame(const Jacobian& src1,const Frame& frame, Jacobian& dest); Twist getColumn(unsigned int i) const; void setColumn(unsigned int i,const Twist& t); diff --git a/orocos_kdl/src/jntarray.hpp b/orocos_kdl/src/jntarray.hpp index c438a67..c026375 100644 --- a/orocos_kdl/src/jntarray.hpp +++ b/orocos_kdl/src/jntarray.hpp @@ -24,6 +24,7 @@ #include "frames.hpp" #include "jacobian.hpp" +#include "kdl_export.hpp" #include @@ -66,7 +67,7 @@ class MyTask : public RTT::TaskContext */ - class JntArray + class KDL_EXPORT JntArray { public: Eigen::VectorXd data; @@ -135,15 +136,15 @@ class MyTask : public RTT::TaskContext */ unsigned int columns()const; - friend void Add(const JntArray& src1,const JntArray& src2,JntArray& dest); - friend void Subtract(const JntArray& src1,const JntArray& src2,JntArray& dest); - friend void Multiply(const JntArray& src,const double& factor,JntArray& dest); - friend void Divide(const JntArray& src,const double& factor,JntArray& dest); - friend void MultiplyJacobian(const Jacobian& jac, const JntArray& src, Twist& dest); - friend void SetToZero(JntArray& array); - friend bool Equal(const JntArray& src1,const JntArray& src2,double eps); + KDL_EXPORT friend void Add(const JntArray& src1,const JntArray& src2,JntArray& dest); + KDL_EXPORT friend void Subtract(const JntArray& src1,const JntArray& src2,JntArray& dest); + KDL_EXPORT friend void Multiply(const JntArray& src,const double& factor,JntArray& dest); + KDL_EXPORT friend void Divide(const JntArray& src,const double& factor,JntArray& dest); + KDL_EXPORT friend void MultiplyJacobian(const Jacobian& jac, const JntArray& src, Twist& dest); + KDL_EXPORT friend void SetToZero(JntArray& array); + KDL_EXPORT friend bool Equal(const JntArray& src1,const JntArray& src2,double eps); - friend bool operator==(const JntArray& src1,const JntArray& src2); + KDL_EXPORT friend bool operator==(const JntArray& src1,const JntArray& src2); //friend bool operator!=(const JntArray& src1,const JntArray& src2); }; diff --git a/orocos_kdl/src/jntarrayacc.hpp b/orocos_kdl/src/jntarrayacc.hpp index c3d929e..5d0ce29 100644 --- a/orocos_kdl/src/jntarrayacc.hpp +++ b/orocos_kdl/src/jntarrayacc.hpp @@ -26,10 +26,11 @@ #include "jntarray.hpp" #include "jntarrayvel.hpp" #include "frameacc.hpp" +#include "kdl_export.hpp" namespace KDL { - class JntArrayAcc + class KDL_EXPORT JntArrayAcc { public: JntArray q; @@ -48,20 +49,20 @@ namespace KDL JntArray deriv()const; JntArray dderiv()const; - friend void Add(const JntArrayAcc& src1,const JntArrayAcc& src2,JntArrayAcc& dest); - friend void Add(const JntArrayAcc& src1,const JntArrayVel& src2,JntArrayAcc& dest); - friend void Add(const JntArrayAcc& src1,const JntArray& src2,JntArrayAcc& dest); - friend void Subtract(const JntArrayAcc& src1,const JntArrayAcc& src2,JntArrayAcc& dest); - friend void Subtract(const JntArrayAcc& src1,const JntArrayVel& src2,JntArrayAcc& dest); - friend void Subtract(const JntArrayAcc& src1,const JntArray& src2,JntArrayAcc& dest); - friend void Multiply(const JntArrayAcc& src,const double& factor,JntArrayAcc& dest); - friend void Multiply(const JntArrayAcc& src,const doubleVel& factor,JntArrayAcc& dest); - friend void Multiply(const JntArrayAcc& src,const doubleAcc& factor,JntArrayAcc& dest); - friend void Divide(const JntArrayAcc& src,const double& factor,JntArrayAcc& dest); - friend void Divide(const JntArrayAcc& src,const doubleVel& factor,JntArrayAcc& dest); - friend void Divide(const JntArrayAcc& src,const doubleAcc& factor,JntArrayAcc& dest); - friend void SetToZero(JntArrayAcc& array); - friend bool Equal(const JntArrayAcc& src1,const JntArrayAcc& src2,double eps=epsilon); + KDL_EXPORT friend void Add(const JntArrayAcc& src1,const JntArrayAcc& src2,JntArrayAcc& dest); + KDL_EXPORT friend void Add(const JntArrayAcc& src1,const JntArrayVel& src2,JntArrayAcc& dest); + KDL_EXPORT friend void Add(const JntArrayAcc& src1,const JntArray& src2,JntArrayAcc& dest); + KDL_EXPORT friend void Subtract(const JntArrayAcc& src1,const JntArrayAcc& src2,JntArrayAcc& dest); + KDL_EXPORT friend void Subtract(const JntArrayAcc& src1,const JntArrayVel& src2,JntArrayAcc& dest); + KDL_EXPORT friend void Subtract(const JntArrayAcc& src1,const JntArray& src2,JntArrayAcc& dest); + KDL_EXPORT friend void Multiply(const JntArrayAcc& src,const double& factor,JntArrayAcc& dest); + KDL_EXPORT friend void Multiply(const JntArrayAcc& src,const doubleVel& factor,JntArrayAcc& dest); + KDL_EXPORT friend void Multiply(const JntArrayAcc& src,const doubleAcc& factor,JntArrayAcc& dest); + KDL_EXPORT friend void Divide(const JntArrayAcc& src,const double& factor,JntArrayAcc& dest); + KDL_EXPORT friend void Divide(const JntArrayAcc& src,const doubleVel& factor,JntArrayAcc& dest); + KDL_EXPORT friend void Divide(const JntArrayAcc& src,const doubleAcc& factor,JntArrayAcc& dest); + KDL_EXPORT friend void SetToZero(JntArrayAcc& array); + KDL_EXPORT friend bool Equal(const JntArrayAcc& src1,const JntArrayAcc& src2,double eps=epsilon); }; } diff --git a/orocos_kdl/src/jntarrayvel.hpp b/orocos_kdl/src/jntarrayvel.hpp index c9cf764..72cb4b1 100644 --- a/orocos_kdl/src/jntarrayvel.hpp +++ b/orocos_kdl/src/jntarrayvel.hpp @@ -25,11 +25,12 @@ #include "utilities/utility.h" #include "jntarray.hpp" #include "framevel.hpp" +#include "kdl_export.hpp" namespace KDL { - class JntArrayVel + class KDL_EXPORT JntArrayVel { public: JntArray q; @@ -45,16 +46,16 @@ namespace KDL JntArray value()const; JntArray deriv()const; - friend void Add(const JntArrayVel& src1,const JntArrayVel& src2,JntArrayVel& dest); - friend void Add(const JntArrayVel& src1,const JntArray& src2,JntArrayVel& dest); - friend void Subtract(const JntArrayVel& src1,const JntArrayVel& src2,JntArrayVel& dest); - friend void Subtract(const JntArrayVel& src1,const JntArray& src2,JntArrayVel& dest); - friend void Multiply(const JntArrayVel& src,const double& factor,JntArrayVel& dest); - friend void Multiply(const JntArrayVel& src,const doubleVel& factor,JntArrayVel& dest); - friend void Divide(const JntArrayVel& src,const double& factor,JntArrayVel& dest); - friend void Divide(const JntArrayVel& src,const doubleVel& factor,JntArrayVel& dest); - friend void SetToZero(JntArrayVel& array); - friend bool Equal(const JntArrayVel& src1,const JntArrayVel& src2,double eps=epsilon); + KDL_EXPORT friend void Add(const JntArrayVel& src1,const JntArrayVel& src2,JntArrayVel& dest); + KDL_EXPORT friend void Add(const JntArrayVel& src1,const JntArray& src2,JntArrayVel& dest); + KDL_EXPORT friend void Subtract(const JntArrayVel& src1,const JntArrayVel& src2,JntArrayVel& dest); + KDL_EXPORT friend void Subtract(const JntArrayVel& src1,const JntArray& src2,JntArrayVel& dest); + KDL_EXPORT friend void Multiply(const JntArrayVel& src,const double& factor,JntArrayVel& dest); + KDL_EXPORT friend void Multiply(const JntArrayVel& src,const doubleVel& factor,JntArrayVel& dest); + KDL_EXPORT friend void Divide(const JntArrayVel& src,const double& factor,JntArrayVel& dest); + KDL_EXPORT friend void Divide(const JntArrayVel& src,const doubleVel& factor,JntArrayVel& dest); + KDL_EXPORT friend void SetToZero(JntArrayVel& array); + KDL_EXPORT friend bool Equal(const JntArrayVel& src1,const JntArrayVel& src2,double eps=epsilon); }; } diff --git a/orocos_kdl/src/jntspaceinertiamatrix.hpp b/orocos_kdl/src/jntspaceinertiamatrix.hpp index 9376d3c..818815e 100644 --- a/orocos_kdl/src/jntspaceinertiamatrix.hpp +++ b/orocos_kdl/src/jntspaceinertiamatrix.hpp @@ -25,6 +25,7 @@ #include "frames.hpp" #include "jacobian.hpp" #include "jntarray.hpp" +#include "kdl_export.hpp" #include @@ -67,7 +68,7 @@ class MyTask : public RTT::TaskContext */ - class JntSpaceInertiaMatrix + class KDL_EXPORT JntSpaceInertiaMatrix { public: Eigen::MatrixXd data; @@ -143,7 +144,7 @@ class MyTask : public RTT::TaskContext * @param src2 B * @param dest C */ - friend void Add(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,JntSpaceInertiaMatrix& dest); + KDL_EXPORT friend void Add(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,JntSpaceInertiaMatrix& dest); /** * Function to subtract two joint matrix, all the arguments must * have the same size: A - B = C. This function is @@ -153,7 +154,7 @@ class MyTask : public RTT::TaskContext * @param src2 B * @param dest C */ - friend void Subtract(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,JntSpaceInertiaMatrix& dest); + KDL_EXPORT friend void Subtract(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,JntSpaceInertiaMatrix& dest); /** * Function to multiply all the array values with a scalar * factor: A*b=C. This function is aliasing-safe, A can be the @@ -163,7 +164,7 @@ class MyTask : public RTT::TaskContext * @param factor b * @param dest C */ - friend void Multiply(const JntSpaceInertiaMatrix& src,const double& factor,JntSpaceInertiaMatrix& dest); + KDL_EXPORT friend void Multiply(const JntSpaceInertiaMatrix& src,const double& factor,JntSpaceInertiaMatrix& dest); /** * Function to divide all the array values with a scalar * factor: A/b=C. This function is aliasing-safe, A can be the @@ -173,7 +174,7 @@ class MyTask : public RTT::TaskContext * @param factor b * @param dest C */ - friend void Divide(const JntSpaceInertiaMatrix& src,const double& factor,JntSpaceInertiaMatrix& dest); + KDL_EXPORT friend void Divide(const JntSpaceInertiaMatrix& src,const double& factor,JntSpaceInertiaMatrix& dest); /** * Function to multiply a KDL::Jacobian with a KDL::JntSpaceInertiaMatrix * to get a KDL::Twist, it should not be used to calculate the @@ -186,13 +187,13 @@ class MyTask : public RTT::TaskContext * @param dest t * @post dest==Twist::Zero() if 0==src.rows() (ie src is empty) */ - friend void Multiply(const JntSpaceInertiaMatrix& src, const JntArray& vec, JntArray& dest); + KDL_EXPORT friend void Multiply(const JntSpaceInertiaMatrix& src, const JntArray& vec, JntArray& dest); /** * Function to set all the values of the array to 0 * * @param array */ - friend void SetToZero(JntSpaceInertiaMatrix& matrix); + KDL_EXPORT friend void SetToZero(JntSpaceInertiaMatrix& matrix); /** * Function to check if two matrices are the same with a *precision of eps @@ -203,9 +204,9 @@ class MyTask : public RTT::TaskContext * @return true if each element of src1 is within eps of the same * element in src2, or if both src1 and src2 have no data (ie 0==rows()) */ - friend bool Equal(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,double eps=epsilon); + KDL_EXPORT friend bool Equal(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2,double eps=epsilon); - friend bool operator==(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2); + KDL_EXPORT friend bool operator==(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2); //friend bool operator!=(const JntSpaceInertiaMatrix& src1,const JntSpaceInertiaMatrix& src2); }; diff --git a/orocos_kdl/src/joint.hpp b/orocos_kdl/src/joint.hpp index 4c677ec..67e2d9e 100644 --- a/orocos_kdl/src/joint.hpp +++ b/orocos_kdl/src/joint.hpp @@ -23,10 +23,10 @@ #define KDL_JOINT_HPP #include "frames.hpp" +#include "kdl_export.hpp" #include #include - namespace KDL { /** @@ -42,7 +42,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class Joint { + class KDL_EXPORT Joint { public: typedef enum { RotAxis,RotX,RotY,RotZ,TransAxis,TransX,TransY,TransZ,None} JointType; /** diff --git a/orocos_kdl/src/kinfam_io.hpp b/orocos_kdl/src/kinfam_io.hpp index c677c20..a476e65 100644 --- a/orocos_kdl/src/kinfam_io.hpp +++ b/orocos_kdl/src/kinfam_io.hpp @@ -22,9 +22,6 @@ #ifndef KDL_KINFAM_IO_HPP #define KDL_KINFAM_IO_HPP -#include -#include - #include "joint.hpp" #include "segment.hpp" #include "chain.hpp" @@ -32,26 +29,31 @@ #include "jacobian.hpp" #include "tree.hpp" #include "jntspaceinertiamatrix.hpp" +#include "kdl_export.hpp" + +#include +#include namespace KDL { -std::ostream& operator <<(std::ostream& os, const Joint& joint); -std::istream& operator >>(std::istream& is, Joint& joint); -std::ostream& operator <<(std::ostream& os, const Segment& segment); -std::istream& operator >>(std::istream& is, Segment& segment); -std::ostream& operator <<(std::ostream& os, const Chain& chain); -std::istream& operator >>(std::istream& is, Chain& chain); -std::ostream& operator <<(std::ostream& os, const Tree& tree); -std::istream& operator >>(std::istream& is, Tree& tree); +KDL_EXPORT std::ostream& operator <<(std::ostream& os, const Joint& joint); +KDL_EXPORT std::istream& operator >>(std::istream& is, Joint& joint); +KDL_EXPORT std::ostream& operator <<(std::ostream& os, const Segment& segment); +KDL_EXPORT std::istream& operator >>(std::istream& is, Segment& segment); +KDL_EXPORT std::ostream& operator <<(std::ostream& os, const Chain& chain); +KDL_EXPORT std::istream& operator >>(std::istream& is, Chain& chain); + +KDL_EXPORT std::ostream& operator <<(std::ostream& os, const Tree& tree); +KDL_EXPORT std::istream& operator >>(std::istream& is, Tree& tree); -std::ostream& operator <<(std::ostream& os, SegmentMap::const_iterator it); +KDL_EXPORT std::ostream& operator <<(std::ostream& os, SegmentMap::const_iterator it); -std::ostream& operator <<(std::ostream& os, const JntArray& array); -std::istream& operator >>(std::istream& is, JntArray& array); -std::ostream& operator <<(std::ostream& os, const Jacobian& jac); -std::istream& operator >>(std::istream& is, Jacobian& jac); -std::ostream& operator <<(std::ostream& os, const JntSpaceInertiaMatrix& jntspaceinertiamatrix); -std::istream& operator >>(std::istream& is, JntSpaceInertiaMatrix& jntspaceinertiamatrix); +KDL_EXPORT std::ostream& operator <<(std::ostream& os, const JntArray& array); +KDL_EXPORT std::istream& operator >>(std::istream& is, JntArray& array); +KDL_EXPORT std::ostream& operator <<(std::ostream& os, const Jacobian& jac); +KDL_EXPORT std::istream& operator >>(std::istream& is, Jacobian& jac); +KDL_EXPORT std::ostream& operator <<(std::ostream& os, const JntSpaceInertiaMatrix& jntspaceinertiamatrix); +KDL_EXPORT std::istream& operator >>(std::istream& is, JntSpaceInertiaMatrix& jntspaceinertiamatrix); /* template diff --git a/orocos_kdl/src/path.hpp b/orocos_kdl/src/path.hpp index 6cffae4..d25dd09 100644 --- a/orocos_kdl/src/path.hpp +++ b/orocos_kdl/src/path.hpp @@ -45,17 +45,16 @@ #define KDL_MOTION_PATH_H #include "frames.hpp" - -#include - #include "frames_io.hpp" +#include "kdl_export.hpp" +#include namespace KDL { /** * The specification of the path of a trajectory. */ -class Path +class KDL_EXPORT Path { public: enum IdentifierType { diff --git a/orocos_kdl/src/path_circle.hpp b/orocos_kdl/src/path_circle.hpp index 36166cf..374446e 100644 --- a/orocos_kdl/src/path_circle.hpp +++ b/orocos_kdl/src/path_circle.hpp @@ -47,7 +47,7 @@ #include "path.hpp" #include "rotational_interpolation.hpp" - +#include "kdl_export.hpp" namespace KDL { @@ -57,7 +57,7 @@ namespace KDL { * have been a better name though. * @ingroup Motion */ -class Path_Circle : public Path +class KDL_EXPORT Path_Circle : public Path { // Orientatie gedeelte diff --git a/orocos_kdl/src/path_composite.hpp b/orocos_kdl/src/path_composite.hpp index 25466eb..e951a14 100644 --- a/orocos_kdl/src/path_composite.hpp +++ b/orocos_kdl/src/path_composite.hpp @@ -47,6 +47,7 @@ #include "frames.hpp" #include "frames_io.hpp" #include "path.hpp" +#include "kdl_export.hpp" #include namespace KDL { @@ -66,7 +67,7 @@ namespace KDL { * * @ingroup Motion */ - class Path_Composite : public Path + class KDL_EXPORT Path_Composite : public Path { typedef std::vector< std::pair > PathVector; typedef std::vector DoubleVector; diff --git a/orocos_kdl/src/path_cyclic_closed.hpp b/orocos_kdl/src/path_cyclic_closed.hpp index 73f98bd..0e751b3 100644 --- a/orocos_kdl/src/path_cyclic_closed.hpp +++ b/orocos_kdl/src/path_cyclic_closed.hpp @@ -47,6 +47,7 @@ #include "frames.hpp" #include "frames_io.hpp" #include "path.hpp" +#include "kdl_export.hpp" #include @@ -57,7 +58,7 @@ namespace KDL { * which is traversed a number of times. * @ingroup Motion */ - class Path_Cyclic_Closed : public Path + class KDL_EXPORT Path_Cyclic_Closed : public Path { int times; Path* geom; diff --git a/orocos_kdl/src/path_line.hpp b/orocos_kdl/src/path_line.hpp index 548aaf4..d974a6e 100644 --- a/orocos_kdl/src/path_line.hpp +++ b/orocos_kdl/src/path_line.hpp @@ -47,6 +47,7 @@ #include "path.hpp" #include "rotational_interpolation.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -56,7 +57,7 @@ namespace KDL { * A path representing a line from A to B. * @ingroup Motion */ -class Path_Line : public Path +class KDL_EXPORT Path_Line : public Path { // Orientatie gedeelte RotationalInterpolation* orient; diff --git a/orocos_kdl/src/path_point.hpp b/orocos_kdl/src/path_point.hpp index 8045cb4..1d79cfd 100644 --- a/orocos_kdl/src/path_point.hpp +++ b/orocos_kdl/src/path_point.hpp @@ -48,7 +48,7 @@ #include "path.hpp" #include "rotational_interpolation.hpp" - +#include "kdl_export.hpp" namespace KDL { @@ -58,7 +58,7 @@ namespace KDL { * A Path consisting only of a point in space. * @ingroup Motion */ -class Path_Point : public Path +class KDL_EXPORT Path_Point : public Path { Frame F_base_start; public: diff --git a/orocos_kdl/src/path_roundedcomposite.hpp b/orocos_kdl/src/path_roundedcomposite.hpp index 79c2657..a8e1894 100644 --- a/orocos_kdl/src/path_roundedcomposite.hpp +++ b/orocos_kdl/src/path_roundedcomposite.hpp @@ -47,6 +47,7 @@ #include "path.hpp" #include "path_composite.hpp" #include "rotational_interpolation.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -55,7 +56,7 @@ namespace KDL { * * @ingroup Motion */ -class Path_RoundedComposite : public Path +class KDL_EXPORT Path_RoundedComposite : public Path { /** a Path_Composite is aggregated to hold the rounded trajectory * with circles and lines diff --git a/orocos_kdl/src/rigidbodyinertia.hpp b/orocos_kdl/src/rigidbodyinertia.hpp index 6bc8f5e..5c81188 100644 --- a/orocos_kdl/src/rigidbodyinertia.hpp +++ b/orocos_kdl/src/rigidbodyinertia.hpp @@ -23,8 +23,8 @@ #define KDL_RIGIDBODYINERTIA_HPP #include "frames.hpp" - #include "rotationalinertia.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -34,7 +34,7 @@ namespace KDL { * The inertia is defined in a certain reference point and a certain reference base. * The reference point does not have to coincide with the origin of the reference frame. */ - class RigidBodyInertia{ + class KDL_EXPORT RigidBodyInertia{ public: /** @@ -56,29 +56,29 @@ namespace KDL { /** * Scalar product: I_new = double * I_old */ - friend RigidBodyInertia operator*(double a,const RigidBodyInertia& I); + KDL_EXPORT friend RigidBodyInertia operator*(double a,const RigidBodyInertia& I); /** * addition I: I_new = I_old1 + I_old2, make sure that I_old1 * and I_old2 are expressed in the same reference frame/point, * otherwise the result is worth nothing */ - friend RigidBodyInertia operator+(const RigidBodyInertia& Ia,const RigidBodyInertia& Ib); + KDL_EXPORT friend RigidBodyInertia operator+(const RigidBodyInertia& Ia,const RigidBodyInertia& Ib); /** * calculate spatial momentum: h = I*v * make sure that the twist v and the inertia are expressed in the same reference frame/point */ - friend Wrench operator*(const RigidBodyInertia& I,const Twist& t); + KDL_EXPORT friend Wrench operator*(const RigidBodyInertia& I,const Twist& t); /** * Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b. */ - friend RigidBodyInertia operator*(const Frame& T,const RigidBodyInertia& I); + KDL_EXPORT friend RigidBodyInertia operator*(const Frame& T,const RigidBodyInertia& I); /** * Reference frame orientation change Ia = R_a_b*Ib with R_a_b * the rotation of b expressed in a */ - friend RigidBodyInertia operator*(const Rotation& R,const RigidBodyInertia& I); + KDL_EXPORT friend RigidBodyInertia operator*(const Rotation& R,const RigidBodyInertia& I); /** * Reference point change with v the vector from the old to diff --git a/orocos_kdl/src/rotational_interpolation.hpp b/orocos_kdl/src/rotational_interpolation.hpp index ced4914..4b13241 100644 --- a/orocos_kdl/src/rotational_interpolation.hpp +++ b/orocos_kdl/src/rotational_interpolation.hpp @@ -46,6 +46,7 @@ #include "frames.hpp" #include "frames_io.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -59,7 +60,7 @@ namespace KDL { * object is responsible for setting these each time * @ingroup Motion */ -class RotationalInterpolation +class KDL_EXPORT RotationalInterpolation { public: /** diff --git a/orocos_kdl/src/rotational_interpolation_sa.hpp b/orocos_kdl/src/rotational_interpolation_sa.hpp index b8a2840..d4d0bed 100644 --- a/orocos_kdl/src/rotational_interpolation_sa.hpp +++ b/orocos_kdl/src/rotational_interpolation_sa.hpp @@ -47,6 +47,7 @@ #include "frames.hpp" #include "frames_io.hpp" #include "rotational_interpolation.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -60,7 +61,7 @@ namespace KDL { * to try to interpolate a 180 degrees rotation. * @ingroup Motion */ -class RotationalInterpolation_SingleAxis: public RotationalInterpolation +class KDL_EXPORT RotationalInterpolation_SingleAxis: public RotationalInterpolation { Rotation R_base_start; Rotation R_base_end; diff --git a/orocos_kdl/src/rotationalinertia.hpp b/orocos_kdl/src/rotationalinertia.hpp index a648392..0791d35 100644 --- a/orocos_kdl/src/rotationalinertia.hpp +++ b/orocos_kdl/src/rotationalinertia.hpp @@ -23,6 +23,7 @@ #define KDL_ROTATIONALINERTIA_HPP #include "frames.hpp" +#include "kdl_export.hpp" //------- class for only the Rotational Inertia -------- @@ -31,7 +32,7 @@ namespace KDL //Forward declaration class RigidBodyInertia; - class RotationalInertia{ + class KDL_EXPORT RotationalInertia{ public: explicit RotationalInertia(double Ixx=0,double Iyy=0,double Izz=0,double Ixy=0,double Ixz=0,double Iyz=0); @@ -40,8 +41,8 @@ namespace KDL return RotationalInertia(0,0,0,0,0,0); }; - friend RotationalInertia operator*(double a, const RotationalInertia& I); - friend RotationalInertia operator+(const RotationalInertia& Ia, const RotationalInertia& Ib); + KDL_EXPORT friend RotationalInertia operator*(double a, const RotationalInertia& I); + KDL_EXPORT friend RotationalInertia operator+(const RotationalInertia& Ia, const RotationalInertia& Ib); /** * This function calculates the angular momentum resulting from a rotational velocity omega @@ -52,15 +53,15 @@ namespace KDL friend class RigidBodyInertia; ///Scalar product - friend RigidBodyInertia operator*(double a,const RigidBodyInertia& I); + KDL_EXPORT friend RigidBodyInertia operator*(double a,const RigidBodyInertia& I); ///addition - friend RigidBodyInertia operator+(const RigidBodyInertia& Ia,const RigidBodyInertia& Ib); + KDL_EXPORT friend RigidBodyInertia operator+(const RigidBodyInertia& Ia,const RigidBodyInertia& Ib); ///calculate spatial momentum - friend Wrench operator*(const RigidBodyInertia& I,const Twist& t); + KDL_EXPORT friend Wrench operator*(const RigidBodyInertia& I,const Twist& t); ///coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b - friend RigidBodyInertia operator*(const Frame& T,const RigidBodyInertia& I); + KDL_EXPORT friend RigidBodyInertia operator*(const Frame& T,const RigidBodyInertia& I); ///base frame orientation change Ia = R_a_b*Ib with R_a_b the rotation for frame from a to b - friend RigidBodyInertia operator*(const Rotation& R,const RigidBodyInertia& I); + KDL_EXPORT friend RigidBodyInertia operator*(const Rotation& R,const RigidBodyInertia& I); double data[9]; }; diff --git a/orocos_kdl/src/segment.hpp b/orocos_kdl/src/segment.hpp index 2ea4666..ea88367 100644 --- a/orocos_kdl/src/segment.hpp +++ b/orocos_kdl/src/segment.hpp @@ -26,6 +26,7 @@ #include "frames.hpp" #include "rigidbodyinertia.hpp" #include "joint.hpp" +#include "kdl_export.hpp" #include namespace KDL { @@ -43,7 +44,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class Segment { + class KDL_EXPORT Segment { friend class Chain; private: std::string name; diff --git a/orocos_kdl/src/stiffness.hpp b/orocos_kdl/src/stiffness.hpp index 907d86d..b32c3f2 100644 --- a/orocos_kdl/src/stiffness.hpp +++ b/orocos_kdl/src/stiffness.hpp @@ -22,7 +22,7 @@ #ifndef KDL_STIFFNESS_H #define KDL_STIFFNESS_H #include "frames.hpp" - +#include "kdl_export.hpp" namespace KDL { /** @@ -33,7 +33,7 @@ namespace KDL { * first 3 elements are stiffness for translations * last 3 elements are stiffness for rotations. */ -class Stiffness { +class KDL_EXPORT Stiffness { double data[6]; public: Stiffness() { diff --git a/orocos_kdl/src/trajectory.hpp b/orocos_kdl/src/trajectory.hpp index f633a0c..0fae899 100644 --- a/orocos_kdl/src/trajectory.hpp +++ b/orocos_kdl/src/trajectory.hpp @@ -61,21 +61,19 @@ #include "frames_io.hpp" #include "path.hpp" #include "velocityprofile.hpp" - +#include "kdl_export.hpp" namespace KDL { - - /** * An abstract class that implements * a trajectory contains a cartesian space trajectory and an underlying * velocity profile. * @ingroup Motion */ - class Trajectory + class KDL_EXPORT Trajectory { public: virtual double Duration() const = 0; diff --git a/orocos_kdl/src/trajectory_composite.hpp b/orocos_kdl/src/trajectory_composite.hpp index a110e39..e3c7b51 100644 --- a/orocos_kdl/src/trajectory_composite.hpp +++ b/orocos_kdl/src/trajectory_composite.hpp @@ -20,7 +20,7 @@ #include "trajectory.hpp" #include "path_composite.hpp" #include - +#include "kdl_export.hpp" namespace KDL { @@ -29,7 +29,7 @@ namespace KDL { * of underlying trajectoria. Call Add to add a trajectory * @ingroup Motion */ -class Trajectory_Composite: public Trajectory +class KDL_EXPORT Trajectory_Composite: public Trajectory { typedef std::vector VectorTraj; typedef std::vector VectorDouble; diff --git a/orocos_kdl/src/trajectory_segment.hpp b/orocos_kdl/src/trajectory_segment.hpp index 8d72503..f2f0a41 100644 --- a/orocos_kdl/src/trajectory_segment.hpp +++ b/orocos_kdl/src/trajectory_segment.hpp @@ -49,6 +49,7 @@ #include "trajectory.hpp" #include "path.hpp" #include "velocityprofile.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -59,7 +60,7 @@ namespace KDL { * trajectory * @ingroup Motion */ - class Trajectory_Segment : public Trajectory + class KDL_EXPORT Trajectory_Segment : public Trajectory { VelocityProfile* motprof; Path* geom; diff --git a/orocos_kdl/src/trajectory_stationary.hpp b/orocos_kdl/src/trajectory_stationary.hpp index 060b2b0..889e249 100644 --- a/orocos_kdl/src/trajectory_stationary.hpp +++ b/orocos_kdl/src/trajectory_stationary.hpp @@ -17,6 +17,7 @@ #define TRAJECTORY_STATIONARY_H #include "trajectory.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -25,7 +26,7 @@ namespace KDL { * for an amount of time. * @ingroup Motion */ - class Trajectory_Stationary : public Trajectory + class KDL_EXPORT Trajectory_Stationary : public Trajectory { double duration; Frame pos; diff --git a/orocos_kdl/src/tree.hpp b/orocos_kdl/src/tree.hpp index 45f0429..2a504b4 100644 --- a/orocos_kdl/src/tree.hpp +++ b/orocos_kdl/src/tree.hpp @@ -24,6 +24,7 @@ #include "segment.hpp" #include "chain.hpp" +#include "kdl_export.hpp" #include #include @@ -34,7 +35,7 @@ namespace KDL class TreeElement; typedef std::map SegmentMap; - class TreeElement + class KDL_EXPORT TreeElement { private: TreeElement(const std::string& name):segment(name), q_nr(0) @@ -62,7 +63,7 @@ namespace KDL * * @ingroup KinematicFamily */ - class Tree + class KDL_EXPORT Tree { private: SegmentMap segments; diff --git a/orocos_kdl/src/treefksolver.hpp b/orocos_kdl/src/treefksolver.hpp index 3d521d3..ff0f83f 100644 --- a/orocos_kdl/src/treefksolver.hpp +++ b/orocos_kdl/src/treefksolver.hpp @@ -31,6 +31,7 @@ #include "jntarray.hpp" //#include "jntarrayvel.hpp" //#include "jntarrayacc.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -42,7 +43,7 @@ namespace KDL { */ //Forward definition - class TreeFkSolverPos { + class KDL_EXPORT TreeFkSolverPos { public: /** * Calculate forward position kinematics for a KDL::Tree, @@ -63,7 +64,7 @@ namespace KDL { * * @ingroup KinematicFamily */ -// class TreeFkSolverVel { +// class KDL_EXPORT TreeFkSolverVel { // public: /** * Calculate forward position and velocity kinematics, from @@ -86,7 +87,7 @@ namespace KDL { * @ingroup KinematicFamily */ -// class TreeFkSolverAcc { +// class KDL_EXPORT TreeFkSolverAcc { // public: /** * Calculate forward position, velocity and accelaration diff --git a/orocos_kdl/src/treefksolverpos_recursive.hpp b/orocos_kdl/src/treefksolverpos_recursive.hpp index 14f6450..9e6e6e7 100644 --- a/orocos_kdl/src/treefksolverpos_recursive.hpp +++ b/orocos_kdl/src/treefksolverpos_recursive.hpp @@ -24,6 +24,7 @@ #define KDLTREEFKSOLVERPOS_RECURSIVE_HPP #include "treefksolver.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -34,7 +35,7 @@ namespace KDL { * * @ingroup KinematicFamily */ - class TreeFkSolverPos_recursive : public TreeFkSolverPos + class KDL_EXPORT TreeFkSolverPos_recursive : public TreeFkSolverPos { public: TreeFkSolverPos_recursive(const Tree& tree); diff --git a/orocos_kdl/src/treeiksolver.hpp b/orocos_kdl/src/treeiksolver.hpp index e6a5200..4526f6b 100644 --- a/orocos_kdl/src/treeiksolver.hpp +++ b/orocos_kdl/src/treeiksolver.hpp @@ -11,6 +11,7 @@ #include "tree.hpp" #include "jntarray.hpp" #include "frames.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -24,7 +25,7 @@ typedef std::map Frames; * * @ingroup KinematicFamily */ -class TreeIkSolverPos { +class KDL_EXPORT TreeIkSolverPos { public: /** * Calculate inverse position kinematics, from cartesian diff --git a/orocos_kdl/src/treeiksolverpos_nr_jl.hpp b/orocos_kdl/src/treeiksolverpos_nr_jl.hpp index 456e7fa..3f56c10 100644 --- a/orocos_kdl/src/treeiksolverpos_nr_jl.hpp +++ b/orocos_kdl/src/treeiksolverpos_nr_jl.hpp @@ -26,6 +26,7 @@ #include "treeiksolver.hpp" #include "treefksolver.hpp" +#include "kdl_export.hpp" #include #include @@ -39,7 +40,7 @@ namespace KDL { * * @ingroup KinematicFamily */ -class TreeIkSolverPos_NR_JL: public TreeIkSolverPos { +class KDL_EXPORT TreeIkSolverPos_NR_JL: public TreeIkSolverPos { public: /** * Constructor of the solver, it needs the tree, a forward diff --git a/orocos_kdl/src/treeiksolverpos_online.hpp b/orocos_kdl/src/treeiksolverpos_online.hpp index 7826eb4..6682b92 100644 --- a/orocos_kdl/src/treeiksolverpos_online.hpp +++ b/orocos_kdl/src/treeiksolverpos_online.hpp @@ -29,6 +29,7 @@ #include #include "treeiksolver.hpp" #include "treefksolver.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -41,7 +42,7 @@ namespace KDL { * * @ingroup KinematicFamily */ -class TreeIkSolverPos_Online: public TreeIkSolverPos { +class KDL_EXPORT TreeIkSolverPos_Online: public TreeIkSolverPos { public: /** * Constructor of the solver, it needs the number of joints of the tree, a list of the endpoints diff --git a/orocos_kdl/src/treeiksolvervel_wdls.hpp b/orocos_kdl/src/treeiksolvervel_wdls.hpp index d268c72..2a5263e 100644 --- a/orocos_kdl/src/treeiksolvervel_wdls.hpp +++ b/orocos_kdl/src/treeiksolvervel_wdls.hpp @@ -10,13 +10,14 @@ #include "treeiksolver.hpp" #include "treejnttojacsolver.hpp" +#include "kdl_export.hpp" #include namespace KDL { using namespace Eigen; - class TreeIkSolverVel_wdls: public TreeIkSolverVel { + class KDL_EXPORT TreeIkSolverVel_wdls: public TreeIkSolverVel { public: TreeIkSolverVel_wdls(const Tree& tree, const std::vector& endpoints); virtual ~TreeIkSolverVel_wdls(); diff --git a/orocos_kdl/src/treejnttojacsolver.hpp b/orocos_kdl/src/treejnttojacsolver.hpp index 84f92ea..c82520f 100644 --- a/orocos_kdl/src/treejnttojacsolver.hpp +++ b/orocos_kdl/src/treejnttojacsolver.hpp @@ -11,10 +11,11 @@ #include "tree.hpp" #include "jacobian.hpp" #include "jntarray.hpp" +#include "kdl_export.hpp" namespace KDL { -class TreeJntToJacSolver { +class KDL_EXPORT TreeJntToJacSolver { public: explicit TreeJntToJacSolver(const Tree& tree); diff --git a/orocos_kdl/src/utilities/utility.h b/orocos_kdl/src/utilities/utility.h index 198f3ff..cd05c7a 100644 --- a/orocos_kdl/src/utilities/utility.h +++ b/orocos_kdl/src/utilities/utility.h @@ -24,6 +24,7 @@ #define KDL_UTILITY_H #include "kdl-config.h" +#include "kdl_export.hpp" #include #include #include @@ -177,16 +178,16 @@ extern int STREAMBUFFERSIZE; extern int MAXLENFILENAME; //! the value of pi -extern const double PI; +extern KDL_EXPORT const double PI; //! the value pi/180 -extern const double deg2rad; +extern KDL_EXPORT const double deg2rad; //! the value 180/pi -extern const double rad2deg; +extern KDL_EXPORT const double rad2deg; //! default precision while comparing with Equal(..,..) functions. Initialized at 0.0000001. -extern double epsilon; +extern KDL_EXPORT double epsilon; //! the number of derivatives used in the RN-... objects. extern int VSIZE; diff --git a/orocos_kdl/src/velocityprofile.hpp b/orocos_kdl/src/velocityprofile.hpp index 827e939..429ac38 100644 --- a/orocos_kdl/src/velocityprofile.hpp +++ b/orocos_kdl/src/velocityprofile.hpp @@ -47,7 +47,7 @@ #include "utilities/utility.h" #include "utilities/utility_io.h" - +#include "kdl_export.hpp" namespace KDL { @@ -59,7 +59,7 @@ namespace KDL { * in function of time. It defines the how a point s moves on a path S. * @ingroup Motion */ -class VelocityProfile +class KDL_EXPORT VelocityProfile { public: // trajectory parameters are set in constructor of diff --git a/orocos_kdl/src/velocityprofile_dirac.hpp b/orocos_kdl/src/velocityprofile_dirac.hpp index ce06b6d..a536fd7 100644 --- a/orocos_kdl/src/velocityprofile_dirac.hpp +++ b/orocos_kdl/src/velocityprofile_dirac.hpp @@ -30,7 +30,7 @@ #define MOTIONPROFILE_DIRAC_H #include "velocityprofile.hpp" - +#include "kdl_export.hpp" namespace KDL { /** @@ -45,7 +45,7 @@ namespace KDL { * Duration() == 0; * @ingroup Motion */ - class VelocityProfile_Dirac : public VelocityProfile + class KDL_EXPORT VelocityProfile_Dirac : public VelocityProfile { double p1,p2,t; public: diff --git a/orocos_kdl/src/velocityprofile_rect.hpp b/orocos_kdl/src/velocityprofile_rect.hpp index 4482779..416d715 100644 --- a/orocos_kdl/src/velocityprofile_rect.hpp +++ b/orocos_kdl/src/velocityprofile_rect.hpp @@ -45,7 +45,7 @@ #define MOTIONPROFILE_RECT_H #include "velocityprofile.hpp" - +#include "kdl_export.hpp" namespace KDL { /** @@ -53,7 +53,7 @@ namespace KDL { * for moving from A to B. * @ingroup Motion */ - class VelocityProfile_Rectangular : public VelocityProfile + class KDL_EXPORT VelocityProfile_Rectangular : public VelocityProfile // Defines a rectangular velocityprofile. // (i.e. constant velocity) { diff --git a/orocos_kdl/src/velocityprofile_spline.hpp b/orocos_kdl/src/velocityprofile_spline.hpp index 0ce9ea8..2211080 100644 --- a/orocos_kdl/src/velocityprofile_spline.hpp +++ b/orocos_kdl/src/velocityprofile_spline.hpp @@ -2,6 +2,7 @@ #define VELOCITYPROFILE_SPLINE_H #include "velocityprofile.hpp" +#include "kdl_export.hpp" namespace KDL { @@ -9,7 +10,7 @@ namespace KDL * \brief A spline VelocityProfile trajectory interpolation. * @ingroup Motion */ -class VelocityProfile_Spline : public VelocityProfile +class KDL_EXPORT VelocityProfile_Spline : public VelocityProfile { public: VelocityProfile_Spline(); diff --git a/orocos_kdl/src/velocityprofile_trap.hpp b/orocos_kdl/src/velocityprofile_trap.hpp index a8e1ba0..535c46b 100644 --- a/orocos_kdl/src/velocityprofile_trap.hpp +++ b/orocos_kdl/src/velocityprofile_trap.hpp @@ -45,19 +45,16 @@ #define KDL_MOTION_VELOCITYPROFILE_TRAP_H #include "velocityprofile.hpp" - - - +#include "kdl_export.hpp" namespace KDL { - /** * A Trapezoidal VelocityProfile implementation. * @ingroup Motion */ -class VelocityProfile_Trap : public VelocityProfile +class KDL_EXPORT VelocityProfile_Trap : public VelocityProfile { // For "running" a motion profile : double a1,a2,a3; // coef. from ^0 -> ^2 of first part diff --git a/orocos_kdl/src/velocityprofile_traphalf.hpp b/orocos_kdl/src/velocityprofile_traphalf.hpp index fcca324..27317a1 100644 --- a/orocos_kdl/src/velocityprofile_traphalf.hpp +++ b/orocos_kdl/src/velocityprofile_traphalf.hpp @@ -47,9 +47,7 @@ #define KDL_MOTION_VELOCITYPROFILE_TRAPHALF_H #include "velocityprofile.hpp" - - - +#include "kdl_export.hpp" namespace KDL { @@ -60,7 +58,7 @@ namespace KDL { * or ending. * @ingroup Motion */ -class VelocityProfile_TrapHalf : public VelocityProfile +class KDL_EXPORT VelocityProfile_TrapHalf : public VelocityProfile { // For "running" a motion profile : double a1,a2,a3; // coef. from ^0 -> ^2 of first part diff --git a/orocos_kdl/tests/CMakeLists.txt b/orocos_kdl/tests/CMakeLists.txt index 5d6395a..cd262f7 100644 --- a/orocos_kdl/tests/CMakeLists.txt +++ b/orocos_kdl/tests/CMakeLists.txt @@ -1,7 +1,7 @@ IF(ENABLE_TESTS) ENABLE_TESTING() - INCLUDE_DIRECTORIES(${PROJ_SOURCE_DIR}/src ${CPPUNIT_HEADERS}) + INCLUDE_DIRECTORIES(${PROJ_SOURCE_DIR}/src ${PROJ_BINARY_DIR}/src ${CPPUNIT_HEADERS}) ADD_EXECUTABLE(framestest framestest.cpp test-runner.cpp) TARGET_LINK_LIBRARIES(framestest orocos-kdl ${CPPUNIT}) diff --git a/orocos_kdl/tests/framestest.cpp b/orocos_kdl/tests/framestest.cpp index fd132db..793fe98 100644 --- a/orocos_kdl/tests/framestest.cpp +++ b/orocos_kdl/tests/framestest.cpp @@ -1,3 +1,4 @@ +#define _USE_MATH_DEFINES // For MSVC #include #include "framestest.hpp" #include @@ -352,17 +353,17 @@ void FramesTest::TestRotation() { TestRangeArbitraryRotation("[0,0,1]", Vector(0,0,1), Vector(0,0,1)); TestRangeArbitraryRotation("[0,0,-1]", Vector(0,0,-1), Vector(0,0,-1)); // X,Y axes - TestRangeArbitraryRotation("[1,1,0]", Vector(1,1,0), Vector(1,1,0)/sqrt(2.0)); - TestRangeArbitraryRotation("[-1,-1,0]", Vector(-1,-1,0), Vector(-1,-1,0)/sqrt(2.0)); + TestRangeArbitraryRotation("[1,1,0]", Vector(1,1,0), Vector(1,1,0)/::sqrt(2.0)); + TestRangeArbitraryRotation("[-1,-1,0]", Vector(-1,-1,0), Vector(-1,-1,0)/::sqrt(2.0)); // X,Z axes - TestRangeArbitraryRotation("[1,0,1]", Vector(1,0,1), Vector(1,0,1)/sqrt(2.0)); - TestRangeArbitraryRotation("[-1,0,-1]", Vector(-1,0,-1), Vector(-1,0,-1)/sqrt(2.0)); + TestRangeArbitraryRotation("[1,0,1]", Vector(1,0,1), Vector(1,0,1)/::sqrt(2.0)); + TestRangeArbitraryRotation("[-1,0,-1]", Vector(-1,0,-1), Vector(-1,0,-1)/::sqrt(2.0)); // Y,Z axes - TestRangeArbitraryRotation("[0,1,1]", Vector(0,1,1), Vector(0,1,1)/sqrt(2.0)); - TestRangeArbitraryRotation("[0,-1,-1]", Vector(0,-1,-1), Vector(0,-1,-1)/sqrt(2.0)); + TestRangeArbitraryRotation("[0,1,1]", Vector(0,1,1), Vector(0,1,1)/::sqrt(2.0)); + TestRangeArbitraryRotation("[0,-1,-1]", Vector(0,-1,-1), Vector(0,-1,-1)/::sqrt(2.0)); // X,Y,Z axes - TestRangeArbitraryRotation("[1,1,1]", Vector(1,1,1), Vector(1,1,1)/sqrt(3.0)); - TestRangeArbitraryRotation("[-1,-1,-1]", Vector(-1,-1,-1), Vector(-1,-1,-1)/sqrt(3.0)); + TestRangeArbitraryRotation("[1,1,1]", Vector(1,1,1), Vector(1,1,1)/::sqrt(3.0)); + TestRangeArbitraryRotation("[-1,-1,-1]", Vector(-1,-1,-1), Vector(-1,-1,-1)/::sqrt(3.0)); // these change ... some of the -180 are the same as the +180, and some // results are the opposite sign. @@ -377,33 +378,33 @@ void FramesTest::TestRotation() { // same as +180 TestOneRotation("rot([0,0,-1],180)", KDL::Rotation::Rot(KDL::Vector(0,0,-1),180*deg2rad), 180*deg2rad, Vector(0,0,1)); - TestOneRotation("rot([1,0,1],180)", KDL::Rotation::Rot(KDL::Vector(1,0,1),180*deg2rad), 180*deg2rad, Vector(1,0,1)/sqrt(2.0)); + TestOneRotation("rot([1,0,1],180)", KDL::Rotation::Rot(KDL::Vector(1,0,1),180*deg2rad), 180*deg2rad, Vector(1,0,1)/::sqrt(2.0)); // same as +180 - TestOneRotation("rot([1,0,1],-180)", KDL::Rotation::Rot(KDL::Vector(1,0,1),-180*deg2rad), 180*deg2rad, Vector(1,0,1)/sqrt(2.0)); - TestOneRotation("rot([-1,0,-1],180)", KDL::Rotation::Rot(KDL::Vector(-1,0,-1),180*deg2rad), 180*deg2rad, Vector(1,0,1)/sqrt(2.0)); + TestOneRotation("rot([1,0,1],-180)", KDL::Rotation::Rot(KDL::Vector(1,0,1),-180*deg2rad), 180*deg2rad, Vector(1,0,1)/::sqrt(2.0)); + TestOneRotation("rot([-1,0,-1],180)", KDL::Rotation::Rot(KDL::Vector(-1,0,-1),180*deg2rad), 180*deg2rad, Vector(1,0,1)/::sqrt(2.0)); // same as +180 - TestOneRotation("rot([-1,0,-1],-180)", KDL::Rotation::Rot(KDL::Vector(-1,0,-1),-180*deg2rad), 180*deg2rad, Vector(1,0,1)/sqrt(2.0)); + TestOneRotation("rot([-1,0,-1],-180)", KDL::Rotation::Rot(KDL::Vector(-1,0,-1),-180*deg2rad), 180*deg2rad, Vector(1,0,1)/::sqrt(2.0)); - TestOneRotation("rot([1,1,0],180)", KDL::Rotation::Rot(KDL::Vector(1,1,0),180*deg2rad), 180*deg2rad, Vector(1,1,0)/sqrt(2.0)); + TestOneRotation("rot([1,1,0],180)", KDL::Rotation::Rot(KDL::Vector(1,1,0),180*deg2rad), 180*deg2rad, Vector(1,1,0)/::sqrt(2.0)); // opposite of +180 - TestOneRotation("rot([1,1,0],-180)", KDL::Rotation::Rot(KDL::Vector(1,1,0),-180*deg2rad), 180*deg2rad, -Vector(1,1,0)/sqrt(2.0)); - TestOneRotation("rot([-1,-1,0],180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,0),180*deg2rad), 180*deg2rad, -Vector(1,1,0)/sqrt(2.0)); + TestOneRotation("rot([1,1,0],-180)", KDL::Rotation::Rot(KDL::Vector(1,1,0),-180*deg2rad), 180*deg2rad, -Vector(1,1,0)/::sqrt(2.0)); + TestOneRotation("rot([-1,-1,0],180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,0),180*deg2rad), 180*deg2rad, -Vector(1,1,0)/::sqrt(2.0)); // opposite of +180 - TestOneRotation("rot([-1,-1,0],-180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,0),-180*deg2rad), 180*deg2rad, Vector(1,1,0)/sqrt(2.0)); + TestOneRotation("rot([-1,-1,0],-180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,0),-180*deg2rad), 180*deg2rad, Vector(1,1,0)/::sqrt(2.0)); - TestOneRotation("rot([0,1,1],180)", KDL::Rotation::Rot(KDL::Vector(0,1,1),180*deg2rad), 180*deg2rad, Vector(0,1,1)/sqrt(2.0)); + TestOneRotation("rot([0,1,1],180)", KDL::Rotation::Rot(KDL::Vector(0,1,1),180*deg2rad), 180*deg2rad, Vector(0,1,1)/::sqrt(2.0)); // same as +180 - TestOneRotation("rot([0,1,1],-180)", KDL::Rotation::Rot(KDL::Vector(0,1,1),-180*deg2rad), 180*deg2rad, Vector(0,1,1)/sqrt(2.0)); - TestOneRotation("rot([0,-1,-1],180)", KDL::Rotation::Rot(KDL::Vector(0,-1,-1),180*deg2rad), 180*deg2rad, Vector(0,1,1)/sqrt(2.0)); + TestOneRotation("rot([0,1,1],-180)", KDL::Rotation::Rot(KDL::Vector(0,1,1),-180*deg2rad), 180*deg2rad, Vector(0,1,1)/::sqrt(2.0)); + TestOneRotation("rot([0,-1,-1],180)", KDL::Rotation::Rot(KDL::Vector(0,-1,-1),180*deg2rad), 180*deg2rad, Vector(0,1,1)/::sqrt(2.0)); // same as +180 - TestOneRotation("rot([0,-1,-1],-180)", KDL::Rotation::Rot(KDL::Vector(0,-1,-1),-180*deg2rad), 180*deg2rad, Vector(0,1,1)/sqrt(2.0)); + TestOneRotation("rot([0,-1,-1],-180)", KDL::Rotation::Rot(KDL::Vector(0,-1,-1),-180*deg2rad), 180*deg2rad, Vector(0,1,1)/::sqrt(2.0)); - TestOneRotation("rot([1,1,1],180)", KDL::Rotation::Rot(KDL::Vector(1,1,1),180*deg2rad), 180*deg2rad, Vector(1,1,1)/sqrt(3.0)); + TestOneRotation("rot([1,1,1],180)", KDL::Rotation::Rot(KDL::Vector(1,1,1),180*deg2rad), 180*deg2rad, Vector(1,1,1)/::sqrt(3.0)); // same as +180 - TestOneRotation("rot([1,1,1],-180)", KDL::Rotation::Rot(KDL::Vector(1,1,1),-180*deg2rad), 180*deg2rad, Vector(1,1,1)/sqrt(3.0)); - TestOneRotation("rot([-1,-1,-1],180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,-1),180*deg2rad), 180*deg2rad, Vector(1,1,1)/sqrt(3.0)); + TestOneRotation("rot([1,1,1],-180)", KDL::Rotation::Rot(KDL::Vector(1,1,1),-180*deg2rad), 180*deg2rad, Vector(1,1,1)/::sqrt(3.0)); + TestOneRotation("rot([-1,-1,-1],180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,-1),180*deg2rad), 180*deg2rad, Vector(1,1,1)/::sqrt(3.0)); // same as +180 - TestOneRotation("rot([-1,-1,-1],-180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,-1),-180*deg2rad), 180*deg2rad, Vector(1,1,1)/sqrt(3.0)); + TestOneRotation("rot([-1,-1,-1],-180)", KDL::Rotation::Rot(KDL::Vector(-1,-1,-1),-180*deg2rad), 180*deg2rad, Vector(1,1,1)/::sqrt(3.0)); } void FramesTest::TestQuaternion() { @@ -420,15 +421,15 @@ void FramesTest::TestQuaternion() { // 45 deg rotation in X R = Rotation::EulerZYX(0,0,45*deg2rad); R.GetQuaternion(x,y,z,w); - CPPUNIT_ASSERT_DOUBLES_EQUAL(x, sin((45*deg2rad)/2), epsilon); + CPPUNIT_ASSERT_DOUBLES_EQUAL(x, ::sin((45*deg2rad)/2), epsilon); CPPUNIT_ASSERT_DOUBLES_EQUAL(y, 0, epsilon); CPPUNIT_ASSERT_DOUBLES_EQUAL(z, 0, epsilon); - CPPUNIT_ASSERT_DOUBLES_EQUAL(w, cos((45*deg2rad)/2), epsilon); + CPPUNIT_ASSERT_DOUBLES_EQUAL(w, ::cos((45*deg2rad)/2), epsilon); R2 = Rotation::Quaternion(x,y,z,w); CPPUNIT_ASSERT_EQUAL(R,R2); // direct 45 deg rotation in X - R2 = Rotation::Quaternion(sin((45*deg2rad)/2), 0, 0, cos((45*deg2rad)/2)); + R2 = Rotation::Quaternion(::sin((45*deg2rad)/2), 0, 0, ::cos((45*deg2rad)/2)); CPPUNIT_ASSERT_EQUAL(R,R2); R2.GetQuaternion(x2,y2,z2,w2); CPPUNIT_ASSERT_DOUBLES_EQUAL(x, x2, epsilon); diff --git a/orocos_kdl/tests/kinfamtest.cpp b/orocos_kdl/tests/kinfamtest.cpp index 2e28676..dc45625 100644 --- a/orocos_kdl/tests/kinfamtest.cpp +++ b/orocos_kdl/tests/kinfamtest.cpp @@ -7,6 +7,10 @@ CPPUNIT_TEST_SUITE_REGISTRATION( KinFamTest ); #ifdef __APPLE__ typedef unsigned int uint; +#else +#ifndef uint +typedef unsigned int uint; +#endif #endif using namespace KDL; diff --git a/orocos_kdl/tests/solvertest.cpp b/orocos_kdl/tests/solvertest.cpp index 7433d26..fe83353 100644 --- a/orocos_kdl/tests/solvertest.cpp +++ b/orocos_kdl/tests/solvertest.cpp @@ -4,6 +4,8 @@ #include #include +#define _USE_MATH_DEFINES // For MSVC +#include CPPUNIT_TEST_SUITE_REGISTRATION( SolverTest ); @@ -416,7 +418,7 @@ void SolverTest::VereshchaginTest() //desired is given by an interpolator //error is the difference between desired-actual //in this test only the actual values are printed. - int k = 1; + const int k = 1; JntArray jointPoses[k]; JntArray jointRates[k]; JntArray jointAccelerations[k]; -- 1.8.0.msysgit.0