From a558fecf6eb37903113e84796a14aaa9fd96606f Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 7 Jan 2016 22:26:42 -0500 Subject: [PATCH 01/34] Add test for joint friction and position limit -- failing --- unittests/testJoints.cpp | 112 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 112 insertions(+) diff --git a/unittests/testJoints.cpp b/unittests/testJoints.cpp index 3fa31769cdd00..0dc4687b224fc 100644 --- a/unittests/testJoints.cpp +++ b/unittests/testJoints.cpp @@ -502,6 +502,118 @@ TEST_F(JOINTS, JOINT_COULOMB_FRICTION) testJointCoulombFrictionForce(timeStep); } +//============================================================================== +TEST_F(JOINTS, JOINT_COULOMB_FRICTION_AND_POSITION_LIMIT) +{ + const double timeStep = 1e-3; + const double tol = 1e-2; + + simulation::World* myWorld + = utils::SkelParser::readWorld( + DART_DATA_PATH"/skel/test/joint_friction_test.skel"); + EXPECT_TRUE(myWorld != nullptr); + + myWorld->setGravity(Eigen::Vector3d(0.0, 0.0, 0.0)); + myWorld->setTimeStep(timeStep); + + dynamics::Skeleton* pendulum = myWorld->getSkeleton("double_pendulum"); + EXPECT_TRUE(pendulum != nullptr); + pendulum->disableSelfCollision(); + + dynamics::Joint* joint0 = pendulum->getJoint("joint0"); + dynamics::Joint* joint1 = pendulum->getJoint("joint1"); + + EXPECT_TRUE(joint0 != nullptr); + EXPECT_TRUE(joint1 != nullptr); + + double frictionForce = 5.0; + + joint0->setPositionLimited(true); + joint1->setPositionLimited(true); + + const double ll = -DART_PI/12.0; // -15 degree + const double ul = +DART_PI/12.0; // +15 degree + + size_t dof0 = joint0->getNumDofs(); + for (size_t i = 0; i < dof0; ++i) + { + joint0->setPosition(i, 0.0); + joint0->setPosition(i, 0.0); + joint0->setPositionLowerLimit(i, ll); + joint0->setPositionUpperLimit(i, ul); + } + + size_t dof1 = joint1->getNumDofs(); + for (size_t i = 0; i < dof1; ++i) + { + joint1->setPosition(i, 0.0); + joint1->setPosition(i, 0.0); + joint1->setPositionLowerLimit(i, ll); + joint1->setPositionUpperLimit(i, ul); + } + + joint0->setCoulombFriction(0, frictionForce); + joint1->setCoulombFriction(0, frictionForce); + + EXPECT_EQ(joint0->getCoulombFriction(0), frictionForce); + EXPECT_EQ(joint1->getCoulombFriction(0), frictionForce); + +#ifndef NDEBUG // Debug mode + double simTime = 0.2; +#else + double simTime = 2.0; +#endif // ------- Debug mode + int nSteps = simTime / timeStep; + + // First two seconds rotating in positive direction with higher control forces + // than the friction forces + for (int i = 0; i < nSteps; i++) + { + joint0->setForce(0, 100.0); + joint1->setForce(0, 100.0); + myWorld->step(); + + double jointPos0 = joint0->getPosition(0); + double jointPos1 = joint1->getPosition(0); + + double jointVel0 = joint0->getVelocity(0); + double jointVel1 = joint1->getVelocity(0); + + EXPECT_GE(std::abs(jointVel0), 0.0); + EXPECT_GE(std::abs(jointVel1), 0.0); + + EXPECT_GE(jointPos0, ll - tol); + EXPECT_LE(jointPos0, ul + tol); + + EXPECT_GE(jointPos1, ll - tol); + EXPECT_LE(jointPos1, ul + tol); + } + + // Another two seconds rotating in negative direction with higher control + // forces than the friction forces + for (int i = 0; i < nSteps; i++) + { + joint0->setForce(0, -100.0); + joint1->setForce(0, -100.0); + myWorld->step(); + + double jointPos0 = joint0->getPosition(0); + double jointPos1 = joint1->getPosition(0); + + double jointVel0 = joint0->getVelocity(0); + double jointVel1 = joint1->getVelocity(0); + + EXPECT_GE(std::abs(jointVel0), 0.0); + EXPECT_GE(std::abs(jointVel1), 0.0); + + EXPECT_GE(jointPos0, ll - tol); + EXPECT_LE(jointPos0, ul + tol); + + EXPECT_GE(jointPos1, ll - tol); + EXPECT_LE(jointPos1, ul + tol); + } +} + //============================================================================== int main(int argc, char* argv[]) { From 3f68bfb0ba6f474ef79d63e329ed2b381f09c406 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 7 Jan 2016 22:32:33 -0500 Subject: [PATCH 02/34] Fix incorrect applying of joint constraint forces --- dart/constraint/JointCoulombFrictionConstraint.cpp | 4 +++- dart/constraint/JointLimitConstraint.cpp | 4 +++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/dart/constraint/JointCoulombFrictionConstraint.cpp b/dart/constraint/JointCoulombFrictionConstraint.cpp index ee99210e0a8fa..0d05f612914a2 100644 --- a/dart/constraint/JointCoulombFrictionConstraint.cpp +++ b/dart/constraint/JointCoulombFrictionConstraint.cpp @@ -200,6 +200,7 @@ void JointCoulombFrictionConstraint::applyUnitImpulse(size_t _index) mJoint->setConstraintImpulse(i, 1.0); skeleton->updateBiasImpulse(mBodyNode); skeleton->updateVelocityChange(); + mJoint->setConstraintImpulse(i, 0.0); } ++localIndex; @@ -262,7 +263,8 @@ void JointCoulombFrictionConstraint::applyImpulse(double* _lambda) if (mActive[i] == false) continue; - mJoint->setConstraintImpulse(i, _lambda[localIndex]); + mJoint->setConstraintImpulse( + i, mJoint->getConstraintImpulse(i) + _lambda[localIndex]); mOldX[i] = _lambda[localIndex]; diff --git a/dart/constraint/JointLimitConstraint.cpp b/dart/constraint/JointLimitConstraint.cpp index d2f7f7d1b3f18..b1a9e9dd33ce2 100644 --- a/dart/constraint/JointLimitConstraint.cpp +++ b/dart/constraint/JointLimitConstraint.cpp @@ -309,6 +309,7 @@ void JointLimitConstraint::applyUnitImpulse(size_t _index) mJoint->setConstraintImpulse(i, 1.0); skeleton->updateBiasImpulse(mBodyNode); skeleton->updateVelocityChange(); + mJoint->setConstraintImpulse(i, 0.0); } ++localIndex; @@ -370,7 +371,8 @@ void JointLimitConstraint::applyImpulse(double* _lambda) if (mActive[i] == false) continue; - mJoint->setConstraintImpulse(i, _lambda[localIndex]); + mJoint->setConstraintImpulse( + i, mJoint->getConstraintImpulse(i) + _lambda[localIndex]); mOldX[i] = _lambda[localIndex]; From ab17051cc2ef4d48d9f8d0dbca99d0964ed33bd8 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 8 Jan 2016 07:31:24 -0500 Subject: [PATCH 03/34] Use trusty (beta) for travis-ci build tests and enable osx --- .travis.yml | 42 ++++++++++++++---------- ci/after_failure_linux.sh | 2 ++ ci/after_failure_osx.sh | 0 ci/appveyor_install.ps1 | 35 ++++++++++++++++++++ ci/before_install.sh | 65 -------------------------------------- ci/before_install_linux.sh | 33 +++++++++++++++++++ ci/before_install_osx.sh | 26 +++++++++++++++ ci/script_linux.sh | 6 ++++ ci/script_osx.sh | 5 +++ 9 files changed, 132 insertions(+), 82 deletions(-) create mode 100755 ci/after_failure_linux.sh create mode 100755 ci/after_failure_osx.sh create mode 100755 ci/appveyor_install.ps1 delete mode 100755 ci/before_install.sh create mode 100755 ci/before_install_linux.sh create mode 100755 ci/before_install_osx.sh create mode 100755 ci/script_linux.sh create mode 100755 ci/script_osx.sh diff --git a/.travis.yml b/.travis.yml index be82e56c0dff1..dcf0ecd839f7a 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,24 +1,32 @@ language: cpp +os: + - linux + - osx +sudo: required +dist: trusty compiler: - gcc - clang -before_install: - - 'ci/before_install.sh' env: - global: - matrix: - - BUILD_CORE_ONLY=OFF BUILD_TYPE=Debug - - BUILD_CORE_ONLY=OFF BUILD_TYPE=Release - - BUILD_CORE_ONLY=ON BUILD_TYPE=Debug - - BUILD_CORE_ONLY=ON BUILD_TYPE=Release -before_script: cmake -DBUILD_CORE_ONLY=$BUILD_CORE_ONLY -DCMAKE_BUILD_TYPE=$BUILD_TYPE . + - BUILD_CORE_ONLY=OFF BUILD_TYPE=Debug + - BUILD_CORE_ONLY=OFF BUILD_TYPE=Release + - BUILD_CORE_ONLY=ON BUILD_TYPE=Debug + - BUILD_CORE_ONLY=ON BUILD_TYPE=Release +matrix: + exclude: + - os: osx + compiler: gcc +before_install: + - if [ "$TRAVIS_OS_NAME" = "linux" ]; then 'ci/before_install_linux.sh' ; fi + - if [ "$TRAVIS_OS_NAME" = "osx" ]; then 'ci/before_install_osx.sh' ; fi +install: + - mkdir build + - cd build + - cmake -DBUILD_CORE_ONLY=$BUILD_CORE_ONLY -DCMAKE_BUILD_TYPE=$BUILD_TYPE .. script: - - make - - sudo ldconfig --verbose # So the test executeables can detect libtinyxml2 - - if [ $BUILD_CORE_ONLY = OFF ]; then make test; fi - # - cd tools/ - # - ./code_check.sh - # - ./abi_check.sh 4.1.0 # Check with DART 4.1.0 + - if [ "$TRAVIS_OS_NAME" = "linux" ]; then '../ci/script_linux.sh' ; fi + - if [ "$TRAVIS_OS_NAME" = "osx" ]; then '../ci/script_osx.sh' ; fi after_failure: - - cat Testing/Temporary/LastTest.log - - cat Testing/Temporary/LastTestsFailed.log + - if [ "$TRAVIS_OS_NAME" = "linux" ]; then '../ci/after_failure_linux.sh' ; fi + - if [ "$TRAVIS_OS_NAME" = "osx" ]; then '../ci/after_failure_osx.sh' ; fi + diff --git a/ci/after_failure_linux.sh b/ci/after_failure_linux.sh new file mode 100755 index 0000000000000..2e649ef4bcef1 --- /dev/null +++ b/ci/after_failure_linux.sh @@ -0,0 +1,2 @@ +cat Testing/Temporary/LastTest.log +cat Testing/Temporary/LastTestsFailed.log \ No newline at end of file diff --git a/ci/after_failure_osx.sh b/ci/after_failure_osx.sh new file mode 100755 index 0000000000000..e69de29bb2d1d diff --git a/ci/appveyor_install.ps1 b/ci/appveyor_install.ps1 new file mode 100755 index 0000000000000..03a1dc8f491bc --- /dev/null +++ b/ci/appveyor_install.ps1 @@ -0,0 +1,35 @@ +function ExecuteCommand($command, $command_args) +{ + Write-Host $command $command_args + Start-Process -FilePath $command -ArgumentList $command_args -Wait -Passthru +} + +function InstallPrerequisites($work_dir, $install_dir) +{ + $old_dir = $pwd + cd $work_dir + + $msi = "dart-prerequisites.msi" + $uri = "https://github.com/dartsim/dart-prerequisites-windows/raw/3e34167fd29fcc870ebed50bf318f3f31f491e6a/DART%205.0-prerequisites-msvc12-md-32bit.msi" + Invoke-WebRequest $uri -OutFile $msi + + $install_command = "msiexec.exe" + $install_args = "/qn /log log.txt /i $msi TARGETDIR=$install_dir" + ExecuteCommand $install_command $install_args + + cd $old_dir +} + +function main() +{ + try + { + InstallPrerequisites "C:/projects" "C:/Golems" + } + catch + { + throw + } +} + +main diff --git a/ci/before_install.sh b/ci/before_install.sh deleted file mode 100755 index 07e63abfc04d5..0000000000000 --- a/ci/before_install.sh +++ /dev/null @@ -1,65 +0,0 @@ -before_install() { - cd /tmp - - # Install nlopt from source since Ubuntu 12.04 does not provide debian package for nlopt - curl -o nlopt-2.4.1.tar.gz http://ab-initio.mit.edu/nlopt/nlopt-2.4.1.tar.gz - tar -xf nlopt-2.4.1.tar.gz - (cd nlopt-2.4.1/; sh autogen.sh; make CPPFLAGS='-fPIC' && sudo make install) -} - -# Install gcc-4.8 and g++-4.8 for C++11 -sudo apt-get -qq --yes install python-software-properties -sudo add-apt-repository --yes ppa:ubuntu-toolchain-r/test -sudo apt-get -qq update -sudo apt-get -qq --yes install gcc-4.8 g++-4.8 -sudo apt-get -qq --yes autoremove -sudo update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-4.8 50 -sudo update-alternatives --install /usr/bin/g++ g++ /usr/bin/g++-4.8 50 - -# Install eigen-3.2.1 (for unsupported/Eigen/Splines) -wget --quiet -O libeigen3-dev_3.2.1-1~precise1_all.deb http://packages.yade-dem.org/precise/libeigen3-dev_3.2.1-1~precise1_all.deb -sudo dpkg -i libeigen3-dev_3.2.1-1~precise1_all.deb - -# Install boost 1.55 compatible with C++11 -wget --quiet -O boost_1_55_0.tar.gz http://sourceforge.net/projects/boost/files/boost/1.55.0/boost_1_55_0.tar.gz/download -tar -xzf boost_1_55_0.tar.gz -cd boost_1_55_0/ -sudo apt-get -qq update -sudo apt-get -qq install build-essential g++ python-dev autotools-dev libicu-dev build-essential libbz2-dev -./bootstrap.sh --prefix=/usr/local &>/dev/null # mute the output -n=`cat /proc/cpuinfo | grep "cpu cores" | uniq | awk '{print $NF}'` -sudo ./b2 --with=all -j $n install &>/dev/null # mute the output -sudo sh -c 'echo "/usr/local/lib" >> /etc/ld.so.conf.d/local.conf' -sudo ldconfig - -sudo add-apt-repository --yes ppa:libccd-debs/ppa -sudo add-apt-repository --yes ppa:fcl-debs/ppa -sudo add-apt-repository --yes ppa:dartsim/ppa -sudo apt-get -qq update - -APT_CORE=' -cmake -libassimp-dev -libccd-dev -libfcl-dev -' - -APT=$APT_CORE' -freeglut3-dev -libxi-dev -libxmu-dev -libflann-dev -libtinyxml-dev -libtinyxml2-dev -liburdfdom-dev -liburdfdom-headers-dev -' - -if [ $BUILD_CORE_ONLY = OFF ]; then - sudo apt-get -qq --yes --force-yes install $APT -else - sudo apt-get -qq --yes --force-yes install $APT_CORE -fi - -(before_install) - diff --git a/ci/before_install_linux.sh b/ci/before_install_linux.sh new file mode 100755 index 0000000000000..dd5eb6739ee19 --- /dev/null +++ b/ci/before_install_linux.sh @@ -0,0 +1,33 @@ +sudo apt-add-repository --yes ppa:libccd-debs/ppa +sudo apt-add-repository --yes ppa:fcl-debs/ppa +sudo apt-add-repository --yes ppa:dartsim/ppa +sudo apt-get -qq update + +APT_CORE=' +cmake +libassimp-dev +libboost-all-dev +libccd-dev +libeigen3-dev +libfcl-dev +' + +APT=$APT_CORE' +freeglut3-dev +libxi-dev +libxmu-dev +libflann-dev +libnlopt-dev +coinor-libipopt-dev +libtinyxml-dev +libtinyxml2-dev +liburdfdom-dev +liburdfdom-headers-dev +' + +if [ $BUILD_CORE_ONLY = OFF ]; then + sudo apt-get -qq --yes --force-yes install $APT +else + sudo apt-get -qq --yes --force-yes install $APT_CORE +fi + diff --git a/ci/before_install_osx.sh b/ci/before_install_osx.sh new file mode 100755 index 0000000000000..e80330ad26dc9 --- /dev/null +++ b/ci/before_install_osx.sh @@ -0,0 +1,26 @@ +brew tap dartsim/dart +brew tap homebrew/science + +brew update > /dev/null + +PACKAGES=' +git +cmake +assimp +fcl +bullet +flann +boost +eigen +tinyxml +tinyxml2 +libccd +nlopt +ipopt +ros/deps/urdfdom +ros/deps/urdfdom_headers +ros/deps/console_bridge +ros/deps/gtest +' + +brew install $PACKAGES | grep -v '%$' diff --git a/ci/script_linux.sh b/ci/script_linux.sh new file mode 100755 index 0000000000000..82eb3f34a58b1 --- /dev/null +++ b/ci/script_linux.sh @@ -0,0 +1,6 @@ + make + sudo ldconfig --verbose # So the test executeables can detect libtinyxml2 + if [ $BUILD_CORE_ONLY = OFF ]; then make test; fi + # cd tools/ + # ./code_check.sh + # ./abi_check.sh 4.1.0 # Check with DART 4.1.0 \ No newline at end of file diff --git a/ci/script_osx.sh b/ci/script_osx.sh new file mode 100755 index 0000000000000..844bb27946b13 --- /dev/null +++ b/ci/script_osx.sh @@ -0,0 +1,5 @@ +make +if [ $BUILD_CORE_ONLY = OFF ]; then make test; fi +# cd tools/ +# ./code_check.sh +# ./abi_check.sh 4.1.0 # Check with DART 4.1.0 \ No newline at end of file From 745d7430709146662d32829e5690b544779218f4 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 8 Jan 2016 12:28:49 -0500 Subject: [PATCH 04/34] Update appveyor.yml --- appveyor.yml | 33 +++++++++++++++++---------------- 1 file changed, 17 insertions(+), 16 deletions(-) diff --git a/appveyor.yml b/appveyor.yml index febd9a49ef331..38f6ebdbe3460 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -2,23 +2,25 @@ version: "{build}" # Operating system (build VM template) -# os: Windows Server 2012 R2 +os: Visual Studio 2015 # build platform, i.e. Win32 (instead of x86), x64, Any CPU. This setting is optional. platform: - Win32 - - x64 + #- x64 Disable build for x64 machine until x64 version of dart-prerequisites is ready # specify custom environment variables environment: - BOOST_ROOT: c:\Libraries\boost - BOOST_LIBRARYDIR: c:\Libraries\boost\stage\lib + MSVC_DEFAULT_OPTIONS: ON + BOOST_ROOT: C:\Libraries\boost + BOOST_LIBRARYDIR: C:\Libraries\boost\lib32-msvc-12.0 + BUILD_EXAMPLES: OFF # don't build examples to not exceed allowed build time (40 min) + BUILD_TUTORIALS: OFF # don't build tutorials to not exceed allowed build time (40 min) matrix: - BUILD_CORE_ONLY: ON - # Diabled since we don't have binaries of DART prerequisites build on Visual Studio 2013 (/MT) yet (See #270) - # - BUILD_CORE_ONLY: OFF + - BUILD_CORE_ONLY: OFF -# build Configuration, i.e. Debug, Release, etc. +# build configuration, i.e. Debug, Release, etc. configuration: - Debug - Release @@ -42,10 +44,8 @@ branches: # scripts that run after cloning repository install: - - cmd: cd C:\projects - - ps: Start-FileDownload 'http://www.prism.gatech.edu/~tkunz3/DART-Prerequisites.msi' - - cmd: C:\projects\DART-Prerequisites.msi - # - cmd: choco install doxygen.install + - ps: cd C:\projects\dart\ci + - ps: .\appveyor_install.ps1 # scripts to run before build before_build: @@ -55,11 +55,12 @@ before_build: # We generate project files for Visual Studio 12 because the boost binaries installed on the test server are for Visual Studio 12. - cmd: if "%platform%"=="Win32" set CMAKE_GENERATOR_NAME=Visual Studio 12 - cmd: if "%platform%"=="x64" set CMAKE_GENERATOR_NAME=Visual Studio 12 Win64 - - cmd: cmake -G "%CMAKE_GENERATOR_NAME%" -DCMAKE_BUILD_TYPE=%configuration% -DBUILD_CORE_ONLY="%BUILD_CORE_ONLY%" -DBOOST_ROOT="%BOOST_ROOT%" -DBOOST_LIBRARYDIR="%BOOST_LIBRARYDIR%" -DBoost_USE_STATIC_LIBS="ON" -Durdfdom_DIR="%urdfdom_DIR%" -Durdfdom_headers_DIR="%urdfdom_headers_DIR%" .. + - cmd: cmake -G "%CMAKE_GENERATOR_NAME%" -DCMAKE_BUILD_TYPE=%configuration% -DBUILD_CORE_ONLY="%BUILD_CORE_ONLY%" -DDART_BUILD_EXAMPLES="%BUILD_EXAMPLES%" -DDART_BUILD_TUTORIALS="%BUILD_TUTORIALS%" -DBOOST_ROOT="%BOOST_ROOT%" -DBOOST_LIBRARYDIR="%BOOST_LIBRARYDIR%" -DBoost_USE_STATIC_LIBS="ON" -Durdfdom_DIR="%urdfdom_DIR%" -Durdfdom_headers_DIR="%urdfdom_headers_DIR%" -DDART_MSVC_DEFAULT_OPTIONS="%MSVC_DEFAULT_OPTIONS%" .. build: - project: C:\projects\dart\build\dart.sln - + project: C:\projects\dart\build\dart.sln # path to Visual Studio solution or project + parallel: true # enable MSBuild parallel builds + verbosity: quiet # MSBuild verbosity level (quiet|minimal|normal|detailed) + test_script: - - cmd: ctest -C Release -VV - - cmd: ctest -C Debug -VV + - cmd: ctest --build-config %configuration% --parallel 4 --output-on-failure From e98694c4b32cad46bab9903610fd60992bb05e14 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 8 Jan 2016 15:16:40 -0500 Subject: [PATCH 05/34] Remove tutorial build option for DART 4.3 in appveyor --- appveyor.yml | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/appveyor.yml b/appveyor.yml index 38f6ebdbe3460..f15e4f626c83b 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -15,7 +15,6 @@ environment: BOOST_ROOT: C:\Libraries\boost BOOST_LIBRARYDIR: C:\Libraries\boost\lib32-msvc-12.0 BUILD_EXAMPLES: OFF # don't build examples to not exceed allowed build time (40 min) - BUILD_TUTORIALS: OFF # don't build tutorials to not exceed allowed build time (40 min) matrix: - BUILD_CORE_ONLY: ON - BUILD_CORE_ONLY: OFF @@ -55,7 +54,7 @@ before_build: # We generate project files for Visual Studio 12 because the boost binaries installed on the test server are for Visual Studio 12. - cmd: if "%platform%"=="Win32" set CMAKE_GENERATOR_NAME=Visual Studio 12 - cmd: if "%platform%"=="x64" set CMAKE_GENERATOR_NAME=Visual Studio 12 Win64 - - cmd: cmake -G "%CMAKE_GENERATOR_NAME%" -DCMAKE_BUILD_TYPE=%configuration% -DBUILD_CORE_ONLY="%BUILD_CORE_ONLY%" -DDART_BUILD_EXAMPLES="%BUILD_EXAMPLES%" -DDART_BUILD_TUTORIALS="%BUILD_TUTORIALS%" -DBOOST_ROOT="%BOOST_ROOT%" -DBOOST_LIBRARYDIR="%BOOST_LIBRARYDIR%" -DBoost_USE_STATIC_LIBS="ON" -Durdfdom_DIR="%urdfdom_DIR%" -Durdfdom_headers_DIR="%urdfdom_headers_DIR%" -DDART_MSVC_DEFAULT_OPTIONS="%MSVC_DEFAULT_OPTIONS%" .. + - cmd: cmake -G "%CMAKE_GENERATOR_NAME%" -DCMAKE_BUILD_TYPE=%configuration% -DBUILD_CORE_ONLY="%BUILD_CORE_ONLY%" -DDART_BUILD_EXAMPLES="%BUILD_EXAMPLES%" -DBOOST_ROOT="%BOOST_ROOT%" -DBOOST_LIBRARYDIR="%BOOST_LIBRARYDIR%" -DBoost_USE_STATIC_LIBS="ON" -Durdfdom_DIR="%urdfdom_DIR%" -Durdfdom_headers_DIR="%urdfdom_headers_DIR%" .. build: project: C:\projects\dart\build\dart.sln # path to Visual Studio solution or project From 15c236cb72802178da7573cab2feec24962ab6d6 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 8 Jan 2016 15:23:49 -0500 Subject: [PATCH 06/34] Add cmake option for speeding up MSVC build --- CMakeLists.txt | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 782e6fde0cae8..2711b158192db 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -45,6 +45,7 @@ option(BUILD_CORE_ONLY "Build only the core of DART" OFF) if(MSVC) set(DART_RUNTIME_LIBRARY "/MT" CACHE STRING "BaseName chosen by the user at CMake configure time") set_property(CACHE DART_RUNTIME_LIBRARY PROPERTY STRINGS /MD /MT) + option(DART_MSVC_DEFAULT_OPTIONS "Build DART with default Visual Studio options" OFF) else() option(BUILD_SHARED_LIBS "Build shared libraries" ON) endif() @@ -341,14 +342,16 @@ endif() # Compiler flags #=============================================================================== if(MSVC) - message(STATUS "Setup Visual Studio Specific Flags") # Visual Studio enables c++11 support by default if(NOT MSVC12) message(FATAL_ERROR "${PROJECT_NAME} requires VS 2013 or greater.") endif() - set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} ${DART_RUNTIME_LIBRARY}d /Zi /Gy /W1 /EHsc") - set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} ${DART_RUNTIME_LIBRARY} /Zi /GL /Gy /W1 /EHsc /arch:SSE2") - set(CMAKE_EXE_LINKER_FLAGS_RELEASE "/LTCG") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /MP4") + set(CMAKE_EXE_LINKER_FLAGS_RELEASE "/LTCG /INCREMENTAL:NO") + if(NOT DART_MSVC_DEFAULT_OPTIONS) + set(CMAKE_CXX_FLAGS_DEBUG "${CMAKE_CXX_FLAGS_DEBUG} ${DART_RUNTIME_LIBRARY}d /Zi /Gy /W1 /EHsc") + set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} ${DART_RUNTIME_LIBRARY} /Zi /GL /Gy /W1 /EHsc /arch:SSE2") + endif(NOT DART_MSVC_DEFAULT_OPTIONS) elseif(CMAKE_COMPILER_IS_GNUCXX) set(CMAKE_CXX_FLAGS "-Wall -msse2 -fPIC") execute_process( From 5249d84f53c6109ca62a45f10c2ae6d7997081fc Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 8 Jan 2016 17:00:13 -0500 Subject: [PATCH 07/34] Pass MSVC_DEFAULT_OPTIONS into the cmake options in appveyor --- appveyor.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/appveyor.yml b/appveyor.yml index f15e4f626c83b..57593f147b641 100644 --- a/appveyor.yml +++ b/appveyor.yml @@ -54,7 +54,7 @@ before_build: # We generate project files for Visual Studio 12 because the boost binaries installed on the test server are for Visual Studio 12. - cmd: if "%platform%"=="Win32" set CMAKE_GENERATOR_NAME=Visual Studio 12 - cmd: if "%platform%"=="x64" set CMAKE_GENERATOR_NAME=Visual Studio 12 Win64 - - cmd: cmake -G "%CMAKE_GENERATOR_NAME%" -DCMAKE_BUILD_TYPE=%configuration% -DBUILD_CORE_ONLY="%BUILD_CORE_ONLY%" -DDART_BUILD_EXAMPLES="%BUILD_EXAMPLES%" -DBOOST_ROOT="%BOOST_ROOT%" -DBOOST_LIBRARYDIR="%BOOST_LIBRARYDIR%" -DBoost_USE_STATIC_LIBS="ON" -Durdfdom_DIR="%urdfdom_DIR%" -Durdfdom_headers_DIR="%urdfdom_headers_DIR%" .. + - cmd: cmake -G "%CMAKE_GENERATOR_NAME%" -DCMAKE_BUILD_TYPE=%configuration% -DBUILD_CORE_ONLY="%BUILD_CORE_ONLY%" -DDART_BUILD_EXAMPLES="%BUILD_EXAMPLES%" -DBOOST_ROOT="%BOOST_ROOT%" -DBOOST_LIBRARYDIR="%BOOST_LIBRARYDIR%" -DBoost_USE_STATIC_LIBS="ON" -Durdfdom_DIR="%urdfdom_DIR%" -Durdfdom_headers_DIR="%urdfdom_headers_DIR%" -DDART_MSVC_DEFAULT_OPTIONS="%MSVC_DEFAULT_OPTIONS%" .. build: project: C:\projects\dart\build\dart.sln # path to Visual Studio solution or project From f160a8dfdb4cdfa6ed062c0dbe1a00f3c4859b59 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 9 Jan 2016 07:18:47 -0500 Subject: [PATCH 08/34] Bump version to 4.3.5 and update changelogs --- CMakeLists.txt | 2 +- Changelog.md | 7 ++++++- debian/changelog | 6 ++++++ 3 files changed, 13 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 2711b158192db..40e6188356306 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -24,7 +24,7 @@ project(dart) set(DART_MAJOR_VERSION "4") set(DART_MINOR_VERSION "3") -set(DART_PATCH_VERSION "4") +set(DART_PATCH_VERSION "5") set(DART_VERSION "${DART_MAJOR_VERSION}.${DART_MINOR_VERSION}.${DART_PATCH_VERSION}") set(DART_PKG_DESC "Dynamic Animation and Robotics Toolkit.") set(DART_PKG_EXTERNAL_DEPS "flann, ccd, fcl") diff --git a/Changelog.md b/Changelog.md index 0751db0a1e59e..f0f7f1fb48e40 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,4 +1,9 @@ -### Version 4.3.3 (2015-01-24) +### Version 4.3.5 (2015-01-24) + +1. Fixed incorrect applying of joint constraint impulses (backported from 6.0.0) + * [Pull request #578](https://github.com/dartsim/dart/pull/578) + +### Version 4.3.4 (2015-01-24) 1. Fixed build issue with gtest on Mac * [Pull request #315](https://github.com/dartsim/dart/pull/315) diff --git a/debian/changelog b/debian/changelog index 0ba3bd9f7301a..3fad01d89d8df 100644 --- a/debian/changelog +++ b/debian/changelog @@ -1,3 +1,9 @@ +dart (4.3.5) unstable; urgency=medium + + * Fixed incorrect applying of joint constraint impulses (backported from 6.0.0) + + -- Jeongseok Lee Sat, 9 Jan 2015 12:00:00 -0500 + dart (4.3.4) unstable; urgency=low * Fixed build issue with gtest on Mac From 4f97999d7ffd1f53ef393af21a10693f838bd38b Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 9 Jan 2016 07:55:14 -0500 Subject: [PATCH 09/34] Suppress debian build warnings --- debian/control | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/debian/control b/debian/control index 3382a3b227dac..363bfc910c2d1 100644 --- a/debian/control +++ b/debian/control @@ -1,4 +1,4 @@ -Source: dart +Source: dart4 Priority: extra Maintainer: Jeongseok Lee Build-Depends: debhelper (>= 9), @@ -13,7 +13,7 @@ Build-Depends: debhelper (>= 9), libtinyxml-dev, libtinyxml2-dev, liburdfdom-dev -Standards-Version: 3.9.5 +Standards-Version: 3.9.6 Section: libs Homepage: http://dartsim.github.io/ Vcs-Git: git://github.com/dartsim/dart.git @@ -22,7 +22,7 @@ Vcs-Browser: https://github.com/dartsim/dart Package: libdart-core4-dev Section: libdevel Architecture: any -Pre-Depends: multiarch-support +Pre-Depends: ${misc:Pre-Depends} Conflicts: libdart-core3-dev Depends: ${misc:Depends}, libdart-core4.3 (= ${binary:Version}), @@ -56,7 +56,7 @@ Description: Dynamic Animation and Robotics Toolkit, core development files Package: libdart4-dev Section: libdevel Architecture: any -Pre-Depends: multiarch-support +Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, libdart-core4-dev, libdart4.3 (= ${binary:Version}), @@ -92,7 +92,7 @@ Description: Dynamic Animation and Robotics Toolkit, development files Package: libdart-core4.3 Section: libs Architecture: any -Pre-Depends: multiarch-support +Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, ${shlibs:Depends} Description: Dynamic Animation and Robotics Toolkit, core library files @@ -122,7 +122,7 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Package: libdart4.3 Section: libs Architecture: any -Pre-Depends: multiarch-support +Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, ${shlibs:Depends} Description: Dynamic Animation and Robotics Toolkit, library files From 214c93e34c90beb15d90d55cc47c4e6b5dfa9749 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 9 Jan 2016 07:55:54 -0500 Subject: [PATCH 10/34] Add version number to the package name in debian build --- debian/changelog | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/debian/changelog b/debian/changelog index 3fad01d89d8df..2e51442ecc43a 100644 --- a/debian/changelog +++ b/debian/changelog @@ -1,4 +1,4 @@ -dart (4.3.5) unstable; urgency=medium +dart4 (4.3.5) unstable; urgency=medium * Fixed incorrect applying of joint constraint impulses (backported from 6.0.0) From 5f9a0264a0cd87490012a6eef63c4a33083c5253 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 9 Jan 2016 08:15:09 -0500 Subject: [PATCH 11/34] Fix release date of DART 4.3.5 in Changelog.md --- Changelog.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Changelog.md b/Changelog.md index f0f7f1fb48e40..4b1ecb63f7eb3 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,4 +1,4 @@ -### Version 4.3.5 (2015-01-24) +### Version 4.3.5 (2016-01-09) 1. Fixed incorrect applying of joint constraint impulses (backported from 6.0.0) * [Pull request #578](https://github.com/dartsim/dart/pull/578) From 228ccf5e9886110e0ee1f94ffc58dc273bd525dc Mon Sep 17 00:00:00 2001 From: "M.X. Grey" Date: Fri, 15 Apr 2016 19:14:48 -0400 Subject: [PATCH 12/34] fix for the double-delete reported by issue #671 --- dart/dynamics/Skeleton.cpp | 43 +++++++++++++++++++++++++++++++++++++- unittests/testBuilding.cpp | 33 +++++++++++++++++++++++++++++ 2 files changed, 75 insertions(+), 1 deletion(-) diff --git a/dart/dynamics/Skeleton.cpp b/dart/dynamics/Skeleton.cpp index 9e8eb3f948426..9632f64ca7765 100644 --- a/dart/dynamics/Skeleton.cpp +++ b/dart/dynamics/Skeleton.cpp @@ -236,6 +236,13 @@ void Skeleton::addBodyNode(BodyNode* _body) { assert(_body && _body->getParentJoint()); + if(std::find(mBodyNodes.begin(), mBodyNodes.end(), _body) + != mBodyNodes.end()) + { + // To help with #671, we prevent BodyNodes from having duplicate entries + return; + } + mBodyNodes.push_back(_body); addEntryToBodyNodeNameMgr(_body); addMarkersOfBodyNode(_body); @@ -428,7 +435,21 @@ void Skeleton::init(double _timeStep, const Eigen::Vector3d& _gravity) for (size_t i = 0; i < mBodyNodes.size(); ++i) { if (mBodyNodes[i]->getParentBodyNode() == NULL) + { + if(std::find(rootBodyNodes.begin(), rootBodyNodes.end(), mBodyNodes[i]) + != rootBodyNodes.end()) + { + // Avoid duplicate BodyNodes + dtmsg << "[Skeleton::init] The root BodyNode named [" + << mBodyNodes[i]->getName() << "] (" << mBodyNodes[i] << ") " + << "appears twice while initializing the Skeleton named [" + << getName() << "] (" << this << "). The second appearance will " + << "be ignored.\n"; + continue; + } + rootBodyNodes.push_back(mBodyNodes[i]); + } } // Rearrange the list of body nodes with BFS (Breadth First Search) @@ -442,9 +463,29 @@ void Skeleton::init(double _timeStep, const Eigen::Vector3d& _gravity) { BodyNode* itBodyNode = queue.front(); queue.pop(); + + if(std::find(mBodyNodes.begin(), mBodyNodes.end(), itBodyNode) + != mBodyNodes.end()) + { + // Addressing issue #671 + const BodyNode* parent = itBodyNode->getParentBodyNode(); + dtwarn << "[Skeleton::init] The BodyNode named [" + << itBodyNode->getName() << "] (" << itBodyNode << ") is being " + << "claimed by multiple parents. This is not allowed! It will " + << "only use [" << parent->getName() << "] (" << parent << ") " + << "as its parent!\n"; + continue; + } + mBodyNodes.push_back(itBodyNode); for (size_t j = 0; j < itBodyNode->getNumChildBodyNodes(); ++j) - queue.push(itBodyNode->getChildBodyNode(j)); + { + BodyNode* child = itBodyNode->getChildBodyNode(j); + queue.push(child); + + // Addressing issue #671 + child->mParentBodyNode = itBodyNode; + } } } diff --git a/unittests/testBuilding.cpp b/unittests/testBuilding.cpp index 60433743b553b..ab0aaeb66ea14 100644 --- a/unittests/testBuilding.cpp +++ b/unittests/testBuilding.cpp @@ -130,6 +130,39 @@ TEST(BUILDING, BASIC) delete world; } +/******************************************************************************/ +TEST(BUILDING, DUPLICATION) +{ + BodyNode* body1 = new BodyNode; + BodyNode* body2 = new BodyNode; + BodyNode* child = new BodyNode; + + RevoluteJoint* joint1 = new RevoluteJoint; + RevoluteJoint* joint2 = new RevoluteJoint; + RevoluteJoint* joint3 = new RevoluteJoint; + + body1->setParentJoint(joint1); + body2->setParentJoint(joint2); + child->setParentJoint(joint3); + + body1->addChildBodyNode(child); + body2->addChildBodyNode(child); + + Skeleton* skel = new Skeleton; + skel->addBodyNode(body1); + skel->addBodyNode(body1); + skel->addBodyNode(body2); + skel->addBodyNode(child); + + skel->init(); + + // Because of how the init queue works, it will use the last BodyNode in the + // list of Skeleton::mBodyNodes which claims it as its child. + EXPECT_EQ(child->getParentBodyNode(), body2); + + delete skel; +} + /******************************************************************************/ int main(int argc, char* argv[]) { From a149314ff9b791a2cda4e29b52c8c2fd078b4166 Mon Sep 17 00:00:00 2001 From: "M.X. Grey" Date: Fri, 15 Apr 2016 19:15:18 -0400 Subject: [PATCH 13/34] increment patch number --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 40e6188356306..eb0c8330fd77b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -24,7 +24,7 @@ project(dart) set(DART_MAJOR_VERSION "4") set(DART_MINOR_VERSION "3") -set(DART_PATCH_VERSION "5") +set(DART_PATCH_VERSION "6") set(DART_VERSION "${DART_MAJOR_VERSION}.${DART_MINOR_VERSION}.${DART_PATCH_VERSION}") set(DART_PKG_DESC "Dynamic Animation and Robotics Toolkit.") set(DART_PKG_EXTERNAL_DEPS "flann, ccd, fcl") From 480a6d419a66e834a276d970de442c72cf9494b3 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 16 Apr 2016 11:21:43 -0400 Subject: [PATCH 14/34] Packaging 4.3.6 --- Changelog.md | 6 ++++++ debian/changelog | 6 ++++++ 2 files changed, 12 insertions(+) diff --git a/Changelog.md b/Changelog.md index 4b1ecb63f7eb3..1f9836ad81916 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,3 +1,9 @@ +### Version 4.3.6 (2016-04-16) + +1. Fixed duplicate entries in Skeleton::mBodyNodes causing segfault in destructor + * [Issue #671](https://github.com/dartsim/dart/issues/671) + * [Pull request #672](https://github.com/dartsim/dart/pull/672) + ### Version 4.3.5 (2016-01-09) 1. Fixed incorrect applying of joint constraint impulses (backported from 6.0.0) diff --git a/debian/changelog b/debian/changelog index 2e51442ecc43a..af3942eb75f57 100644 --- a/debian/changelog +++ b/debian/changelog @@ -1,3 +1,9 @@ +dart4 (4.3.6) unstable; urgency=medium + + * Fixed duplicate entries in Skeleton::mBodyNodes causing segfault in destructor + + -- Jeongseok Lee Sat, 16 Apr 2015 12:00:00 -0500 + dart4 (4.3.5) unstable; urgency=medium * Fixed incorrect applying of joint constraint impulses (backported from 6.0.0) From fc52599e0fac8ce94413495d9a718e90bcb70e12 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 16 Apr 2016 12:12:56 -0400 Subject: [PATCH 15/34] Add major version number to debian source name --- debian/changelog | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/debian/changelog b/debian/changelog index 266ef62ed4212..b338b13e9d352 100644 --- a/debian/changelog +++ b/debian/changelog @@ -1,4 +1,4 @@ -dart (6.0.0) unstable; urgency=medium +dart6 (6.0.0) unstable; urgency=medium * Added missing 'liburdfdom-dev' dependency in Ubuntu package From ebe4a12964551f6175637fb5836ecd92c4ad0c94 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 16 Apr 2016 14:41:55 -0400 Subject: [PATCH 16/34] Update debian files * Rename library names to libdart6[-component_name][-dev] * Add libdart6-all-dev library --- debian/control | 156 +++++++++++------- debian/libdart6-all-dev.install | 15 ++ ...0-dev.install => libdart6-gui-dev.install} | 0 ...v.install => libdart6-gui-osg-dev.install} | 0 ...sg0.1.install => libdart6-gui-osg.install} | 0 ...rt-gui0.1.install => libdart6-gui.install} | 0 ...l => libdart6-optimizer-ipopt-dev.install} | 0 ...stall => libdart6-optimizer-ipopt.install} | 0 ...l => libdart6-optimizer-nlopt-dev.install} | 0 ...stall => libdart6-optimizer-nlopt.install} | 0 ....install => libdart6-planning-dev.install} | 0 ...g0.1.install => libdart6-planning.install} | 0 ...dev.install => libdart6-utils-dev.install} | 0 ...tils0.1.install => libdart6-utils.install} | 0 .../{libdart6.0.install => libdart6.install} | 0 15 files changed, 108 insertions(+), 63 deletions(-) create mode 100644 debian/libdart6-all-dev.install rename debian/{libdart-gui0-dev.install => libdart6-gui-dev.install} (100%) rename debian/{libdart-gui-osg0-dev.install => libdart6-gui-osg-dev.install} (100%) rename debian/{libdart-gui-osg0.1.install => libdart6-gui-osg.install} (100%) rename debian/{libdart-gui0.1.install => libdart6-gui.install} (100%) rename debian/{libdart-optimizer-ipopt0-dev.install => libdart6-optimizer-ipopt-dev.install} (100%) rename debian/{libdart-optimizer-ipopt0.1.install => libdart6-optimizer-ipopt.install} (100%) rename debian/{libdart-optimizer-nlopt0-dev.install => libdart6-optimizer-nlopt-dev.install} (100%) rename debian/{libdart-optimizer-nlopt0.1.install => libdart6-optimizer-nlopt.install} (100%) rename debian/{libdart-planning0-dev.install => libdart6-planning-dev.install} (100%) rename debian/{libdart-planning0.1.install => libdart6-planning.install} (100%) rename debian/{libdart-utils0-dev.install => libdart6-utils-dev.install} (100%) rename debian/{libdart-utils0.1.install => libdart6-utils.install} (100%) rename debian/{libdart6.0.install => libdart6.install} (100%) diff --git a/debian/control b/debian/control index f6e17219cd62e..9ba26d7714c6b 100644 --- a/debian/control +++ b/debian/control @@ -4,6 +4,7 @@ Maintainer: Jeongseok Lee Build-Depends: debhelper (>= 9), cmake, libeigen3-dev, + libccd-dev libfcl-dev (>= 0.2.7), libbullet-dev, libassimp-dev (>= 3), @@ -27,19 +28,49 @@ Homepage: http://dartsim.github.io/ Vcs-Git: git://github.com/dartsim/dart.git Vcs-Browser: https://github.com/dartsim/dart +Package: libdart6 +Section: libs +Architecture: any +Pre-Depends: ${misc:Pre-Depends} +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: Dynamic Animation and Robotics Toolkit - Shared Library + DART is a collaborative, cross-platform, open source library created by the + Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data + structures and algorithms for kinematic and dynamic applications in robotics + and computer animation. + DART is distinguished by it's accuracy and stability due to its use of + generalized coordinates to represent articulated rigid body systems and + computation of Lagrange's equations derived from D.Alembert's principle to + describe the dynamics of motion. + For developers, in contrast to many popular physics engines which view the + simulator as a black box, DART gives full access to internal kinematic and + dynamic quantities, such as the mass matrix, Coriolis and centrifugal forces, + transformation matrices and their derivatives. DART also provides efficient + computation of Jacobian matrices for arbitrary body points and coordinate + frames. Contact and collision are handled using an implicit time-stepping, + velocity-based LCP (linear-complementarity problem) to guarantee + non-penetration, directional friction, and approximated Coulomb friction cone + conditions. For collision detection, DART uses FCL developed by Willow Garage + and the UNC Gamma Lab. + DART has applications in robotics and computer animation because it features a + multibody dynamic simulator and tools for control and motion planning. + Multibody dynamic simulation in DART is an extension of RTQL8, an open source + software created by the Georgia Tech Graphics Lab. + Package: libdart6-dev Section: libdevel Architecture: any Pre-Depends: ${misc:Pre-Depends} Conflicts: libdart-core3-dev, libdart-core4-dev, libdart-core5-dev Depends: ${misc:Depends}, - libdart6.0 (= ${binary:Version}), + libdart6 (= ${binary:Version}), libeigen3-dev, libassimp-dev (>= 3), + libccd-dev libfcl-dev, libbullet-dev, libboost-all-dev (>= 1.54.0.1ubuntu1) -Description: Dynamic Animation and Robotics Toolkit, core development files +Description: Dynamic Animation and Robotics Toolkit - Development Files DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -63,13 +94,12 @@ Description: Dynamic Animation and Robotics Toolkit, core development files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart6.0 +Package: libdart6-optimizer-nlopt Section: libs Architecture: any Pre-Depends: ${misc:Pre-Depends} -Depends: ${misc:Depends}, - ${shlibs:Depends} -Description: Dynamic Animation and Robotics Toolkit, core library files +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: Dynamic Animation and Robotics Toolkit - Optimizer-nlopt Component Shared Library DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -93,15 +123,15 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-planning6-dev +Package: libdart6-optimizer-nlopt-dev Section: libdevel Architecture: any Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, libdart6-dev, - libdart-planning6.0 (= ${binary:Version}), - libflann-dev -Description: Dynamic Animation and Robotics Toolkit, core library files + libdart6-optimizer-nlopt (= ${binary:Version}), + libnlopt-dev +Description: Dynamic Animation and Robotics Toolkit - Optimizer-nlopt Component Development Files DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -125,13 +155,12 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-planning6.0 +Package: libdart6-optimizer-ipopt Section: libs Architecture: any Pre-Depends: ${misc:Pre-Depends} -Depends: ${misc:Depends}, - ${shlibs:Depends} -Description: Dynamic Animation and Robotics Toolkit, core library files +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: Dynamic Animation and Robotics Toolkit - Optimizer-ipopt Component Shared Library DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -155,17 +184,15 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-utils6-dev +Package: libdart6-optimizer-ipopt-dev Section: libdevel Architecture: any Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, libdart6-dev, - libdart-utils6.0 (= ${binary:Version}), - libtinyxml-dev, - libtinyxml2-dev, - liburdfdom-dev -Description: Dynamic Animation and Robotics Toolkit, core library files + libdart6-optimizer-ipopt (= ${binary:Version}), + coinor-libipopt-dev +Description: Dynamic Animation and Robotics Toolkit - Optimizer-ipopt Component Development Files DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -189,13 +216,12 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-utils6.0 +Package: libdart6-planning Section: libs Architecture: any Pre-Depends: ${misc:Pre-Depends} -Depends: ${misc:Depends}, - ${shlibs:Depends} -Description: Dynamic Animation and Robotics Toolkit, core library files +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: Dynamic Animation and Robotics Toolkit - Planning Component Shared Library DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -219,18 +245,15 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-gui6-dev +Package: libdart6-planning-dev Section: libdevel Architecture: any Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, libdart6-dev, - libdart-utils6-dev, - libdart-gui6.0 (= ${binary:Version}), - freeglut3-dev, - libxi-dev, - libxmu-dev -Description: Dynamic Animation and Robotics Toolkit, core library files + libdart6-planning (= ${binary:Version}), + libflann-dev +Description: Dynamic Animation and Robotics Toolkit - Planning Component Development Files DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -254,13 +277,12 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-gui6.0 +Package: libdart6-utils Section: libs Architecture: any Pre-Depends: ${misc:Pre-Depends} -Depends: ${misc:Depends}, - ${shlibs:Depends} -Description: Dynamic Animation and Robotics Toolkit, core library files +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: Dynamic Animation and Robotics Toolkit - Utils Component Shared Library DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -284,16 +306,17 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-gui-osg6-dev +Package: libdart6-utils-dev Section: libdevel Architecture: any Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, - libdart-gui6-dev, - libdart-gui-osg6.0 (= ${binary:Version}), - libopenthreads-dev, - libopenscenegraph-dev -Description: Dynamic Animation and Robotics Toolkit, core library files + libdart6-dev, + libdart6-utils (= ${binary:Version}), + libtinyxml-dev, + libtinyxml2-dev, + liburdfdom-dev +Description: Dynamic Animation and Robotics Toolkit - Utils Component Development Files DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -317,13 +340,12 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-gui-osg6.0 +Package: libdart6-gui Section: libs Architecture: any Pre-Depends: ${misc:Pre-Depends} -Depends: ${misc:Depends}, - ${shlibs:Depends} -Description: Dynamic Animation and Robotics Toolkit, core library files +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: Dynamic Animation and Robotics Toolkit - GUI Component Shared Library DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -347,15 +369,17 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-optimizer-nlopt6-dev +Package: libdart6-gui-dev Section: libdevel Architecture: any Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, - libdart6-dev, - libdart-optimizer-nlopt6.0 (= ${binary:Version}), - libnlopt-dev -Description: Dynamic Animation and Robotics Toolkit, core library files + libdart6-utils-dev, + libdart6-gui (= ${binary:Version}), + freeglut3-dev, + libxi-dev, + libxmu-dev +Description: Dynamic Animation and Robotics Toolkit - GUI Component Development Files DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -379,13 +403,12 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-optimizer-nlopt6.0 +Package: libdart6-gui-osg Section: libs Architecture: any Pre-Depends: ${misc:Pre-Depends} -Depends: ${misc:Depends}, - ${shlibs:Depends} -Description: Dynamic Animation and Robotics Toolkit, core library files +Depends: ${shlibs:Depends}, ${misc:Depends} +Description: Dynamic Animation and Robotics Toolkit - GUI-osg Component Shared Library DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -409,15 +432,16 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-optimizer-ipopt6-dev +Package: libdart6-gui-osg-dev Section: libdevel Architecture: any Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, - libdart6-dev, - libdart-optimizer-ipopt6.0 (= ${binary:Version}), - coinor-libipopt-dev -Description: Dynamic Animation and Robotics Toolkit, core library files + libdart6-gui-dev, + libdart6-gui-osg (= ${binary:Version}), + libopenthreads-dev, + libopenscenegraph-dev +Description: Dynamic Animation and Robotics Toolkit - GUI-osg Component Development Files DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics @@ -441,13 +465,19 @@ Description: Dynamic Animation and Robotics Toolkit, core library files Multibody dynamic simulation in DART is an extension of RTQL8, an open source software created by the Georgia Tech Graphics Lab. -Package: libdart-optimizer-ipopt6.0 -Section: libs +Package: libdart6-all-dev +Section: libdevel Architecture: any Pre-Depends: ${misc:Pre-Depends} Depends: ${misc:Depends}, - ${shlibs:Depends} -Description: Dynamic Animation and Robotics Toolkit, core library files + libdart6-dev, + libdart6-planning-dev, + libdart6-utils-dev, + libdart6-gui-dev, + libdart6-gui-osg-dev, + libdart6-optimizer-nlopt-dev, + libdart6-optimizer-ipopt-dev +Description: Dynamic Animation and Robotics Toolkit - All Development Files DART is a collaborative, cross-platform, open source library created by the Georgia Tech Graphics Lab and Humanoid Robotics Lab. The library provides data structures and algorithms for kinematic and dynamic applications in robotics diff --git a/debian/libdart6-all-dev.install b/debian/libdart6-all-dev.install new file mode 100644 index 0000000000000..e4b1376bc30ed --- /dev/null +++ b/debian/libdart6-all-dev.install @@ -0,0 +1,15 @@ +usr/include/dart/dart.h +usr/include/dart/config.h +usr/include/dart/collision/* +usr/include/dart/common/* +usr/include/dart/constraint/* +usr/include/dart/dynamics/* +usr/include/dart/integration/* +usr/include/dart/lcpsolver/* +usr/include/dart/math/* +usr/include/dart/optimizer/*.* +usr/include/dart/simulation/* +usr/share/dart/DARTConfig.cmake +usr/share/dart/DARTConfigVersion.cmake +usr/share/dart/DARTTargets.cmake +usr/lib/libdart.so diff --git a/debian/libdart-gui0-dev.install b/debian/libdart6-gui-dev.install similarity index 100% rename from debian/libdart-gui0-dev.install rename to debian/libdart6-gui-dev.install diff --git a/debian/libdart-gui-osg0-dev.install b/debian/libdart6-gui-osg-dev.install similarity index 100% rename from debian/libdart-gui-osg0-dev.install rename to debian/libdart6-gui-osg-dev.install diff --git a/debian/libdart-gui-osg0.1.install b/debian/libdart6-gui-osg.install similarity index 100% rename from debian/libdart-gui-osg0.1.install rename to debian/libdart6-gui-osg.install diff --git a/debian/libdart-gui0.1.install b/debian/libdart6-gui.install similarity index 100% rename from debian/libdart-gui0.1.install rename to debian/libdart6-gui.install diff --git a/debian/libdart-optimizer-ipopt0-dev.install b/debian/libdart6-optimizer-ipopt-dev.install similarity index 100% rename from debian/libdart-optimizer-ipopt0-dev.install rename to debian/libdart6-optimizer-ipopt-dev.install diff --git a/debian/libdart-optimizer-ipopt0.1.install b/debian/libdart6-optimizer-ipopt.install similarity index 100% rename from debian/libdart-optimizer-ipopt0.1.install rename to debian/libdart6-optimizer-ipopt.install diff --git a/debian/libdart-optimizer-nlopt0-dev.install b/debian/libdart6-optimizer-nlopt-dev.install similarity index 100% rename from debian/libdart-optimizer-nlopt0-dev.install rename to debian/libdart6-optimizer-nlopt-dev.install diff --git a/debian/libdart-optimizer-nlopt0.1.install b/debian/libdart6-optimizer-nlopt.install similarity index 100% rename from debian/libdart-optimizer-nlopt0.1.install rename to debian/libdart6-optimizer-nlopt.install diff --git a/debian/libdart-planning0-dev.install b/debian/libdart6-planning-dev.install similarity index 100% rename from debian/libdart-planning0-dev.install rename to debian/libdart6-planning-dev.install diff --git a/debian/libdart-planning0.1.install b/debian/libdart6-planning.install similarity index 100% rename from debian/libdart-planning0.1.install rename to debian/libdart6-planning.install diff --git a/debian/libdart-utils0-dev.install b/debian/libdart6-utils-dev.install similarity index 100% rename from debian/libdart-utils0-dev.install rename to debian/libdart6-utils-dev.install diff --git a/debian/libdart-utils0.1.install b/debian/libdart6-utils.install similarity index 100% rename from debian/libdart-utils0.1.install rename to debian/libdart6-utils.install diff --git a/debian/libdart6.0.install b/debian/libdart6.install similarity index 100% rename from debian/libdart6.0.install rename to debian/libdart6.install From 0e936b546fb8140c53a7a06b15508aca7ea8a6a3 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 16 Apr 2016 14:44:02 -0400 Subject: [PATCH 17/34] Don't need to install files for libdart6-all-dev --- debian/libdart6-all-dev.install | 15 --------------- 1 file changed, 15 deletions(-) diff --git a/debian/libdart6-all-dev.install b/debian/libdart6-all-dev.install index e4b1376bc30ed..e69de29bb2d1d 100644 --- a/debian/libdart6-all-dev.install +++ b/debian/libdart6-all-dev.install @@ -1,15 +0,0 @@ -usr/include/dart/dart.h -usr/include/dart/config.h -usr/include/dart/collision/* -usr/include/dart/common/* -usr/include/dart/constraint/* -usr/include/dart/dynamics/* -usr/include/dart/integration/* -usr/include/dart/lcpsolver/* -usr/include/dart/math/* -usr/include/dart/optimizer/*.* -usr/include/dart/simulation/* -usr/share/dart/DARTConfig.cmake -usr/share/dart/DARTConfigVersion.cmake -usr/share/dart/DARTTargets.cmake -usr/lib/libdart.so From 5397e5d8afe526145b46cf9e39cb10a6d0660ae6 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 16 Apr 2016 20:43:29 -0400 Subject: [PATCH 18/34] Add missing comma in debian/control --- debian/control | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/debian/control b/debian/control index 9ba26d7714c6b..8afe23c103b96 100644 --- a/debian/control +++ b/debian/control @@ -4,7 +4,7 @@ Maintainer: Jeongseok Lee Build-Depends: debhelper (>= 9), cmake, libeigen3-dev, - libccd-dev + libccd-dev, libfcl-dev (>= 0.2.7), libbullet-dev, libassimp-dev (>= 3), @@ -66,7 +66,7 @@ Depends: ${misc:Depends}, libdart6 (= ${binary:Version}), libeigen3-dev, libassimp-dev (>= 3), - libccd-dev + libccd-dev, libfcl-dev, libbullet-dev, libboost-all-dev (>= 1.54.0.1ubuntu1) From 3e889a9b3624aa22fe65df3c58579bed4988c808 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 21 Apr 2016 16:48:35 -0400 Subject: [PATCH 19/34] Update copyright years up to 2016 --- LICENSE | 4 +- apps/addDeleteSkels/Main.cpp | 2 +- apps/addDeleteSkels/MyWindow.cpp | 2 +- apps/addDeleteSkels/MyWindow.h | 2 +- apps/atlasSimbicon/Controller.cpp | 2 +- apps/atlasSimbicon/Controller.h | 2 +- apps/atlasSimbicon/Humanoid.cpp | 2 +- apps/atlasSimbicon/Humanoid.h | 2 +- apps/atlasSimbicon/Main.cpp | 2 +- apps/atlasSimbicon/MyWindow.cpp | 2 +- apps/atlasSimbicon/MyWindow.h | 2 +- apps/atlasSimbicon/State.cpp | 2 +- apps/atlasSimbicon/State.h | 2 +- apps/atlasSimbicon/StateMachine.cpp | 2 +- apps/atlasSimbicon/StateMachine.h | 2 +- apps/atlasSimbicon/TerminalCondition.cpp | 2 +- apps/atlasSimbicon/TerminalCondition.h | 2 +- apps/bipedStand/Controller.cpp | 2 +- apps/bipedStand/Controller.h | 2 +- apps/bipedStand/Main.cpp | 2 +- apps/bipedStand/MyWindow.cpp | 2 +- apps/bipedStand/MyWindow.h | 2 +- apps/hardcodedDesign/Main.cpp | 2 +- apps/hardcodedDesign/MyWindow.cpp | 2 +- apps/hardcodedDesign/MyWindow.h | 2 +- apps/hybridDynamics/Main.cpp | 2 +- apps/hybridDynamics/MyWindow.cpp | 2 +- apps/hybridDynamics/MyWindow.h | 2 +- apps/jointConstraints/Controller.cpp | 2 +- apps/jointConstraints/Controller.h | 2 +- apps/jointConstraints/Main.cpp | 2 +- apps/jointConstraints/MyWindow.cpp | 2 +- apps/jointConstraints/MyWindow.h | 2 +- apps/mixedChain/Main.cpp | 2 +- apps/mixedChain/MyWindow.cpp | 2 +- apps/mixedChain/MyWindow.h | 2 +- apps/operationalSpaceControl/Controller.cpp | 2 +- apps/operationalSpaceControl/Controller.h | 2 +- apps/operationalSpaceControl/Main.cpp | 2 +- apps/operationalSpaceControl/MyWindow.cpp | 2 +- apps/operationalSpaceControl/MyWindow.h | 2 +- apps/rigidChain/Main.cpp | 2 +- apps/rigidChain/MyWindow.cpp | 2 +- apps/rigidChain/MyWindow.h | 2 +- apps/rigidCubes/Main.cpp | 2 +- apps/rigidCubes/MyWindow.cpp | 2 +- apps/rigidCubes/MyWindow.h | 2 +- apps/rigidLoop/Main.cpp | 2 +- apps/rigidLoop/MyWindow.cpp | 2 +- apps/rigidLoop/MyWindow.h | 2 +- apps/rigidShapes/Main.cpp | 2 +- apps/rigidShapes/MyWindow.cpp | 2 +- apps/rigidShapes/MyWindow.h | 2 +- apps/simpleFrames/Main.cpp | 2 +- apps/softBodies/Main.cpp | 2 +- apps/softBodies/MyWindow.cpp | 2 +- apps/softBodies/MyWindow.h | 2 +- apps/speedTest/Main.cpp | 2 +- apps/vehicle/Main.cpp | 2 +- apps/vehicle/MyWindow.cpp | 2 +- apps/vehicle/MyWindow.h | 2 +- cmake/FindASSIMP.cmake | 2 +- cmake/FindCCD.cmake | 2 +- cmake/FindEIGEN3.cmake | 2 +- cmake/FindFCL.cmake | 2 +- cmake/FindFLANN.cmake | 2 +- cmake/FindIPOPT.cmake | 2 +- cmake/FindNLOPT.cmake | 2 +- cmake/FindSHARK.cmake | 2 +- cmake/FindTINYXML.cmake | 2 +- cmake/FindTINYXML2.cmake | 2 +- dart/collision/CollisionDetector.cpp | 2 +- dart/collision/CollisionDetector.h | 2 +- .../bullet/BulletCollisionDetector.cpp | 2 +- .../bullet/BulletCollisionDetector.h | 2 +- dart/collision/bullet/BulletTypes.cpp | 2 +- dart/collision/bullet/BulletTypes.h | 2 +- dart/collision/dart/DARTCollide.cpp | 2 +- dart/collision/dart/DARTCollide.h | 2 +- dart/collision/dart/DARTCollisionDetector.cpp | 2 +- dart/collision/dart/DARTCollisionDetector.h | 2 +- dart/collision/fcl/CollisionShapes.h | 2 +- dart/collision/fcl/FCLCollisionDetector.cpp | 2 +- dart/collision/fcl/FCLCollisionDetector.h | 2 +- dart/collision/fcl/FCLTypes.cpp | 2 +- dart/collision/fcl/FCLTypes.h | 2 +- .../collision/fcl/tri_tri_intersection_test.h | 46 ++++++++++++++++--- dart/common/Aspect.cpp | 2 +- dart/common/Aspect.h | 2 +- dart/common/Cloneable.h | 2 +- dart/common/Composite.cpp | 2 +- dart/common/Composite.h | 2 +- dart/common/CompositeJoiner.h | 2 +- dart/common/Console.cpp | 2 +- dart/common/Console.h | 2 +- dart/common/Deprecated.h | 2 +- dart/common/Empty.h | 2 +- dart/common/LocalResource.cpp | 2 +- dart/common/LocalResource.h | 2 +- dart/common/LocalResourceRetriever.cpp | 2 +- dart/common/LocalResourceRetriever.h | 2 +- dart/common/Memory.h | 2 +- dart/common/NameManager.h | 2 +- dart/common/Observer.cpp | 2 +- dart/common/Observer.h | 2 +- dart/common/Resource.h | 2 +- dart/common/ResourceRetriever.h | 2 +- dart/common/Signal.cpp | 2 +- dart/common/Signal.h | 2 +- dart/common/SpecializedForAspect.h | 2 +- dart/common/Subject.cpp | 2 +- dart/common/Subject.h | 2 +- dart/common/Timer.cpp | 2 +- dart/common/Timer.h | 2 +- dart/common/Uri.cpp | 2 +- dart/common/Uri.h | 2 +- dart/common/Virtual.h | 2 +- dart/common/detail/Aspect.h | 2 +- dart/common/detail/Cloneable.h | 2 +- dart/common/detail/Composite.h | 2 +- dart/common/detail/CompositeJoiner.h | 2 +- dart/common/detail/ConnectionBody.cpp | 2 +- dart/common/detail/ConnectionBody.h | 2 +- dart/common/detail/NameManager.h | 2 +- dart/common/detail/NoOp.h | 2 +- dart/common/detail/Signal.h | 2 +- dart/common/detail/SpecializedForAspect.h | 2 +- dart/common/detail/sub_ptr.h | 2 +- dart/common/sub_ptr.h | 2 +- dart/constraint/BalanceConstraint.cpp | 2 +- dart/constraint/BalanceConstraint.h | 2 +- dart/constraint/BallJointConstraint.cpp | 2 +- dart/constraint/BallJointConstraint.h | 2 +- dart/constraint/ConstrainedGroup.cpp | 2 +- dart/constraint/ConstrainedGroup.h | 2 +- dart/constraint/ConstraintBase.cpp | 2 +- dart/constraint/ConstraintBase.h | 2 +- dart/constraint/ConstraintSolver.cpp | 2 +- dart/constraint/ConstraintSolver.h | 2 +- dart/constraint/ContactConstraint.cpp | 2 +- dart/constraint/ContactConstraint.h | 2 +- dart/constraint/DantzigLCPSolver.cpp | 2 +- dart/constraint/DantzigLCPSolver.h | 2 +- dart/constraint/JointConstraint.cpp | 2 +- dart/constraint/JointConstraint.h | 2 +- .../JointCoulombFrictionConstraint.cpp | 2 +- .../JointCoulombFrictionConstraint.h | 2 +- dart/constraint/JointLimitConstraint.cpp | 2 +- dart/constraint/JointLimitConstraint.h | 2 +- dart/constraint/LCPSolver.cpp | 2 +- dart/constraint/LCPSolver.h | 2 +- dart/constraint/PGSLCPSolver.cpp | 2 +- dart/constraint/PGSLCPSolver.h | 2 +- dart/constraint/ServoMotorConstraint.cpp | 2 +- dart/constraint/ServoMotorConstraint.h | 2 +- dart/constraint/SoftContactConstraint.cpp | 2 +- dart/constraint/SoftContactConstraint.h | 2 +- dart/constraint/WeldJointConstraint.cpp | 2 +- dart/constraint/WeldJointConstraint.h | 2 +- dart/dart.h | 2 +- dart/dynamics/ArrowShape.cpp | 2 +- dart/dynamics/ArrowShape.h | 2 +- dart/dynamics/AssimpInputResourceAdaptor.cpp | 36 +++++++++++++++ dart/dynamics/AssimpInputResourceAdaptor.h | 2 +- dart/dynamics/BallJoint.cpp | 2 +- dart/dynamics/BallJoint.h | 2 +- dart/dynamics/BodyNode.cpp | 2 +- dart/dynamics/BodyNode.h | 2 +- dart/dynamics/BoxShape.cpp | 2 +- dart/dynamics/BoxShape.h | 2 +- dart/dynamics/Branch.cpp | 2 +- dart/dynamics/Branch.h | 2 +- dart/dynamics/Chain.cpp | 2 +- dart/dynamics/Chain.h | 2 +- dart/dynamics/CylinderShape.cpp | 2 +- dart/dynamics/CylinderShape.h | 2 +- dart/dynamics/DegreeOfFreedom.cpp | 2 +- dart/dynamics/DegreeOfFreedom.h | 2 +- dart/dynamics/EllipsoidShape.cpp | 2 +- dart/dynamics/EllipsoidShape.h | 2 +- dart/dynamics/EndEffector.cpp | 2 +- dart/dynamics/EndEffector.h | 2 +- dart/dynamics/Entity.cpp | 2 +- dart/dynamics/Entity.h | 2 +- dart/dynamics/EulerJoint.cpp | 2 +- dart/dynamics/EulerJoint.h | 2 +- dart/dynamics/FixedFrame.cpp | 2 +- dart/dynamics/FixedFrame.h | 2 +- dart/dynamics/Frame.cpp | 2 +- dart/dynamics/Frame.h | 2 +- dart/dynamics/FreeJoint.cpp | 2 +- dart/dynamics/FreeJoint.h | 2 +- dart/dynamics/Group.cpp | 2 +- dart/dynamics/Group.h | 2 +- dart/dynamics/HierarchicalIK.cpp | 2 +- dart/dynamics/HierarchicalIK.h | 2 +- dart/dynamics/Inertia.cpp | 2 +- dart/dynamics/Inertia.h | 2 +- dart/dynamics/InvalidIndex.h | 2 +- dart/dynamics/InverseKinematics.cpp | 2 +- dart/dynamics/InverseKinematics.h | 2 +- dart/dynamics/JacobianNode.cpp | 2 +- dart/dynamics/JacobianNode.h | 2 +- dart/dynamics/Joint.cpp | 2 +- dart/dynamics/Joint.h | 2 +- dart/dynamics/LineSegmentShape.cpp | 2 +- dart/dynamics/LineSegmentShape.h | 2 +- dart/dynamics/Linkage.cpp | 2 +- dart/dynamics/Linkage.h | 2 +- dart/dynamics/Marker.cpp | 2 +- dart/dynamics/Marker.h | 2 +- dart/dynamics/MeshShape.cpp | 2 +- dart/dynamics/MeshShape.h | 2 +- dart/dynamics/MetaSkeleton.cpp | 2 +- dart/dynamics/MetaSkeleton.h | 2 +- dart/dynamics/MultiDofJoint.h | 2 +- dart/dynamics/Node.cpp | 2 +- dart/dynamics/Node.h | 2 +- dart/dynamics/PlanarJoint.cpp | 2 +- dart/dynamics/PlanarJoint.h | 2 +- dart/dynamics/PlaneShape.cpp | 2 +- dart/dynamics/PlaneShape.h | 2 +- dart/dynamics/PointMass.cpp | 2 +- dart/dynamics/PointMass.h | 2 +- dart/dynamics/PrismaticJoint.cpp | 2 +- dart/dynamics/PrismaticJoint.h | 2 +- dart/dynamics/ReferentialSkeleton.cpp | 2 +- dart/dynamics/ReferentialSkeleton.h | 2 +- dart/dynamics/RevoluteJoint.cpp | 2 +- dart/dynamics/RevoluteJoint.h | 2 +- dart/dynamics/ScrewJoint.cpp | 2 +- dart/dynamics/ScrewJoint.h | 2 +- dart/dynamics/Shape.cpp | 2 +- dart/dynamics/Shape.h | 2 +- dart/dynamics/SimpleFrame.cpp | 2 +- dart/dynamics/SimpleFrame.h | 2 +- dart/dynamics/SingleDofJoint.cpp | 2 +- dart/dynamics/SingleDofJoint.h | 2 +- dart/dynamics/Skeleton.cpp | 2 +- dart/dynamics/Skeleton.h | 2 +- dart/dynamics/SmartPointer.h | 2 +- dart/dynamics/SoftBodyNode.cpp | 2 +- dart/dynamics/SoftBodyNode.h | 2 +- dart/dynamics/SoftMeshShape.cpp | 2 +- dart/dynamics/SoftMeshShape.h | 2 +- dart/dynamics/SpecializedNodeManager.h | 2 +- dart/dynamics/TemplatedJacobianNode.h | 2 +- dart/dynamics/TranslationalJoint.cpp | 2 +- dart/dynamics/TranslationalJoint.h | 2 +- dart/dynamics/UniversalJoint.cpp | 2 +- dart/dynamics/UniversalJoint.h | 2 +- dart/dynamics/WeldJoint.cpp | 2 +- dart/dynamics/WeldJoint.h | 2 +- dart/dynamics/ZeroDofJoint.cpp | 2 +- dart/dynamics/ZeroDofJoint.h | 2 +- dart/dynamics/detail/BasicNodeManager.h | 2 +- dart/dynamics/detail/BodyNode.h | 2 +- dart/dynamics/detail/BodyNodePtr.h | 2 +- dart/dynamics/detail/DegreeOfFreedomPtr.h | 2 +- dart/dynamics/detail/EulerJointAspect.cpp | 2 +- dart/dynamics/detail/EulerJointAspect.h | 2 +- dart/dynamics/detail/InverseKinematics.h | 2 +- dart/dynamics/detail/InverseKinematicsPtr.h | 2 +- dart/dynamics/detail/JointPtr.h | 2 +- dart/dynamics/detail/MultiDofJoint.h | 2 +- dart/dynamics/detail/MultiDofJointAspect.h | 2 +- dart/dynamics/detail/Node.h | 2 +- dart/dynamics/detail/NodePtr.h | 2 +- dart/dynamics/detail/PlanarJointAspect.cpp | 2 +- dart/dynamics/detail/PlanarJointAspect.h | 2 +- dart/dynamics/detail/PrismaticJointAspect.cpp | 2 +- dart/dynamics/detail/PrismaticJointAspect.h | 2 +- dart/dynamics/detail/RevoluteJointAspect.cpp | 2 +- dart/dynamics/detail/RevoluteJointAspect.h | 2 +- dart/dynamics/detail/ScrewJointAspect.cpp | 2 +- dart/dynamics/detail/ScrewJointAspect.h | 2 +- dart/dynamics/detail/SingleDofJointAspect.cpp | 2 +- dart/dynamics/detail/SingleDofJointAspect.h | 2 +- dart/dynamics/detail/Skeleton.h | 2 +- dart/dynamics/detail/SpecializedNodeManager.h | 2 +- dart/dynamics/detail/TemplatedJacobianNode.h | 2 +- dart/dynamics/detail/UniversalJointAspect.cpp | 2 +- dart/dynamics/detail/UniversalJointAspect.h | 2 +- dart/gui/GLFuncs.cpp | 2 +- dart/gui/GLFuncs.h | 2 +- dart/gui/GlutWindow.cpp | 2 +- dart/gui/GlutWindow.h | 2 +- dart/gui/GraphWindow.cpp | 2 +- dart/gui/GraphWindow.h | 2 +- dart/gui/LoadGlut.h | 2 +- dart/gui/LoadOpengl.h | 2 +- dart/gui/OpenGLRenderInterface.cpp | 2 +- dart/gui/OpenGLRenderInterface.h | 2 +- dart/gui/RenderInterface.cpp | 2 +- dart/gui/RenderInterface.h | 2 +- dart/gui/SimWindow.cpp | 2 +- dart/gui/SimWindow.h | 2 +- dart/gui/SoftSimWindow.cpp | 2 +- dart/gui/SoftSimWindow.h | 2 +- dart/gui/Trackball.cpp | 2 +- dart/gui/Trackball.h | 2 +- dart/gui/Win2D.cpp | 2 +- dart/gui/Win2D.h | 2 +- dart/gui/Win3D.cpp | 2 +- dart/gui/Win3D.h | 2 +- dart/gui/osg/DefaultEventHandler.cpp | 2 +- dart/gui/osg/DefaultEventHandler.h | 2 +- dart/gui/osg/DragAndDrop.cpp | 2 +- dart/gui/osg/DragAndDrop.h | 2 +- dart/gui/osg/InteractiveFrame.cpp | 2 +- dart/gui/osg/InteractiveFrame.h | 2 +- dart/gui/osg/MouseEventHandler.h | 2 +- dart/gui/osg/ShapeFrameNode.cpp | 2 +- dart/gui/osg/ShapeFrameNode.h | 2 +- dart/gui/osg/SupportPolygonVisual.cpp | 2 +- dart/gui/osg/SupportPolygonVisual.h | 2 +- dart/gui/osg/TrackballManipulator.cpp | 2 +- dart/gui/osg/TrackballManipulator.h | 2 +- dart/gui/osg/Utils.h | 2 +- dart/gui/osg/Viewer.cpp | 2 +- dart/gui/osg/Viewer.h | 2 +- dart/gui/osg/WorldNode.cpp | 2 +- dart/gui/osg/WorldNode.h | 2 +- dart/gui/osg/examples/osgAtlasPuppet.cpp | 2 +- dart/gui/osg/examples/osgDragAndDrop.cpp | 2 +- dart/gui/osg/examples/osgHuboPuppet.cpp | 2 +- .../examples/osgOperationalSpaceControl.cpp | 2 +- dart/gui/osg/examples/osgSoftBodies.cpp | 2 +- dart/gui/osg/render/BoxShapeNode.cpp | 2 +- dart/gui/osg/render/BoxShapeNode.h | 2 +- dart/gui/osg/render/CylinderShapeNode.cpp | 2 +- dart/gui/osg/render/CylinderShapeNode.h | 2 +- dart/gui/osg/render/EllipsoidShapeNode.cpp | 2 +- dart/gui/osg/render/EllipsoidShapeNode.h | 2 +- dart/gui/osg/render/LineSegmentShapeNode.cpp | 2 +- dart/gui/osg/render/LineSegmentShapeNode.h | 2 +- dart/gui/osg/render/MeshShapeNode.cpp | 2 +- dart/gui/osg/render/MeshShapeNode.h | 2 +- dart/gui/osg/render/PlaneShapeNode.cpp | 2 +- dart/gui/osg/render/PlaneShapeNode.h | 2 +- dart/gui/osg/render/ShapeNode.cpp | 2 +- dart/gui/osg/render/ShapeNode.h | 2 +- dart/gui/osg/render/SoftMeshShapeNode.cpp | 2 +- dart/gui/osg/render/SoftMeshShapeNode.h | 2 +- dart/gui/osg/render/WarningShapeNode.cpp | 2 +- dart/gui/osg/render/WarningShapeNode.h | 2 +- dart/integration/EulerIntegrator.cpp | 2 +- dart/integration/EulerIntegrator.h | 2 +- dart/integration/Integrator.cpp | 2 +- dart/integration/Integrator.h | 2 +- dart/integration/RK4Integrator.cpp | 2 +- dart/integration/RK4Integrator.h | 2 +- .../SemiImplicitEulerIntegrator.cpp | 2 +- .../integration/SemiImplicitEulerIntegrator.h | 2 +- dart/lcpsolver/Lemke.cpp | 2 +- dart/lcpsolver/Lemke.h | 2 +- dart/lcpsolver/ODELCPSolver.cpp | 2 +- dart/lcpsolver/ODELCPSolver.h | 2 +- dart/lcpsolver/fastdot.cpp | 22 +++++++++ dart/lcpsolver/fastldlt.cpp | 22 +++++++++ dart/lcpsolver/fastlsolve.cpp | 22 +++++++++ dart/lcpsolver/fastltsolve.cpp | 22 +++++++++ dart/lcpsolver/odeconfig.h | 22 +++++++++ dart/math/Geometry.cpp | 2 +- dart/math/Geometry.h | 2 +- dart/math/Helpers.h | 2 +- dart/math/MathTypes.h | 2 +- dart/optimizer/Function.cpp | 2 +- dart/optimizer/Function.h | 2 +- dart/optimizer/GradientDescentSolver.cpp | 2 +- dart/optimizer/GradientDescentSolver.h | 2 +- dart/optimizer/Problem.cpp | 2 +- dart/optimizer/Problem.h | 2 +- dart/optimizer/Solver.cpp | 2 +- dart/optimizer/Solver.h | 2 +- dart/optimizer/ipopt/IpoptSolver.cpp | 2 +- dart/optimizer/ipopt/IpoptSolver.h | 2 +- dart/optimizer/nlopt/NloptSolver.cpp | 2 +- dart/optimizer/nlopt/NloptSolver.h | 2 +- dart/planning/Path.cpp | 2 +- dart/planning/Path.h | 2 +- dart/planning/PathFollowingTrajectory.cpp | 2 +- dart/planning/PathFollowingTrajectory.h | 2 +- dart/planning/PathPlanner.h | 37 +++++++++++++++ dart/planning/PathShortener.cpp | 36 +++++++++++++++ dart/planning/PathShortener.h | 45 ++++++++++++++++-- dart/planning/RRT.cpp | 2 +- dart/planning/RRT.h | 2 +- dart/planning/Trajectory.h | 2 +- dart/simulation/Recording.cpp | 2 +- dart/simulation/Recording.h | 2 +- dart/simulation/World.cpp | 2 +- dart/simulation/World.h | 2 +- dart/utils/C3D.cpp | 2 +- dart/utils/C3D.h | 2 +- dart/utils/CompositeResourceRetriever.cpp | 2 +- dart/utils/CompositeResourceRetriever.h | 2 +- dart/utils/FileInfoC3D.cpp | 2 +- dart/utils/FileInfoC3D.h | 2 +- dart/utils/FileInfoDof.cpp | 2 +- dart/utils/FileInfoDof.h | 2 +- dart/utils/FileInfoWorld.cpp | 2 +- dart/utils/FileInfoWorld.h | 2 +- dart/utils/PackageResourceRetriever.cpp | 2 +- dart/utils/PackageResourceRetriever.h | 2 +- dart/utils/SkelParser.cpp | 2 +- dart/utils/SkelParser.h | 2 +- dart/utils/VskParser.cpp | 2 +- dart/utils/VskParser.h | 2 +- dart/utils/XmlHelpers.cpp | 2 +- dart/utils/XmlHelpers.h | 2 +- dart/utils/urdf/DartLoader.cpp | 36 +++++++++++++++ dart/utils/urdf/DartLoader.h | 36 ++++++++++++++- mkdocs.yml | 2 +- tutorials/tutorialBiped-Finished.cpp | 2 +- tutorials/tutorialBiped.cpp | 2 +- tutorials/tutorialCollisions-Finished.cpp | 2 +- tutorials/tutorialCollisions.cpp | 2 +- tutorials/tutorialDominoes-Finished.cpp | 2 +- tutorials/tutorialDominoes.cpp | 2 +- tutorials/tutorialMultiPendulum-Finished.cpp | 2 +- tutorials/tutorialMultiPendulum.cpp | 2 +- unittests/CMakeLists.txt | 2 +- unittests/testAspect.cpp | 2 +- unittests/testBuilding.cpp | 2 +- unittests/testCollision.cpp | 2 +- unittests/testCommon.cpp | 2 +- unittests/testCompositeResourceRetriever.cpp | 2 +- unittests/testConcurrency.cpp | 2 +- unittests/testConstraint.cpp | 2 +- unittests/testDartLoader.cpp | 2 +- unittests/testDynamics.cpp | 2 +- unittests/testFileInfoWorld.cpp | 2 +- unittests/testForwardKinematics.cpp | 2 +- unittests/testFrames.cpp | 2 +- unittests/testGeometry.cpp | 2 +- unittests/testInverseKinematics.cpp | 2 +- unittests/testJoints.cpp | 2 +- unittests/testLocalResourceRetriever.cpp | 2 +- unittests/testMath.cpp | 2 +- unittests/testNameManagement.cpp | 2 +- unittests/testOptimizer.cpp | 2 +- unittests/testPackageResourceRetriever.cpp | 2 +- unittests/testSdfParser.cpp | 2 +- unittests/testSignal.cpp | 2 +- unittests/testSkelParser.cpp | 2 +- unittests/testSkeleton.cpp | 2 +- unittests/testSoftDynamics.cpp | 2 +- unittests/testSubscriptions.cpp | 2 +- unittests/testUri.cpp | 2 +- unittests/testUtilities.cpp | 2 +- unittests/testVskParser.cpp | 2 +- unittests/testWorld.cpp | 2 +- 453 files changed, 810 insertions(+), 456 deletions(-) diff --git a/LICENSE b/LICENSE index 2a2f1e0d5f15b..a131a71e07fe1 100644 --- a/LICENSE +++ b/LICENSE @@ -1,4 +1,4 @@ -Copyright (c) 2011-2015, Georgia Tech Research Corporation +Copyright (c) 2011-2016, Georgia Tech Research Corporation All rights reserved. Georgia Tech Graphics Lab and Humanoid Robotics Lab @@ -28,4 +28,4 @@ This file is provided under the following "BSD-style" License: 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. \ No newline at end of file + POSSIBILITY OF SUCH DAMAGE. diff --git a/apps/addDeleteSkels/Main.cpp b/apps/addDeleteSkels/Main.cpp index 51ac98497dd40..803fe7749543e 100644 --- a/apps/addDeleteSkels/Main.cpp +++ b/apps/addDeleteSkels/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/addDeleteSkels/MyWindow.cpp b/apps/addDeleteSkels/MyWindow.cpp index 4f841f7e28c26..f00d96eda1445 100644 --- a/apps/addDeleteSkels/MyWindow.cpp +++ b/apps/addDeleteSkels/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/addDeleteSkels/MyWindow.h b/apps/addDeleteSkels/MyWindow.h index ca498eccac516..cb50f4a662981 100644 --- a/apps/addDeleteSkels/MyWindow.h +++ b/apps/addDeleteSkels/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/atlasSimbicon/Controller.cpp b/apps/atlasSimbicon/Controller.cpp index 16f7ed69c4e83..9b8d3a029fa19 100644 --- a/apps/atlasSimbicon/Controller.cpp +++ b/apps/atlasSimbicon/Controller.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/atlasSimbicon/Controller.h b/apps/atlasSimbicon/Controller.h index 6855b4414881c..a3c0f6d073bb7 100644 --- a/apps/atlasSimbicon/Controller.h +++ b/apps/atlasSimbicon/Controller.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/atlasSimbicon/Humanoid.cpp b/apps/atlasSimbicon/Humanoid.cpp index 9b32911dbb328..b09c6bc0f80df 100644 --- a/apps/atlasSimbicon/Humanoid.cpp +++ b/apps/atlasSimbicon/Humanoid.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/atlasSimbicon/Humanoid.h b/apps/atlasSimbicon/Humanoid.h index 5d0fa7393a939..83d74d1cae1f7 100644 --- a/apps/atlasSimbicon/Humanoid.h +++ b/apps/atlasSimbicon/Humanoid.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/atlasSimbicon/Main.cpp b/apps/atlasSimbicon/Main.cpp index f6029bf33b078..69856deffb58e 100644 --- a/apps/atlasSimbicon/Main.cpp +++ b/apps/atlasSimbicon/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/atlasSimbicon/MyWindow.cpp b/apps/atlasSimbicon/MyWindow.cpp index 6a08f7b4e44f7..d06c654b3ddd6 100644 --- a/apps/atlasSimbicon/MyWindow.cpp +++ b/apps/atlasSimbicon/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/atlasSimbicon/MyWindow.h b/apps/atlasSimbicon/MyWindow.h index 5f5d7549684eb..222be0bd73f33 100644 --- a/apps/atlasSimbicon/MyWindow.h +++ b/apps/atlasSimbicon/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/atlasSimbicon/State.cpp b/apps/atlasSimbicon/State.cpp index 7209e903a3bcf..a67316a6efe15 100644 --- a/apps/atlasSimbicon/State.cpp +++ b/apps/atlasSimbicon/State.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/atlasSimbicon/State.h b/apps/atlasSimbicon/State.h index 6accbd0e72510..15c39393d707c 100644 --- a/apps/atlasSimbicon/State.h +++ b/apps/atlasSimbicon/State.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/atlasSimbicon/StateMachine.cpp b/apps/atlasSimbicon/StateMachine.cpp index 83d6788de149a..76e063956dc45 100644 --- a/apps/atlasSimbicon/StateMachine.cpp +++ b/apps/atlasSimbicon/StateMachine.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/atlasSimbicon/StateMachine.h b/apps/atlasSimbicon/StateMachine.h index 90b6f29c90ade..1614af27b536c 100644 --- a/apps/atlasSimbicon/StateMachine.h +++ b/apps/atlasSimbicon/StateMachine.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/atlasSimbicon/TerminalCondition.cpp b/apps/atlasSimbicon/TerminalCondition.cpp index b215db4780eaa..a6918e826d4bb 100644 --- a/apps/atlasSimbicon/TerminalCondition.cpp +++ b/apps/atlasSimbicon/TerminalCondition.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/atlasSimbicon/TerminalCondition.h b/apps/atlasSimbicon/TerminalCondition.h index e007c1df51956..9db7b03dd1292 100644 --- a/apps/atlasSimbicon/TerminalCondition.h +++ b/apps/atlasSimbicon/TerminalCondition.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/bipedStand/Controller.cpp b/apps/bipedStand/Controller.cpp index 64cafa603f5ea..a8854e5060049 100644 --- a/apps/bipedStand/Controller.cpp +++ b/apps/bipedStand/Controller.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/bipedStand/Controller.h b/apps/bipedStand/Controller.h index 7ab9a1c0f7f67..dd3a940494628 100644 --- a/apps/bipedStand/Controller.h +++ b/apps/bipedStand/Controller.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/bipedStand/Main.cpp b/apps/bipedStand/Main.cpp index 5af4ab9eee082..79ab04fc6cb66 100644 --- a/apps/bipedStand/Main.cpp +++ b/apps/bipedStand/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/bipedStand/MyWindow.cpp b/apps/bipedStand/MyWindow.cpp index de0830a412cb2..8b222b95fdb7a 100644 --- a/apps/bipedStand/MyWindow.cpp +++ b/apps/bipedStand/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/bipedStand/MyWindow.h b/apps/bipedStand/MyWindow.h index a801c13661e7b..eea5a1aa15efa 100644 --- a/apps/bipedStand/MyWindow.h +++ b/apps/bipedStand/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/hardcodedDesign/Main.cpp b/apps/hardcodedDesign/Main.cpp index af90329bdfaf3..aaf8b63fa2d81 100644 --- a/apps/hardcodedDesign/Main.cpp +++ b/apps/hardcodedDesign/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Can Erdogan diff --git a/apps/hardcodedDesign/MyWindow.cpp b/apps/hardcodedDesign/MyWindow.cpp index eddcad0766e88..155c388515fa8 100644 --- a/apps/hardcodedDesign/MyWindow.cpp +++ b/apps/hardcodedDesign/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Can Erdogan diff --git a/apps/hardcodedDesign/MyWindow.h b/apps/hardcodedDesign/MyWindow.h index 8a6e708edf639..d9bca07895bd1 100644 --- a/apps/hardcodedDesign/MyWindow.h +++ b/apps/hardcodedDesign/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Can Erdogan diff --git a/apps/hybridDynamics/Main.cpp b/apps/hybridDynamics/Main.cpp index 987a70ea06d36..22f0377d93bfd 100644 --- a/apps/hybridDynamics/Main.cpp +++ b/apps/hybridDynamics/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/hybridDynamics/MyWindow.cpp b/apps/hybridDynamics/MyWindow.cpp index 09dc06eb27040..1fa5a91c899b8 100644 --- a/apps/hybridDynamics/MyWindow.cpp +++ b/apps/hybridDynamics/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/hybridDynamics/MyWindow.h b/apps/hybridDynamics/MyWindow.h index 38fc9bc0f4e7b..b8190d1df9093 100644 --- a/apps/hybridDynamics/MyWindow.h +++ b/apps/hybridDynamics/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/jointConstraints/Controller.cpp b/apps/jointConstraints/Controller.cpp index 487f7171ce278..e93b69cb7d4e1 100644 --- a/apps/jointConstraints/Controller.cpp +++ b/apps/jointConstraints/Controller.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/apps/jointConstraints/Controller.h b/apps/jointConstraints/Controller.h index bb88fe9d9280f..05fa693644b13 100644 --- a/apps/jointConstraints/Controller.h +++ b/apps/jointConstraints/Controller.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/apps/jointConstraints/Main.cpp b/apps/jointConstraints/Main.cpp index 866916cab7159..91fb7df866ac2 100644 --- a/apps/jointConstraints/Main.cpp +++ b/apps/jointConstraints/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/apps/jointConstraints/MyWindow.cpp b/apps/jointConstraints/MyWindow.cpp index b1c1e6f81f71f..55846bc39c0b5 100644 --- a/apps/jointConstraints/MyWindow.cpp +++ b/apps/jointConstraints/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/apps/jointConstraints/MyWindow.h b/apps/jointConstraints/MyWindow.h index 98c25d07a0e37..fd17a7dc0a181 100644 --- a/apps/jointConstraints/MyWindow.h +++ b/apps/jointConstraints/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/apps/mixedChain/Main.cpp b/apps/mixedChain/Main.cpp index 9c8ea57815b5e..8bc2810be083d 100644 --- a/apps/mixedChain/Main.cpp +++ b/apps/mixedChain/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/mixedChain/MyWindow.cpp b/apps/mixedChain/MyWindow.cpp index 7aec0ed8b9cac..eb99784511ffe 100644 --- a/apps/mixedChain/MyWindow.cpp +++ b/apps/mixedChain/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/mixedChain/MyWindow.h b/apps/mixedChain/MyWindow.h index e4cee8a50bfd0..6a420ac68e3e5 100644 --- a/apps/mixedChain/MyWindow.h +++ b/apps/mixedChain/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/operationalSpaceControl/Controller.cpp b/apps/operationalSpaceControl/Controller.cpp index 0a532ff1ff521..df4ebe105f3ad 100644 --- a/apps/operationalSpaceControl/Controller.cpp +++ b/apps/operationalSpaceControl/Controller.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/operationalSpaceControl/Controller.h b/apps/operationalSpaceControl/Controller.h index 3cbff7de5f48f..58b07f29143d5 100644 --- a/apps/operationalSpaceControl/Controller.h +++ b/apps/operationalSpaceControl/Controller.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/operationalSpaceControl/Main.cpp b/apps/operationalSpaceControl/Main.cpp index a00e047d460f7..3e4946eaa719e 100644 --- a/apps/operationalSpaceControl/Main.cpp +++ b/apps/operationalSpaceControl/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/operationalSpaceControl/MyWindow.cpp b/apps/operationalSpaceControl/MyWindow.cpp index 44c2256aea232..9f5388a3ece58 100644 --- a/apps/operationalSpaceControl/MyWindow.cpp +++ b/apps/operationalSpaceControl/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/operationalSpaceControl/MyWindow.h b/apps/operationalSpaceControl/MyWindow.h index 5b5fd1778f8db..d515bbb4301b8 100644 --- a/apps/operationalSpaceControl/MyWindow.h +++ b/apps/operationalSpaceControl/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/rigidChain/Main.cpp b/apps/rigidChain/Main.cpp index 5c37f0e3e41b8..b9d5b88bd312d 100644 --- a/apps/rigidChain/Main.cpp +++ b/apps/rigidChain/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/rigidChain/MyWindow.cpp b/apps/rigidChain/MyWindow.cpp index 710f37fc25aae..fa5596ab30e44 100644 --- a/apps/rigidChain/MyWindow.cpp +++ b/apps/rigidChain/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/rigidChain/MyWindow.h b/apps/rigidChain/MyWindow.h index 9eaebabbd73d7..a887235932e12 100644 --- a/apps/rigidChain/MyWindow.h +++ b/apps/rigidChain/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/rigidCubes/Main.cpp b/apps/rigidCubes/Main.cpp index 4bdd9d597f48f..7e22ae6d212e5 100644 --- a/apps/rigidCubes/Main.cpp +++ b/apps/rigidCubes/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/rigidCubes/MyWindow.cpp b/apps/rigidCubes/MyWindow.cpp index 143f37ad2458d..e6d34dc9a5713 100644 --- a/apps/rigidCubes/MyWindow.cpp +++ b/apps/rigidCubes/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/rigidCubes/MyWindow.h b/apps/rigidCubes/MyWindow.h index e59abd436ef9e..e6e9abb604a93 100644 --- a/apps/rigidCubes/MyWindow.h +++ b/apps/rigidCubes/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu , diff --git a/apps/rigidLoop/Main.cpp b/apps/rigidLoop/Main.cpp index 19bc2878b6e3a..e2c8fccfdfb66 100644 --- a/apps/rigidLoop/Main.cpp +++ b/apps/rigidLoop/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/apps/rigidLoop/MyWindow.cpp b/apps/rigidLoop/MyWindow.cpp index 40fde6006b334..1430c080b6dc0 100644 --- a/apps/rigidLoop/MyWindow.cpp +++ b/apps/rigidLoop/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/apps/rigidLoop/MyWindow.h b/apps/rigidLoop/MyWindow.h index 37a2233ae4c18..7a7da3a1de62f 100644 --- a/apps/rigidLoop/MyWindow.h +++ b/apps/rigidLoop/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/apps/rigidShapes/Main.cpp b/apps/rigidShapes/Main.cpp index ddddaaef2eab2..adf1b124d5452 100644 --- a/apps/rigidShapes/Main.cpp +++ b/apps/rigidShapes/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/rigidShapes/MyWindow.cpp b/apps/rigidShapes/MyWindow.cpp index 07c5723122c49..e063925ba2581 100644 --- a/apps/rigidShapes/MyWindow.cpp +++ b/apps/rigidShapes/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/rigidShapes/MyWindow.h b/apps/rigidShapes/MyWindow.h index 45629de0e48b8..2a8c34de7f9fd 100644 --- a/apps/rigidShapes/MyWindow.h +++ b/apps/rigidShapes/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/simpleFrames/Main.cpp b/apps/simpleFrames/Main.cpp index 7fd234a32648b..fd56f25cf1c93 100644 --- a/apps/simpleFrames/Main.cpp +++ b/apps/simpleFrames/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/apps/softBodies/Main.cpp b/apps/softBodies/Main.cpp index 04c54377969fe..e309c58f2a2bd 100644 --- a/apps/softBodies/Main.cpp +++ b/apps/softBodies/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/softBodies/MyWindow.cpp b/apps/softBodies/MyWindow.cpp index 297ef081c194e..1f541e5d57caf 100644 --- a/apps/softBodies/MyWindow.cpp +++ b/apps/softBodies/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/softBodies/MyWindow.h b/apps/softBodies/MyWindow.h index 23f108bdc3e8b..f365ca7ab153f 100644 --- a/apps/softBodies/MyWindow.h +++ b/apps/softBodies/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/speedTest/Main.cpp b/apps/speedTest/Main.cpp index ef72aceb3ec7b..39d11df62850b 100644 --- a/apps/speedTest/Main.cpp +++ b/apps/speedTest/Main.cpp @@ -1,6 +1,6 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/apps/vehicle/Main.cpp b/apps/vehicle/Main.cpp index c5c688bb1fc74..ed006321055a6 100644 --- a/apps/vehicle/Main.cpp +++ b/apps/vehicle/Main.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/vehicle/MyWindow.cpp b/apps/vehicle/MyWindow.cpp index c46ba8b9c8afc..8f16ba1bf1acf 100644 --- a/apps/vehicle/MyWindow.cpp +++ b/apps/vehicle/MyWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/apps/vehicle/MyWindow.h b/apps/vehicle/MyWindow.h index f5f3e8d49b548..b2f7308be40b9 100644 --- a/apps/vehicle/MyWindow.h +++ b/apps/vehicle/MyWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/cmake/FindASSIMP.cmake b/cmake/FindASSIMP.cmake index c82b98b44e332..7d4fd8e66227d 100644 --- a/cmake/FindASSIMP.cmake +++ b/cmake/FindASSIMP.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find ASSIMP diff --git a/cmake/FindCCD.cmake b/cmake/FindCCD.cmake index 5ef05daf532b1..b3e2f1aa7e7f7 100644 --- a/cmake/FindCCD.cmake +++ b/cmake/FindCCD.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find CCD diff --git a/cmake/FindEIGEN3.cmake b/cmake/FindEIGEN3.cmake index 2dcd0ae31ca2f..99290097cffef 100644 --- a/cmake/FindEIGEN3.cmake +++ b/cmake/FindEIGEN3.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find Eigen diff --git a/cmake/FindFCL.cmake b/cmake/FindFCL.cmake index b5d881dd7cd20..5d6a0297d71e3 100644 --- a/cmake/FindFCL.cmake +++ b/cmake/FindFCL.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find FCL diff --git a/cmake/FindFLANN.cmake b/cmake/FindFLANN.cmake index 382213e9108d6..bb5dc1f72fff4 100644 --- a/cmake/FindFLANN.cmake +++ b/cmake/FindFLANN.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find FLANN diff --git a/cmake/FindIPOPT.cmake b/cmake/FindIPOPT.cmake index e72dfe03aea52..49768a760ebda 100644 --- a/cmake/FindIPOPT.cmake +++ b/cmake/FindIPOPT.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find IPOPT diff --git a/cmake/FindNLOPT.cmake b/cmake/FindNLOPT.cmake index 259a42976fb00..4509a8b6cdb0d 100644 --- a/cmake/FindNLOPT.cmake +++ b/cmake/FindNLOPT.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find NLOPT diff --git a/cmake/FindSHARK.cmake b/cmake/FindSHARK.cmake index 53178d8675538..aabc8cb827367 100644 --- a/cmake/FindSHARK.cmake +++ b/cmake/FindSHARK.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find SHARK diff --git a/cmake/FindTINYXML.cmake b/cmake/FindTINYXML.cmake index c1218c230cda2..28d70240eccb9 100644 --- a/cmake/FindTINYXML.cmake +++ b/cmake/FindTINYXML.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find TINYXML diff --git a/cmake/FindTINYXML2.cmake b/cmake/FindTINYXML2.cmake index 2b109806cc9e8..f47c75dba3d07 100644 --- a/cmake/FindTINYXML2.cmake +++ b/cmake/FindTINYXML2.cmake @@ -1,4 +1,4 @@ -# Copyright (c) 2015, Georgia Tech Graphics Lab and Humanoid Robotics Lab +# Copyright (c) 2015-2016, Georgia Tech Graphics Lab and Humanoid Robotics Lab # This file is provided under the "BSD-style" License # Find TINYXML2 diff --git a/dart/collision/CollisionDetector.cpp b/dart/collision/CollisionDetector.cpp index c2444a4bf05cf..029b700403ea8 100644 --- a/dart/collision/CollisionDetector.cpp +++ b/dart/collision/CollisionDetector.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee , diff --git a/dart/collision/CollisionDetector.h b/dart/collision/CollisionDetector.h index 59e0ec3282088..9b788c752d9e8 100644 --- a/dart/collision/CollisionDetector.h +++ b/dart/collision/CollisionDetector.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee , diff --git a/dart/collision/bullet/BulletCollisionDetector.cpp b/dart/collision/bullet/BulletCollisionDetector.cpp index 2a7ab88fd11fd..ccc26eed6d06b 100644 --- a/dart/collision/bullet/BulletCollisionDetector.cpp +++ b/dart/collision/bullet/BulletCollisionDetector.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/bullet/BulletCollisionDetector.h b/dart/collision/bullet/BulletCollisionDetector.h index 225baa77ad427..bc6bc8dcb6e02 100644 --- a/dart/collision/bullet/BulletCollisionDetector.h +++ b/dart/collision/bullet/BulletCollisionDetector.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/bullet/BulletTypes.cpp b/dart/collision/bullet/BulletTypes.cpp index ab57cd7d69500..1a59d161c0f58 100644 --- a/dart/collision/bullet/BulletTypes.cpp +++ b/dart/collision/bullet/BulletTypes.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/bullet/BulletTypes.h b/dart/collision/bullet/BulletTypes.h index 51354f8b2dfbd..81ab464779d39 100644 --- a/dart/collision/bullet/BulletTypes.h +++ b/dart/collision/bullet/BulletTypes.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/dart/DARTCollide.cpp b/dart/collision/dart/DARTCollide.cpp index 7e453ad2f5a92..ed9944bae2a93 100644 --- a/dart/collision/dart/DARTCollide.cpp +++ b/dart/collision/dart/DARTCollide.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/dart/DARTCollide.h b/dart/collision/dart/DARTCollide.h index 06ce1fb279cec..9e903d3d9d636 100644 --- a/dart/collision/dart/DARTCollide.h +++ b/dart/collision/dart/DARTCollide.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/dart/DARTCollisionDetector.cpp b/dart/collision/dart/DARTCollisionDetector.cpp index fa9590bf0ecab..5b90e0b1434c0 100644 --- a/dart/collision/dart/DARTCollisionDetector.cpp +++ b/dart/collision/dart/DARTCollisionDetector.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/dart/DARTCollisionDetector.h b/dart/collision/dart/DARTCollisionDetector.h index 5c661d73a667e..6c5f4750675dd 100644 --- a/dart/collision/dart/DARTCollisionDetector.h +++ b/dart/collision/dart/DARTCollisionDetector.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/fcl/CollisionShapes.h b/dart/collision/fcl/CollisionShapes.h index 0635439352e7c..7a4c33f7ccfb3 100644 --- a/dart/collision/fcl/CollisionShapes.h +++ b/dart/collision/fcl/CollisionShapes.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Chen Tang diff --git a/dart/collision/fcl/FCLCollisionDetector.cpp b/dart/collision/fcl/FCLCollisionDetector.cpp index 047bc8dcd763b..18a634c2e833c 100644 --- a/dart/collision/fcl/FCLCollisionDetector.cpp +++ b/dart/collision/fcl/FCLCollisionDetector.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Chen Tang , diff --git a/dart/collision/fcl/FCLCollisionDetector.h b/dart/collision/fcl/FCLCollisionDetector.h index 60495d24dfe00..dbfce62fabb29 100644 --- a/dart/collision/fcl/FCLCollisionDetector.h +++ b/dart/collision/fcl/FCLCollisionDetector.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Chen Tang , diff --git a/dart/collision/fcl/FCLTypes.cpp b/dart/collision/fcl/FCLTypes.cpp index 681ff0b178a55..bd2883fb3372a 100644 --- a/dart/collision/fcl/FCLTypes.cpp +++ b/dart/collision/fcl/FCLTypes.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/fcl/FCLTypes.h b/dart/collision/fcl/FCLTypes.h index d901b2b41cdf6..49b5adc625689 100644 --- a/dart/collision/fcl/FCLTypes.h +++ b/dart/collision/fcl/FCLTypes.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/collision/fcl/tri_tri_intersection_test.h b/dart/collision/fcl/tri_tri_intersection_test.h index 8af674824cb68..5599436567be2 100644 --- a/dart/collision/fcl/tri_tri_intersection_test.h +++ b/dart/collision/fcl/tri_tri_intersection_test.h @@ -1,6 +1,41 @@ -#ifndef _TRI_TRI_INTERSECTION_TEST_ -#define _TRI_TRI_INTERSECTION_TEST_ - +/* + * Copyright (c) 2011-2016, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Karen Liu + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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. + */ + +#ifndef DART_COLLISION_TRITRIINTERSECTIONTEST_H_ +#define DART_COLLISION_TRITRIINTERSECTIONTEST_H_ #include @@ -293,7 +328,4 @@ inline int tri_tri_intersect(float V0[3],float V1[3],float V2[3], return 1; } - - - -#endif +#endif // DART_COLLISION_TRITRIINTERSECTIONTEST_H_ diff --git a/dart/common/Aspect.cpp b/dart/common/Aspect.cpp index 113349a730ca0..10b52f407b390 100644 --- a/dart/common/Aspect.cpp +++ b/dart/common/Aspect.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Aspect.h b/dart/common/Aspect.h index 712e2ddc9dd6b..06ca51c7ba21a 100644 --- a/dart/common/Aspect.h +++ b/dart/common/Aspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Cloneable.h b/dart/common/Cloneable.h index b330db55fb8a3..aaeb72c7c654b 100644 --- a/dart/common/Cloneable.h +++ b/dart/common/Cloneable.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Composite.cpp b/dart/common/Composite.cpp index c55f02b4d9cff..32dcdc371059c 100644 --- a/dart/common/Composite.cpp +++ b/dart/common/Composite.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Composite.h b/dart/common/Composite.h index 7116a8c7a83ca..cb737602ec0e6 100644 --- a/dart/common/Composite.h +++ b/dart/common/Composite.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/CompositeJoiner.h b/dart/common/CompositeJoiner.h index 45d6f828f30a2..2fcf439b1237f 100644 --- a/dart/common/CompositeJoiner.h +++ b/dart/common/CompositeJoiner.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Console.cpp b/dart/common/Console.cpp index 21d46b622e666..fa3849ba5913e 100644 --- a/dart/common/Console.cpp +++ b/dart/common/Console.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain , diff --git a/dart/common/Console.h b/dart/common/Console.h index bb9e4271a0a48..53d6c7087ca43 100644 --- a/dart/common/Console.h +++ b/dart/common/Console.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain , diff --git a/dart/common/Deprecated.h b/dart/common/Deprecated.h index 263103485b6d2..21f64c46df88b 100644 --- a/dart/common/Deprecated.h +++ b/dart/common/Deprecated.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/common/Empty.h b/dart/common/Empty.h index 8c9eedf20573a..05245cdfbb22a 100644 --- a/dart/common/Empty.h +++ b/dart/common/Empty.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/LocalResource.cpp b/dart/common/LocalResource.cpp index 5d39fd94506c8..99df39378100c 100644 --- a/dart/common/LocalResource.cpp +++ b/dart/common/LocalResource.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/common/LocalResource.h b/dart/common/LocalResource.h index 58729141240a3..276f87ea388b8 100644 --- a/dart/common/LocalResource.h +++ b/dart/common/LocalResource.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/common/LocalResourceRetriever.cpp b/dart/common/LocalResourceRetriever.cpp index 351903c293989..198cb396fdf17 100644 --- a/dart/common/LocalResourceRetriever.cpp +++ b/dart/common/LocalResourceRetriever.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/common/LocalResourceRetriever.h b/dart/common/LocalResourceRetriever.h index 1b8aecacf8a6c..f8196af213e8b 100644 --- a/dart/common/LocalResourceRetriever.h +++ b/dart/common/LocalResourceRetriever.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/common/Memory.h b/dart/common/Memory.h index d96cf6a024f57..1295488031df1 100644 --- a/dart/common/Memory.h +++ b/dart/common/Memory.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/common/NameManager.h b/dart/common/NameManager.h index c2c12ae079b34..cb368da7b836e 100644 --- a/dart/common/NameManager.h +++ b/dart/common/NameManager.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee , diff --git a/dart/common/Observer.cpp b/dart/common/Observer.cpp index bc831e4048b5a..7584b1794a118 100644 --- a/dart/common/Observer.cpp +++ b/dart/common/Observer.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Observer.h b/dart/common/Observer.h index a36bc2bb33099..9fc612a3d0c0d 100644 --- a/dart/common/Observer.h +++ b/dart/common/Observer.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Resource.h b/dart/common/Resource.h index 960e3b512ecb9..47000f3d0a2b1 100644 --- a/dart/common/Resource.h +++ b/dart/common/Resource.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/common/ResourceRetriever.h b/dart/common/ResourceRetriever.h index 7836e82f693f9..203f7203211ce 100644 --- a/dart/common/ResourceRetriever.h +++ b/dart/common/ResourceRetriever.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/common/Signal.cpp b/dart/common/Signal.cpp index 3931ce565696e..87cae61c721f4 100644 --- a/dart/common/Signal.cpp +++ b/dart/common/Signal.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/common/Signal.h b/dart/common/Signal.h index 8125865da990f..cefb78b60f3d4 100644 --- a/dart/common/Signal.h +++ b/dart/common/Signal.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/common/SpecializedForAspect.h b/dart/common/SpecializedForAspect.h index c4dddf451a207..6e4ce38a297cd 100644 --- a/dart/common/SpecializedForAspect.h +++ b/dart/common/SpecializedForAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Subject.cpp b/dart/common/Subject.cpp index 16fe435fc3141..8c85e65acb092 100644 --- a/dart/common/Subject.cpp +++ b/dart/common/Subject.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Subject.h b/dart/common/Subject.h index 9338713713f84..d8cf62033a1e1 100644 --- a/dart/common/Subject.h +++ b/dart/common/Subject.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/Timer.cpp b/dart/common/Timer.cpp index bd96d21609353..6a11be131a533 100644 --- a/dart/common/Timer.cpp +++ b/dart/common/Timer.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/common/Timer.h b/dart/common/Timer.h index e482f28c72a48..40e3792daeeb6 100644 --- a/dart/common/Timer.h +++ b/dart/common/Timer.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/common/Uri.cpp b/dart/common/Uri.cpp index df22c6027c181..80ee728d37af4 100644 --- a/dart/common/Uri.cpp +++ b/dart/common/Uri.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/common/Uri.h b/dart/common/Uri.h index e277b29270ffd..259a2a1508443 100644 --- a/dart/common/Uri.h +++ b/dart/common/Uri.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/common/Virtual.h b/dart/common/Virtual.h index c2ea57916f4b5..e4ccb4e944eff 100644 --- a/dart/common/Virtual.h +++ b/dart/common/Virtual.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/detail/Aspect.h b/dart/common/detail/Aspect.h index a0381b99086b6..65d52910ff71c 100644 --- a/dart/common/detail/Aspect.h +++ b/dart/common/detail/Aspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/detail/Cloneable.h b/dart/common/detail/Cloneable.h index 9236ce7c27e68..a2662fb0b4151 100644 --- a/dart/common/detail/Cloneable.h +++ b/dart/common/detail/Cloneable.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/detail/Composite.h b/dart/common/detail/Composite.h index f34b527e0fd9f..ccd81c06fcfd0 100644 --- a/dart/common/detail/Composite.h +++ b/dart/common/detail/Composite.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/detail/CompositeJoiner.h b/dart/common/detail/CompositeJoiner.h index dd9face3f8872..6ac31526be29d 100644 --- a/dart/common/detail/CompositeJoiner.h +++ b/dart/common/detail/CompositeJoiner.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/detail/ConnectionBody.cpp b/dart/common/detail/ConnectionBody.cpp index 4d57f79012051..77ffb2d35f8cb 100644 --- a/dart/common/detail/ConnectionBody.cpp +++ b/dart/common/detail/ConnectionBody.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/common/detail/ConnectionBody.h b/dart/common/detail/ConnectionBody.h index 5ee8b27ab6431..8615f8579bb25 100644 --- a/dart/common/detail/ConnectionBody.h +++ b/dart/common/detail/ConnectionBody.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/common/detail/NameManager.h b/dart/common/detail/NameManager.h index 0e55febebb23b..e2b2bab769dd9 100644 --- a/dart/common/detail/NameManager.h +++ b/dart/common/detail/NameManager.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee , diff --git a/dart/common/detail/NoOp.h b/dart/common/detail/NoOp.h index b71d48e836a98..9b0e7109d50da 100644 --- a/dart/common/detail/NoOp.h +++ b/dart/common/detail/NoOp.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/detail/Signal.h b/dart/common/detail/Signal.h index 00d86f70c24e6..a63e1361864aa 100644 --- a/dart/common/detail/Signal.h +++ b/dart/common/detail/Signal.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/common/detail/SpecializedForAspect.h b/dart/common/detail/SpecializedForAspect.h index bd0c7fdf2a5d4..452c157a97010 100644 --- a/dart/common/detail/SpecializedForAspect.h +++ b/dart/common/detail/SpecializedForAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/detail/sub_ptr.h b/dart/common/detail/sub_ptr.h index 488a51ef38157..8761e6d6a9913 100644 --- a/dart/common/detail/sub_ptr.h +++ b/dart/common/detail/sub_ptr.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/common/sub_ptr.h b/dart/common/sub_ptr.h index e4efadc24967b..c32bc4cca0d90 100644 --- a/dart/common/sub_ptr.h +++ b/dart/common/sub_ptr.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/constraint/BalanceConstraint.cpp b/dart/constraint/BalanceConstraint.cpp index 30f4f5bb5a8bc..3dd2db9c83b08 100644 --- a/dart/constraint/BalanceConstraint.cpp +++ b/dart/constraint/BalanceConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/constraint/BalanceConstraint.h b/dart/constraint/BalanceConstraint.h index 49b6afe81239f..2a6180b57f833 100644 --- a/dart/constraint/BalanceConstraint.h +++ b/dart/constraint/BalanceConstraint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/constraint/BallJointConstraint.cpp b/dart/constraint/BallJointConstraint.cpp index ce3c6981a0371..190bd853d98a8 100644 --- a/dart/constraint/BallJointConstraint.cpp +++ b/dart/constraint/BallJointConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/BallJointConstraint.h b/dart/constraint/BallJointConstraint.h index 91434e952f12b..bca05ea45c29b 100644 --- a/dart/constraint/BallJointConstraint.h +++ b/dart/constraint/BallJointConstraint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ConstrainedGroup.cpp b/dart/constraint/ConstrainedGroup.cpp index e294a3c07780f..79d72052517b4 100644 --- a/dart/constraint/ConstrainedGroup.cpp +++ b/dart/constraint/ConstrainedGroup.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ConstrainedGroup.h b/dart/constraint/ConstrainedGroup.h index 50a23a387f3db..4c736d133f450 100644 --- a/dart/constraint/ConstrainedGroup.h +++ b/dart/constraint/ConstrainedGroup.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ConstraintBase.cpp b/dart/constraint/ConstraintBase.cpp index 03268140439af..15085acd69695 100644 --- a/dart/constraint/ConstraintBase.cpp +++ b/dart/constraint/ConstraintBase.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ConstraintBase.h b/dart/constraint/ConstraintBase.h index 2d96fd54a845c..c063f13856609 100644 --- a/dart/constraint/ConstraintBase.h +++ b/dart/constraint/ConstraintBase.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ConstraintSolver.cpp b/dart/constraint/ConstraintSolver.cpp index 0ba8b795b35f2..e4f666722e652 100644 --- a/dart/constraint/ConstraintSolver.cpp +++ b/dart/constraint/ConstraintSolver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ConstraintSolver.h b/dart/constraint/ConstraintSolver.h index 19b92bf2129ee..746056132f7f5 100644 --- a/dart/constraint/ConstraintSolver.h +++ b/dart/constraint/ConstraintSolver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ContactConstraint.cpp b/dart/constraint/ContactConstraint.cpp index 960a195fc853e..6b8797d8a5144 100644 --- a/dart/constraint/ContactConstraint.cpp +++ b/dart/constraint/ContactConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ContactConstraint.h b/dart/constraint/ContactConstraint.h index 1b17d627d6d56..fcb6b1f491d4d 100644 --- a/dart/constraint/ContactConstraint.h +++ b/dart/constraint/ContactConstraint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/DantzigLCPSolver.cpp b/dart/constraint/DantzigLCPSolver.cpp index c16e3755b5238..d0972eb5d106c 100644 --- a/dart/constraint/DantzigLCPSolver.cpp +++ b/dart/constraint/DantzigLCPSolver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/DantzigLCPSolver.h b/dart/constraint/DantzigLCPSolver.h index e434b7bbd886d..5595a1b271599 100644 --- a/dart/constraint/DantzigLCPSolver.h +++ b/dart/constraint/DantzigLCPSolver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/JointConstraint.cpp b/dart/constraint/JointConstraint.cpp index c0bbce7feeeef..fcd134acfaaf1 100644 --- a/dart/constraint/JointConstraint.cpp +++ b/dart/constraint/JointConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/JointConstraint.h b/dart/constraint/JointConstraint.h index d93fc1f12a771..24d5b31513d36 100644 --- a/dart/constraint/JointConstraint.h +++ b/dart/constraint/JointConstraint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/JointCoulombFrictionConstraint.cpp b/dart/constraint/JointCoulombFrictionConstraint.cpp index 9234143ab9928..c5aa3469877dd 100644 --- a/dart/constraint/JointCoulombFrictionConstraint.cpp +++ b/dart/constraint/JointCoulombFrictionConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/JointCoulombFrictionConstraint.h b/dart/constraint/JointCoulombFrictionConstraint.h index 5c2ba6b5e0497..8d481b929fc1e 100644 --- a/dart/constraint/JointCoulombFrictionConstraint.h +++ b/dart/constraint/JointCoulombFrictionConstraint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/JointLimitConstraint.cpp b/dart/constraint/JointLimitConstraint.cpp index 802138dfa94c0..6ed396df609a2 100644 --- a/dart/constraint/JointLimitConstraint.cpp +++ b/dart/constraint/JointLimitConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/JointLimitConstraint.h b/dart/constraint/JointLimitConstraint.h index 88cefcf3c7f41..8a4721f209d4b 100644 --- a/dart/constraint/JointLimitConstraint.h +++ b/dart/constraint/JointLimitConstraint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/LCPSolver.cpp b/dart/constraint/LCPSolver.cpp index 0d9cbb0069e6f..4171335e0f963 100644 --- a/dart/constraint/LCPSolver.cpp +++ b/dart/constraint/LCPSolver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/LCPSolver.h b/dart/constraint/LCPSolver.h index 9e7da5ae8a9cf..af051baec4f84 100644 --- a/dart/constraint/LCPSolver.h +++ b/dart/constraint/LCPSolver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/PGSLCPSolver.cpp b/dart/constraint/PGSLCPSolver.cpp index 11128f7061f9a..1f9530ed2931d 100644 --- a/dart/constraint/PGSLCPSolver.cpp +++ b/dart/constraint/PGSLCPSolver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/PGSLCPSolver.h b/dart/constraint/PGSLCPSolver.h index 9b6229d4d2ca2..6e65ee24380d4 100644 --- a/dart/constraint/PGSLCPSolver.h +++ b/dart/constraint/PGSLCPSolver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ServoMotorConstraint.cpp b/dart/constraint/ServoMotorConstraint.cpp index 6f8aea62a296c..fabec0e26b690 100644 --- a/dart/constraint/ServoMotorConstraint.cpp +++ b/dart/constraint/ServoMotorConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/ServoMotorConstraint.h b/dart/constraint/ServoMotorConstraint.h index f23e73b820d95..cea5b5e90b3b0 100644 --- a/dart/constraint/ServoMotorConstraint.h +++ b/dart/constraint/ServoMotorConstraint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/SoftContactConstraint.cpp b/dart/constraint/SoftContactConstraint.cpp index 4facef794a1ab..0bf2c25b8f6ea 100644 --- a/dart/constraint/SoftContactConstraint.cpp +++ b/dart/constraint/SoftContactConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/SoftContactConstraint.h b/dart/constraint/SoftContactConstraint.h index c17f96d3b5bd2..d490b7b79edc8 100644 --- a/dart/constraint/SoftContactConstraint.h +++ b/dart/constraint/SoftContactConstraint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/WeldJointConstraint.cpp b/dart/constraint/WeldJointConstraint.cpp index ce28116605742..5419659ff8439 100644 --- a/dart/constraint/WeldJointConstraint.cpp +++ b/dart/constraint/WeldJointConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/constraint/WeldJointConstraint.h b/dart/constraint/WeldJointConstraint.h index dedba61548f3c..fb6a952bb0964 100644 --- a/dart/constraint/WeldJointConstraint.h +++ b/dart/constraint/WeldJointConstraint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dart.h b/dart/dart.h index 75759b40a196a..36b42b2e65ca0 100644 --- a/dart/dart.h +++ b/dart/dart.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/ArrowShape.cpp b/dart/dynamics/ArrowShape.cpp index 5eec8a39902ea..f8d43453d44a2 100644 --- a/dart/dynamics/ArrowShape.cpp +++ b/dart/dynamics/ArrowShape.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/ArrowShape.h b/dart/dynamics/ArrowShape.h index b17d1c34c6679..ba351900e2377 100644 --- a/dart/dynamics/ArrowShape.h +++ b/dart/dynamics/ArrowShape.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/AssimpInputResourceAdaptor.cpp b/dart/dynamics/AssimpInputResourceAdaptor.cpp index 49bb0094b9548..c665fc0ce3783 100644 --- a/dart/dynamics/AssimpInputResourceAdaptor.cpp +++ b/dart/dynamics/AssimpInputResourceAdaptor.cpp @@ -1,3 +1,39 @@ +/* + * Copyright (c) 2015-2016, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Michael Koval + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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. + */ + #include #include #include diff --git a/dart/dynamics/AssimpInputResourceAdaptor.h b/dart/dynamics/AssimpInputResourceAdaptor.h index 7ca786461e560..bff110ac5a302 100644 --- a/dart/dynamics/AssimpInputResourceAdaptor.h +++ b/dart/dynamics/AssimpInputResourceAdaptor.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/dynamics/BallJoint.cpp b/dart/dynamics/BallJoint.cpp index d2c72061b3b6f..1a7481b6446e6 100644 --- a/dart/dynamics/BallJoint.cpp +++ b/dart/dynamics/BallJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/BallJoint.h b/dart/dynamics/BallJoint.h index 46bcd2f37d76a..fd2475afb2a76 100644 --- a/dart/dynamics/BallJoint.h +++ b/dart/dynamics/BallJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/BodyNode.cpp b/dart/dynamics/BodyNode.cpp index c91cd39fda42e..5882a3569e210 100644 --- a/dart/dynamics/BodyNode.cpp +++ b/dart/dynamics/BodyNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/dynamics/BodyNode.h b/dart/dynamics/BodyNode.h index b3f770b6b0fc8..df0d52db79194 100644 --- a/dart/dynamics/BodyNode.h +++ b/dart/dynamics/BodyNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/BoxShape.cpp b/dart/dynamics/BoxShape.cpp index 1a5a5d20026a7..9107324c7b874 100644 --- a/dart/dynamics/BoxShape.cpp +++ b/dart/dynamics/BoxShape.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/BoxShape.h b/dart/dynamics/BoxShape.h index 8e5b8cec2c36a..3c87c90fac5fa 100644 --- a/dart/dynamics/BoxShape.h +++ b/dart/dynamics/BoxShape.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/Branch.cpp b/dart/dynamics/Branch.cpp index 579d4902ef561..357a397fcb904 100644 --- a/dart/dynamics/Branch.cpp +++ b/dart/dynamics/Branch.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Branch.h b/dart/dynamics/Branch.h index 969bf85fcd3c8..308f79d21808a 100644 --- a/dart/dynamics/Branch.h +++ b/dart/dynamics/Branch.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Chain.cpp b/dart/dynamics/Chain.cpp index 928e4170c2dbb..12c5ee0d7bbd9 100644 --- a/dart/dynamics/Chain.cpp +++ b/dart/dynamics/Chain.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Chain.h b/dart/dynamics/Chain.h index 7a13cf951fa7a..56381f546bb75 100644 --- a/dart/dynamics/Chain.h +++ b/dart/dynamics/Chain.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/CylinderShape.cpp b/dart/dynamics/CylinderShape.cpp index 6526e3c95e967..e6d9ed25f5808 100644 --- a/dart/dynamics/CylinderShape.cpp +++ b/dart/dynamics/CylinderShape.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Tobias Kunz diff --git a/dart/dynamics/CylinderShape.h b/dart/dynamics/CylinderShape.h index 4e502e957c11b..0b03ab882b76b 100644 --- a/dart/dynamics/CylinderShape.h +++ b/dart/dynamics/CylinderShape.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Tobias Kunz diff --git a/dart/dynamics/DegreeOfFreedom.cpp b/dart/dynamics/DegreeOfFreedom.cpp index f9383594f740c..03546c18a36fd 100644 --- a/dart/dynamics/DegreeOfFreedom.cpp +++ b/dart/dynamics/DegreeOfFreedom.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/DegreeOfFreedom.h b/dart/dynamics/DegreeOfFreedom.h index a7df00b4f0dad..e72035d4b18b3 100644 --- a/dart/dynamics/DegreeOfFreedom.h +++ b/dart/dynamics/DegreeOfFreedom.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/EllipsoidShape.cpp b/dart/dynamics/EllipsoidShape.cpp index 59ebf7de41786..eeed6443a36a0 100644 --- a/dart/dynamics/EllipsoidShape.cpp +++ b/dart/dynamics/EllipsoidShape.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/EllipsoidShape.h b/dart/dynamics/EllipsoidShape.h index b77e3bf01def9..a2039b489ab86 100644 --- a/dart/dynamics/EllipsoidShape.h +++ b/dart/dynamics/EllipsoidShape.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/EndEffector.cpp b/dart/dynamics/EndEffector.cpp index 6f2201ceec819..1eb7d37c42f95 100644 --- a/dart/dynamics/EndEffector.cpp +++ b/dart/dynamics/EndEffector.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/EndEffector.h b/dart/dynamics/EndEffector.h index be94396ddeaf2..190487e8c9d24 100644 --- a/dart/dynamics/EndEffector.h +++ b/dart/dynamics/EndEffector.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Entity.cpp b/dart/dynamics/Entity.cpp index aba230ca6957a..7970245cb31b0 100644 --- a/dart/dynamics/Entity.cpp +++ b/dart/dynamics/Entity.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Entity.h b/dart/dynamics/Entity.h index 9179a7658cf17..3e42e884c6cc9 100644 --- a/dart/dynamics/Entity.h +++ b/dart/dynamics/Entity.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/EulerJoint.cpp b/dart/dynamics/EulerJoint.cpp index d653dd363b7ab..4a0a3f8911a24 100644 --- a/dart/dynamics/EulerJoint.cpp +++ b/dart/dynamics/EulerJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/EulerJoint.h b/dart/dynamics/EulerJoint.h index 30d355a7917ac..74664b652b2b9 100644 --- a/dart/dynamics/EulerJoint.h +++ b/dart/dynamics/EulerJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/FixedFrame.cpp b/dart/dynamics/FixedFrame.cpp index 9d558950a8f78..6345d0b431aed 100644 --- a/dart/dynamics/FixedFrame.cpp +++ b/dart/dynamics/FixedFrame.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/FixedFrame.h b/dart/dynamics/FixedFrame.h index 9a8a582df99d9..ab4358da42781 100644 --- a/dart/dynamics/FixedFrame.h +++ b/dart/dynamics/FixedFrame.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Frame.cpp b/dart/dynamics/Frame.cpp index 5978b2e4d527d..244bdec6bbe64 100644 --- a/dart/dynamics/Frame.cpp +++ b/dart/dynamics/Frame.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Frame.h b/dart/dynamics/Frame.h index f3f2738a2bb17..4bfadb683c9d1 100644 --- a/dart/dynamics/Frame.h +++ b/dart/dynamics/Frame.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/FreeJoint.cpp b/dart/dynamics/FreeJoint.cpp index a3dfcf053002b..8e74af8fdd5d2 100644 --- a/dart/dynamics/FreeJoint.cpp +++ b/dart/dynamics/FreeJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/FreeJoint.h b/dart/dynamics/FreeJoint.h index dc1287f8c09e5..50c2cc685ebf9 100644 --- a/dart/dynamics/FreeJoint.h +++ b/dart/dynamics/FreeJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/Group.cpp b/dart/dynamics/Group.cpp index 9572220a93961..37e0f33a6c3d4 100644 --- a/dart/dynamics/Group.cpp +++ b/dart/dynamics/Group.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Group.h b/dart/dynamics/Group.h index a2f90da5283c6..41da9db5096ee 100644 --- a/dart/dynamics/Group.h +++ b/dart/dynamics/Group.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/HierarchicalIK.cpp b/dart/dynamics/HierarchicalIK.cpp index 2dfa618633f89..ab8e269b5076c 100644 --- a/dart/dynamics/HierarchicalIK.cpp +++ b/dart/dynamics/HierarchicalIK.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/HierarchicalIK.h b/dart/dynamics/HierarchicalIK.h index 4b2bb6a8e144a..85bf9f071ef50 100644 --- a/dart/dynamics/HierarchicalIK.h +++ b/dart/dynamics/HierarchicalIK.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Inertia.cpp b/dart/dynamics/Inertia.cpp index f6210a8c3c6a8..0bbd1bc47e390 100644 --- a/dart/dynamics/Inertia.cpp +++ b/dart/dynamics/Inertia.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Inertia.h b/dart/dynamics/Inertia.h index 32987e47550ef..92f43856786d1 100644 --- a/dart/dynamics/Inertia.h +++ b/dart/dynamics/Inertia.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/InvalidIndex.h b/dart/dynamics/InvalidIndex.h index d5b42b86f2358..6d7df702a74c2 100644 --- a/dart/dynamics/InvalidIndex.h +++ b/dart/dynamics/InvalidIndex.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/InverseKinematics.cpp b/dart/dynamics/InverseKinematics.cpp index 1b0e3f7e04ee4..3ca8f49dd2587 100644 --- a/dart/dynamics/InverseKinematics.cpp +++ b/dart/dynamics/InverseKinematics.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/InverseKinematics.h b/dart/dynamics/InverseKinematics.h index d68552987bb41..c1ddeb24aaef9 100644 --- a/dart/dynamics/InverseKinematics.h +++ b/dart/dynamics/InverseKinematics.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/JacobianNode.cpp b/dart/dynamics/JacobianNode.cpp index 8be5a1eccb368..2d862a34f6dde 100644 --- a/dart/dynamics/JacobianNode.cpp +++ b/dart/dynamics/JacobianNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/JacobianNode.h b/dart/dynamics/JacobianNode.h index d238362ddfcc0..c96036c588471 100644 --- a/dart/dynamics/JacobianNode.h +++ b/dart/dynamics/JacobianNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Joint.cpp b/dart/dynamics/Joint.cpp index 43f972fbe709c..a10e2d46e09ba 100644 --- a/dart/dynamics/Joint.cpp +++ b/dart/dynamics/Joint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/Joint.h b/dart/dynamics/Joint.h index 0145c9c27521d..5eb9a59cd3a86 100644 --- a/dart/dynamics/Joint.h +++ b/dart/dynamics/Joint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/dynamics/LineSegmentShape.cpp b/dart/dynamics/LineSegmentShape.cpp index 67f489716bbde..6588047a7bfd0 100644 --- a/dart/dynamics/LineSegmentShape.cpp +++ b/dart/dynamics/LineSegmentShape.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/LineSegmentShape.h b/dart/dynamics/LineSegmentShape.h index 5cd4e40577712..860c29b268453 100644 --- a/dart/dynamics/LineSegmentShape.h +++ b/dart/dynamics/LineSegmentShape.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Linkage.cpp b/dart/dynamics/Linkage.cpp index 18b2f83781a54..c2ef589a46711 100644 --- a/dart/dynamics/Linkage.cpp +++ b/dart/dynamics/Linkage.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Linkage.h b/dart/dynamics/Linkage.h index da248e47d6a82..2d6473d77fa25 100644 --- a/dart/dynamics/Linkage.h +++ b/dart/dynamics/Linkage.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Marker.cpp b/dart/dynamics/Marker.cpp index 2c3c8f23ae3cf..c01b8966b7efa 100644 --- a/dart/dynamics/Marker.cpp +++ b/dart/dynamics/Marker.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/dynamics/Marker.h b/dart/dynamics/Marker.h index 58a67b9b49d11..97f261000f54c 100644 --- a/dart/dynamics/Marker.h +++ b/dart/dynamics/Marker.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/dynamics/MeshShape.cpp b/dart/dynamics/MeshShape.cpp index ca102df1ebe21..14d8ac7ab970d 100644 --- a/dart/dynamics/MeshShape.cpp +++ b/dart/dynamics/MeshShape.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): diff --git a/dart/dynamics/MeshShape.h b/dart/dynamics/MeshShape.h index 50b9c0d8927c5..dcaa896121d88 100644 --- a/dart/dynamics/MeshShape.h +++ b/dart/dynamics/MeshShape.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): diff --git a/dart/dynamics/MetaSkeleton.cpp b/dart/dynamics/MetaSkeleton.cpp index 8f3a6ada3d8d5..827a2bcbdf49f 100644 --- a/dart/dynamics/MetaSkeleton.cpp +++ b/dart/dynamics/MetaSkeleton.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/MetaSkeleton.h b/dart/dynamics/MetaSkeleton.h index 53e4aa36fce5c..528ef9a08af0e 100644 --- a/dart/dynamics/MetaSkeleton.h +++ b/dart/dynamics/MetaSkeleton.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/MultiDofJoint.h b/dart/dynamics/MultiDofJoint.h index 05d43b0af4fc0..12ed7d27802e6 100644 --- a/dart/dynamics/MultiDofJoint.h +++ b/dart/dynamics/MultiDofJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/Node.cpp b/dart/dynamics/Node.cpp index 42e264efa8292..27bf29e6ac257 100644 --- a/dart/dynamics/Node.cpp +++ b/dart/dynamics/Node.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/Node.h b/dart/dynamics/Node.h index 763ff0dfd28b4..2d87d4b0c41fd 100644 --- a/dart/dynamics/Node.h +++ b/dart/dynamics/Node.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/PlanarJoint.cpp b/dart/dynamics/PlanarJoint.cpp index fe8ee9c1c4116..65905ffec8546 100644 --- a/dart/dynamics/PlanarJoint.cpp +++ b/dart/dynamics/PlanarJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/PlanarJoint.h b/dart/dynamics/PlanarJoint.h index f5c049307e260..cc6d621a302cd 100644 --- a/dart/dynamics/PlanarJoint.h +++ b/dart/dynamics/PlanarJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/PlaneShape.cpp b/dart/dynamics/PlaneShape.cpp index dca92ca84e3af..19e871a4c9e4b 100644 --- a/dart/dynamics/PlaneShape.cpp +++ b/dart/dynamics/PlaneShape.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/PlaneShape.h b/dart/dynamics/PlaneShape.h index 4966c7a3f7ed5..c4317491d0d7e 100644 --- a/dart/dynamics/PlaneShape.h +++ b/dart/dynamics/PlaneShape.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/PointMass.cpp b/dart/dynamics/PointMass.cpp index 8281b1c3c25f1..2cb2c8a2fe587 100644 --- a/dart/dynamics/PointMass.cpp +++ b/dart/dynamics/PointMass.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/PointMass.h b/dart/dynamics/PointMass.h index 9001132dc322b..2685708347f9e 100644 --- a/dart/dynamics/PointMass.h +++ b/dart/dynamics/PointMass.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/PrismaticJoint.cpp b/dart/dynamics/PrismaticJoint.cpp index a4f5eeafb67b4..099dd9b53f5ed 100644 --- a/dart/dynamics/PrismaticJoint.cpp +++ b/dart/dynamics/PrismaticJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/PrismaticJoint.h b/dart/dynamics/PrismaticJoint.h index b4d041a507c11..8416bdce12242 100644 --- a/dart/dynamics/PrismaticJoint.h +++ b/dart/dynamics/PrismaticJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/ReferentialSkeleton.cpp b/dart/dynamics/ReferentialSkeleton.cpp index 9743a19742d5f..90f96d763d4df 100644 --- a/dart/dynamics/ReferentialSkeleton.cpp +++ b/dart/dynamics/ReferentialSkeleton.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/ReferentialSkeleton.h b/dart/dynamics/ReferentialSkeleton.h index fc69bad483f07..cf7a2a96542a8 100644 --- a/dart/dynamics/ReferentialSkeleton.h +++ b/dart/dynamics/ReferentialSkeleton.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/RevoluteJoint.cpp b/dart/dynamics/RevoluteJoint.cpp index ddd8192018db5..dae6771165ab9 100644 --- a/dart/dynamics/RevoluteJoint.cpp +++ b/dart/dynamics/RevoluteJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/RevoluteJoint.h b/dart/dynamics/RevoluteJoint.h index a916069bdbc71..156e8a72f2505 100644 --- a/dart/dynamics/RevoluteJoint.h +++ b/dart/dynamics/RevoluteJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/ScrewJoint.cpp b/dart/dynamics/ScrewJoint.cpp index de75db5664cbc..cf14ec18fab8e 100644 --- a/dart/dynamics/ScrewJoint.cpp +++ b/dart/dynamics/ScrewJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/ScrewJoint.h b/dart/dynamics/ScrewJoint.h index ec84e69a03e8d..2a1726ba705fd 100644 --- a/dart/dynamics/ScrewJoint.h +++ b/dart/dynamics/ScrewJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/Shape.cpp b/dart/dynamics/Shape.cpp index 104189dae1317..6b1899ef9c9a7 100644 --- a/dart/dynamics/Shape.cpp +++ b/dart/dynamics/Shape.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/Shape.h b/dart/dynamics/Shape.h index 04b6a3f0625f4..5d82fcf649102 100644 --- a/dart/dynamics/Shape.h +++ b/dart/dynamics/Shape.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/SimpleFrame.cpp b/dart/dynamics/SimpleFrame.cpp index b99d6c6ea7720..55c55e1ceb34e 100644 --- a/dart/dynamics/SimpleFrame.cpp +++ b/dart/dynamics/SimpleFrame.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/SimpleFrame.h b/dart/dynamics/SimpleFrame.h index 9338092bf4417..29c9259173d7b 100644 --- a/dart/dynamics/SimpleFrame.h +++ b/dart/dynamics/SimpleFrame.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/SingleDofJoint.cpp b/dart/dynamics/SingleDofJoint.cpp index c1ff570fc875d..16c394e795fb3 100644 --- a/dart/dynamics/SingleDofJoint.cpp +++ b/dart/dynamics/SingleDofJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/SingleDofJoint.h b/dart/dynamics/SingleDofJoint.h index 63436be44da1c..eefd025f2a742 100644 --- a/dart/dynamics/SingleDofJoint.h +++ b/dart/dynamics/SingleDofJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/Skeleton.cpp b/dart/dynamics/Skeleton.cpp index 9d0e28307090e..3c10a6ae9d2fc 100644 --- a/dart/dynamics/Skeleton.cpp +++ b/dart/dynamics/Skeleton.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/Skeleton.h b/dart/dynamics/Skeleton.h index a007f3864147a..328b12bb87ee6 100644 --- a/dart/dynamics/Skeleton.h +++ b/dart/dynamics/Skeleton.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/dynamics/SmartPointer.h b/dart/dynamics/SmartPointer.h index 74dc9bf3b1eee..de62041077f27 100644 --- a/dart/dynamics/SmartPointer.h +++ b/dart/dynamics/SmartPointer.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/SoftBodyNode.cpp b/dart/dynamics/SoftBodyNode.cpp index 23867c95af04c..83842dc89ac43 100644 --- a/dart/dynamics/SoftBodyNode.cpp +++ b/dart/dynamics/SoftBodyNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/SoftBodyNode.h b/dart/dynamics/SoftBodyNode.h index 40fca20374fa6..07ae366a5b413 100644 --- a/dart/dynamics/SoftBodyNode.h +++ b/dart/dynamics/SoftBodyNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/SoftMeshShape.cpp b/dart/dynamics/SoftMeshShape.cpp index 9728a9b0453cf..f6f558c665018 100644 --- a/dart/dynamics/SoftMeshShape.cpp +++ b/dart/dynamics/SoftMeshShape.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/SoftMeshShape.h b/dart/dynamics/SoftMeshShape.h index 6c10cceac0b1b..d2a17469cca8e 100644 --- a/dart/dynamics/SoftMeshShape.h +++ b/dart/dynamics/SoftMeshShape.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/SpecializedNodeManager.h b/dart/dynamics/SpecializedNodeManager.h index db3d21b59f1fa..9c986ae8d20d3 100644 --- a/dart/dynamics/SpecializedNodeManager.h +++ b/dart/dynamics/SpecializedNodeManager.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/TemplatedJacobianNode.h b/dart/dynamics/TemplatedJacobianNode.h index 5e1433e668413..ce860843cbbc0 100644 --- a/dart/dynamics/TemplatedJacobianNode.h +++ b/dart/dynamics/TemplatedJacobianNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/TranslationalJoint.cpp b/dart/dynamics/TranslationalJoint.cpp index 70dbfd9103535..8ad1ae20a5fe8 100644 --- a/dart/dynamics/TranslationalJoint.cpp +++ b/dart/dynamics/TranslationalJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/TranslationalJoint.h b/dart/dynamics/TranslationalJoint.h index 07efe0fc5c410..c2f19b50ccf9b 100644 --- a/dart/dynamics/TranslationalJoint.h +++ b/dart/dynamics/TranslationalJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/UniversalJoint.cpp b/dart/dynamics/UniversalJoint.cpp index 0e03160d94b1a..9112fa0875e1b 100644 --- a/dart/dynamics/UniversalJoint.cpp +++ b/dart/dynamics/UniversalJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/UniversalJoint.h b/dart/dynamics/UniversalJoint.h index 2f00622f93c90..ef9dc6bb9085f 100644 --- a/dart/dynamics/UniversalJoint.h +++ b/dart/dynamics/UniversalJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/WeldJoint.cpp b/dart/dynamics/WeldJoint.cpp index 9abb2ca66d2a8..7bb7f2274f1cc 100644 --- a/dart/dynamics/WeldJoint.cpp +++ b/dart/dynamics/WeldJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/WeldJoint.h b/dart/dynamics/WeldJoint.h index 746cc698c8440..dde3eb0e09943 100644 --- a/dart/dynamics/WeldJoint.h +++ b/dart/dynamics/WeldJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/ZeroDofJoint.cpp b/dart/dynamics/ZeroDofJoint.cpp index 7beadc31046ca..85b40d4140b21 100644 --- a/dart/dynamics/ZeroDofJoint.cpp +++ b/dart/dynamics/ZeroDofJoint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/ZeroDofJoint.h b/dart/dynamics/ZeroDofJoint.h index a587ad5eea316..314d75e11b46e 100644 --- a/dart/dynamics/ZeroDofJoint.h +++ b/dart/dynamics/ZeroDofJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/dynamics/detail/BasicNodeManager.h b/dart/dynamics/detail/BasicNodeManager.h index 51ded235e451b..ecff7b40a38cf 100644 --- a/dart/dynamics/detail/BasicNodeManager.h +++ b/dart/dynamics/detail/BasicNodeManager.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/BodyNode.h b/dart/dynamics/detail/BodyNode.h index b39789d8a6da5..03af89aad5317 100644 --- a/dart/dynamics/detail/BodyNode.h +++ b/dart/dynamics/detail/BodyNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/BodyNodePtr.h b/dart/dynamics/detail/BodyNodePtr.h index de7460c8fc169..d18a706dec741 100644 --- a/dart/dynamics/detail/BodyNodePtr.h +++ b/dart/dynamics/detail/BodyNodePtr.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/DegreeOfFreedomPtr.h b/dart/dynamics/detail/DegreeOfFreedomPtr.h index dc0452fbb8211..406512aac3ea4 100644 --- a/dart/dynamics/detail/DegreeOfFreedomPtr.h +++ b/dart/dynamics/detail/DegreeOfFreedomPtr.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/EulerJointAspect.cpp b/dart/dynamics/detail/EulerJointAspect.cpp index 81fc06e332a55..4b50b0a1d8572 100644 --- a/dart/dynamics/detail/EulerJointAspect.cpp +++ b/dart/dynamics/detail/EulerJointAspect.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/EulerJointAspect.h b/dart/dynamics/detail/EulerJointAspect.h index cb5c5f6379664..00043a5d98ecd 100644 --- a/dart/dynamics/detail/EulerJointAspect.h +++ b/dart/dynamics/detail/EulerJointAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/InverseKinematics.h b/dart/dynamics/detail/InverseKinematics.h index ea72fc28fad21..b5354001cce39 100644 --- a/dart/dynamics/detail/InverseKinematics.h +++ b/dart/dynamics/detail/InverseKinematics.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/InverseKinematicsPtr.h b/dart/dynamics/detail/InverseKinematicsPtr.h index d9866c778c470..0509ec205d850 100644 --- a/dart/dynamics/detail/InverseKinematicsPtr.h +++ b/dart/dynamics/detail/InverseKinematicsPtr.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/JointPtr.h b/dart/dynamics/detail/JointPtr.h index d9a71956f1098..8870351f59477 100644 --- a/dart/dynamics/detail/JointPtr.h +++ b/dart/dynamics/detail/JointPtr.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/MultiDofJoint.h b/dart/dynamics/detail/MultiDofJoint.h index fb22acc2c09d2..3c048f73575e9 100644 --- a/dart/dynamics/detail/MultiDofJoint.h +++ b/dart/dynamics/detail/MultiDofJoint.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/MultiDofJointAspect.h b/dart/dynamics/detail/MultiDofJointAspect.h index 44d1962283054..f1be847fa5fd0 100644 --- a/dart/dynamics/detail/MultiDofJointAspect.h +++ b/dart/dynamics/detail/MultiDofJointAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/Node.h b/dart/dynamics/detail/Node.h index a3723fbd80ac7..2bd2f9a2feda2 100644 --- a/dart/dynamics/detail/Node.h +++ b/dart/dynamics/detail/Node.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/NodePtr.h b/dart/dynamics/detail/NodePtr.h index d489cdecd61b6..e5c782b560ecb 100644 --- a/dart/dynamics/detail/NodePtr.h +++ b/dart/dynamics/detail/NodePtr.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/PlanarJointAspect.cpp b/dart/dynamics/detail/PlanarJointAspect.cpp index bb170e2d5209a..fe2d56615ab33 100644 --- a/dart/dynamics/detail/PlanarJointAspect.cpp +++ b/dart/dynamics/detail/PlanarJointAspect.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/PlanarJointAspect.h b/dart/dynamics/detail/PlanarJointAspect.h index ce067f865c1bc..7cb8c8c51ab4d 100644 --- a/dart/dynamics/detail/PlanarJointAspect.h +++ b/dart/dynamics/detail/PlanarJointAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/PrismaticJointAspect.cpp b/dart/dynamics/detail/PrismaticJointAspect.cpp index 667f155eec1f7..99a3fd5de9d61 100644 --- a/dart/dynamics/detail/PrismaticJointAspect.cpp +++ b/dart/dynamics/detail/PrismaticJointAspect.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/PrismaticJointAspect.h b/dart/dynamics/detail/PrismaticJointAspect.h index 292a1eb6800d7..0efcb7ab8e960 100644 --- a/dart/dynamics/detail/PrismaticJointAspect.h +++ b/dart/dynamics/detail/PrismaticJointAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/RevoluteJointAspect.cpp b/dart/dynamics/detail/RevoluteJointAspect.cpp index 59de65ac26741..6c52890c4a771 100644 --- a/dart/dynamics/detail/RevoluteJointAspect.cpp +++ b/dart/dynamics/detail/RevoluteJointAspect.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/RevoluteJointAspect.h b/dart/dynamics/detail/RevoluteJointAspect.h index 9daa10482bf2d..dd6a9b3490c4e 100644 --- a/dart/dynamics/detail/RevoluteJointAspect.h +++ b/dart/dynamics/detail/RevoluteJointAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/ScrewJointAspect.cpp b/dart/dynamics/detail/ScrewJointAspect.cpp index 9292f236b64ea..8381bc947898e 100644 --- a/dart/dynamics/detail/ScrewJointAspect.cpp +++ b/dart/dynamics/detail/ScrewJointAspect.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/ScrewJointAspect.h b/dart/dynamics/detail/ScrewJointAspect.h index 4158d03ae0705..73456fd19859e 100644 --- a/dart/dynamics/detail/ScrewJointAspect.h +++ b/dart/dynamics/detail/ScrewJointAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/SingleDofJointAspect.cpp b/dart/dynamics/detail/SingleDofJointAspect.cpp index 17cb99148eff8..743a6e72eed0d 100644 --- a/dart/dynamics/detail/SingleDofJointAspect.cpp +++ b/dart/dynamics/detail/SingleDofJointAspect.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/SingleDofJointAspect.h b/dart/dynamics/detail/SingleDofJointAspect.h index 8e0935a7a193c..be5d69fdef3dd 100644 --- a/dart/dynamics/detail/SingleDofJointAspect.h +++ b/dart/dynamics/detail/SingleDofJointAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/Skeleton.h b/dart/dynamics/detail/Skeleton.h index 74db73f04ccd9..e97a0784d29fa 100644 --- a/dart/dynamics/detail/Skeleton.h +++ b/dart/dynamics/detail/Skeleton.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/SpecializedNodeManager.h b/dart/dynamics/detail/SpecializedNodeManager.h index 3445e9d7dd2e4..290e18dc36705 100644 --- a/dart/dynamics/detail/SpecializedNodeManager.h +++ b/dart/dynamics/detail/SpecializedNodeManager.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/TemplatedJacobianNode.h b/dart/dynamics/detail/TemplatedJacobianNode.h index f2cff60f404a6..457d5159e2187 100644 --- a/dart/dynamics/detail/TemplatedJacobianNode.h +++ b/dart/dynamics/detail/TemplatedJacobianNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/UniversalJointAspect.cpp b/dart/dynamics/detail/UniversalJointAspect.cpp index e9c348478ce33..d2d55982ab645 100644 --- a/dart/dynamics/detail/UniversalJointAspect.cpp +++ b/dart/dynamics/detail/UniversalJointAspect.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/dynamics/detail/UniversalJointAspect.h b/dart/dynamics/detail/UniversalJointAspect.h index df986a3951662..54f12a6e5034b 100644 --- a/dart/dynamics/detail/UniversalJointAspect.h +++ b/dart/dynamics/detail/UniversalJointAspect.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/GLFuncs.cpp b/dart/gui/GLFuncs.cpp index 0a10c829fb1d4..04f237110066b 100644 --- a/dart/gui/GLFuncs.cpp +++ b/dart/gui/GLFuncs.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/GLFuncs.h b/dart/gui/GLFuncs.h index 09b3dad04b5c8..7defaff944f68 100644 --- a/dart/gui/GLFuncs.h +++ b/dart/gui/GLFuncs.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/GlutWindow.cpp b/dart/gui/GlutWindow.cpp index 8329d6d634971..13b58bfffdb5c 100644 --- a/dart/gui/GlutWindow.cpp +++ b/dart/gui/GlutWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/GlutWindow.h b/dart/gui/GlutWindow.h index b9f9392aba776..e4e15bb06fd27 100644 --- a/dart/gui/GlutWindow.h +++ b/dart/gui/GlutWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/GraphWindow.cpp b/dart/gui/GraphWindow.cpp index 7c3ffa7cd1a21..d786856821c66 100644 --- a/dart/gui/GraphWindow.cpp +++ b/dart/gui/GraphWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/dart/gui/GraphWindow.h b/dart/gui/GraphWindow.h index fa360183c19cb..ded6b9e44a6a3 100644 --- a/dart/gui/GraphWindow.h +++ b/dart/gui/GraphWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/dart/gui/LoadGlut.h b/dart/gui/LoadGlut.h index e21e6cbbff54e..b8c8e0051011a 100644 --- a/dart/gui/LoadGlut.h +++ b/dart/gui/LoadGlut.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongsoek Lee diff --git a/dart/gui/LoadOpengl.h b/dart/gui/LoadOpengl.h index ca0e2e7850870..09d68f47bee90 100644 --- a/dart/gui/LoadOpengl.h +++ b/dart/gui/LoadOpengl.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/gui/OpenGLRenderInterface.cpp b/dart/gui/OpenGLRenderInterface.cpp index 244c91129c8a5..6482293261515 100644 --- a/dart/gui/OpenGLRenderInterface.cpp +++ b/dart/gui/OpenGLRenderInterface.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jie (Jay) Tan diff --git a/dart/gui/OpenGLRenderInterface.h b/dart/gui/OpenGLRenderInterface.h index d775d7baa2049..f3fd494e07449 100644 --- a/dart/gui/OpenGLRenderInterface.h +++ b/dart/gui/OpenGLRenderInterface.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jie (Jay) Tan diff --git a/dart/gui/RenderInterface.cpp b/dart/gui/RenderInterface.cpp index 4ce89d4848617..5e415c00729b9 100644 --- a/dart/gui/RenderInterface.cpp +++ b/dart/gui/RenderInterface.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jie (Jay) Tan diff --git a/dart/gui/RenderInterface.h b/dart/gui/RenderInterface.h index 7602d4039647a..c95acecdf018f 100644 --- a/dart/gui/RenderInterface.h +++ b/dart/gui/RenderInterface.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jie (Jay) Tan diff --git a/dart/gui/SimWindow.cpp b/dart/gui/SimWindow.cpp index 8d20f55458bdc..d3e3f740c3ba7 100644 --- a/dart/gui/SimWindow.cpp +++ b/dart/gui/SimWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/dart/gui/SimWindow.h b/dart/gui/SimWindow.h index b3b072f7c64ab..5906fc55b9ef2 100644 --- a/dart/gui/SimWindow.h +++ b/dart/gui/SimWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/dart/gui/SoftSimWindow.cpp b/dart/gui/SoftSimWindow.cpp index 6d6b2c7a9691c..554030768b4f1 100644 --- a/dart/gui/SoftSimWindow.cpp +++ b/dart/gui/SoftSimWindow.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/gui/SoftSimWindow.h b/dart/gui/SoftSimWindow.h index e2fe2108465ea..17c76c0b59cad 100644 --- a/dart/gui/SoftSimWindow.h +++ b/dart/gui/SoftSimWindow.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/gui/Trackball.cpp b/dart/gui/Trackball.cpp index 1e95f15248c51..3178b9c9df7d9 100644 --- a/dart/gui/Trackball.cpp +++ b/dart/gui/Trackball.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/Trackball.h b/dart/gui/Trackball.h index 4289a77f46d45..06e038db0b274 100644 --- a/dart/gui/Trackball.h +++ b/dart/gui/Trackball.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/Win2D.cpp b/dart/gui/Win2D.cpp index 4b1bf47c51208..5dfa7a5d54947 100644 --- a/dart/gui/Win2D.cpp +++ b/dart/gui/Win2D.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/Win2D.h b/dart/gui/Win2D.h index 0e5ce9ce3625a..5cbcc8be513a3 100644 --- a/dart/gui/Win2D.h +++ b/dart/gui/Win2D.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/Win3D.cpp b/dart/gui/Win3D.cpp index 5f0bee2bd01c0..bbe1a3983c83d 100644 --- a/dart/gui/Win3D.cpp +++ b/dart/gui/Win3D.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/Win3D.h b/dart/gui/Win3D.h index 2e617932e2041..72ef91fccc7ac 100644 --- a/dart/gui/Win3D.h +++ b/dart/gui/Win3D.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain diff --git a/dart/gui/osg/DefaultEventHandler.cpp b/dart/gui/osg/DefaultEventHandler.cpp index a7ea9afeb0fd2..b627d030cf0cd 100644 --- a/dart/gui/osg/DefaultEventHandler.cpp +++ b/dart/gui/osg/DefaultEventHandler.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/DefaultEventHandler.h b/dart/gui/osg/DefaultEventHandler.h index d72b346351458..969705526594c 100644 --- a/dart/gui/osg/DefaultEventHandler.h +++ b/dart/gui/osg/DefaultEventHandler.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/DragAndDrop.cpp b/dart/gui/osg/DragAndDrop.cpp index 58226eb2423f2..43ea2d3284bd6 100644 --- a/dart/gui/osg/DragAndDrop.cpp +++ b/dart/gui/osg/DragAndDrop.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/DragAndDrop.h b/dart/gui/osg/DragAndDrop.h index 2766d4286ba4a..501e05e79855d 100644 --- a/dart/gui/osg/DragAndDrop.h +++ b/dart/gui/osg/DragAndDrop.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/InteractiveFrame.cpp b/dart/gui/osg/InteractiveFrame.cpp index 75a8f88a2b5ab..755bbad7a5ab0 100644 --- a/dart/gui/osg/InteractiveFrame.cpp +++ b/dart/gui/osg/InteractiveFrame.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/InteractiveFrame.h b/dart/gui/osg/InteractiveFrame.h index a3b6d67642e44..4bf05ebe6d67c 100644 --- a/dart/gui/osg/InteractiveFrame.h +++ b/dart/gui/osg/InteractiveFrame.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/MouseEventHandler.h b/dart/gui/osg/MouseEventHandler.h index d67b8d402d5e8..a2dd740bf3cbb 100644 --- a/dart/gui/osg/MouseEventHandler.h +++ b/dart/gui/osg/MouseEventHandler.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/ShapeFrameNode.cpp b/dart/gui/osg/ShapeFrameNode.cpp index 25fc6f4762052..4c133f953f810 100644 --- a/dart/gui/osg/ShapeFrameNode.cpp +++ b/dart/gui/osg/ShapeFrameNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/ShapeFrameNode.h b/dart/gui/osg/ShapeFrameNode.h index 440a74fb1ec09..2cec89e1e26fc 100644 --- a/dart/gui/osg/ShapeFrameNode.h +++ b/dart/gui/osg/ShapeFrameNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/SupportPolygonVisual.cpp b/dart/gui/osg/SupportPolygonVisual.cpp index b2e070d11cb08..201afcacf0b9a 100644 --- a/dart/gui/osg/SupportPolygonVisual.cpp +++ b/dart/gui/osg/SupportPolygonVisual.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/SupportPolygonVisual.h b/dart/gui/osg/SupportPolygonVisual.h index 05f15468dfa0c..617647c639982 100644 --- a/dart/gui/osg/SupportPolygonVisual.h +++ b/dart/gui/osg/SupportPolygonVisual.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/TrackballManipulator.cpp b/dart/gui/osg/TrackballManipulator.cpp index f05d4c7cdd212..2da12d385e399 100644 --- a/dart/gui/osg/TrackballManipulator.cpp +++ b/dart/gui/osg/TrackballManipulator.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/TrackballManipulator.h b/dart/gui/osg/TrackballManipulator.h index 5968220e74ec5..c2e2f6cbd22cf 100644 --- a/dart/gui/osg/TrackballManipulator.h +++ b/dart/gui/osg/TrackballManipulator.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/Utils.h b/dart/gui/osg/Utils.h index 26c646d590f52..e281c0d475b45 100644 --- a/dart/gui/osg/Utils.h +++ b/dart/gui/osg/Utils.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/Viewer.cpp b/dart/gui/osg/Viewer.cpp index fd8d730b9bd5c..edba0b1affebf 100644 --- a/dart/gui/osg/Viewer.cpp +++ b/dart/gui/osg/Viewer.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/Viewer.h b/dart/gui/osg/Viewer.h index 26fa18555ac3b..97bc70050a07d 100644 --- a/dart/gui/osg/Viewer.h +++ b/dart/gui/osg/Viewer.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/WorldNode.cpp b/dart/gui/osg/WorldNode.cpp index 9679f74ace6b1..a9253f42d0434 100644 --- a/dart/gui/osg/WorldNode.cpp +++ b/dart/gui/osg/WorldNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/WorldNode.h b/dart/gui/osg/WorldNode.h index abece7352cd63..893ef09a17a22 100644 --- a/dart/gui/osg/WorldNode.h +++ b/dart/gui/osg/WorldNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/examples/osgAtlasPuppet.cpp b/dart/gui/osg/examples/osgAtlasPuppet.cpp index 7e9d54d638a32..c635a4df5ac89 100644 --- a/dart/gui/osg/examples/osgAtlasPuppet.cpp +++ b/dart/gui/osg/examples/osgAtlasPuppet.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/examples/osgDragAndDrop.cpp b/dart/gui/osg/examples/osgDragAndDrop.cpp index 4010fbafbb595..6c82b7771648b 100644 --- a/dart/gui/osg/examples/osgDragAndDrop.cpp +++ b/dart/gui/osg/examples/osgDragAndDrop.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/examples/osgHuboPuppet.cpp b/dart/gui/osg/examples/osgHuboPuppet.cpp index 07db569a1228a..708410e1b14be 100644 --- a/dart/gui/osg/examples/osgHuboPuppet.cpp +++ b/dart/gui/osg/examples/osgHuboPuppet.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/examples/osgOperationalSpaceControl.cpp b/dart/gui/osg/examples/osgOperationalSpaceControl.cpp index 68fea7c1786d4..348f864b29cd6 100644 --- a/dart/gui/osg/examples/osgOperationalSpaceControl.cpp +++ b/dart/gui/osg/examples/osgOperationalSpaceControl.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/examples/osgSoftBodies.cpp b/dart/gui/osg/examples/osgSoftBodies.cpp index 49fef7bd9fb80..95db54c82e7c8 100644 --- a/dart/gui/osg/examples/osgSoftBodies.cpp +++ b/dart/gui/osg/examples/osgSoftBodies.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/BoxShapeNode.cpp b/dart/gui/osg/render/BoxShapeNode.cpp index 9e7182798ba22..b4988f1145342 100644 --- a/dart/gui/osg/render/BoxShapeNode.cpp +++ b/dart/gui/osg/render/BoxShapeNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/BoxShapeNode.h b/dart/gui/osg/render/BoxShapeNode.h index 93202440fc5a8..7b5f0208581ab 100644 --- a/dart/gui/osg/render/BoxShapeNode.h +++ b/dart/gui/osg/render/BoxShapeNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/CylinderShapeNode.cpp b/dart/gui/osg/render/CylinderShapeNode.cpp index 572beed9cbf74..8e9010a6a5f40 100644 --- a/dart/gui/osg/render/CylinderShapeNode.cpp +++ b/dart/gui/osg/render/CylinderShapeNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/CylinderShapeNode.h b/dart/gui/osg/render/CylinderShapeNode.h index de66f4bb10b48..304d849b699ab 100644 --- a/dart/gui/osg/render/CylinderShapeNode.h +++ b/dart/gui/osg/render/CylinderShapeNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/EllipsoidShapeNode.cpp b/dart/gui/osg/render/EllipsoidShapeNode.cpp index 6ef21cf7f0000..a251126b2c2af 100644 --- a/dart/gui/osg/render/EllipsoidShapeNode.cpp +++ b/dart/gui/osg/render/EllipsoidShapeNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/EllipsoidShapeNode.h b/dart/gui/osg/render/EllipsoidShapeNode.h index ab242e9b7d520..3b47b75a9be26 100644 --- a/dart/gui/osg/render/EllipsoidShapeNode.h +++ b/dart/gui/osg/render/EllipsoidShapeNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/LineSegmentShapeNode.cpp b/dart/gui/osg/render/LineSegmentShapeNode.cpp index cc2bfc7fafb6f..b070e63771186 100644 --- a/dart/gui/osg/render/LineSegmentShapeNode.cpp +++ b/dart/gui/osg/render/LineSegmentShapeNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/LineSegmentShapeNode.h b/dart/gui/osg/render/LineSegmentShapeNode.h index 858ec9c5d9511..e469345342ff2 100644 --- a/dart/gui/osg/render/LineSegmentShapeNode.h +++ b/dart/gui/osg/render/LineSegmentShapeNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/MeshShapeNode.cpp b/dart/gui/osg/render/MeshShapeNode.cpp index 7ec7baaa744ed..adb23f05adcbb 100644 --- a/dart/gui/osg/render/MeshShapeNode.cpp +++ b/dart/gui/osg/render/MeshShapeNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/MeshShapeNode.h b/dart/gui/osg/render/MeshShapeNode.h index 9b953475c0d2d..ee8002e645da4 100644 --- a/dart/gui/osg/render/MeshShapeNode.h +++ b/dart/gui/osg/render/MeshShapeNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/PlaneShapeNode.cpp b/dart/gui/osg/render/PlaneShapeNode.cpp index a71c7b5d9c5b8..61785b613cdc9 100644 --- a/dart/gui/osg/render/PlaneShapeNode.cpp +++ b/dart/gui/osg/render/PlaneShapeNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/PlaneShapeNode.h b/dart/gui/osg/render/PlaneShapeNode.h index b9a64ad83014c..12fd8a2ab7938 100644 --- a/dart/gui/osg/render/PlaneShapeNode.h +++ b/dart/gui/osg/render/PlaneShapeNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/ShapeNode.cpp b/dart/gui/osg/render/ShapeNode.cpp index 5b448b95a134b..06fb4d0491f00 100644 --- a/dart/gui/osg/render/ShapeNode.cpp +++ b/dart/gui/osg/render/ShapeNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/ShapeNode.h b/dart/gui/osg/render/ShapeNode.h index 6cbc4ff7bcad3..17fe635f9fad0 100644 --- a/dart/gui/osg/render/ShapeNode.h +++ b/dart/gui/osg/render/ShapeNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/SoftMeshShapeNode.cpp b/dart/gui/osg/render/SoftMeshShapeNode.cpp index 339c1771a0c4b..69540eb417d54 100644 --- a/dart/gui/osg/render/SoftMeshShapeNode.cpp +++ b/dart/gui/osg/render/SoftMeshShapeNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/SoftMeshShapeNode.h b/dart/gui/osg/render/SoftMeshShapeNode.h index 094a5342b2447..4273ac62d5aff 100644 --- a/dart/gui/osg/render/SoftMeshShapeNode.h +++ b/dart/gui/osg/render/SoftMeshShapeNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/WarningShapeNode.cpp b/dart/gui/osg/render/WarningShapeNode.cpp index a96590044f680..29f7828f685fc 100644 --- a/dart/gui/osg/render/WarningShapeNode.cpp +++ b/dart/gui/osg/render/WarningShapeNode.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/gui/osg/render/WarningShapeNode.h b/dart/gui/osg/render/WarningShapeNode.h index d74f6f55743d5..a39e7de2495cb 100644 --- a/dart/gui/osg/render/WarningShapeNode.h +++ b/dart/gui/osg/render/WarningShapeNode.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/integration/EulerIntegrator.cpp b/dart/integration/EulerIntegrator.cpp index a93d1a701b9ee..6cc84231e8cd9 100644 --- a/dart/integration/EulerIntegrator.cpp +++ b/dart/integration/EulerIntegrator.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Kristin Siu , diff --git a/dart/integration/EulerIntegrator.h b/dart/integration/EulerIntegrator.h index d2e9031824efc..f260731141448 100644 --- a/dart/integration/EulerIntegrator.h +++ b/dart/integration/EulerIntegrator.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Kristin Siu , diff --git a/dart/integration/Integrator.cpp b/dart/integration/Integrator.cpp index cd3b5ed0bd579..259ff099122e8 100644 --- a/dart/integration/Integrator.cpp +++ b/dart/integration/Integrator.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Kristin Siu , diff --git a/dart/integration/Integrator.h b/dart/integration/Integrator.h index 3953bf75b195f..940dd5a10174d 100644 --- a/dart/integration/Integrator.h +++ b/dart/integration/Integrator.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Kristin Siu , diff --git a/dart/integration/RK4Integrator.cpp b/dart/integration/RK4Integrator.cpp index b0212594a84cd..89b2c0ef00890 100644 --- a/dart/integration/RK4Integrator.cpp +++ b/dart/integration/RK4Integrator.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Kristin Siu , diff --git a/dart/integration/RK4Integrator.h b/dart/integration/RK4Integrator.h index 6e94df60e6c3f..7d11ac33a7812 100644 --- a/dart/integration/RK4Integrator.h +++ b/dart/integration/RK4Integrator.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Kristin Siu , diff --git a/dart/integration/SemiImplicitEulerIntegrator.cpp b/dart/integration/SemiImplicitEulerIntegrator.cpp index 278235978a239..8931f5ba03ad5 100644 --- a/dart/integration/SemiImplicitEulerIntegrator.cpp +++ b/dart/integration/SemiImplicitEulerIntegrator.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Kristin Siu , diff --git a/dart/integration/SemiImplicitEulerIntegrator.h b/dart/integration/SemiImplicitEulerIntegrator.h index 9195f51292804..795227aa0a5f3 100644 --- a/dart/integration/SemiImplicitEulerIntegrator.h +++ b/dart/integration/SemiImplicitEulerIntegrator.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/lcpsolver/Lemke.cpp b/dart/lcpsolver/Lemke.cpp index 78acdf7cfd719..96700c39f9bb6 100644 --- a/dart/lcpsolver/Lemke.cpp +++ b/dart/lcpsolver/Lemke.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jie (Jay) Tan , diff --git a/dart/lcpsolver/Lemke.h b/dart/lcpsolver/Lemke.h index f6c5a6cc176ea..ca6fb097bbb44 100644 --- a/dart/lcpsolver/Lemke.h +++ b/dart/lcpsolver/Lemke.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jie (Jay) Tan , diff --git a/dart/lcpsolver/ODELCPSolver.cpp b/dart/lcpsolver/ODELCPSolver.cpp index 619ccf927e3aa..1b99829efee12 100644 --- a/dart/lcpsolver/ODELCPSolver.cpp +++ b/dart/lcpsolver/ODELCPSolver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jie (Jay) Tan diff --git a/dart/lcpsolver/ODELCPSolver.h b/dart/lcpsolver/ODELCPSolver.h index b1a617d75084c..841f60dc826cd 100644 --- a/dart/lcpsolver/ODELCPSolver.h +++ b/dart/lcpsolver/ODELCPSolver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jie (Jay) Tan diff --git a/dart/lcpsolver/fastdot.cpp b/dart/lcpsolver/fastdot.cpp index 7d4eeac20f21d..0014de4680c48 100644 --- a/dart/lcpsolver/fastdot.cpp +++ b/dart/lcpsolver/fastdot.cpp @@ -1,3 +1,25 @@ +/************************************************************************* + * * + * Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * + * All rights reserved. Email: russ@q12.org Web: www.q12.org * + * * + * This library is free software; you can redistribute it and/or * + * modify it under the terms of EITHER: * + * (1) The GNU Lesser General Public License as published by the Free * + * Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. The text of the GNU Lesser * + * General Public License is included with this library in the * + * file LICENSE.TXT. * + * (2) The BSD-style license that is included with this library in * + * the file LICENSE-BSD.TXT. * + * * + * This library is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * + * LICENSE.TXT and LICENSE-BSD.TXT for more details. * + * * + *************************************************************************/ + /* generated code, do not edit. */ #include "dart/lcpsolver/matrix.h" diff --git a/dart/lcpsolver/fastldlt.cpp b/dart/lcpsolver/fastldlt.cpp index e458ad44205d1..dc169ad9830f5 100644 --- a/dart/lcpsolver/fastldlt.cpp +++ b/dart/lcpsolver/fastldlt.cpp @@ -1,3 +1,25 @@ +/************************************************************************* + * * + * Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * + * All rights reserved. Email: russ@q12.org Web: www.q12.org * + * * + * This library is free software; you can redistribute it and/or * + * modify it under the terms of EITHER: * + * (1) The GNU Lesser General Public License as published by the Free * + * Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. The text of the GNU Lesser * + * General Public License is included with this library in the * + * file LICENSE.TXT. * + * (2) The BSD-style license that is included with this library in * + * the file LICENSE-BSD.TXT. * + * * + * This library is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * + * LICENSE.TXT and LICENSE-BSD.TXT for more details. * + * * + *************************************************************************/ + /* generated code, do not edit. */ #include "dart/lcpsolver/matrix.h" diff --git a/dart/lcpsolver/fastlsolve.cpp b/dart/lcpsolver/fastlsolve.cpp index 463969bc70659..7cef0f0d503e9 100644 --- a/dart/lcpsolver/fastlsolve.cpp +++ b/dart/lcpsolver/fastlsolve.cpp @@ -1,3 +1,25 @@ +/************************************************************************* + * * + * Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * + * All rights reserved. Email: russ@q12.org Web: www.q12.org * + * * + * This library is free software; you can redistribute it and/or * + * modify it under the terms of EITHER: * + * (1) The GNU Lesser General Public License as published by the Free * + * Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. The text of the GNU Lesser * + * General Public License is included with this library in the * + * file LICENSE.TXT. * + * (2) The BSD-style license that is included with this library in * + * the file LICENSE-BSD.TXT. * + * * + * This library is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * + * LICENSE.TXT and LICENSE-BSD.TXT for more details. * + * * + *************************************************************************/ + /* generated code, do not edit. */ #include "dart/lcpsolver/matrix.h" diff --git a/dart/lcpsolver/fastltsolve.cpp b/dart/lcpsolver/fastltsolve.cpp index b9b15720c31ec..9cd21add3f099 100644 --- a/dart/lcpsolver/fastltsolve.cpp +++ b/dart/lcpsolver/fastltsolve.cpp @@ -1,3 +1,25 @@ +/************************************************************************* + * * + * Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * + * All rights reserved. Email: russ@q12.org Web: www.q12.org * + * * + * This library is free software; you can redistribute it and/or * + * modify it under the terms of EITHER: * + * (1) The GNU Lesser General Public License as published by the Free * + * Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. The text of the GNU Lesser * + * General Public License is included with this library in the * + * file LICENSE.TXT. * + * (2) The BSD-style license that is included with this library in * + * the file LICENSE-BSD.TXT. * + * * + * This library is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * + * LICENSE.TXT and LICENSE-BSD.TXT for more details. * + * * + *************************************************************************/ + /* generated code, do not edit. */ #include "dart/lcpsolver/matrix.h" diff --git a/dart/lcpsolver/odeconfig.h b/dart/lcpsolver/odeconfig.h index 6a2e475113e62..8977b6964510f 100644 --- a/dart/lcpsolver/odeconfig.h +++ b/dart/lcpsolver/odeconfig.h @@ -1,3 +1,25 @@ +/************************************************************************* + * * + * Open Dynamics Engine, Copyright (C) 2001,2002 Russell L. Smith. * + * All rights reserved. Email: russ@q12.org Web: www.q12.org * + * * + * This library is free software; you can redistribute it and/or * + * modify it under the terms of EITHER: * + * (1) The GNU Lesser General Public License as published by the Free * + * Software Foundation; either version 2.1 of the License, or (at * + * your option) any later version. The text of the GNU Lesser * + * General Public License is included with this library in the * + * file LICENSE.TXT. * + * (2) The BSD-style license that is included with this library in * + * the file LICENSE-BSD.TXT. * + * * + * This library is distributed in the hope that it will be useful, * + * but WITHOUT ANY WARRANTY; without even the implied warranty of * + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the files * + * LICENSE.TXT and LICENSE-BSD.TXT for more details. * + * * + *************************************************************************/ + #ifndef _ODE_CONFIG_H_ #define _ODE_CONFIG_H_ diff --git a/dart/math/Geometry.cpp b/dart/math/Geometry.cpp index 98d3066cd3a5d..b41d29f9294b5 100644 --- a/dart/math/Geometry.cpp +++ b/dart/math/Geometry.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/math/Geometry.h b/dart/math/Geometry.h index 4857568622324..0bc363bfded2b 100644 --- a/dart/math/Geometry.h +++ b/dart/math/Geometry.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/math/Helpers.h b/dart/math/Helpers.h index c7e34fc82d777..39d8f61c39a95 100644 --- a/dart/math/Helpers.h +++ b/dart/math/Helpers.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/math/MathTypes.h b/dart/math/MathTypes.h index d8c93b434b049..ead135e4bcb2b 100644 --- a/dart/math/MathTypes.h +++ b/dart/math/MathTypes.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/optimizer/Function.cpp b/dart/optimizer/Function.cpp index 1c99d2bd42a72..e858c212db78b 100644 --- a/dart/optimizer/Function.cpp +++ b/dart/optimizer/Function.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/optimizer/Function.h b/dart/optimizer/Function.h index 0b93d3ef3df90..59781664950fd 100644 --- a/dart/optimizer/Function.h +++ b/dart/optimizer/Function.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/optimizer/GradientDescentSolver.cpp b/dart/optimizer/GradientDescentSolver.cpp index 746b833fe1be7..a0bd360f84446 100644 --- a/dart/optimizer/GradientDescentSolver.cpp +++ b/dart/optimizer/GradientDescentSolver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/optimizer/GradientDescentSolver.h b/dart/optimizer/GradientDescentSolver.h index 0023aaf5a484e..820c1ce26a3b3 100644 --- a/dart/optimizer/GradientDescentSolver.h +++ b/dart/optimizer/GradientDescentSolver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/dart/optimizer/Problem.cpp b/dart/optimizer/Problem.cpp index 50a843a3035e6..fd1b0216b508b 100644 --- a/dart/optimizer/Problem.cpp +++ b/dart/optimizer/Problem.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/optimizer/Problem.h b/dart/optimizer/Problem.h index efc91910d214d..71bd57c9ca47d 100644 --- a/dart/optimizer/Problem.h +++ b/dart/optimizer/Problem.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/optimizer/Solver.cpp b/dart/optimizer/Solver.cpp index 4cd2c5e6adfee..90e517d6e9a70 100644 --- a/dart/optimizer/Solver.cpp +++ b/dart/optimizer/Solver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/optimizer/Solver.h b/dart/optimizer/Solver.h index 20d725ff13bf7..af02827521d38 100644 --- a/dart/optimizer/Solver.h +++ b/dart/optimizer/Solver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/optimizer/ipopt/IpoptSolver.cpp b/dart/optimizer/ipopt/IpoptSolver.cpp index 3ccd9e9527141..9ccd29e91cffa 100644 --- a/dart/optimizer/ipopt/IpoptSolver.cpp +++ b/dart/optimizer/ipopt/IpoptSolver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/optimizer/ipopt/IpoptSolver.h b/dart/optimizer/ipopt/IpoptSolver.h index c02daa91924bd..90f8946dab996 100644 --- a/dart/optimizer/ipopt/IpoptSolver.h +++ b/dart/optimizer/ipopt/IpoptSolver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/optimizer/nlopt/NloptSolver.cpp b/dart/optimizer/nlopt/NloptSolver.cpp index 8c81a411251cc..f9fb8cbc770b4 100644 --- a/dart/optimizer/nlopt/NloptSolver.cpp +++ b/dart/optimizer/nlopt/NloptSolver.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/optimizer/nlopt/NloptSolver.h b/dart/optimizer/nlopt/NloptSolver.h index 794ae5a71fdb4..c227c27efddfa 100644 --- a/dart/optimizer/nlopt/NloptSolver.h +++ b/dart/optimizer/nlopt/NloptSolver.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/planning/Path.cpp b/dart/planning/Path.cpp index 8ae5a4bab6c54..084ad9b5da1fa 100644 --- a/dart/planning/Path.cpp +++ b/dart/planning/Path.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author: Tobias Kunz diff --git a/dart/planning/Path.h b/dart/planning/Path.h index 23b478deb8ec8..033e2357f3c23 100644 --- a/dart/planning/Path.h +++ b/dart/planning/Path.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author: Tobias Kunz diff --git a/dart/planning/PathFollowingTrajectory.cpp b/dart/planning/PathFollowingTrajectory.cpp index 568a189d5510e..78bed3ea57c3a 100644 --- a/dart/planning/PathFollowingTrajectory.cpp +++ b/dart/planning/PathFollowingTrajectory.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author: Tobias Kunz diff --git a/dart/planning/PathFollowingTrajectory.h b/dart/planning/PathFollowingTrajectory.h index e00f67b86f212..9b76e82cc7201 100644 --- a/dart/planning/PathFollowingTrajectory.h +++ b/dart/planning/PathFollowingTrajectory.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author: Tobias Kunz diff --git a/dart/planning/PathPlanner.h b/dart/planning/PathPlanner.h index df1139c0bbfab..18aaba81369c8 100644 --- a/dart/planning/PathPlanner.h +++ b/dart/planning/PathPlanner.h @@ -1,3 +1,40 @@ +/* + * Copyright (c) 2011-2016, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Can Erdogan , + * Tobias Kunz , + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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. + */ + /** * @file PathPlanner.h * @author Tobias Kunz (?), Can Erdogan diff --git a/dart/planning/PathShortener.cpp b/dart/planning/PathShortener.cpp index 81688a885746a..b4317eeebfe7c 100644 --- a/dart/planning/PathShortener.cpp +++ b/dart/planning/PathShortener.cpp @@ -1,3 +1,39 @@ +/* + * Copyright (c) 2011-2016, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Tobias Kunz + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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. + */ + #include "PathShortener.h" #include "dart/simulation/World.h" #include "RRT.h" diff --git a/dart/planning/PathShortener.h b/dart/planning/PathShortener.h index 5e6187865b30d..785af0e7176d4 100644 --- a/dart/planning/PathShortener.h +++ b/dart/planning/PathShortener.h @@ -1,4 +1,41 @@ -#pragma once +/* + * Copyright (c) 2011-2016, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Tobias Kunz + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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. + */ + +#ifndef DART_PLANNING_PATHSHORTENER_H_ +#define DART_PLANNING_PATHSHORTENER_H_ #include #include @@ -7,10 +44,6 @@ #include "dart/simulation/World.h" namespace dart { - -namespace simulation { class World; } -namespace dynamics { class Skeleton; } - namespace planning { class PathShortener @@ -31,3 +64,5 @@ class PathShortener } // namespace planning } // namespace dart + +#endif // DART_PLANNING_PATHSHORTENER_H_ diff --git a/dart/planning/RRT.cpp b/dart/planning/RRT.cpp index 20ad39b84eb76..731c1da630b4d 100644 --- a/dart/planning/RRT.cpp +++ b/dart/planning/RRT.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2010, Georgia Tech Research Corporation + * Copyright (c) 2010-2016, Georgia Tech Research Corporation * All rights reserved. * * Redistribution and use in source and binary forms, with or without diff --git a/dart/planning/RRT.h b/dart/planning/RRT.h index 043d4d980b2fc..10b505ad552ba 100644 --- a/dart/planning/RRT.h +++ b/dart/planning/RRT.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2010, Georgia Tech Research Corporation + * Copyright (c) 2010-2016, Georgia Tech Research Corporation * All rights reserved. * * Redistribution and use in source and binary forms, with or without diff --git a/dart/planning/Trajectory.h b/dart/planning/Trajectory.h index 8a2c4c9866bc7..f5695da664af8 100644 --- a/dart/planning/Trajectory.h +++ b/dart/planning/Trajectory.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author: Tobias Kunz diff --git a/dart/simulation/Recording.cpp b/dart/simulation/Recording.cpp index 5434e7b8a35fd..bb87fa712283d 100644 --- a/dart/simulation/Recording.cpp +++ b/dart/simulation/Recording.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/dart/simulation/Recording.h b/dart/simulation/Recording.h index f03ccb6d7b6ad..7df0f24984fd7 100644 --- a/dart/simulation/Recording.h +++ b/dart/simulation/Recording.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/dart/simulation/World.cpp b/dart/simulation/World.cpp index 60bbccd1faa33..294727ca8acb9 100644 --- a/dart/simulation/World.cpp +++ b/dart/simulation/World.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/simulation/World.h b/dart/simulation/World.h index 66315383109ab..9cf0c3ad5c7ab 100644 --- a/dart/simulation/World.h +++ b/dart/simulation/World.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/utils/C3D.cpp b/dart/utils/C3D.cpp index 94f8e345aa377..38fcfa386eccb 100644 --- a/dart/utils/C3D.cpp +++ b/dart/utils/C3D.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/utils/C3D.h b/dart/utils/C3D.h index 64bc8f8510e2e..0e8d79ab136ac 100644 --- a/dart/utils/C3D.h +++ b/dart/utils/C3D.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/utils/CompositeResourceRetriever.cpp b/dart/utils/CompositeResourceRetriever.cpp index 87cd1f2a9cb54..e7d7253d9a56b 100644 --- a/dart/utils/CompositeResourceRetriever.cpp +++ b/dart/utils/CompositeResourceRetriever.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/utils/CompositeResourceRetriever.h b/dart/utils/CompositeResourceRetriever.h index bb645a173c59b..ed71078953d15 100644 --- a/dart/utils/CompositeResourceRetriever.h +++ b/dart/utils/CompositeResourceRetriever.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/utils/FileInfoC3D.cpp b/dart/utils/FileInfoC3D.cpp index add200edb1f11..1863453e9688d 100644 --- a/dart/utils/FileInfoC3D.cpp +++ b/dart/utils/FileInfoC3D.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/utils/FileInfoC3D.h b/dart/utils/FileInfoC3D.h index 63c0f6d7d41d2..61bbdd895f6f0 100644 --- a/dart/utils/FileInfoC3D.h +++ b/dart/utils/FileInfoC3D.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/utils/FileInfoDof.cpp b/dart/utils/FileInfoDof.cpp index f0b4411c9f7da..41a6ce3825131 100644 --- a/dart/utils/FileInfoDof.cpp +++ b/dart/utils/FileInfoDof.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/utils/FileInfoDof.h b/dart/utils/FileInfoDof.h index 65c46795559eb..1c807d5dcbe88 100644 --- a/dart/utils/FileInfoDof.h +++ b/dart/utils/FileInfoDof.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/utils/FileInfoWorld.cpp b/dart/utils/FileInfoWorld.cpp index 5ecc91df339b3..d4ad6d558b7de 100644 --- a/dart/utils/FileInfoWorld.cpp +++ b/dart/utils/FileInfoWorld.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/dart/utils/FileInfoWorld.h b/dart/utils/FileInfoWorld.h index b3cbeb328fa7a..e7ba9bad7516c 100644 --- a/dart/utils/FileInfoWorld.h +++ b/dart/utils/FileInfoWorld.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/dart/utils/PackageResourceRetriever.cpp b/dart/utils/PackageResourceRetriever.cpp index 7abdc443759b9..9011a8c166f82 100644 --- a/dart/utils/PackageResourceRetriever.cpp +++ b/dart/utils/PackageResourceRetriever.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/utils/PackageResourceRetriever.h b/dart/utils/PackageResourceRetriever.h index 130b3d50d418b..fa73ab84e5224 100644 --- a/dart/utils/PackageResourceRetriever.h +++ b/dart/utils/PackageResourceRetriever.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/dart/utils/SkelParser.cpp b/dart/utils/SkelParser.cpp index b6105fc53ccda..4421a3b313a92 100644 --- a/dart/utils/SkelParser.cpp +++ b/dart/utils/SkelParser.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/utils/SkelParser.h b/dart/utils/SkelParser.h index 57e396294a280..1280e87bfc0e7 100644 --- a/dart/utils/SkelParser.h +++ b/dart/utils/SkelParser.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/utils/VskParser.cpp b/dart/utils/VskParser.cpp index 70a7f3ef5de50..eeaea52805250 100644 --- a/dart/utils/VskParser.cpp +++ b/dart/utils/VskParser.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2012-2015, Georgia Tech Research Corporation + * Copyright (c) 2012-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha , diff --git a/dart/utils/VskParser.h b/dart/utils/VskParser.h index 3693a847c14a8..f092b330b6b34 100644 --- a/dart/utils/VskParser.h +++ b/dart/utils/VskParser.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sehoon Ha diff --git a/dart/utils/XmlHelpers.cpp b/dart/utils/XmlHelpers.cpp index 1182e28e34b1a..2aa6260433f93 100644 --- a/dart/utils/XmlHelpers.cpp +++ b/dart/utils/XmlHelpers.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/utils/XmlHelpers.h b/dart/utils/XmlHelpers.h index cbb46d7947302..df09379a71c45 100644 --- a/dart/utils/XmlHelpers.h +++ b/dart/utils/XmlHelpers.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/dart/utils/urdf/DartLoader.cpp b/dart/utils/urdf/DartLoader.cpp index bb24e2eb2e606..be4f56fa43327 100644 --- a/dart/utils/urdf/DartLoader.cpp +++ b/dart/utils/urdf/DartLoader.cpp @@ -1,3 +1,39 @@ +/* + * Copyright (c) 2011-2016, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Ana C. Huamán Quispe + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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. + */ + #include "DartLoader.h" #include diff --git a/dart/utils/urdf/DartLoader.h b/dart/utils/urdf/DartLoader.h index 9a70e46b2b3c5..263eec1e3ed48 100644 --- a/dart/utils/urdf/DartLoader.h +++ b/dart/utils/urdf/DartLoader.h @@ -1,5 +1,37 @@ -/** - * @file DartLoader.h +/* + * Copyright (c) 2011-2016, Georgia Tech Research Corporation + * All rights reserved. + * + * Author(s): Ana C. Huamán Quispe + * + * Georgia Tech Graphics Lab and Humanoid Robotics Lab + * + * Directed by Prof. C. Karen Liu and Prof. Mike Stilman + * + * + * This file is provided under the following "BSD-style" License: + * 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. + * 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. */ #ifndef DART_UTILS_URDF_LOADER_H diff --git a/mkdocs.yml b/mkdocs.yml index 11140ebea446e..33e000bd9aa17 100644 --- a/mkdocs.yml +++ b/mkdocs.yml @@ -4,7 +4,7 @@ repo_url: https://github.com/dartsim/dart.git repo_name: GitHub site_description: Dynamic Animation and Robotics Toolkit # site_favicon: null # todo: add dart.ico -copyright: Copyright (c) 2011-2015, Georgia Tech Research Corporation +copyright: Copyright (c) 2011-2016, Georgia Tech Research Corporation # Build directories theme: readthedocs diff --git a/tutorials/tutorialBiped-Finished.cpp b/tutorials/tutorialBiped-Finished.cpp index c2525d5f654fa..210a0cb659bf7 100644 --- a/tutorials/tutorialBiped-Finished.cpp +++ b/tutorials/tutorialBiped-Finished.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/tutorials/tutorialBiped.cpp b/tutorials/tutorialBiped.cpp index edb762f117f6c..72902de753eba 100644 --- a/tutorials/tutorialBiped.cpp +++ b/tutorials/tutorialBiped.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Karen Liu diff --git a/tutorials/tutorialCollisions-Finished.cpp b/tutorials/tutorialCollisions-Finished.cpp index c3dea0e226a63..05f4d83cdd399 100644 --- a/tutorials/tutorialCollisions-Finished.cpp +++ b/tutorials/tutorialCollisions-Finished.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/tutorials/tutorialCollisions.cpp b/tutorials/tutorialCollisions.cpp index d1ddf64479ade..a1d2486010ff8 100644 --- a/tutorials/tutorialCollisions.cpp +++ b/tutorials/tutorialCollisions.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/tutorials/tutorialDominoes-Finished.cpp b/tutorials/tutorialDominoes-Finished.cpp index 0b13cd1691e0b..f12e5f2747228 100644 --- a/tutorials/tutorialDominoes-Finished.cpp +++ b/tutorials/tutorialDominoes-Finished.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/tutorials/tutorialDominoes.cpp b/tutorials/tutorialDominoes.cpp index f76ac143e26a7..e027fe2f5ea1a 100644 --- a/tutorials/tutorialDominoes.cpp +++ b/tutorials/tutorialDominoes.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/tutorials/tutorialMultiPendulum-Finished.cpp b/tutorials/tutorialMultiPendulum-Finished.cpp index f7fc372fd5310..c01b3a0a3a14a 100644 --- a/tutorials/tutorialMultiPendulum-Finished.cpp +++ b/tutorials/tutorialMultiPendulum-Finished.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/tutorials/tutorialMultiPendulum.cpp b/tutorials/tutorialMultiPendulum.cpp index d664db0fd75c3..df7962c710c65 100644 --- a/tutorials/tutorialMultiPendulum.cpp +++ b/tutorials/tutorialMultiPendulum.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/unittests/CMakeLists.txt b/unittests/CMakeLists.txt index 5de8239a4318c..1d6fc6117db42 100644 --- a/unittests/CMakeLists.txt +++ b/unittests/CMakeLists.txt @@ -1,5 +1,5 @@ # -# Copyright (c) 2013-2015, Georgia Tech Research Corporation +# Copyright (c) 2013-2016, Georgia Tech Research Corporation # All rights reserved. # # Author(s): Can Erdogan , diff --git a/unittests/testAspect.cpp b/unittests/testAspect.cpp index 9a6ef70bf4e72..29308d6ec1996 100644 --- a/unittests/testAspect.cpp +++ b/unittests/testAspect.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/unittests/testBuilding.cpp b/unittests/testBuilding.cpp index 83bd18ce136db..8d18f2d762d4c 100644 --- a/unittests/testBuilding.cpp +++ b/unittests/testBuilding.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testCollision.cpp b/unittests/testCollision.cpp index e74dbd1e3a9a1..418d8980ad581 100644 --- a/unittests/testCollision.cpp +++ b/unittests/testCollision.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testCommon.cpp b/unittests/testCommon.cpp index 7db4966c00c10..e37589223eaa5 100644 --- a/unittests/testCommon.cpp +++ b/unittests/testCommon.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testCompositeResourceRetriever.cpp b/unittests/testCompositeResourceRetriever.cpp index 4edc7338e11f2..40ff96e8bedc5 100644 --- a/unittests/testCompositeResourceRetriever.cpp +++ b/unittests/testCompositeResourceRetriever.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/unittests/testConcurrency.cpp b/unittests/testConcurrency.cpp index 4cb0ac38e555d..84220e39ca4ae 100644 --- a/unittests/testConcurrency.cpp +++ b/unittests/testConcurrency.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/unittests/testConstraint.cpp b/unittests/testConstraint.cpp index 8e21517c8d07b..7d3fd18ebcc92 100644 --- a/unittests/testConstraint.cpp +++ b/unittests/testConstraint.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain , diff --git a/unittests/testDartLoader.cpp b/unittests/testDartLoader.cpp index 3072babcf04d7..dfd2f245d72df 100644 --- a/unittests/testDartLoader.cpp +++ b/unittests/testDartLoader.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/unittests/testDynamics.cpp b/unittests/testDynamics.cpp index 12e7e4be600b1..3f8ed377304c8 100644 --- a/unittests/testDynamics.cpp +++ b/unittests/testDynamics.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Sumit Jain , diff --git a/unittests/testFileInfoWorld.cpp b/unittests/testFileInfoWorld.cpp index f9ff9c07a95c3..85ddf23231fb8 100644 --- a/unittests/testFileInfoWorld.cpp +++ b/unittests/testFileInfoWorld.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testForwardKinematics.cpp b/unittests/testForwardKinematics.cpp index b675a2008c48f..3ad131140e580 100644 --- a/unittests/testForwardKinematics.cpp +++ b/unittests/testForwardKinematics.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Can Erdogan diff --git a/unittests/testFrames.cpp b/unittests/testFrames.cpp index bfeb408e63b98..2d5397b5cc082 100644 --- a/unittests/testFrames.cpp +++ b/unittests/testFrames.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/unittests/testGeometry.cpp b/unittests/testGeometry.cpp index eda4116c93471..97937538f2aa8 100644 --- a/unittests/testGeometry.cpp +++ b/unittests/testGeometry.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testInverseKinematics.cpp b/unittests/testInverseKinematics.cpp index 6d4f0e11b4589..1bba46cad501a 100644 --- a/unittests/testInverseKinematics.cpp +++ b/unittests/testInverseKinematics.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testJoints.cpp b/unittests/testJoints.cpp index dad5cdec0ed88..a859cd55613b0 100644 --- a/unittests/testJoints.cpp +++ b/unittests/testJoints.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testLocalResourceRetriever.cpp b/unittests/testLocalResourceRetriever.cpp index edfa9753d8ef3..f5989b568302b 100644 --- a/unittests/testLocalResourceRetriever.cpp +++ b/unittests/testLocalResourceRetriever.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/unittests/testMath.cpp b/unittests/testMath.cpp index 8e01bc1410a4b..77c3232745d23 100644 --- a/unittests/testMath.cpp +++ b/unittests/testMath.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testNameManagement.cpp b/unittests/testNameManagement.cpp index 825e520941703..d0b90fc883651 100644 --- a/unittests/testNameManagement.cpp +++ b/unittests/testNameManagement.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/unittests/testOptimizer.cpp b/unittests/testOptimizer.cpp index a32a62d46bd53..6ba4669761bd0 100644 --- a/unittests/testOptimizer.cpp +++ b/unittests/testOptimizer.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testPackageResourceRetriever.cpp b/unittests/testPackageResourceRetriever.cpp index 73f8a985e713b..c648dca3a5015 100644 --- a/unittests/testPackageResourceRetriever.cpp +++ b/unittests/testPackageResourceRetriever.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/unittests/testSdfParser.cpp b/unittests/testSdfParser.cpp index 7d4467887dcea..8a35393919389 100644 --- a/unittests/testSdfParser.cpp +++ b/unittests/testSdfParser.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testSignal.cpp b/unittests/testSignal.cpp index ed7a69b5f1499..a95e8d3e06e1c 100644 --- a/unittests/testSignal.cpp +++ b/unittests/testSignal.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testSkelParser.cpp b/unittests/testSkelParser.cpp index 0da673dbb6e2d..40773a07bd23c 100644 --- a/unittests/testSkelParser.cpp +++ b/unittests/testSkelParser.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testSkeleton.cpp b/unittests/testSkeleton.cpp index 7022e9378564d..9c06dbc9a55c4 100644 --- a/unittests/testSkeleton.cpp +++ b/unittests/testSkeleton.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/unittests/testSoftDynamics.cpp b/unittests/testSoftDynamics.cpp index 8e57aef0dfee1..55060892195d7 100644 --- a/unittests/testSoftDynamics.cpp +++ b/unittests/testSoftDynamics.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2014-2015, Georgia Tech Research Corporation + * Copyright (c) 2014-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testSubscriptions.cpp b/unittests/testSubscriptions.cpp index 2b7f1a3123399..804dafe80d443 100644 --- a/unittests/testSubscriptions.cpp +++ b/unittests/testSubscriptions.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael X. Grey diff --git a/unittests/testUri.cpp b/unittests/testUri.cpp index cc607f7d5b59f..a0d366c72b675 100644 --- a/unittests/testUri.cpp +++ b/unittests/testUri.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Michael Koval diff --git a/unittests/testUtilities.cpp b/unittests/testUtilities.cpp index b89e3ace60239..dfce9a1805a11 100644 --- a/unittests/testUtilities.cpp +++ b/unittests/testUtilities.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2011-2015, Georgia Tech Research Corporation + * Copyright (c) 2011-2016, Georgia Tech Research Corporation * All rights reserved. * * Georgia Tech Graphics Lab and Humanoid Robotics Lab diff --git a/unittests/testVskParser.cpp b/unittests/testVskParser.cpp index a82c3c6c5b54c..73e8acab0e951 100644 --- a/unittests/testVskParser.cpp +++ b/unittests/testVskParser.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2015, Georgia Tech Research Corporation + * Copyright (c) 2015-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee diff --git a/unittests/testWorld.cpp b/unittests/testWorld.cpp index 898296462f9a7..9f2cdc5d177a5 100644 --- a/unittests/testWorld.cpp +++ b/unittests/testWorld.cpp @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2015, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Jeongseok Lee From 2ed319c1267ee14b9697af95061e2112a037e5dd Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 21 Apr 2016 17:30:48 -0400 Subject: [PATCH 20/34] Remove unnecessary virtual keyword from overridden functions --- apps/addDeleteSkels/MyWindow.h | 4 +- apps/atlasSimbicon/MyWindow.h | 6 +- apps/atlasSimbicon/TerminalCondition.h | 4 +- apps/bipedStand/MyWindow.h | 6 +- apps/hardcodedDesign/MyWindow.h | 4 +- apps/hybridDynamics/MyWindow.h | 6 +- apps/jointConstraints/MyWindow.h | 10 +- apps/mixedChain/MyWindow.h | 6 +- apps/operationalSpaceControl/MyWindow.h | 6 +- apps/rigidChain/MyWindow.h | 2 +- apps/rigidCubes/MyWindow.h | 6 +- apps/rigidLoop/MyWindow.h | 10 +- apps/rigidShapes/MyWindow.h | 6 +- apps/softBodies/MyWindow.h | 6 +- apps/vehicle/MyWindow.h | 6 +- dart/common/sub_ptr.h | 3 +- dart/constraint/BallJointConstraint.h | 20 +- dart/constraint/ConstraintBase.cpp | 6 + dart/constraint/ConstraintBase.h | 2 +- dart/constraint/ContactConstraint.h | 20 +- dart/constraint/DantzigLCPSolver.h | 2 +- .../JointCoulombFrictionConstraint.h | 18 +- dart/constraint/JointLimitConstraint.h | 18 +- dart/constraint/PGSLCPSolver.h | 2 +- dart/constraint/ServoMotorConstraint.h | 18 +- dart/constraint/SoftContactConstraint.h | 20 +- dart/constraint/WeldJointConstraint.h | 20 +- dart/dynamics/Branch.h | 2 +- dart/dynamics/EndEffector.h | 2 +- dart/dynamics/EulerJoint.h | 14 +- dart/dynamics/FreeJoint.h | 4 +- dart/dynamics/LineSegmentShape.h | 2 +- dart/dynamics/MultiDofJoint.h | 80 +++---- dart/dynamics/PlanarJoint.h | 14 +- dart/dynamics/PrismaticJoint.h | 12 +- dart/dynamics/RevoluteJoint.h | 12 +- dart/dynamics/ScrewJoint.h | 12 +- dart/dynamics/SingleDofJoint.h | 38 ++-- dart/dynamics/SoftBodyNode.h | 86 +++---- dart/dynamics/TranslationalJoint.h | 14 +- dart/dynamics/UniversalJoint.h | 14 +- dart/dynamics/WeldJoint.h | 22 +- dart/dynamics/ZeroDofJoint.h | 210 +++++++++--------- dart/gui/GraphWindow.h | 4 +- dart/gui/OpenGLRenderInterface.h | 56 ++--- dart/gui/SimWindow.h | 6 +- dart/gui/SoftSimWindow.h | 2 +- dart/gui/Win2D.h | 10 +- dart/gui/Win3D.h | 12 +- dart/gui/osg/DefaultEventHandler.h | 6 +- dart/gui/osg/DragAndDrop.h | 4 +- dart/gui/osg/MouseEventHandler.h | 2 +- dart/gui/osg/TrackballManipulator.h | 12 +- dart/integration/EulerIntegrator.h | 6 +- dart/integration/RK4Integrator.h | 2 +- .../integration/SemiImplicitEulerIntegrator.h | 6 +- dart/optimizer/Function.h | 16 +- dart/optimizer/GradientDescentSolver.h | 6 +- dart/optimizer/ipopt/IpoptSolver.h | 134 +++++------ unittests/testConstraint.cpp | 2 +- unittests/testDynamics.cpp | 2 +- unittests/testJoints.cpp | 2 +- unittests/testOptimizer.cpp | 12 +- unittests/testSoftDynamics.cpp | 2 +- 64 files changed, 542 insertions(+), 537 deletions(-) diff --git a/apps/addDeleteSkels/MyWindow.h b/apps/addDeleteSkels/MyWindow.h index cb50f4a662981..d440b2c656235 100644 --- a/apps/addDeleteSkels/MyWindow.h +++ b/apps/addDeleteSkels/MyWindow.h @@ -51,10 +51,10 @@ class MyWindow : public dart::gui::SimWindow { virtual ~MyWindow(); /// \brief - virtual void drawWorld() const override; + void drawWorld() const override; /// \brief - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; /// \brief void spawnCube( diff --git a/apps/atlasSimbicon/MyWindow.h b/apps/atlasSimbicon/MyWindow.h index 222be0bd73f33..bbf19a732b0fc 100644 --- a/apps/atlasSimbicon/MyWindow.h +++ b/apps/atlasSimbicon/MyWindow.h @@ -54,13 +54,13 @@ class MyWindow : public dart::gui::SimWindow virtual ~MyWindow(); // Documentation inherited - virtual void timeStepping(); + void timeStepping() override; // Documentation inherited - virtual void drawSkels(); + void drawSkels() override; // Documentation inherited - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; private: /// \brief External force to exert on Atlas robot diff --git a/apps/atlasSimbicon/TerminalCondition.h b/apps/atlasSimbicon/TerminalCondition.h index 9db7b03dd1292..0f52cf358f37d 100644 --- a/apps/atlasSimbicon/TerminalCondition.h +++ b/apps/atlasSimbicon/TerminalCondition.h @@ -77,7 +77,7 @@ class TimerCondition : public TerminalCondition virtual ~TimerCondition(); // Documentation inherited. - virtual bool isSatisfied(); + bool isSatisfied() override; protected: /// \brief Duration @@ -96,7 +96,7 @@ class BodyContactCondition : public TerminalCondition virtual ~BodyContactCondition(); // Documentation inherited. - virtual bool isSatisfied(); + bool isSatisfied() override; protected: /// \brief Body node to be tested diff --git a/apps/bipedStand/MyWindow.h b/apps/bipedStand/MyWindow.h index eea5a1aa15efa..a81d71ecbea30 100644 --- a/apps/bipedStand/MyWindow.h +++ b/apps/bipedStand/MyWindow.h @@ -52,9 +52,9 @@ class MyWindow : public dart::gui::SimWindow { MyWindow(); virtual ~MyWindow(); - virtual void timeStepping(); - virtual void drawWorld() const override; - virtual void keyboard(unsigned char _key, int _x, int _y); + void timeStepping() override; + void drawWorld() const override; + void keyboard(unsigned char _key, int _x, int _y) override; void setController(Controller* _controller); diff --git a/apps/hardcodedDesign/MyWindow.h b/apps/hardcodedDesign/MyWindow.h index d9bca07895bd1..6560476d46ecb 100644 --- a/apps/hardcodedDesign/MyWindow.h +++ b/apps/hardcodedDesign/MyWindow.h @@ -59,10 +59,10 @@ class MyWindow : public dart::gui::SimWindow { } /// \brief Draw the skeleton - virtual void draw(); + void draw() override; /// \brief Move the joints with the {1,2,3} keys and '-' to change direction - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; /// \brief Hardcoded skeleton dart::dynamics::SkeletonPtr skel; diff --git a/apps/hybridDynamics/MyWindow.h b/apps/hybridDynamics/MyWindow.h index b8190d1df9093..f45c820142c78 100644 --- a/apps/hybridDynamics/MyWindow.h +++ b/apps/hybridDynamics/MyWindow.h @@ -51,13 +51,13 @@ class MyWindow : public dart::gui::SimWindow virtual ~MyWindow(); /// \brief - virtual void timeStepping(); + void timeStepping() override; /// \brief - virtual void drawWorld() const override; + void drawWorld() const override; /// \brief - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; private: bool mHarnessOn; diff --git a/apps/jointConstraints/MyWindow.h b/apps/jointConstraints/MyWindow.h index fd17a7dc0a181..efc397bddd7fe 100644 --- a/apps/jointConstraints/MyWindow.h +++ b/apps/jointConstraints/MyWindow.h @@ -59,11 +59,11 @@ class MyWindow : public dart::gui::SimWindow } virtual ~MyWindow() {} - virtual void timeStepping(); - virtual void drawSkels(); - // virtual void displayTimer(int _val); - // virtual void draw(); - virtual void keyboard(unsigned char key, int x, int y); + void timeStepping() override; + void drawSkels() override; + // void displayTimer(int _val) override; + // void draw() override; + void keyboard(unsigned char key, int x, int y) override; void setController(Controller* _controller) { diff --git a/apps/mixedChain/MyWindow.h b/apps/mixedChain/MyWindow.h index 6a420ac68e3e5..a428a22999cf7 100644 --- a/apps/mixedChain/MyWindow.h +++ b/apps/mixedChain/MyWindow.h @@ -57,13 +57,13 @@ class MyWindow : public dart::gui::SoftSimWindow virtual ~MyWindow(); /// \brief - virtual void timeStepping(); + void timeStepping() override; /// \brief - virtual void keyboard(unsigned char key, int x, int y); + void keyboard(unsigned char key, int x, int y) override; /// \brief - virtual void drawWorld() const override; + void drawWorld() const override; private: /// \brief diff --git a/apps/operationalSpaceControl/MyWindow.h b/apps/operationalSpaceControl/MyWindow.h index d515bbb4301b8..56a4433d7a991 100644 --- a/apps/operationalSpaceControl/MyWindow.h +++ b/apps/operationalSpaceControl/MyWindow.h @@ -53,13 +53,13 @@ class MyWindow : public dart::gui::SimWindow virtual ~MyWindow(); // Documentation inherited - virtual void timeStepping(); + void timeStepping() override; // Documentation inherited - virtual void drawWorld() const override; + void drawWorld() const override; // Documentation inherited - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; private: /// \brief Operational space controller diff --git a/apps/rigidChain/MyWindow.h b/apps/rigidChain/MyWindow.h index a887235932e12..a9d5b5409c6c1 100644 --- a/apps/rigidChain/MyWindow.h +++ b/apps/rigidChain/MyWindow.h @@ -47,7 +47,7 @@ class MyWindow : public dart::gui::SimWindow { virtual ~MyWindow(); - virtual void timeStepping(); + void timeStepping() override; private: Eigen::VectorXd computeDamping(); diff --git a/apps/rigidCubes/MyWindow.h b/apps/rigidCubes/MyWindow.h index e6e9abb604a93..f91e502145437 100644 --- a/apps/rigidCubes/MyWindow.h +++ b/apps/rigidCubes/MyWindow.h @@ -51,13 +51,13 @@ class MyWindow : public dart::gui::SimWindow { virtual ~MyWindow(); /// \brief - virtual void timeStepping(); + void timeStepping() override; /// \brief - virtual void drawWorld() const override; + void drawWorld() const override; /// \brief - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; private: /// \brief diff --git a/apps/rigidLoop/MyWindow.h b/apps/rigidLoop/MyWindow.h index 7a7da3a1de62f..18b1e24b12f5d 100644 --- a/apps/rigidLoop/MyWindow.h +++ b/apps/rigidLoop/MyWindow.h @@ -46,11 +46,11 @@ class MyWindow : public dart::gui::SimWindow MyWindow() : SimWindow() {} virtual ~MyWindow() {} - virtual void timeStepping(); - // virtual void drawSkels(); - // virtual void displayTimer(int _val); - // virtual void draw(); - // virtual void keyboard(unsigned char key, int x, int y); + void timeStepping() override; + // void drawSkels() override; + // void displayTimer(int _val) override; + // void draw() override; + // void keyboard(unsigned char key, int x, int y) override; private: Eigen::VectorXd computeDamping(); diff --git a/apps/rigidShapes/MyWindow.h b/apps/rigidShapes/MyWindow.h index 2a8c34de7f9fd..9e314b1846c80 100644 --- a/apps/rigidShapes/MyWindow.h +++ b/apps/rigidShapes/MyWindow.h @@ -57,13 +57,13 @@ class MyWindow : public dart::gui::SimWindow virtual ~MyWindow(); // Documentation inherited - virtual void timeStepping() override; + void timeStepping() override; // Documentation inherited - virtual void keyboard(unsigned char key, int x, int y) override; + void keyboard(unsigned char key, int x, int y) override; // Documentation inherited - virtual void drawWorld() const override; + void drawWorld() const override; /// Spawn a box into the world void spawnBox( diff --git a/apps/softBodies/MyWindow.h b/apps/softBodies/MyWindow.h index f365ca7ab153f..f83c2621678b6 100644 --- a/apps/softBodies/MyWindow.h +++ b/apps/softBodies/MyWindow.h @@ -57,13 +57,13 @@ class MyWindow : public dart::gui::SoftSimWindow virtual ~MyWindow(); /// \brief - virtual void timeStepping(); + void timeStepping() override; /// \brief - virtual void keyboard(unsigned char key, int x, int y); + void keyboard(unsigned char key, int x, int y) override; /// \brief - virtual void drawWorld() const override; + void drawWorld() const override; private: /// \brief diff --git a/apps/vehicle/MyWindow.h b/apps/vehicle/MyWindow.h index b2f7308be40b9..4d8d9f41bef4e 100644 --- a/apps/vehicle/MyWindow.h +++ b/apps/vehicle/MyWindow.h @@ -51,13 +51,13 @@ class MyWindow : public dart::gui::SimWindow { virtual ~MyWindow(); /// \brief - virtual void timeStepping(); + void timeStepping() override; /// \brief - virtual void drawWorld() const override; + void drawWorld() const override; /// \brief - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; private: /// \brief diff --git a/dart/common/sub_ptr.h b/dart/common/sub_ptr.h index c32bc4cca0d90..36bbc1362ee56 100644 --- a/dart/common/sub_ptr.h +++ b/dart/common/sub_ptr.h @@ -83,8 +83,7 @@ class sub_ptr : public Observer protected: - virtual void handleDestructionNotification( - const Subject* _subject) override; + void handleDestructionNotification(const Subject* _subject) override; /// Store the pointer to the full object T* mT; diff --git a/dart/constraint/BallJointConstraint.h b/dart/constraint/BallJointConstraint.h index bca05ea45c29b..d555be87c17a2 100644 --- a/dart/constraint/BallJointConstraint.h +++ b/dart/constraint/BallJointConstraint.h @@ -72,34 +72,34 @@ class BallJointConstraint : public JointConstraint //---------------------------------------------------------------------------- // Documentation inherited - virtual void update(); + void update() override; // Documentation inherited - virtual void getInformation(ConstraintInfo* _lcp); + void getInformation(ConstraintInfo* _lcp) override; // Documentation inherited - virtual void applyUnitImpulse(size_t _index); + void applyUnitImpulse(size_t _index) override; // Documentation inherited - virtual void getVelocityChange(double* _vel, bool _withCfm); + void getVelocityChange(double* _vel, bool _withCfm) override; // Documentation inherited - virtual void excite(); + void excite() override; // Documentation inherited - virtual void unexcite(); + void unexcite() override; // Documentation inherited - virtual void applyImpulse(double* _lambda); + void applyImpulse(double* _lambda) override; // Documentation inherited - virtual bool isActive() const; + bool isActive() const override; // Documentation inherited - virtual dynamics::SkeletonPtr getRootSkeleton() const; + dynamics::SkeletonPtr getRootSkeleton() const override; // Documentation inherited - virtual void uniteSkeletons(); + void uniteSkeletons() override; private: /// Offset from the origin of body frame 1 to the ball joint position where diff --git a/dart/constraint/ConstraintBase.cpp b/dart/constraint/ConstraintBase.cpp index 15085acd69695..591829489033a 100644 --- a/dart/constraint/ConstraintBase.cpp +++ b/dart/constraint/ConstraintBase.cpp @@ -63,6 +63,12 @@ size_t ConstraintBase::getDimension() const return mDim; } +//============================================================================== +void ConstraintBase::uniteSkeletons() +{ + // Do nothing +} + //============================================================================== dynamics::SkeletonPtr ConstraintBase::compressPath( dynamics::SkeletonPtr _skeleton) diff --git a/dart/constraint/ConstraintBase.h b/dart/constraint/ConstraintBase.h index c063f13856609..20956a5302181 100644 --- a/dart/constraint/ConstraintBase.h +++ b/dart/constraint/ConstraintBase.h @@ -109,7 +109,7 @@ class ConstraintBase virtual dynamics::SkeletonPtr getRootSkeleton() const = 0; /// - virtual void uniteSkeletons() {} + virtual void uniteSkeletons(); /// static dynamics::SkeletonPtr compressPath(dynamics::SkeletonPtr _skeleton); diff --git a/dart/constraint/ContactConstraint.h b/dart/constraint/ContactConstraint.h index fcb6b1f491d4d..875d9761d51db 100644 --- a/dart/constraint/ContactConstraint.h +++ b/dart/constraint/ContactConstraint.h @@ -108,34 +108,34 @@ class ContactConstraint : public ConstraintBase //---------------------------------------------------------------------------- // Documentation inherited - virtual void update(); + void update() override; // Documentation inherited - virtual void getInformation(ConstraintInfo* _info); + void getInformation(ConstraintInfo* _info) override; // Documentation inherited - virtual void applyUnitImpulse(size_t _idx); + void applyUnitImpulse(size_t _idx) override; // Documentation inherited - virtual void getVelocityChange(double* _vel, bool _withCfm); + void getVelocityChange(double* _vel, bool _withCfm) override; // Documentation inherited - virtual void excite(); + void excite() override; // Documentation inherited - virtual void unexcite(); + void unexcite() override; // Documentation inherited - virtual void applyImpulse(double* _lambda); + void applyImpulse(double* _lambda) override; // Documentation inherited - virtual dynamics::SkeletonPtr getRootSkeleton() const; + dynamics::SkeletonPtr getRootSkeleton() const override; // Documentation inherited - virtual void uniteSkeletons(); + void uniteSkeletons() override; // Documentation inherited - virtual bool isActive() const; + bool isActive() const override; private: /// Get change in relative velocity at contact point due to external impulse diff --git a/dart/constraint/DantzigLCPSolver.h b/dart/constraint/DantzigLCPSolver.h index 5595a1b271599..60e1e99623ff3 100644 --- a/dart/constraint/DantzigLCPSolver.h +++ b/dart/constraint/DantzigLCPSolver.h @@ -57,7 +57,7 @@ class DantzigLCPSolver : public LCPSolver virtual ~DantzigLCPSolver(); // Documentation inherited - virtual void solve(ConstrainedGroup* _group); + void solve(ConstrainedGroup* _group) override; #ifndef NDEBUG private: diff --git a/dart/constraint/JointCoulombFrictionConstraint.h b/dart/constraint/JointCoulombFrictionConstraint.h index 8d481b929fc1e..09e6103e6836b 100644 --- a/dart/constraint/JointCoulombFrictionConstraint.h +++ b/dart/constraint/JointCoulombFrictionConstraint.h @@ -81,31 +81,31 @@ class JointCoulombFrictionConstraint : public ConstraintBase //---------------------------------------------------------------------------- // Documentation inherited - virtual void update(); + void update() override; // Documentation inherited - virtual void getInformation(ConstraintInfo* _lcp); + void getInformation(ConstraintInfo* _lcp) override; // Documentation inherited - virtual void applyUnitImpulse(size_t _index); + void applyUnitImpulse(size_t _index) override; // Documentation inherited - virtual void getVelocityChange(double* _delVel, bool _withCfm); + void getVelocityChange(double* _delVel, bool _withCfm) override; // Documentation inherited - virtual void excite(); + void excite() override; // Documentation inherited - virtual void unexcite(); + void unexcite() override; // Documentation inherited - virtual void applyImpulse(double* _lambda); + void applyImpulse(double* _lambda) override; // Documentation inherited - virtual dynamics::SkeletonPtr getRootSkeleton() const; + dynamics::SkeletonPtr getRootSkeleton() const override; // Documentation inherited - virtual bool isActive() const; + bool isActive() const override; private: /// diff --git a/dart/constraint/JointLimitConstraint.h b/dart/constraint/JointLimitConstraint.h index 8a4721f209d4b..6886ca7687220 100644 --- a/dart/constraint/JointLimitConstraint.h +++ b/dart/constraint/JointLimitConstraint.h @@ -100,31 +100,31 @@ class JointLimitConstraint : public ConstraintBase //---------------------------------------------------------------------------- // Documentation inherited - virtual void update(); + void update() override; // Documentation inherited - virtual void getInformation(ConstraintInfo* _lcp); + void getInformation(ConstraintInfo* _lcp) override; // Documentation inherited - virtual void applyUnitImpulse(size_t _index); + void applyUnitImpulse(size_t _index) override; // Documentation inherited - virtual void getVelocityChange(double* _delVel, bool _withCfm); + void getVelocityChange(double* _delVel, bool _withCfm) override; // Documentation inherited - virtual void excite(); + void excite() override; // Documentation inherited - virtual void unexcite(); + void unexcite() override; // Documentation inherited - virtual void applyImpulse(double* _lambda); + void applyImpulse(double* _lambda) override; // Documentation inherited - virtual dynamics::SkeletonPtr getRootSkeleton() const; + dynamics::SkeletonPtr getRootSkeleton() const override; // Documentation inherited - virtual bool isActive() const; + bool isActive() const override; private: /// diff --git a/dart/constraint/PGSLCPSolver.h b/dart/constraint/PGSLCPSolver.h index 6e65ee24380d4..64480092880c3 100644 --- a/dart/constraint/PGSLCPSolver.h +++ b/dart/constraint/PGSLCPSolver.h @@ -56,7 +56,7 @@ class PGSLCPSolver : public LCPSolver virtual ~PGSLCPSolver(); // Documentation inherited - virtual void solve(ConstrainedGroup* _group); + void solve(ConstrainedGroup* _group) override; #ifndef NDEBUG private: diff --git a/dart/constraint/ServoMotorConstraint.h b/dart/constraint/ServoMotorConstraint.h index cea5b5e90b3b0..8e9820ffc4225 100644 --- a/dart/constraint/ServoMotorConstraint.h +++ b/dart/constraint/ServoMotorConstraint.h @@ -81,31 +81,31 @@ class ServoMotorConstraint : public ConstraintBase //---------------------------------------------------------------------------- // Documentation inherited - virtual void update(); + void update() override; // Documentation inherited - virtual void getInformation(ConstraintInfo* lcp); + void getInformation(ConstraintInfo* lcp) override; // Documentation inherited - virtual void applyUnitImpulse(size_t index); + void applyUnitImpulse(size_t index) override; // Documentation inherited - virtual void getVelocityChange(double* delVel, bool withCfm); + void getVelocityChange(double* delVel, bool withCfm) override; // Documentation inherited - virtual void excite(); + void excite() override; // Documentation inherited - virtual void unexcite(); + void unexcite() override; // Documentation inherited - virtual void applyImpulse(double* lambda); + void applyImpulse(double* lambda) override; // Documentation inherited - virtual dynamics::SkeletonPtr getRootSkeleton() const; + dynamics::SkeletonPtr getRootSkeleton() const override; // Documentation inherited - virtual bool isActive() const; + bool isActive() const override; private: /// diff --git a/dart/constraint/SoftContactConstraint.h b/dart/constraint/SoftContactConstraint.h index d490b7b79edc8..ca7839564b2f1 100644 --- a/dart/constraint/SoftContactConstraint.h +++ b/dart/constraint/SoftContactConstraint.h @@ -114,34 +114,34 @@ class SoftContactConstraint : public ConstraintBase //---------------------------------------------------------------------------- // Documentation inherited - virtual void update(); + void update() override; // Documentation inherited - virtual void getInformation(ConstraintInfo* _info); + void getInformation(ConstraintInfo* _info) override; // Documentation inherited - virtual void applyUnitImpulse(size_t _idx); + void applyUnitImpulse(size_t _idx) override; // Documentation inherited - virtual void getVelocityChange(double* _vel, bool _withCfm); + void getVelocityChange(double* _vel, bool _withCfm) override; // Documentation inherited - virtual void excite(); + void excite() override; // Documentation inherited - virtual void unexcite(); + void unexcite() override; // Documentation inherited - virtual void applyImpulse(double* _lambda); + void applyImpulse(double* _lambda) override; // Documentation inherited - virtual dynamics::SkeletonPtr getRootSkeleton() const; + dynamics::SkeletonPtr getRootSkeleton() const override; // Documentation inherited - virtual void uniteSkeletons(); + void uniteSkeletons() override; // Documentation inherited - virtual bool isActive() const; + bool isActive() const override; private: /// Get change in relative velocity at contact point due to external impulse diff --git a/dart/constraint/WeldJointConstraint.h b/dart/constraint/WeldJointConstraint.h index fb6a952bb0964..50b31f6b3f77d 100644 --- a/dart/constraint/WeldJointConstraint.h +++ b/dart/constraint/WeldJointConstraint.h @@ -65,34 +65,34 @@ class WeldJointConstraint : public JointConstraint //---------------------------------------------------------------------------- // Documentation inherited - virtual void update(); + void update() override; // Documentation inherited - virtual void getInformation(ConstraintInfo* _lcp); + void getInformation(ConstraintInfo* _lcp) override; // Documentation inherited - virtual void applyUnitImpulse(size_t _index); + void applyUnitImpulse(size_t _index) override; // Documentation inherited - virtual void getVelocityChange(double* _vel, bool _withCfm); + void getVelocityChange(double* _vel, bool _withCfm) override; // Documentation inherited - virtual void excite(); + void excite() override; // Documentation inherited - virtual void unexcite(); + void unexcite() override; // Documentation inherited - virtual void applyImpulse(double* _lambda); + void applyImpulse(double* _lambda) override; // Documentation inherited - virtual bool isActive() const; + bool isActive() const override; // Documentation inherited - virtual dynamics::SkeletonPtr getRootSkeleton() const; + dynamics::SkeletonPtr getRootSkeleton() const override; // Documentation inherited - virtual void uniteSkeletons(); + void uniteSkeletons() override; private: /// diff --git a/dart/dynamics/Branch.h b/dart/dynamics/Branch.h index 308f79d21808a..7d79ee3720ba4 100644 --- a/dart/dynamics/Branch.h +++ b/dart/dynamics/Branch.h @@ -85,7 +85,7 @@ class Branch : public Linkage const std::string& _name = "Branch"); // Documentation inherited - virtual void update(); + void update() override; /// The original number of child nodes for each BodyNode of this Branch std::vector mNumChildNodes; diff --git a/dart/dynamics/EndEffector.h b/dart/dynamics/EndEffector.h index 190487e8c9d24..0dd263972ef0d 100644 --- a/dart/dynamics/EndEffector.h +++ b/dart/dynamics/EndEffector.h @@ -149,7 +149,7 @@ class EndEffector final : //---------------------------------------------------------------------------- // Documentation inherited - virtual void notifyTransformUpdate() override; + void notifyTransformUpdate() override; /// \} diff --git a/dart/dynamics/EulerJoint.h b/dart/dynamics/EulerJoint.h index 74664b652b2b9..43fd233d45f12 100644 --- a/dart/dynamics/EulerJoint.h +++ b/dart/dynamics/EulerJoint.h @@ -82,13 +82,13 @@ class EulerJoint : public detail::EulerJointBase EulerJoint& operator=(const EulerJoint& _otherJoint); // Documentation inherited - virtual const std::string& getType() const override; + const std::string& getType() const override; /// Get joint type for this class static const std::string& getStaticType(); // Documentation inherited - virtual bool isCyclic(size_t _index) const override; + bool isCyclic(size_t _index) const override; /// Set the axis order /// \param[in] _order Axis order @@ -156,22 +156,22 @@ class EulerJoint : public detail::EulerJointBase EulerJoint(const Properties& properties); // Documentation inherited - virtual Joint* clone() const override; + Joint* clone() const override; using MultiDofJoint::getLocalJacobianStatic; /// Set the names of this joint's DegreesOfFreedom. Used during construction /// and when axis order is changed. - virtual void updateDegreeOfFreedomNames() override; + void updateDegreeOfFreedomNames() override; // Documentation inherited - virtual void updateLocalTransform() const override; + void updateLocalTransform() const override; // Documentation inherited - virtual void updateLocalJacobian(bool =true) const override; + void updateLocalJacobian(bool =true) const override; // Documentation inherited - virtual void updateLocalJacobianTimeDeriv() const override; + void updateLocalJacobianTimeDeriv() const override; public: // To get byte-aligned Eigen vectors diff --git a/dart/dynamics/FreeJoint.h b/dart/dynamics/FreeJoint.h index 50c2cc685ebf9..7e1481122f9f2 100644 --- a/dart/dynamics/FreeJoint.h +++ b/dart/dynamics/FreeJoint.h @@ -70,13 +70,13 @@ class FreeJoint : public MultiDofJoint<6> Properties getFreeJointProperties() const; // Documentation inherited - virtual const std::string& getType() const override; + const std::string& getType() const override; /// Get joint type for this class static const std::string& getStaticType(); // Documentation inherited - virtual bool isCyclic(size_t _index) const override; + bool isCyclic(size_t _index) const override; /// Convert a transform into a 6D vector that can be used to set the positions /// of a FreeJoint. The positions returned by this function will result in a diff --git a/dart/dynamics/LineSegmentShape.h b/dart/dynamics/LineSegmentShape.h index 860c29b268453..f1729c0ed65ad 100644 --- a/dart/dynamics/LineSegmentShape.h +++ b/dart/dynamics/LineSegmentShape.h @@ -102,7 +102,7 @@ class LineSegmentShape : public Shape /// The returned inertia matrix will be like a very thin cylinder. The _mass /// will be evenly distributed across all lines. - virtual Eigen::Matrix3d computeInertia(double mass) const override; + Eigen::Matrix3d computeInertia(double mass) const override; // TODO(MXG): Consider supporting colors-per-vertex diff --git a/dart/dynamics/MultiDofJoint.h b/dart/dynamics/MultiDofJoint.h index 12ed7d27802e6..c51cfefc93fd1 100644 --- a/dart/dynamics/MultiDofJoint.h +++ b/dart/dynamics/MultiDofJoint.h @@ -129,29 +129,29 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF const std::string& getDofName(size_t _index) const override; // Documentation inherited - virtual size_t getIndexInSkeleton(size_t _index) const override; + size_t getIndexInSkeleton(size_t _index) const override; // Documentation inherited - virtual size_t getIndexInTree(size_t _index) const override; + size_t getIndexInTree(size_t _index) const override; //---------------------------------------------------------------------------- // Command //---------------------------------------------------------------------------- // Documentation inherited - virtual void setCommand(size_t _index, double command) override; + void setCommand(size_t _index, double command) override; // Documentation inherited - virtual double getCommand(size_t _index) const override; + double getCommand(size_t _index) const override; // Documentation inherited - virtual void setCommands(const Eigen::VectorXd& _commands) override; + void setCommands(const Eigen::VectorXd& _commands) override; // Documentation inherited - virtual Eigen::VectorXd getCommands() const override; + Eigen::VectorXd getCommands() const override; // Documentation inherited - virtual void resetCommands() override; + void resetCommands() override; //---------------------------------------------------------------------------- // Position @@ -182,7 +182,7 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF double getPositionUpperLimit(size_t _index) const override; // Documentation inherited - virtual bool hasPositionLimit(size_t _index) const override; + bool hasPositionLimit(size_t _index) const override; // Documentation inherited void resetPosition(size_t _index) override; @@ -343,36 +343,36 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF //---------------------------------------------------------------------------- // Documentation inherited - virtual void setVelocityChange(size_t _index, double _velocityChange) override; + void setVelocityChange(size_t _index, double _velocityChange) override; // Documentation inherited - virtual double getVelocityChange(size_t _index) const override; + double getVelocityChange(size_t _index) const override; // Documentation inherited - virtual void resetVelocityChanges() override; + void resetVelocityChanges() override; //---------------------------------------------------------------------------- // Constraint impulse //---------------------------------------------------------------------------- // Documentation inherited - virtual void setConstraintImpulse(size_t _index, double _impulse) override; + void setConstraintImpulse(size_t _index, double _impulse) override; // Documentation inherited - virtual double getConstraintImpulse(size_t _index) const override; + double getConstraintImpulse(size_t _index) const override; // Documentation inherited - virtual void resetConstraintImpulses() override; + void resetConstraintImpulses() override; //---------------------------------------------------------------------------- // Integration and finite difference //---------------------------------------------------------------------------- // Documentation inherited - virtual void integratePositions(double _dt) override; + void integratePositions(double _dt) override; // Documentation inherited - virtual void integrateVelocities(double _dt) override; + void integrateVelocities(double _dt) override; // Documentation inherited Eigen::VectorXd getPositionDifferences( @@ -387,38 +387,38 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF //---------------------------------------------------------------------------- // Documentation inherited - virtual void setSpringStiffness(size_t _index, double _k) override; + void setSpringStiffness(size_t _index, double _k) override; // Documentation inherited - virtual double getSpringStiffness(size_t _index) const override; + double getSpringStiffness(size_t _index) const override; // Documentation inherited - virtual void setRestPosition(size_t _index, double _q0) override; + void setRestPosition(size_t _index, double _q0) override; // Documentation inherited - virtual double getRestPosition(size_t _index) const override; + double getRestPosition(size_t _index) const override; // Documentation inherited - virtual void setDampingCoefficient(size_t _index, double _d) override; + void setDampingCoefficient(size_t _index, double _d) override; // Documentation inherited - virtual double getDampingCoefficient(size_t _index) const override; + double getDampingCoefficient(size_t _index) const override; // Documentation inherited - virtual void setCoulombFriction(size_t _index, double _friction) override; + void setCoulombFriction(size_t _index, double _friction) override; // Documentation inherited - virtual double getCoulombFriction(size_t _index) const override; + double getCoulombFriction(size_t _index) const override; /// \} //---------------------------------------------------------------------------- // Documentation inherited - virtual double getPotentialEnergy() const override; + double getPotentialEnergy() const override; // Documentation inherited - virtual Eigen::Vector6d getBodyConstraintWrench() const override; + Eigen::Vector6d getBodyConstraintWrench() const override; protected: @@ -477,13 +477,13 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF const Eigen::Vector6d& _childVelocity) override; // Documentation inherited - virtual void addAccelerationTo(Eigen::Vector6d& _acc) override; + void addAccelerationTo(Eigen::Vector6d& _acc) override; // Documentation inherited - virtual void addVelocityChangeTo(Eigen::Vector6d& _velocityChange) override; + void addVelocityChangeTo(Eigen::Vector6d& _velocityChange) override; // Documentation inherited - virtual void addChildArtInertiaTo( + void addChildArtInertiaTo( Eigen::Matrix6d& _parentArtInertia, const Eigen::Matrix6d& _childArtInertia) override; @@ -535,25 +535,25 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF const Eigen::Vector6d& _velocityChange) override; // Documentation inherited - virtual void updateForceID(const Eigen::Vector6d& _bodyForce, - double _timeStep, - bool _withDampingForces, - bool _withSpringForces) override; + void updateForceID(const Eigen::Vector6d& _bodyForce, + double _timeStep, + bool _withDampingForces, + bool _withSpringForces) override; // Documentation inherited - virtual void updateForceFD(const Eigen::Vector6d& _bodyForce, - double _timeStep, - bool _withDampingForces, - bool _withSpringForces) override; + void updateForceFD(const Eigen::Vector6d& _bodyForce, + double _timeStep, + bool _withDampingForces, + bool _withSpringForces) override; // Documentation inherited - virtual void updateImpulseID(const Eigen::Vector6d& _bodyImpulse) override; + void updateImpulseID(const Eigen::Vector6d& _bodyImpulse) override; // Documentation inherited - virtual void updateImpulseFD(const Eigen::Vector6d& _bodyImpulse) override; + void updateImpulseFD(const Eigen::Vector6d& _bodyImpulse) override; // Documentation inherited - virtual void updateConstrainedTerms(double _timeStep) override; + void updateConstrainedTerms(double _timeStep) override; /// \} diff --git a/dart/dynamics/PlanarJoint.h b/dart/dynamics/PlanarJoint.h index cc6d621a302cd..26bc0e63970dc 100644 --- a/dart/dynamics/PlanarJoint.h +++ b/dart/dynamics/PlanarJoint.h @@ -87,13 +87,13 @@ class PlanarJoint : public detail::PlanarJointBase PlanarJoint& operator=(const PlanarJoint& _otherJoint); // Documentation inherited - virtual const std::string& getType() const override; + const std::string& getType() const override; /// Get joint type for this class static const std::string& getStaticType(); // Documentation inherited - virtual bool isCyclic(size_t _index) const override; + bool isCyclic(size_t _index) const override; /// \brief Set plane type as XY-plane /// \param[in] _renameDofs If true, the names of dofs in this joint will be @@ -140,22 +140,22 @@ class PlanarJoint : public detail::PlanarJointBase PlanarJoint(const Properties& properties); // Documentation inherited - virtual Joint* clone() const override; + Joint* clone() const override; using MultiDofJoint::getLocalJacobianStatic; /// Set the names of this joint's DegreesOfFreedom. Used during construction /// and when the Plane type is changed. - virtual void updateDegreeOfFreedomNames() override; + void updateDegreeOfFreedomNames() override; // Documentation inherited - virtual void updateLocalTransform() const override; + void updateLocalTransform() const override; // Documentation inherited - virtual void updateLocalJacobian(bool =true) const override; + void updateLocalJacobian(bool =true) const override; // Documentation inherited - virtual void updateLocalJacobianTimeDeriv() const override; + void updateLocalJacobianTimeDeriv() const override; public: // To get byte-aligned Eigen vectors diff --git a/dart/dynamics/PrismaticJoint.h b/dart/dynamics/PrismaticJoint.h index 8416bdce12242..5b257000b1160 100644 --- a/dart/dynamics/PrismaticJoint.h +++ b/dart/dynamics/PrismaticJoint.h @@ -80,13 +80,13 @@ class PrismaticJoint : public detail::PrismaticJointBase PrismaticJoint& operator=(const PrismaticJoint& _otherJoint); // Documentation inherited - virtual const std::string& getType() const override; + const std::string& getType() const override; /// Get joint type for this class static const std::string& getStaticType(); // Documentation inherited - virtual bool isCyclic(size_t _index) const override; + bool isCyclic(size_t _index) const override; /// void setAxis(const Eigen::Vector3d& _axis); @@ -100,16 +100,16 @@ class PrismaticJoint : public detail::PrismaticJointBase PrismaticJoint(const Properties& properties); // Documentation inherited - virtual Joint* clone() const override; + Joint* clone() const override; // Documentation inherited - virtual void updateLocalTransform() const override; + void updateLocalTransform() const override; // Documentation inherited - virtual void updateLocalJacobian(bool _mandatory=true) const override; + void updateLocalJacobian(bool _mandatory=true) const override; // Documentation inherited - virtual void updateLocalJacobianTimeDeriv() const override; + void updateLocalJacobianTimeDeriv() const override; public: // To get byte-aligned Eigen vectors diff --git a/dart/dynamics/RevoluteJoint.h b/dart/dynamics/RevoluteJoint.h index 156e8a72f2505..bb633b0efc054 100644 --- a/dart/dynamics/RevoluteJoint.h +++ b/dart/dynamics/RevoluteJoint.h @@ -81,10 +81,10 @@ class RevoluteJoint : public detail::RevoluteJointBase RevoluteJoint& operator=(const RevoluteJoint& _otherJoint); // Documentation inherited - virtual const std::string& getType() const override; + const std::string& getType() const override; // Documentation inherited - virtual bool isCyclic(size_t _index) const override; + bool isCyclic(size_t _index) const override; /// Get joint type for this class static const std::string& getStaticType(); @@ -101,16 +101,16 @@ class RevoluteJoint : public detail::RevoluteJointBase RevoluteJoint(const Properties& properties); // Documentation inherited - virtual Joint* clone() const override; + Joint* clone() const override; // Documentation inherited - virtual void updateLocalTransform() const override; + void updateLocalTransform() const override; // Documentation inherited - virtual void updateLocalJacobian(bool _mandatory=true) const override; + void updateLocalJacobian(bool _mandatory=true) const override; // Documentation inherited - virtual void updateLocalJacobianTimeDeriv() const override; + void updateLocalJacobianTimeDeriv() const override; public: diff --git a/dart/dynamics/ScrewJoint.h b/dart/dynamics/ScrewJoint.h index 2a1726ba705fd..b6d7383b8ed73 100644 --- a/dart/dynamics/ScrewJoint.h +++ b/dart/dynamics/ScrewJoint.h @@ -81,13 +81,13 @@ class ScrewJoint : public detail::ScrewJointBase ScrewJoint& operator=(const ScrewJoint& _otherJoint); // Documentation inherited - virtual const std::string& getType() const override; + const std::string& getType() const override; /// Get joint type for this class static const std::string& getStaticType(); // Documentation inherited - virtual bool isCyclic(size_t _index) const override; + bool isCyclic(size_t _index) const override; /// void setAxis(const Eigen::Vector3d& _axis); @@ -107,16 +107,16 @@ class ScrewJoint : public detail::ScrewJointBase ScrewJoint(const Properties& properties); // Documentation inherited - virtual Joint* clone() const override; + Joint* clone() const override; // Documentation inherited - virtual void updateLocalTransform() const override; + void updateLocalTransform() const override; // Documentation inherited - virtual void updateLocalJacobian(bool _mandatory=true) const override; + void updateLocalJacobian(bool _mandatory=true) const override; // Documentation inherited - virtual void updateLocalJacobianTimeDeriv() const override; + void updateLocalJacobianTimeDeriv() const override; public: // To get byte-aligned Eigen vectors diff --git a/dart/dynamics/SingleDofJoint.h b/dart/dynamics/SingleDofJoint.h index eefd025f2a742..5e88facb49fce 100644 --- a/dart/dynamics/SingleDofJoint.h +++ b/dart/dynamics/SingleDofJoint.h @@ -326,36 +326,36 @@ class SingleDofJoint : public detail::SingleDofJointBase //---------------------------------------------------------------------------- // Documentation inherited - virtual void setVelocityChange(size_t _index, double _velocityChange) override; + void setVelocityChange(size_t _index, double _velocityChange) override; // Documentation inherited - virtual double getVelocityChange(size_t _index) const override; + double getVelocityChange(size_t _index) const override; // Documentation inherited - virtual void resetVelocityChanges() override; + void resetVelocityChanges() override; //---------------------------------------------------------------------------- // Constraint impulse //---------------------------------------------------------------------------- // Documentation inherited - virtual void setConstraintImpulse(size_t _index, double _impulse) override; + void setConstraintImpulse(size_t _index, double _impulse) override; // Documentation inherited - virtual double getConstraintImpulse(size_t _index) const override; + double getConstraintImpulse(size_t _index) const override; // Documentation inherited - virtual void resetConstraintImpulses() override; + void resetConstraintImpulses() override; //---------------------------------------------------------------------------- // Integration and finite difference //---------------------------------------------------------------------------- // Documentation inherited - virtual void integratePositions(double _dt) override; + void integratePositions(double _dt) override; // Documentation inherited - virtual void integrateVelocities(double _dt) override; + void integrateVelocities(double _dt) override; // Documentation inherited Eigen::VectorXd getPositionDifferences( @@ -369,35 +369,35 @@ class SingleDofJoint : public detail::SingleDofJointBase //---------------------------------------------------------------------------- // Documentation inherited - virtual void setSpringStiffness(size_t _index, double _k) override; + void setSpringStiffness(size_t _index, double _k) override; // Documentation inherited - virtual double getSpringStiffness(size_t _index) const override; + double getSpringStiffness(size_t _index) const override; // Documentation inherited - virtual void setRestPosition(size_t _index, double _q0) override; + void setRestPosition(size_t _index, double _q0) override; // Documentation inherited - virtual double getRestPosition(size_t _index) const override; + double getRestPosition(size_t _index) const override; // Documentation inherited - virtual void setDampingCoefficient(size_t _index, double _d) override; + void setDampingCoefficient(size_t _index, double _d) override; // Documentation inherited - virtual double getDampingCoefficient(size_t _index) const override; + double getDampingCoefficient(size_t _index) const override; // Documentation inherited - virtual void setCoulombFriction(size_t _index, double _friction) override; + void setCoulombFriction(size_t _index, double _friction) override; // Documentation inherited - virtual double getCoulombFriction(size_t _index) const override; + double getCoulombFriction(size_t _index) const override; /// \} //---------------------------------------------------------------------------- /// Get potential energy - virtual double getPotentialEnergy() const override; + double getPotentialEnergy() const override; // Documentation inherited const math::Jacobian getLocalJacobian() const override; @@ -410,7 +410,7 @@ class SingleDofJoint : public detail::SingleDofJointBase const math::Jacobian getLocalJacobianTimeDeriv() const override; // Documentation inherited - virtual Eigen::Vector6d getBodyConstraintWrench() const override; + Eigen::Vector6d getBodyConstraintWrench() const override; protected: @@ -424,7 +424,7 @@ class SingleDofJoint : public detail::SingleDofJointBase std::string changeDofName(const std::string& name); // Documentation inherited - virtual void updateDegreeOfFreedomNames() override; + void updateDegreeOfFreedomNames() override; //---------------------------------------------------------------------------- /// \{ \name Recursive dynamics routines diff --git a/dart/dynamics/SoftBodyNode.h b/dart/dynamics/SoftBodyNode.h index 07ae366a5b413..a0130ba62daef 100644 --- a/dart/dynamics/SoftBodyNode.h +++ b/dart/dynamics/SoftBodyNode.h @@ -153,7 +153,7 @@ class SoftBodyNode : public detail::SoftBodyNodeBase size_t getNumFaces() const; // Documentation inherited. - virtual void clearConstraintImpulse() override; + void clearConstraintImpulse() override; protected: @@ -163,8 +163,8 @@ class SoftBodyNode : public detail::SoftBodyNodeBase /// Create a clone of this SoftBodyNode. This may only be called by the /// Skeleton class. - virtual BodyNode* clone(BodyNode* _parentBodyNode, Joint* _parentJoint, - bool cloneNodes) const override; + BodyNode* clone(BodyNode* _parentBodyNode, Joint* _parentJoint, + bool cloneNodes) const override; /// Used by SoftBodyAspect to have this SoftBodyNode reconstruct its /// SoftMeshShape @@ -174,7 +174,7 @@ class SoftBodyNode : public detail::SoftBodyNodeBase // Sub-functions for Recursive Kinematics Algorithms //-------------------------------------------------------------------------- // Documentation inherited. - virtual void init(const SkeletonPtr& _skeleton) override; + void init(const SkeletonPtr& _skeleton) override; // Documentation inherited. // virtual void aggregateGenCoords(std::vector* _genCoords); @@ -190,59 +190,59 @@ class SoftBodyNode : public detail::SoftBodyNodeBase void checkArticulatedInertiaUpdate() const; // Documentation inherited. - virtual void updateTransform() override; + void updateTransform() override; // Documentation inherited. - virtual void updateVelocity() override; + void updateVelocity() override; // Documentation inherited. - virtual void updatePartialAcceleration() const override; + void updatePartialAcceleration() const override; // Documentation inherited. - virtual void updateArtInertia(double _timeStep) const override; + void updateArtInertia(double _timeStep) const override; // Documentation inherited. - virtual void updateBiasForce(const Eigen::Vector3d& _gravity, - double _timeStep) override; + void updateBiasForce(const Eigen::Vector3d& _gravity, + double _timeStep) override; // Documentation inherited. - virtual void updateBiasImpulse() override; + void updateBiasImpulse() override; // Documentation inherited. - virtual void updateAccelerationID() override; + void updateAccelerationID() override; // Documentation inherited. - virtual void updateAccelerationFD() override; + void updateAccelerationFD() override; // Documentation inherited. - virtual void updateVelocityChangeFD() override; + void updateVelocityChangeFD() override; // Documentation inherited. - virtual void updateTransmittedForceID( + void updateTransmittedForceID( const Eigen::Vector3d& _gravity, bool _withExternalForces = false) override; // Documentation inherited. - virtual void updateTransmittedForceFD() override; + void updateTransmittedForceFD() override; // Documentation inherited. - virtual void updateTransmittedImpulse() override; + void updateTransmittedImpulse() override; // Documentation inherited. - virtual void updateJointForceID(double _timeStep, - bool _withDampingForces, - bool _withSpringForces) override; + void updateJointForceID(double _timeStep, + bool _withDampingForces, + bool _withSpringForces) override; // Documentation inherited. - virtual void updateJointForceFD(double _timeStep, - bool _withDampingForces, - bool _withSpringForces) override; + void updateJointForceFD(double _timeStep, + bool _withDampingForces, + bool _withSpringForces) override; // Documentation inherited. - virtual void updateJointImpulseFD() override; + void updateJointImpulseFD() override; // Documentation inherited. - virtual void updateConstrainedTerms(double _timeStep) override; + void updateConstrainedTerms(double _timeStep) override; /// \} @@ -251,52 +251,52 @@ class SoftBodyNode : public detail::SoftBodyNodeBase //---------------------------------------------------------------------------- // Documentation inherited. - virtual void updateMassMatrix() override; + void updateMassMatrix() override; // Documentation inherited. - virtual void aggregateMassMatrix(Eigen::MatrixXd& _MCol, size_t _col) override; + void aggregateMassMatrix(Eigen::MatrixXd& _MCol, size_t _col) override; // Documentation inherited. - virtual void aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, - double _timeStep) override; + void aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, + double _timeStep) override; // Documentation inherited. - virtual void updateInvMassMatrix() override; + void updateInvMassMatrix() override; // Documentation inherited. - virtual void updateInvAugMassMatrix() override; + void updateInvAugMassMatrix() override; // Documentation inherited. - virtual void aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col) override; + void aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col) override; // Documentation inherited. - virtual void aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col, - double _timeStep) override; + void aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col, + double _timeStep) override; // Documentation inherited. // TODO(JS): Not implemented yet. - virtual void aggregateCoriolisForceVector(Eigen::VectorXd& _C) override; + void aggregateCoriolisForceVector(Eigen::VectorXd& _C) override; // Documentation inherited. - virtual void aggregateGravityForceVector(Eigen::VectorXd& _g, - const Eigen::Vector3d& _gravity) override; + void aggregateGravityForceVector(Eigen::VectorXd& _g, + const Eigen::Vector3d& _gravity) override; // Documentation inherited. - virtual void updateCombinedVector() override; + void updateCombinedVector() override; // Documentation inherited. - virtual void aggregateCombinedVector(Eigen::VectorXd& _Cg, - const Eigen::Vector3d& _gravity) override; + void aggregateCombinedVector(Eigen::VectorXd& _Cg, + const Eigen::Vector3d& _gravity) override; // Documentation inherited. - virtual void aggregateExternalForces(Eigen::VectorXd& _Fext) override; + void aggregateExternalForces(Eigen::VectorXd& _Fext) override; /// \} // Documentation inherited. - virtual void clearExternalForces() override; + void clearExternalForces() override; - virtual void clearInternalForces() override; + void clearInternalForces() override; protected: diff --git a/dart/dynamics/TranslationalJoint.h b/dart/dynamics/TranslationalJoint.h index c2f19b50ccf9b..dc5254102a572 100644 --- a/dart/dynamics/TranslationalJoint.h +++ b/dart/dynamics/TranslationalJoint.h @@ -68,13 +68,13 @@ class TranslationalJoint : public MultiDofJoint<3> Properties getTranslationalJointProperties() const; // Documentation inherited - virtual const std::string& getType() const override; + const std::string& getType() const override; /// Get joint type for this class static const std::string& getStaticType(); // Documentation inherited - virtual bool isCyclic(size_t _index) const override; + bool isCyclic(size_t _index) const override; Eigen::Matrix getLocalJacobianStatic( const Eigen::Vector3d& _positions) const override; @@ -85,21 +85,21 @@ class TranslationalJoint : public MultiDofJoint<3> TranslationalJoint(const Properties& properties); // Documentation inherited - virtual Joint* clone() const override; + Joint* clone() const override; using MultiDofJoint::getLocalJacobianStatic; // Documentation inherited - virtual void updateDegreeOfFreedomNames() override; + void updateDegreeOfFreedomNames() override; // Documentation inherited - virtual void updateLocalTransform() const override; + void updateLocalTransform() const override; // Documentation inherited - virtual void updateLocalJacobian(bool _mandatory = true) const override; + void updateLocalJacobian(bool _mandatory = true) const override; // Documentation inherited - virtual void updateLocalJacobianTimeDeriv() const override; + void updateLocalJacobianTimeDeriv() const override; public: // To get byte-aligned Eigen vectors diff --git a/dart/dynamics/UniversalJoint.h b/dart/dynamics/UniversalJoint.h index ef9dc6bb9085f..e04c8a830f94d 100644 --- a/dart/dynamics/UniversalJoint.h +++ b/dart/dynamics/UniversalJoint.h @@ -81,13 +81,13 @@ class UniversalJoint : public detail::UniversalJointBase UniversalJoint& operator=(const UniversalJoint& _otherJoint); // Documentation inherited - virtual const std::string& getType() const override; + const std::string& getType() const override; /// Get joint type for this class static const std::string& getStaticType(); // Documentation inherited - virtual bool isCyclic(size_t _index) const override; + bool isCyclic(size_t _index) const override; /// void setAxis1(const Eigen::Vector3d& _axis); @@ -111,21 +111,21 @@ class UniversalJoint : public detail::UniversalJointBase UniversalJoint(const Properties& properties); // Documentation inherited - virtual Joint* clone() const override; + Joint* clone() const override; using MultiDofJoint::getLocalJacobianStatic; // Documentation inherited - virtual void updateDegreeOfFreedomNames() override; + void updateDegreeOfFreedomNames() override; // Documentation inherited - virtual void updateLocalTransform() const override; + void updateLocalTransform() const override; // Documentation inherited - virtual void updateLocalJacobian(bool =true) const override; + void updateLocalJacobian(bool =true) const override; // Documentation inherited - virtual void updateLocalJacobianTimeDeriv() const override; + void updateLocalJacobianTimeDeriv() const override; public: // To get byte-aligned Eigen vectors diff --git a/dart/dynamics/WeldJoint.h b/dart/dynamics/WeldJoint.h index dde3eb0e09943..998deb38b5e36 100644 --- a/dart/dynamics/WeldJoint.h +++ b/dart/dynamics/WeldJoint.h @@ -68,19 +68,19 @@ class WeldJoint : public ZeroDofJoint Properties getWeldJointProperties() const; // Documentation inherited - virtual const std::string& getType() const override; + const std::string& getType() const override; /// Get joint type for this class static const std::string& getStaticType(); // Documentation inherited - virtual bool isCyclic(size_t _index) const override; + bool isCyclic(size_t _index) const override; // Documentation inherited - virtual void setTransformFromParentBodyNode(const Eigen::Isometry3d& _T) override; + void setTransformFromParentBodyNode(const Eigen::Isometry3d& _T) override; // Documentation inherited - virtual void setTransformFromChildBodyNode(const Eigen::Isometry3d& _T) override; + void setTransformFromChildBodyNode(const Eigen::Isometry3d& _T) override; protected: @@ -88,29 +88,29 @@ class WeldJoint : public ZeroDofJoint WeldJoint(const Properties& properties); // Documentation inherited - virtual Joint* clone() const override; + Joint* clone() const override; //---------------------------------------------------------------------------- // Recursive algorithms //---------------------------------------------------------------------------- // Documentation inherited - virtual void updateLocalTransform() const override; + void updateLocalTransform() const override; // Documentation inherited - virtual void updateLocalSpatialVelocity() const override; + void updateLocalSpatialVelocity() const override; // Documentation inherited - virtual void updateLocalSpatialAcceleration() const override; + void updateLocalSpatialAcceleration() const override; // Documentation inherited - virtual void updateLocalPrimaryAcceleration() const override; + void updateLocalPrimaryAcceleration() const override; // Documentation inherited - virtual void updateLocalJacobian(bool =true) const override; + void updateLocalJacobian(bool =true) const override; // Documentation inherited - virtual void updateLocalJacobianTimeDeriv() const override; + void updateLocalJacobianTimeDeriv() const override; public: // To get byte-aligned Eigen vectors diff --git a/dart/dynamics/ZeroDofJoint.h b/dart/dynamics/ZeroDofJoint.h index 314d75e11b46e..ac24b0a196896 100644 --- a/dart/dynamics/ZeroDofJoint.h +++ b/dart/dynamics/ZeroDofJoint.h @@ -71,10 +71,10 @@ class ZeroDofJoint : public Joint //---------------------------------------------------------------------------- // Documentation inherited - virtual DegreeOfFreedom* getDof(size_t) override; + DegreeOfFreedom* getDof(size_t) override; // Documentation inherited - virtual const DegreeOfFreedom* getDof(size_t) const override; + const DegreeOfFreedom* getDof(size_t) const override; // Documentation inherited const std::string& setDofName(size_t, const std::string&, bool ) override; @@ -88,225 +88,225 @@ class ZeroDofJoint : public Joint const std::string& getDofName(size_t) const override; // Documentation inherited - virtual size_t getNumDofs() const override; + size_t getNumDofs() const override; // Documentation inherited - virtual size_t getIndexInSkeleton(size_t _index) const override; + size_t getIndexInSkeleton(size_t _index) const override; // Documentation inherited - virtual size_t getIndexInTree(size_t _index) const override; + size_t getIndexInTree(size_t _index) const override; //---------------------------------------------------------------------------- // Command //---------------------------------------------------------------------------- // Documentation inherited - virtual void setCommand(size_t _index, double _command) override; + void setCommand(size_t _index, double _command) override; // Documentation inherited - virtual double getCommand(size_t _index) const override; + double getCommand(size_t _index) const override; // Documentation inherited - virtual void setCommands(const Eigen::VectorXd& _commands) override; + void setCommands(const Eigen::VectorXd& _commands) override; // Documentation inherited - virtual Eigen::VectorXd getCommands() const override; + Eigen::VectorXd getCommands() const override; // Documentation inherited - virtual void resetCommands() override; + void resetCommands() override; //---------------------------------------------------------------------------- // Position //---------------------------------------------------------------------------- // Documentation inherited - virtual void setPosition(size_t, double) override; + void setPosition(size_t, double) override; // Documentation inherited - virtual double getPosition(size_t _index) const override; + double getPosition(size_t _index) const override; // Documentation inherited - virtual void setPositions(const Eigen::VectorXd& _positions) override; + void setPositions(const Eigen::VectorXd& _positions) override; // Documentation inherited - virtual Eigen::VectorXd getPositions() const override; + Eigen::VectorXd getPositions() const override; // Documentation inherited - virtual void setPositionLowerLimit(size_t _index, double _position) override; + void setPositionLowerLimit(size_t _index, double _position) override; // Documentation inherited - virtual double getPositionLowerLimit(size_t _index) const override; + double getPositionLowerLimit(size_t _index) const override; // Documentation inherited - virtual void setPositionUpperLimit(size_t _index, double _position) override; + void setPositionUpperLimit(size_t _index, double _position) override; // Documentation inherited - virtual double getPositionUpperLimit(size_t _index) const override; + double getPositionUpperLimit(size_t _index) const override; // Documentation inherited - virtual bool hasPositionLimit(size_t _index) const override; + bool hasPositionLimit(size_t _index) const override; // Documentation inherited - virtual void resetPosition(size_t _index) override; + void resetPosition(size_t _index) override; // Documentation inherited - virtual void resetPositions() override; + void resetPositions() override; // Documentation inherited - virtual void setInitialPosition(size_t _index, double _initial) override; + void setInitialPosition(size_t _index, double _initial) override; // Documentation inherited - virtual double getInitialPosition(size_t _index) const override; + double getInitialPosition(size_t _index) const override; // Documentation inherited - virtual void setInitialPositions(const Eigen::VectorXd& _initial) override; + void setInitialPositions(const Eigen::VectorXd& _initial) override; // Documentation inherited - virtual Eigen::VectorXd getInitialPositions() const override; + Eigen::VectorXd getInitialPositions() const override; //---------------------------------------------------------------------------- // Velocity //---------------------------------------------------------------------------- // Documentation inherited - virtual void setVelocity(size_t _index, double _velocity) override; + void setVelocity(size_t _index, double _velocity) override; // Documentation inherited - virtual double getVelocity(size_t _index) const override; + double getVelocity(size_t _index) const override; // Documentation inherited - virtual void setVelocities(const Eigen::VectorXd& _velocities) override; + void setVelocities(const Eigen::VectorXd& _velocities) override; // Documentation inherited - virtual Eigen::VectorXd getVelocities() const override; + Eigen::VectorXd getVelocities() const override; // Documentation inherited - virtual void setVelocityLowerLimit(size_t _index, double _velocity) override; + void setVelocityLowerLimit(size_t _index, double _velocity) override; // Documentation inherited - virtual double getVelocityLowerLimit(size_t _index) const override; + double getVelocityLowerLimit(size_t _index) const override; // Documentation inherited - virtual void setVelocityUpperLimit(size_t _index, double _velocity) override; + void setVelocityUpperLimit(size_t _index, double _velocity) override; // Documentation inherited - virtual double getVelocityUpperLimit(size_t _index) const override; + double getVelocityUpperLimit(size_t _index) const override; // Documentation inherited - virtual void resetVelocity(size_t _index) override; + void resetVelocity(size_t _index) override; // Documentation inherited - virtual void resetVelocities() override; + void resetVelocities() override; // Documentation inherited - virtual void setInitialVelocity(size_t _index, double _initial) override; + void setInitialVelocity(size_t _index, double _initial) override; // Documentation inherited - virtual double getInitialVelocity(size_t _index) const override; + double getInitialVelocity(size_t _index) const override; // Documentation inherited - virtual void setInitialVelocities(const Eigen::VectorXd& _initial) override; + void setInitialVelocities(const Eigen::VectorXd& _initial) override; // Documentation inherited - virtual Eigen::VectorXd getInitialVelocities() const override; + Eigen::VectorXd getInitialVelocities() const override; //---------------------------------------------------------------------------- // Acceleration //---------------------------------------------------------------------------- // Documentation inherited - virtual void setAcceleration(size_t _index, double _acceleration) override; + void setAcceleration(size_t _index, double _acceleration) override; // Documentation inherited - virtual double getAcceleration(size_t _index) const override; + double getAcceleration(size_t _index) const override; // Documentation inherited - virtual void setAccelerations(const Eigen::VectorXd& _accelerations) override; + void setAccelerations(const Eigen::VectorXd& _accelerations) override; // Documentation inherited - virtual Eigen::VectorXd getAccelerations() const override; + Eigen::VectorXd getAccelerations() const override; // Documentation inherited - virtual void resetAccelerations() override; + void resetAccelerations() override; // Documentation inherited - virtual void setAccelerationLowerLimit(size_t _index, double _acceleration) override; + void setAccelerationLowerLimit(size_t _index, double _acceleration) override; // Documentation inherited - virtual double getAccelerationLowerLimit(size_t _index) const override; + double getAccelerationLowerLimit(size_t _index) const override; // Documentation inherited - virtual void setAccelerationUpperLimit(size_t _index, double _acceleration) override; + void setAccelerationUpperLimit(size_t _index, double _acceleration) override; // Documentation inherited - virtual double getAccelerationUpperLimit(size_t _index) const override; + double getAccelerationUpperLimit(size_t _index) const override; //---------------------------------------------------------------------------- // Force //---------------------------------------------------------------------------- // Documentation inherited - virtual void setForce(size_t _index, double _force) override; + void setForce(size_t _index, double _force) override; // Documentation inherited - virtual double getForce(size_t _index) override; + double getForce(size_t _index) override; // Documentation inherited - virtual void setForces(const Eigen::VectorXd& _forces) override; + void setForces(const Eigen::VectorXd& _forces) override; // Documentation inherited - virtual Eigen::VectorXd getForces() const override; + Eigen::VectorXd getForces() const override; // Documentation inherited - virtual void resetForces() override; + void resetForces() override; // Documentation inherited - virtual void setForceLowerLimit(size_t _index, double _force) override; + void setForceLowerLimit(size_t _index, double _force) override; // Documentation inherited - virtual double getForceLowerLimit(size_t _index) const override; + double getForceLowerLimit(size_t _index) const override; // Documentation inherited - virtual void setForceUpperLimit(size_t _index, double _force) override; + void setForceUpperLimit(size_t _index, double _force) override; // Documentation inherited - virtual double getForceUpperLimit(size_t _index) const override; + double getForceUpperLimit(size_t _index) const override; //---------------------------------------------------------------------------- // Velocity change //---------------------------------------------------------------------------- // Documentation inherited - virtual void setVelocityChange(size_t _index, double _velocityChange) override; + void setVelocityChange(size_t _index, double _velocityChange) override; // Documentation inherited - virtual double getVelocityChange(size_t _index) const override; + double getVelocityChange(size_t _index) const override; // Documentation inherited - virtual void resetVelocityChanges() override; + void resetVelocityChanges() override; //---------------------------------------------------------------------------- // Constraint impulse //---------------------------------------------------------------------------- // Documentation inherited - virtual void setConstraintImpulse(size_t _index, double _impulse) override; + void setConstraintImpulse(size_t _index, double _impulse) override; // Documentation inherited - virtual double getConstraintImpulse(size_t _index) const override; + double getConstraintImpulse(size_t _index) const override; // Documentation inherited - virtual void resetConstraintImpulses() override; + void resetConstraintImpulses() override; //---------------------------------------------------------------------------- // Integration and finite difference //---------------------------------------------------------------------------- // Documentation inherited - virtual void integratePositions(double _dt) override; + void integratePositions(double _dt) override; // Documentation inherited - virtual void integrateVelocities(double _dt) override; + void integrateVelocities(double _dt) override; // Documentation inherited Eigen::VectorXd getPositionDifferences( @@ -317,38 +317,38 @@ class ZeroDofJoint : public Joint //---------------------------------------------------------------------------- // Documentation inherited - virtual void setSpringStiffness(size_t _index, double _k) override; + void setSpringStiffness(size_t _index, double _k) override; // Documentation inherited - virtual double getSpringStiffness(size_t _index) const override; + double getSpringStiffness(size_t _index) const override; // Documentation inherited - virtual void setRestPosition(size_t _index, double _q0) override; + void setRestPosition(size_t _index, double _q0) override; // Documentation inherited - virtual double getRestPosition(size_t _index) const override; + double getRestPosition(size_t _index) const override; // Documentation inherited - virtual void setDampingCoefficient(size_t _index, double _d) override; + void setDampingCoefficient(size_t _index, double _d) override; // Documentation inherited - virtual double getDampingCoefficient(size_t _index) const override; + double getDampingCoefficient(size_t _index) const override; // Documentation inherited - virtual void setCoulombFriction(size_t _index, double _friction) override; + void setCoulombFriction(size_t _index, double _friction) override; // Documentation inherited - virtual double getCoulombFriction(size_t _index) const override; + double getCoulombFriction(size_t _index) const override; /// \} //---------------------------------------------------------------------------- /// Get potential energy - virtual double getPotentialEnergy() const override; + double getPotentialEnergy() const override; // Documentation inherited - virtual Eigen::Vector6d getBodyConstraintWrench() const override; + Eigen::Vector6d getBodyConstraintWrench() const override; protected: @@ -359,109 +359,109 @@ class ZeroDofJoint : public Joint void registerDofs() override; // Documentation inherited - virtual void updateDegreeOfFreedomNames() override; + void updateDegreeOfFreedomNames() override; //---------------------------------------------------------------------------- /// \{ \name Recursive dynamics routines //---------------------------------------------------------------------------- // Documentation inherited - virtual const math::Jacobian getLocalJacobian() const override; + const math::Jacobian getLocalJacobian() const override; // Documentation inherited math::Jacobian getLocalJacobian( const Eigen::VectorXd& _positions) const override; // Documentation inherited - virtual const math::Jacobian getLocalJacobianTimeDeriv() const override; + const math::Jacobian getLocalJacobianTimeDeriv() const override; // Documentation inherited - virtual void addVelocityTo(Eigen::Vector6d& _vel) override; + void addVelocityTo(Eigen::Vector6d& _vel) override; // Documentation inherited - virtual void setPartialAccelerationTo( + void setPartialAccelerationTo( Eigen::Vector6d& _partialAcceleration, const Eigen::Vector6d& _childVelocity) override; // Documentation inherited - virtual void addAccelerationTo(Eigen::Vector6d& _acc) override; + void addAccelerationTo(Eigen::Vector6d& _acc) override; // Documentation inherited - virtual void addVelocityChangeTo(Eigen::Vector6d& _velocityChange) override; + void addVelocityChangeTo(Eigen::Vector6d& _velocityChange) override; // Documentation inherited - virtual void addChildArtInertiaTo( + void addChildArtInertiaTo( Eigen::Matrix6d& _parentArtInertia, const Eigen::Matrix6d& _childArtInertia) override; // Documentation inherited - virtual void addChildArtInertiaImplicitTo( + void addChildArtInertiaImplicitTo( Eigen::Matrix6d& _parentArtInertia, const Eigen::Matrix6d& _childArtInertia) override; // Documentation inherited - virtual void updateInvProjArtInertia( + void updateInvProjArtInertia( const Eigen::Matrix6d& _artInertia) override; // Documentation inherited - virtual void updateInvProjArtInertiaImplicit( + void updateInvProjArtInertiaImplicit( const Eigen::Matrix6d& _artInertia, double _timeStep) override; // Documentation inherited - virtual void addChildBiasForceTo( + void addChildBiasForceTo( Eigen::Vector6d& _parentBiasForce, const Eigen::Matrix6d& _childArtInertia, const Eigen::Vector6d& _childBiasForce, const Eigen::Vector6d& _childPartialAcc) override; // Documentation inherited - virtual void addChildBiasImpulseTo( + void addChildBiasImpulseTo( Eigen::Vector6d& _parentBiasImpulse, const Eigen::Matrix6d& _childArtInertia, const Eigen::Vector6d& _childBiasImpulse) override; // Documentation inherited - virtual void updateTotalForce(const Eigen::Vector6d& _bodyForce, + void updateTotalForce(const Eigen::Vector6d& _bodyForce, double _timeStep) override; // Documentation inherited - virtual void updateTotalImpulse( + void updateTotalImpulse( const Eigen::Vector6d& _bodyImpulse) override; // Documentation inherited - virtual void resetTotalImpulses() override; + void resetTotalImpulses() override; // Documentation inherited - virtual void updateAcceleration( + void updateAcceleration( const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) override; // Documentation inherited - virtual void updateVelocityChange( + void updateVelocityChange( const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _velocityChange) override; // Documentation inherited - virtual void updateForceID(const Eigen::Vector6d& _bodyForce, + void updateForceID(const Eigen::Vector6d& _bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces) override; // Documentation inherited - virtual void updateForceFD(const Eigen::Vector6d& _bodyForce, + void updateForceFD(const Eigen::Vector6d& _bodyForce, double _timeStep, bool _withDampingForces, bool _withSpringForces) override; // Documentation inherited - virtual void updateImpulseID(const Eigen::Vector6d& _bodyImpulse) override; + void updateImpulseID(const Eigen::Vector6d& _bodyImpulse) override; // Documentation inherited - virtual void updateImpulseFD(const Eigen::Vector6d& _bodyImpulse) override; + void updateImpulseFD(const Eigen::Vector6d& _bodyImpulse) override; // Documentation inherited - virtual void updateConstrainedTerms(double _timeStep) override; + void updateConstrainedTerms(double _timeStep) override; /// \} @@ -470,38 +470,38 @@ class ZeroDofJoint : public Joint //---------------------------------------------------------------------------- /// Add child's bias force to parent's one - virtual void addChildBiasForceForInvMassMatrix( + void addChildBiasForceForInvMassMatrix( Eigen::Vector6d& _parentBiasForce, const Eigen::Matrix6d& _childArtInertia, const Eigen::Vector6d& _childBiasForce) override; /// Add child's bias force to parent's one - virtual void addChildBiasForceForInvAugMassMatrix( + void addChildBiasForceForInvAugMassMatrix( Eigen::Vector6d& _parentBiasForce, const Eigen::Matrix6d& _childArtInertia, const Eigen::Vector6d& _childBiasForce) override; /// - virtual void updateTotalForceForInvMassMatrix( + void updateTotalForceForInvMassMatrix( const Eigen::Vector6d& _bodyForce) override; // Documentation inherited - virtual void getInvMassMatrixSegment(Eigen::MatrixXd& _invMassMat, + void getInvMassMatrixSegment(Eigen::MatrixXd& _invMassMat, const size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) override; // Documentation inherited - virtual void getInvAugMassMatrixSegment(Eigen::MatrixXd& _invMassMat, + void getInvAugMassMatrixSegment(Eigen::MatrixXd& _invMassMat, const size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) override; // Documentation inherited - virtual void addInvMassMatrixSegmentTo(Eigen::Vector6d& _acc) override; + void addInvMassMatrixSegmentTo(Eigen::Vector6d& _acc) override; // Documentation inherited - virtual Eigen::VectorXd getSpatialToGeneralized( + Eigen::VectorXd getSpatialToGeneralized( const Eigen::Vector6d& _spatial) override; /// \} diff --git a/dart/gui/GraphWindow.h b/dart/gui/GraphWindow.h index ded6b9e44a6a3..be7bb64afd7f6 100644 --- a/dart/gui/GraphWindow.h +++ b/dart/gui/GraphWindow.h @@ -62,10 +62,10 @@ class GraphWindow : public Win2D { virtual ~GraphWindow(); /// \brief - virtual void draw(); + void draw() override; /// \brief - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; void setData(Eigen::VectorXd _data); diff --git a/dart/gui/OpenGLRenderInterface.h b/dart/gui/OpenGLRenderInterface.h index f3fd494e07449..51ec36ed0424f 100644 --- a/dart/gui/OpenGLRenderInterface.h +++ b/dart/gui/OpenGLRenderInterface.h @@ -58,49 +58,49 @@ class OpenGLRenderInterface : public RenderInterface { OpenGLRenderInterface() : mViewportX(0.0), mViewportY(0.0), mViewportWidth(0.0), mViewportHeight(0.0) {} virtual ~OpenGLRenderInterface(){} - virtual void initialize() override; - virtual void destroy() override; + void initialize() override; + void destroy() override; - virtual void setViewport(int _x,int _y,int _width,int _height) override; - virtual void getViewport(int& _x, int& _y, int& _width, int& _height) const override; + void setViewport(int _x,int _y,int _width,int _height) override; + void getViewport(int& _x, int& _y, int& _width, int& _height) const override; - virtual void clear(const Eigen::Vector3d& _color) override; + void clear(const Eigen::Vector3d& _color) override; - virtual void setMaterial(const Eigen::Vector3d& _diffuse, const Eigen::Vector3d& _specular, double _cosinePow) override; - virtual void getMaterial(Eigen::Vector3d& _diffuse, Eigen::Vector3d& _specular, double& _cosinePow) const override; - virtual void setDefaultMaterial() override; + void setMaterial(const Eigen::Vector3d& _diffuse, const Eigen::Vector3d& _specular, double _cosinePow) override; + void getMaterial(Eigen::Vector3d& _diffuse, Eigen::Vector3d& _specular, double& _cosinePow) const override; + void setDefaultMaterial() override; - virtual void pushMatrix() override; - virtual void popMatrix() override; - virtual void pushName(int _id) override; - virtual void popName() override; + void pushMatrix() override; + void popMatrix() override; + void pushName(int _id) override; + void popName() override; - virtual void translate(const Eigen::Vector3d& _offset) override; //glTranslate - virtual void rotate(const Eigen::Vector3d& _axis, double _rad) override; //glRotate - virtual void transform(const Eigen::Isometry3d& _transform) override; //glMultMatrix - virtual void scale(const Eigen::Vector3d& _scale) override; //glScale + void translate(const Eigen::Vector3d& _offset) override; //glTranslate + void rotate(const Eigen::Vector3d& _axis, double _rad) override; //glRotate + void transform(const Eigen::Isometry3d& _transform) override; //glMultMatrix + void scale(const Eigen::Vector3d& _scale) override; //glScale void compileList(dynamics::Skeleton* _skel); void compileList(dynamics::BodyNode* _node); void compileList(dynamics::Shape* _shape); GLuint compileList(const Eigen::Vector3d& _scale, const aiScene* _mesh); - virtual void drawEllipsoid(const Eigen::Vector3d& _size) override; - virtual void drawCube(const Eigen::Vector3d& _size) override; - virtual void drawCylinder(double _radius, double _height) override; - virtual void drawMesh(const Eigen::Vector3d& _scale, const aiScene* _mesh) override; - virtual void drawSoftMesh(const aiMesh* mesh); - virtual void drawList(GLuint index) override; - virtual void drawLineSegments(const std::vector& _vertices, + void drawEllipsoid(const Eigen::Vector3d& _size) override; + void drawCube(const Eigen::Vector3d& _size) override; + void drawCylinder(double _radius, double _height) override; + void drawMesh(const Eigen::Vector3d& _scale, const aiScene* _mesh) override; + void drawSoftMesh(const aiMesh* mesh); + void drawList(GLuint index) override; + void drawLineSegments(const std::vector& _vertices, const Eigen::aligned_vector& _connections) override; - virtual void setPenColor(const Eigen::Vector4d& _col) override; - virtual void setPenColor(const Eigen::Vector3d& _col) override; + void setPenColor(const Eigen::Vector4d& _col) override; + void setPenColor(const Eigen::Vector3d& _col) override; - virtual void setLineWidth(float _width) override; + void setLineWidth(float _width) override; - virtual void saveToImage(const char* _filename, DecoBufferType _buffType = BT_Back) override; - virtual void readFrameBuffer(DecoBufferType _buffType, DecoColorChannel _ch, void* _pixels) override; + void saveToImage(const char* _filename, DecoBufferType _buffType = BT_Back) override; + void readFrameBuffer(DecoBufferType _buffType, DecoColorChannel _ch, void* _pixels) override; private: void color4_to_float4(const aiColor4D *c, float f[4]); diff --git a/dart/gui/SimWindow.h b/dart/gui/SimWindow.h index 5906fc55b9ef2..1cbe2289403f3 100644 --- a/dart/gui/SimWindow.h +++ b/dart/gui/SimWindow.h @@ -78,13 +78,13 @@ class SimWindow : public Win3D { virtual void drawEntities(); /// \brief - virtual void displayTimer(int _val); + void displayTimer(int _val) override; /// \brief - virtual void draw(); + void draw() override; /// \brief - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; /// \brief void setWorld(dart::simulation::WorldPtr _world); diff --git a/dart/gui/SoftSimWindow.h b/dart/gui/SoftSimWindow.h index 17c76c0b59cad..99902ef0d6a76 100644 --- a/dart/gui/SoftSimWindow.h +++ b/dart/gui/SoftSimWindow.h @@ -59,7 +59,7 @@ class SoftSimWindow : public SimWindow virtual ~SoftSimWindow(); /// \brief - virtual void keyboard(unsigned char key, int x, int y); + void keyboard(unsigned char key, int x, int y) override; protected: /// \brief diff --git a/dart/gui/Win2D.h b/dart/gui/Win2D.h index 5cbcc8be513a3..c210d19658639 100644 --- a/dart/gui/Win2D.h +++ b/dart/gui/Win2D.h @@ -49,19 +49,19 @@ class Win2D : public GlutWindow { Win2D(); /// \brief - virtual void resize(int _w, int _h); + void resize(int _w, int _h) override; /// \brief - virtual void render(); + void render() override; /// \brief - virtual void keyboard(unsigned char _key, int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; /// \brief - virtual void click(int _button, int _state, int _x, int _y); + void click(int _button, int _state, int _x, int _y) override; /// \brief - virtual void drag(int _x, int _y); + void drag(int _x, int _y) override; /// \brief virtual void initGL(); diff --git a/dart/gui/Win3D.h b/dart/gui/Win3D.h index 72ef91fccc7ac..19976ff1490a6 100644 --- a/dart/gui/Win3D.h +++ b/dart/gui/Win3D.h @@ -49,13 +49,13 @@ class Win3D : public GlutWindow { public: Win3D(); - virtual void initWindow(int _w, int _h, const char* _name); - virtual void resize(int _w, int _h); - virtual void render(); + void initWindow(int _w, int _h, const char* _name) override; + void resize(int _w, int _h) override; + void render() override; - virtual void keyboard(unsigned char _key, int _x, int _y); - virtual void click(int _button, int _state, int _x, int _y); - virtual void drag(int _x, int _y); + void keyboard(unsigned char _key, int _x, int _y) override; + void click(int _button, int _state, int _x, int _y) override; + void drag(int _x, int _y) override; virtual void initGL(); virtual void initLights(); diff --git a/dart/gui/osg/DefaultEventHandler.h b/dart/gui/osg/DefaultEventHandler.h index 969705526594c..9f5f0a762aa26 100644 --- a/dart/gui/osg/DefaultEventHandler.h +++ b/dart/gui/osg/DefaultEventHandler.h @@ -182,8 +182,8 @@ class DefaultEventHandler : public ::osgGA::GUIEventHandler, const std::set& getMouseEventHandlers() const; /// Handle incoming user input - virtual bool handle(const ::osgGA::GUIEventAdapter& ea, - ::osgGA::GUIActionAdapter&) override; + bool handle(const ::osgGA::GUIEventAdapter& ea, + ::osgGA::GUIActionAdapter&) override; protected: @@ -196,7 +196,7 @@ class DefaultEventHandler : public ::osgGA::GUIEventHandler, /// Clear out the current button events void clearButtonEvents(); - virtual void handleDestructionNotification( + void handleDestructionNotification( const dart::common::Subject* _subject) override; /// dart::gui::osg::Viewer that this event handler is tied to diff --git a/dart/gui/osg/DragAndDrop.h b/dart/gui/osg/DragAndDrop.h index 501e05e79855d..341f45384a3bf 100644 --- a/dart/gui/osg/DragAndDrop.h +++ b/dart/gui/osg/DragAndDrop.h @@ -142,7 +142,7 @@ class DragAndDrop : public dart::common::Subject, protected: /// Perform cleanup when the subject is destroyed - virtual void handleDestructionNotification( + void handleDestructionNotification( const dart::common::Subject* subscription) override; /// Pointer to the DnD's Viewer @@ -232,7 +232,7 @@ class SimpleFrameShapeDnD : public SimpleFrameDnD protected: // Documentation inherited - virtual void handleDestructionNotification( + void handleDestructionNotification( const dart::common::Subject* subscription) override; /// Shape associated with this DnD diff --git a/dart/gui/osg/MouseEventHandler.h b/dart/gui/osg/MouseEventHandler.h index a2dd740bf3cbb..8e12de9bd3041 100644 --- a/dart/gui/osg/MouseEventHandler.h +++ b/dart/gui/osg/MouseEventHandler.h @@ -63,7 +63,7 @@ class MouseEventHandler : public virtual dart::common::Subject, protected: - inline virtual void handleDestructionNotification(const Subject* _subject) override + void handleDestructionNotification(const Subject* _subject) override { if(mEventHandler == _subject) delete this; diff --git a/dart/gui/osg/TrackballManipulator.h b/dart/gui/osg/TrackballManipulator.h index c2e2f6cbd22cf..2bc2ae197a58a 100644 --- a/dart/gui/osg/TrackballManipulator.h +++ b/dart/gui/osg/TrackballManipulator.h @@ -67,14 +67,14 @@ class OSGGA_EXPORT TrackballManipulator : public ::osgGA::OrbitManipulator virtual ~TrackballManipulator(); /// Overriding behavior of left mouse button - virtual bool performMovementLeftMouseButton(const double eventTimeDelta, - const double dx, - const double dy) override; + bool performMovementLeftMouseButton(const double eventTimeDelta, + const double dx, + const double dy) override; /// Overriding behavior of right mouse button - virtual bool performMovementRightMouseButton(const double eventTimeDelta, - const double dx, - const double dy) override; + bool performMovementRightMouseButton(const double eventTimeDelta, + const double dx, + const double dy) override; DART_META_Object( dart-gui-osg, TrackballManipulator ) // TODO(MXG): Consider applying the META macros to every dart::gui::osg Node diff --git a/dart/integration/EulerIntegrator.h b/dart/integration/EulerIntegrator.h index f260731141448..8c4104b9623d7 100644 --- a/dart/integration/EulerIntegrator.h +++ b/dart/integration/EulerIntegrator.h @@ -54,13 +54,13 @@ class EulerIntegrator : public Integrator virtual ~EulerIntegrator(); // Documentation inherited - virtual void integrate(IntegrableSystem* _system, double _dt); + void integrate(IntegrableSystem* _system, double _dt) override; // Documentation inherited - virtual void integratePos(IntegrableSystem* _system, double _dt); + void integratePos(IntegrableSystem* _system, double _dt) override; // Documentation inherited - virtual void integrateVel(IntegrableSystem* _system, double _dt); + void integrateVel(IntegrableSystem* _system, double _dt) override; }; } // namespace integration diff --git a/dart/integration/RK4Integrator.h b/dart/integration/RK4Integrator.h index 7d11ac33a7812..94bb9e0613cda 100644 --- a/dart/integration/RK4Integrator.h +++ b/dart/integration/RK4Integrator.h @@ -54,7 +54,7 @@ class RK4Integrator : public Integrator virtual ~RK4Integrator(); // Documentation inherited - virtual void integrate(IntegrableSystem* _system, double _dt); + void integrate(IntegrableSystem* _system, double _dt) override; private: /// \brief Initial configurations diff --git a/dart/integration/SemiImplicitEulerIntegrator.h b/dart/integration/SemiImplicitEulerIntegrator.h index 795227aa0a5f3..493f49db47d99 100644 --- a/dart/integration/SemiImplicitEulerIntegrator.h +++ b/dart/integration/SemiImplicitEulerIntegrator.h @@ -53,13 +53,13 @@ class SemiImplicitEulerIntegrator : public Integrator virtual ~SemiImplicitEulerIntegrator(); // Documentation inherited - virtual void integrate(IntegrableSystem* _system, double _dt); + void integrate(IntegrableSystem* _system, double _dt) override; // Documentation inherited - virtual void integratePos(IntegrableSystem* _system, double _dt); + void integratePos(IntegrableSystem* _system, double _dt) override; // Documentation inherited - virtual void integrateVel(IntegrableSystem* _system, double _dt); + void integrateVel(IntegrableSystem* _system, double _dt) override; }; } // namespace integration diff --git a/dart/optimizer/Function.h b/dart/optimizer/Function.h index 59781664950fd..e8c2c37d7aea5 100644 --- a/dart/optimizer/Function.h +++ b/dart/optimizer/Function.h @@ -113,16 +113,16 @@ class ModularFunction : public Function /// \brief eval() will now call whatever CostFunction you set using /// setCostFunction() - virtual double eval(const Eigen::VectorXd& _x) override; + double eval(const Eigen::VectorXd& _x) override; /// \brief evalGradient() will now call whatever GradientFunction you set /// using setGradientFunction() - virtual void evalGradient(const Eigen::VectorXd& _x, - Eigen::Map _grad) override; + void evalGradient(const Eigen::VectorXd& _x, + Eigen::Map _grad) override; /// \brief evalHessian() will now call whatever HessianFunction you set using /// setHessianFunction() - virtual void evalHessian( + void evalHessian( const Eigen::VectorXd& _x, Eigen::Map _Hess) override; @@ -171,16 +171,16 @@ class NullFunction : public Function virtual ~NullFunction(); /// \brief eval() will always return exactly zero - virtual double eval(const Eigen::VectorXd&) override; + double eval(const Eigen::VectorXd&) override; /// \brief evalGradient will always set _grad to a zero vector that /// matches the dimensionality of _x - virtual void evalGradient(const Eigen::VectorXd& _x, - Eigen::Map _grad) override; + void evalGradient(const Eigen::VectorXd& _x, + Eigen::Map _grad) override; /// \brief evalHessian() will always set _Hess to a zero matrix that matches /// the dimensionality of _x - virtual void evalHessian( + void evalHessian( const Eigen::VectorXd& _x, Eigen::Map _Hess) override; }; diff --git a/dart/optimizer/GradientDescentSolver.h b/dart/optimizer/GradientDescentSolver.h index 820c1ce26a3b3..89385c6f9fc51 100644 --- a/dart/optimizer/GradientDescentSolver.h +++ b/dart/optimizer/GradientDescentSolver.h @@ -132,16 +132,16 @@ class GradientDescentSolver : public Solver virtual ~GradientDescentSolver(); // Documentation inherited - virtual bool solve() override; + bool solve() override; /// Get the last configuration that was used by the Solver Eigen::VectorXd getLastConfiguration() const; // Documentation inherited - virtual std::string getType() const override; + std::string getType() const override; // Documentation inherited - virtual std::shared_ptr clone() const override; + std::shared_ptr clone() const override; /// Set the Properties of this GradientDescentSolver void setProperties(const Properties& _properties); diff --git a/dart/optimizer/ipopt/IpoptSolver.h b/dart/optimizer/ipopt/IpoptSolver.h index 90f8946dab996..65bf08cabb5b4 100644 --- a/dart/optimizer/ipopt/IpoptSolver.h +++ b/dart/optimizer/ipopt/IpoptSolver.h @@ -72,13 +72,13 @@ class IpoptSolver : public Solver virtual ~IpoptSolver(); // Documentation inherited - virtual bool solve() override; + bool solve() override; // Documentation inherited - virtual std::string getType() const override; + std::string getType() const override; // Documentation inherited - virtual std::shared_ptr clone() const override; + std::shared_ptr clone() const override; /// Get the application interface for this IpoptSolver const Ipopt::SmartPtr& getApplication(); @@ -111,93 +111,93 @@ class DartTNLP : public Ipopt::TNLP //------------------------- Ipopt::TNLP -------------------------------------- /// \brief Method to return some info about the nlp - virtual bool get_nlp_info(Ipopt::Index& n, - Ipopt::Index& m, - Ipopt::Index& nnz_jac_g, - Ipopt::Index& nnz_h_lag, - Ipopt::TNLP::IndexStyleEnum& index_style) override; + bool get_nlp_info(Ipopt::Index& n, + Ipopt::Index& m, + Ipopt::Index& nnz_jac_g, + Ipopt::Index& nnz_h_lag, + Ipopt::TNLP::IndexStyleEnum& index_style) override; /// \brief Method to return the bounds for my problem - virtual bool get_bounds_info(Ipopt::Index n, - Ipopt::Number* x_l, - Ipopt::Number* x_u, - Ipopt::Index m, - Ipopt::Number* g_l, - Ipopt::Number* g_u) override; + bool get_bounds_info(Ipopt::Index n, + Ipopt::Number* x_l, + Ipopt::Number* x_u, + Ipopt::Index m, + Ipopt::Number* g_l, + Ipopt::Number* g_u) override; /// \brief Method to return the starting point for the algorithm - virtual bool get_starting_point(Ipopt::Index n, - bool init_x, - Ipopt::Number* x, - bool init_z, - Ipopt::Number* z_L, - Ipopt::Number* z_U, - Ipopt::Index m, - bool init_lambda, - Ipopt::Number* lambda) override; + bool get_starting_point(Ipopt::Index n, + bool init_x, + Ipopt::Number* x, + bool init_z, + Ipopt::Number* z_L, + Ipopt::Number* z_U, + Ipopt::Index m, + bool init_lambda, + Ipopt::Number* lambda) override; /// \brief Method to return the objective value - virtual bool eval_f(Ipopt::Index _n, - const Ipopt::Number* _x, - bool _new_x, - Ipopt::Number& - _obj_value) override; + bool eval_f(Ipopt::Index _n, + const Ipopt::Number* _x, + bool _new_x, + Ipopt::Number& + _obj_value) override; /// \brief Method to return the gradient of the objective - virtual bool eval_grad_f(Ipopt::Index _n, - const Ipopt::Number* _x, - bool _new_x, - Ipopt::Number* _grad_f) override; + bool eval_grad_f(Ipopt::Index _n, + const Ipopt::Number* _x, + bool _new_x, + Ipopt::Number* _grad_f) override; /// \brief Method to return the constraint residuals - virtual bool eval_g(Ipopt::Index _n, - const Ipopt::Number* _x, - bool _new_x, - Ipopt::Index _m, - Ipopt::Number* _g) override; + bool eval_g(Ipopt::Index _n, + const Ipopt::Number* _x, + bool _new_x, + Ipopt::Index _m, + Ipopt::Number* _g) override; /// \brief Method to return: /// 1) The structure of the jacobian (if "values" is nullptr) /// 2) The values of the jacobian (if "values" is not nullptr) - virtual bool eval_jac_g(Ipopt::Index _n, - const Ipopt::Number* _x, - bool _new_x, - Ipopt::Index _m, - Ipopt::Index _nele_jac, - Ipopt::Index* _iRow, - Ipopt::Index* _jCol, - Ipopt::Number* _values) override; + bool eval_jac_g(Ipopt::Index _n, + const Ipopt::Number* _x, + bool _new_x, + Ipopt::Index _m, + Ipopt::Index _nele_jac, + Ipopt::Index* _iRow, + Ipopt::Index* _jCol, + Ipopt::Number* _values) override; /// \brief Method to return: /// 1) The structure of the hessian of the lagrangian (if "values" is /// nullptr) /// 2) The values of the hessian of the lagrangian (if "values" is not /// nullptr) - virtual bool eval_h(Ipopt::Index _n, - const Ipopt::Number* _x, - bool _new_x, - Ipopt::Number _obj_factor, - Ipopt::Index _m, - const Ipopt::Number* _lambda, - bool _new_lambda, - Ipopt::Index _nele_hess, - Ipopt::Index* _iRow, - Ipopt::Index* _jCol, - Ipopt::Number* _values) override; + bool eval_h(Ipopt::Index _n, + const Ipopt::Number* _x, + bool _new_x, + Ipopt::Number _obj_factor, + Ipopt::Index _m, + const Ipopt::Number* _lambda, + bool _new_lambda, + Ipopt::Index _nele_hess, + Ipopt::Index* _iRow, + Ipopt::Index* _jCol, + Ipopt::Number* _values) override; /// \brief This method is called when the algorithm is complete so the TNLP /// can store/write the solution - virtual void finalize_solution(Ipopt::SolverReturn _status, - Ipopt::Index _n, - const Ipopt::Number* _x, - const Ipopt::Number* _z_L, - const Ipopt::Number* _z_U, - Ipopt::Index _m, - const Ipopt::Number* _g, - const Ipopt::Number* _lambda, - Ipopt::Number _obj_value, - const Ipopt::IpoptData* _ip_data, - Ipopt::IpoptCalculatedQuantities* _ip_cq) override; + void finalize_solution(Ipopt::SolverReturn _status, + Ipopt::Index _n, + const Ipopt::Number* _x, + const Ipopt::Number* _z_L, + const Ipopt::Number* _z_U, + Ipopt::Index _m, + const Ipopt::Number* _g, + const Ipopt::Number* _lambda, + Ipopt::Number _obj_value, + const Ipopt::IpoptData* _ip_data, + Ipopt::IpoptCalculatedQuantities* _ip_cq) override; private: diff --git a/unittests/testConstraint.cpp b/unittests/testConstraint.cpp index 7d3fd18ebcc92..34f60863e68b0 100644 --- a/unittests/testConstraint.cpp +++ b/unittests/testConstraint.cpp @@ -63,7 +63,7 @@ class ConstraintTest : public ::testing::Test protected: // Sets up the test fixture. - virtual void SetUp(); + void SetUp() override; // Skel file list. std::vector list; diff --git a/unittests/testDynamics.cpp b/unittests/testDynamics.cpp index 3f8ed377304c8..bd485d6a82e15 100644 --- a/unittests/testDynamics.cpp +++ b/unittests/testDynamics.cpp @@ -114,7 +114,7 @@ class DynamicsTest : public ::testing::Test protected: // Sets up the test fixture. - virtual void SetUp(); + void SetUp() override; // Skel file list. std::vector fileList; diff --git a/unittests/testJoints.cpp b/unittests/testJoints.cpp index a859cd55613b0..c39f19431ae76 100644 --- a/unittests/testJoints.cpp +++ b/unittests/testJoints.cpp @@ -93,7 +93,7 @@ class JOINTS : public testing::Test protected: // Sets up the test fixture. - virtual void SetUp(); + void SetUp() override; std::vector frames; }; diff --git a/unittests/testOptimizer.cpp b/unittests/testOptimizer.cpp index 6ba4669761bd0..f9342b52f1282 100644 --- a/unittests/testOptimizer.cpp +++ b/unittests/testOptimizer.cpp @@ -77,14 +77,14 @@ class SampleObjFunc : public Function virtual ~SampleObjFunc() {} /// \copydoc Function::eval - virtual double eval(const Eigen::VectorXd& _x) override + double eval(const Eigen::VectorXd& _x) override { return std::sqrt(_x[1]); } /// \copydoc Function::evalGradient - virtual void evalGradient(const Eigen::VectorXd& _x, - Eigen::Map _grad) override + void evalGradient(const Eigen::VectorXd& _x, + Eigen::Map _grad) override { _grad[0] = 0.0; _grad[1] = 0.5 / std::sqrt(_x[1]); @@ -102,14 +102,14 @@ class SampleConstFunc : public Function virtual ~SampleConstFunc() {} /// \copydoc Function::eval - virtual double eval(const Eigen::VectorXd& _x) override + double eval(const Eigen::VectorXd& _x) override { return ((mA*_x[0] + mB) * (mA*_x[0] + mB) * (mA*_x[0] + mB) - _x[1]); } /// \copydoc Function::evalGradient - virtual void evalGradient(const Eigen::VectorXd& _x, - Eigen::Map _grad) override + void evalGradient(const Eigen::VectorXd& _x, + Eigen::Map _grad) override { _grad[0] = 3 * mA * (mA*_x[0] + mB) * (mA*_x[0] + mB); _grad[1] = -1.0; diff --git a/unittests/testSoftDynamics.cpp b/unittests/testSoftDynamics.cpp index 55060892195d7..dc7914c8177bc 100644 --- a/unittests/testSoftDynamics.cpp +++ b/unittests/testSoftDynamics.cpp @@ -113,7 +113,7 @@ class SoftDynamicsTest : public ::testing::Test protected: // Sets up the test fixture. - virtual void SetUp(); + void SetUp() override; // Skel file list. std::vector list; From 6dafbae2d7852d9a9f83c0f3db9ad740b26ed5e4 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 21 Apr 2016 17:39:49 -0400 Subject: [PATCH 21/34] Use std::size_t instead of size_t --- apps/atlasSimbicon/Controller.cpp | 8 +- apps/atlasSimbicon/Controller.h | 10 +- apps/atlasSimbicon/State.cpp | 10 +- apps/atlasSimbicon/State.h | 16 +- apps/atlasSimbicon/StateMachine.cpp | 2 +- apps/atlasSimbicon/StateMachine.h | 2 +- apps/atlasSimbicon/TerminalCondition.cpp | 2 +- apps/bipedStand/Controller.cpp | 2 +- apps/bipedStand/Controller.h | 4 +- apps/hardcodedDesign/MyWindow.cpp | 2 +- apps/hybridDynamics/Main.cpp | 4 +- apps/hybridDynamics/MyWindow.cpp | 12 +- apps/jointConstraints/Controller.cpp | 2 +- apps/jointConstraints/Main.cpp | 2 +- apps/softBodies/Main.cpp | 4 +- apps/speedTest/Main.cpp | 24 +- apps/vehicle/MyWindow.cpp | 2 +- dart/collision/CollisionGroup.cpp | 2 +- dart/collision/CollisionGroup.h | 2 +- dart/collision/Option.cpp | 2 +- dart/collision/Option.h | 4 +- dart/collision/Result.cpp | 6 +- dart/collision/Result.h | 6 +- .../bullet/BulletCollisionDetector.h | 2 +- dart/collision/fcl/FCLCollisionDetector.cpp | 14 +- dart/common/LocalResource.cpp | 8 +- dart/common/LocalResource.h | 6 +- dart/common/NameManager.h | 2 +- dart/common/Resource.h | 6 +- dart/common/Signal.h | 4 +- dart/common/StlHelpers.h | 2 +- dart/common/Uri.cpp | 18 +- dart/common/VersionCounter.cpp | 4 +- dart/common/VersionCounter.h | 6 +- dart/common/detail/AspectWithVersion.h | 4 +- dart/common/detail/Cloneable.h | 2 +- dart/common/detail/NameManager.h | 10 +- dart/common/detail/Signal.h | 8 +- dart/constraint/BalanceConstraint.cpp | 16 +- dart/constraint/BalanceConstraint.h | 4 +- dart/constraint/BallJointConstraint.cpp | 8 +- dart/constraint/BallJointConstraint.h | 4 +- dart/constraint/ConstrainedGroup.cpp | 10 +- dart/constraint/ConstrainedGroup.h | 6 +- dart/constraint/ConstraintBase.cpp | 2 +- dart/constraint/ConstraintBase.h | 6 +- dart/constraint/ConstraintSolver.cpp | 10 +- dart/constraint/ContactConstraint.cpp | 24 +- dart/constraint/ContactConstraint.h | 4 +- dart/constraint/DantzigLCPSolver.cpp | 72 +-- dart/constraint/DantzigLCPSolver.h | 6 +- .../JointCoulombFrictionConstraint.cpp | 32 +- .../JointCoulombFrictionConstraint.h | 6 +- dart/constraint/JointLimitConstraint.cpp | 32 +- dart/constraint/JointLimitConstraint.h | 6 +- dart/constraint/PGSLCPSolver.cpp | 72 +-- dart/constraint/PGSLCPSolver.h | 6 +- dart/constraint/ServoMotorConstraint.cpp | 30 +- dart/constraint/ServoMotorConstraint.h | 6 +- dart/constraint/SoftContactConstraint.cpp | 26 +- dart/constraint/SoftContactConstraint.h | 4 +- dart/constraint/WeldJointConstraint.cpp | 4 +- dart/constraint/WeldJointConstraint.h | 4 +- dart/dynamics/ArrowShape.cpp | 42 +- dart/dynamics/ArrowShape.h | 4 +- dart/dynamics/AssimpInputResourceAdaptor.cpp | 26 +- dart/dynamics/AssimpInputResourceAdaptor.h | 10 +- dart/dynamics/BallJoint.cpp | 2 +- dart/dynamics/BallJoint.h | 2 +- dart/dynamics/BodyNode.cpp | 124 ++--- dart/dynamics/BodyNode.h | 64 +-- dart/dynamics/Branch.cpp | 4 +- dart/dynamics/Branch.h | 2 +- dart/dynamics/Chain.cpp | 2 +- dart/dynamics/DegreeOfFreedom.cpp | 10 +- dart/dynamics/DegreeOfFreedom.h | 20 +- dart/dynamics/EulerJoint.cpp | 4 +- dart/dynamics/EulerJoint.h | 2 +- dart/dynamics/FixedJacobianNode.cpp | 14 +- dart/dynamics/FixedJacobianNode.h | 14 +- dart/dynamics/Frame.cpp | 4 +- dart/dynamics/Frame.h | 4 +- dart/dynamics/FreeJoint.cpp | 6 +- dart/dynamics/FreeJoint.h | 2 +- dart/dynamics/Group.cpp | 30 +- dart/dynamics/Group.h | 4 +- dart/dynamics/HierarchicalIK.cpp | 54 +- dart/dynamics/Inertia.cpp | 48 +- dart/dynamics/InvalidIndex.h | 2 +- dart/dynamics/InverseKinematics.cpp | 64 +-- dart/dynamics/InverseKinematics.h | 18 +- dart/dynamics/JacobianNode.h | 14 +- dart/dynamics/Joint.cpp | 12 +- dart/dynamics/Joint.h | 122 ++--- dart/dynamics/LineSegmentShape.cpp | 28 +- dart/dynamics/LineSegmentShape.h | 20 +- dart/dynamics/Linkage.cpp | 14 +- dart/dynamics/MeshShape.cpp | 22 +- dart/dynamics/MetaSkeleton.cpp | 104 ++-- dart/dynamics/MetaSkeleton.h | 96 ++-- dart/dynamics/MultiDofJoint.h | 116 ++-- dart/dynamics/Node.cpp | 2 +- dart/dynamics/Node.h | 14 +- dart/dynamics/NodeManagerJoiner.h | 12 +- dart/dynamics/PlanarJoint.cpp | 4 +- dart/dynamics/PlanarJoint.h | 2 +- dart/dynamics/PointMass.cpp | 44 +- dart/dynamics/PointMass.h | 48 +- dart/dynamics/PrismaticJoint.cpp | 2 +- dart/dynamics/PrismaticJoint.h | 2 +- dart/dynamics/ReferentialSkeleton.cpp | 92 ++-- dart/dynamics/ReferentialSkeleton.h | 32 +- dart/dynamics/RevoluteJoint.cpp | 2 +- dart/dynamics/RevoluteJoint.h | 2 +- dart/dynamics/ScrewJoint.cpp | 2 +- dart/dynamics/ScrewJoint.h | 2 +- dart/dynamics/SingleDofJoint.cpp | 134 ++--- dart/dynamics/SingleDofJoint.h | 112 ++-- dart/dynamics/Skeleton.cpp | 504 +++++++++--------- dart/dynamics/Skeleton.h | 126 ++--- dart/dynamics/SoftBodyNode.cpp | 320 +++++------ dart/dynamics/SoftBodyNode.h | 40 +- dart/dynamics/SoftMeshShape.cpp | 4 +- dart/dynamics/SpecializedNodeManager.h | 40 +- dart/dynamics/TranslationalJoint.cpp | 2 +- dart/dynamics/TranslationalJoint.h | 2 +- dart/dynamics/UniversalJoint.cpp | 2 +- dart/dynamics/UniversalJoint.h | 2 +- dart/dynamics/WeldJoint.cpp | 2 +- dart/dynamics/WeldJoint.h | 2 +- dart/dynamics/ZeroDofJoint.cpp | 112 ++-- dart/dynamics/ZeroDofJoint.h | 112 ++-- dart/dynamics/detail/BasicNodeManager.h | 60 +-- dart/dynamics/detail/BodyNode.h | 2 +- dart/dynamics/detail/DegreeOfFreedomPtr.h | 6 +- dart/dynamics/detail/InverseKinematics.h | 2 +- dart/dynamics/detail/MultiDofJoint.h | 462 ++++++++-------- dart/dynamics/detail/MultiDofJointAspect.h | 34 +- dart/dynamics/detail/Node.h | 98 ++-- dart/dynamics/detail/NodeManagerJoiner.h | 12 +- dart/dynamics/detail/SoftBodyNodeAspect.h | 2 +- dart/dynamics/detail/SpecializedNodeManager.h | 34 +- dart/gui/OpenGLRenderInterface.cpp | 2 +- dart/gui/SimWindow.cpp | 12 +- dart/gui/osg/DefaultEventHandler.cpp | 6 +- dart/gui/osg/DragAndDrop.cpp | 44 +- dart/gui/osg/DragAndDrop.h | 2 +- dart/gui/osg/InteractiveFrame.cpp | 62 +-- dart/gui/osg/InteractiveFrame.h | 4 +- dart/gui/osg/SupportPolygonVisual.cpp | 8 +- dart/gui/osg/SupportPolygonVisual.h | 6 +- dart/gui/osg/Viewer.cpp | 2 +- dart/gui/osg/Viewer.h | 6 +- dart/gui/osg/WorldNode.cpp | 12 +- dart/gui/osg/WorldNode.h | 6 +- dart/gui/osg/examples/osgAtlasPuppet.cpp | 22 +- dart/gui/osg/examples/osgHuboPuppet.cpp | 54 +- .../examples/osgOperationalSpaceControl.cpp | 20 +- dart/gui/osg/examples/osgSoftBodies.cpp | 12 +- dart/gui/osg/render/LineSegmentShapeNode.cpp | 4 +- dart/gui/osg/render/MeshShapeNode.cpp | 26 +- dart/gui/osg/render/MeshShapeNode.h | 2 +- dart/gui/osg/render/SoftMeshShapeNode.cpp | 16 +- dart/lcpsolver/Lemke.cpp | 14 +- dart/math/Geometry.cpp | 60 +-- dart/math/Geometry.h | 10 +- dart/math/Helpers.h | 22 +- dart/math/MathTypes.h | 6 +- dart/optimizer/GradientDescentSolver.cpp | 24 +- dart/optimizer/GradientDescentSolver.h | 20 +- dart/optimizer/Problem.cpp | 28 +- dart/optimizer/Problem.h | 22 +- dart/optimizer/Solver.cpp | 12 +- dart/optimizer/Solver.h | 16 +- dart/optimizer/ipopt/IpoptSolver.cpp | 28 +- dart/optimizer/nlopt/NloptSolver.cpp | 8 +- dart/planning/PathPlanner.h | 12 +- dart/planning/PathShortener.cpp | 2 +- dart/planning/PathShortener.h | 4 +- dart/planning/RRT.cpp | 8 +- dart/planning/RRT.h | 8 +- dart/simulation/Recording.cpp | 12 +- dart/simulation/World.cpp | 20 +- dart/simulation/World.h | 8 +- dart/utils/FileInfoDof.cpp | 26 +- dart/utils/FileInfoDof.h | 6 +- dart/utils/FileInfoWorld.cpp | 2 +- dart/utils/SkelParser.cpp | 34 +- dart/utils/VskParser.cpp | 16 +- dart/utils/XmlHelpers.cpp | 16 +- dart/utils/urdf/DartLoader.cpp | 8 +- tutorials/tutorialBiped-Finished.cpp | 10 +- tutorials/tutorialBiped.cpp | 4 +- tutorials/tutorialCollisions-Finished.cpp | 18 +- tutorials/tutorialCollisions.cpp | 6 +- tutorials/tutorialDominoes-Finished.cpp | 2 +- tutorials/tutorialMultiPendulum-Finished.cpp | 16 +- tutorials/tutorialMultiPendulum.cpp | 6 +- unittests/testAspect.cpp | 4 +- unittests/testCollision.cpp | 12 +- unittests/testConcurrency.cpp | 6 +- unittests/testConstraint.cpp | 6 +- unittests/testDynamics.cpp | 166 +++--- unittests/testFileInfoWorld.cpp | 22 +- unittests/testForwardKinematics.cpp | 18 +- unittests/testFrames.cpp | 52 +- unittests/testInverseKinematics.cpp | 18 +- unittests/testJoints.cpp | 24 +- unittests/testNameManagement.cpp | 2 +- unittests/testOptimizer.cpp | 4 +- unittests/testSkeleton.cpp | 92 ++-- unittests/testSoftDynamics.cpp | 24 +- unittests/testWorld.cpp | 32 +- 213 files changed, 2785 insertions(+), 2785 deletions(-) diff --git a/apps/atlasSimbicon/Controller.cpp b/apps/atlasSimbicon/Controller.cpp index 9b8d3a029fa19..e49abbce0bad7 100644 --- a/apps/atlasSimbicon/Controller.cpp +++ b/apps/atlasSimbicon/Controller.cpp @@ -144,7 +144,7 @@ void Controller::changeStateMachine(const string& _name, double _currentTime) } //============================================================================== -void Controller::changeStateMachine(size_t _idx, double _currentTime) +void Controller::changeStateMachine(std::size_t _idx, double _currentTime) { assert(_idx <= mStateMachines.size() && "Invalid index of StateMachine."); @@ -207,7 +207,7 @@ void Controller::printDebugInfo() const << " NUM DOF : " << mAtlasRobot->getNumDofs() << std::endl << " NUM JOINTS: " << mAtlasRobot->getNumBodyNodes() << std::endl; - for(size_t i = 0; i < mAtlasRobot->getNumBodyNodes(); ++i) + for(std::size_t i = 0; i < mAtlasRobot->getNumBodyNodes(); ++i) { Joint* joint = mAtlasRobot->getJoint(i); BodyNode* body = mAtlasRobot->getBodyNode(i); @@ -819,12 +819,12 @@ StateMachine* Controller::_createRunningStateMachine() //============================================================================== void Controller::_setJointDamping() { - for (size_t i = 1; i < mAtlasRobot->getNumBodyNodes(); ++i) + for (std::size_t i = 1; i < mAtlasRobot->getNumBodyNodes(); ++i) { Joint* joint = mAtlasRobot->getJoint(i); if (joint->getNumDofs() > 0) { - for (size_t j = 0; j < joint->getNumDofs(); ++j) + for (std::size_t j = 0; j < joint->getNumDofs(); ++j) joint->setDampingCoefficient(j, 80.0); } } diff --git a/apps/atlasSimbicon/Controller.h b/apps/atlasSimbicon/Controller.h index a3c0f6d073bb7..4c5f6c50d700b 100644 --- a/apps/atlasSimbicon/Controller.h +++ b/apps/atlasSimbicon/Controller.h @@ -73,7 +73,7 @@ class Controller void changeStateMachine(const std::string& _name, double _currentTime); /// \brief Change state machine to a state machine whose index is _idx - void changeStateMachine(size_t _idx, double _currentTime); + void changeStateMachine(std::size_t _idx, double _currentTime); /// \brief Keyboard control void keyboard(unsigned char _key, int _x, int _y, double _currentTime); @@ -125,16 +125,16 @@ class Controller bool mRightFootHarnessOn; /// \brief Index for coronal left hip - size_t mCoronalLeftHip; + std::size_t mCoronalLeftHip; /// \brief Index for coronal right hip - size_t mCoronalRightHip; + std::size_t mCoronalRightHip; /// \brief Index for sagital left hip - size_t mSagitalLeftHip; + std::size_t mSagitalLeftHip; /// \brief Index for sagital right hip - size_t mSagitalRightHip; + std::size_t mSagitalRightHip; private: /// \brief Check if this controller contains _stateMachine diff --git a/apps/atlasSimbicon/State.cpp b/apps/atlasSimbicon/State.cpp index a67316a6efe15..43a2e0083e599 100644 --- a/apps/atlasSimbicon/State.cpp +++ b/apps/atlasSimbicon/State.cpp @@ -533,7 +533,7 @@ double State::getElapsedTime() const //============================================================================== void State::setDesiredJointPosition(const string& _jointName, double _val) { - size_t index = mSkeleton->getDof(_jointName)->getIndexInSkeleton(); + std::size_t index = mSkeleton->getDof(_jointName)->getIndexInSkeleton(); mDesiredJointPositions[index] = _val; } @@ -646,7 +646,7 @@ double State::getDerivativeGain(int _idx) const //} //============================================================================== -void State::setFeedbackSagitalCOMDistance(size_t _index, double _val) +void State::setFeedbackSagitalCOMDistance(std::size_t _index, double _val) { assert(static_cast(_index) <= mSagitalCd.size() && "Invalid index."); @@ -654,7 +654,7 @@ void State::setFeedbackSagitalCOMDistance(size_t _index, double _val) } //============================================================================== -void State::setFeedbackSagitalCOMVelocity(size_t _index, double _val) +void State::setFeedbackSagitalCOMVelocity(std::size_t _index, double _val) { assert(static_cast(_index) <= mSagitalCv.size() && "Invalid index."); @@ -662,7 +662,7 @@ void State::setFeedbackSagitalCOMVelocity(size_t _index, double _val) } //============================================================================== -void State::setFeedbackCoronalCOMDistance(size_t _index, double _val) +void State::setFeedbackCoronalCOMDistance(std::size_t _index, double _val) { assert(static_cast(_index) <= mCoronalCd.size() && "Invalid index."); @@ -670,7 +670,7 @@ void State::setFeedbackCoronalCOMDistance(size_t _index, double _val) } //============================================================================== -void State::setFeedbackCoronalCOMVelocity(size_t _index, double _val) +void State::setFeedbackCoronalCOMVelocity(std::size_t _index, double _val) { assert(static_cast(_index) <= mCoronalCv.size() && "Invalid index."); diff --git a/apps/atlasSimbicon/State.h b/apps/atlasSimbicon/State.h index 15c39393d707c..abdda3a92f817 100644 --- a/apps/atlasSimbicon/State.h +++ b/apps/atlasSimbicon/State.h @@ -141,16 +141,16 @@ class State // double getDerivativeGain(const std::string& _jointName) const; /// \brief Set balance feedback gain parameter for sagital com distance - void setFeedbackSagitalCOMDistance(size_t _index, double _val); + void setFeedbackSagitalCOMDistance(std::size_t _index, double _val); /// \brief Set balance feedback gain parameter for sagital com velocity - void setFeedbackSagitalCOMVelocity(size_t _index, double _val); + void setFeedbackSagitalCOMVelocity(std::size_t _index, double _val); /// \brief Set balance feedback gain parameter for sagital com distance - void setFeedbackCoronalCOMDistance(size_t _index, double _val); + void setFeedbackCoronalCOMDistance(std::size_t _index, double _val); /// \brief Set balance feedback gain parameter for sagital com velocity - void setFeedbackCoronalCOMVelocity(size_t _index, double _val); + void setFeedbackCoronalCOMVelocity(std::size_t _index, double _val); /// \brief Set stance foot to left foot void setStanceFootToLeftFoot(); @@ -321,16 +321,16 @@ class State dart::dynamics::BodyNode* mRightFoot; /// \brief Index for coronal left hip - size_t mCoronalLeftHip; + std::size_t mCoronalLeftHip; /// \brief Index for coronal right hip - size_t mCoronalRightHip; + std::size_t mCoronalRightHip; /// \brief Index for sagital left hip - size_t mSagitalLeftHip; + std::size_t mSagitalLeftHip; /// \brief Index for sagital right hip - size_t mSagitalRightHip; + std::size_t mSagitalRightHip; /// \brief Desired joint positions with balance feedback Eigen::VectorXd mDesiredJointPositionsBalance; diff --git a/apps/atlasSimbicon/StateMachine.cpp b/apps/atlasSimbicon/StateMachine.cpp index 76e063956dc45..dad6348b6f5ad 100644 --- a/apps/atlasSimbicon/StateMachine.cpp +++ b/apps/atlasSimbicon/StateMachine.cpp @@ -178,7 +178,7 @@ void StateMachine::transiteTo(string& _stateName, double _currentTime) } //============================================================================== -void StateMachine::transiteTo(size_t _idx, double _currentTime) +void StateMachine::transiteTo(std::size_t _idx, double _currentTime) { assert(_idx <= mStates.size() && "Invalid index of State."); diff --git a/apps/atlasSimbicon/StateMachine.h b/apps/atlasSimbicon/StateMachine.h index 1614af27b536c..b0a574255c826 100644 --- a/apps/atlasSimbicon/StateMachine.h +++ b/apps/atlasSimbicon/StateMachine.h @@ -94,7 +94,7 @@ class StateMachine void transiteTo(std::string& _stateName, double _currentTime); /// \brief Change state to a state whose index is _idx - void transiteTo(size_t _idx, double _currentTime); + void transiteTo(std::size_t _idx, double _currentTime); protected: /// \brief Name diff --git a/apps/atlasSimbicon/TerminalCondition.cpp b/apps/atlasSimbicon/TerminalCondition.cpp index a6918e826d4bb..84df24074a7dd 100644 --- a/apps/atlasSimbicon/TerminalCondition.cpp +++ b/apps/atlasSimbicon/TerminalCondition.cpp @@ -104,7 +104,7 @@ bool BodyContactCondition::isSatisfied() SoftBodyNode* soft = dynamic_cast(mBodyNode); if (soft) { - for (size_t i = 0; i < soft->getNumPointMasses(); ++i) + for (std::size_t i = 0; i < soft->getNumPointMasses(); ++i) { PointMass* pm = soft->getPointMass(i); if (pm->isColliding() > 0) diff --git a/apps/bipedStand/Controller.cpp b/apps/bipedStand/Controller.cpp index a8854e5060049..301a735f0e3e5 100644 --- a/apps/bipedStand/Controller.cpp +++ b/apps/bipedStand/Controller.cpp @@ -93,7 +93,7 @@ void Controller::computeTorques() { Eigen::VectorXd constrForces = mSkel->getConstraintForces(); // SPD tracking - //size_t nDof = mSkel->getNumDofs(); + //std::size_t nDof = mSkel->getNumDofs(); Eigen::MatrixXd invM = (mSkel->getMassMatrix() + mKd * mTimestep).inverse(); Eigen::VectorXd p = -mKp * (_dof + _dofVel * mTimestep - mDesiredDofs); Eigen::VectorXd d = -mKd * _dofVel; diff --git a/apps/bipedStand/Controller.h b/apps/bipedStand/Controller.h index dd3a940494628..e17625835106b 100644 --- a/apps/bipedStand/Controller.h +++ b/apps/bipedStand/Controller.h @@ -66,8 +66,8 @@ class Controller { Eigen::VectorXd mDesiredDofs; Eigen::MatrixXd mKp; Eigen::MatrixXd mKd; - size_t mLeftFoot[2]; - size_t mRightFoot[2]; + std::size_t mLeftFoot[2]; + std::size_t mRightFoot[2]; int mFrame; double mTimestep; double mPreOffset; diff --git a/apps/hardcodedDesign/MyWindow.cpp b/apps/hardcodedDesign/MyWindow.cpp index 155c388515fa8..4ae321d31df63 100644 --- a/apps/hardcodedDesign/MyWindow.cpp +++ b/apps/hardcodedDesign/MyWindow.cpp @@ -60,7 +60,7 @@ void MyWindow::keyboard(unsigned char _key, int _x, int _y) { case '1': case '2': case '3': { - size_t dofIdx = _key - 49; + std::size_t dofIdx = _key - 49; Eigen::VectorXd pose = skel->getPositions(); pose(dofIdx) = pose(dofIdx) + (inverse ? -dDOF : dDOF); skel->setPositions(pose); diff --git a/apps/hybridDynamics/Main.cpp b/apps/hybridDynamics/Main.cpp index 22f0377d93bfd..6ab1d4b778284 100644 --- a/apps/hybridDynamics/Main.cpp +++ b/apps/hybridDynamics/Main.cpp @@ -50,7 +50,7 @@ int main(int argc, char* argv[]) dart::dynamics::SkeletonPtr skel = myWorld->getSkeleton(1); - std::vector genCoordIds; + std::vector genCoordIds; genCoordIds.push_back(1); genCoordIds.push_back(6); // left hip genCoordIds.push_back(9); // left knee @@ -65,7 +65,7 @@ int main(int argc, char* argv[]) dart::dynamics::Joint* joint0 = skel->getJoint(0); joint0->setActuatorType(dart::dynamics::Joint::PASSIVE); - for (size_t i = 1; i < skel->getNumBodyNodes(); ++i) + for (std::size_t i = 1; i < skel->getNumBodyNodes(); ++i) { dart::dynamics::Joint* joint = skel->getJoint(i); joint->setActuatorType(dart::dynamics::Joint::VELOCITY); diff --git a/apps/hybridDynamics/MyWindow.cpp b/apps/hybridDynamics/MyWindow.cpp index 1fa5a91c899b8..f197cf6abd133 100644 --- a/apps/hybridDynamics/MyWindow.cpp +++ b/apps/hybridDynamics/MyWindow.cpp @@ -53,13 +53,13 @@ void MyWindow::timeStepping() { dart::dynamics::SkeletonPtr skel = mWorld->getSkeleton(1); - size_t index0 = skel->getJoint("j_scapula_left")->getIndexInSkeleton(0); - size_t index1 = skel->getJoint("j_scapula_right")->getIndexInSkeleton(0); - size_t index2 = skel->getJoint("j_forearm_left")->getIndexInSkeleton(0); - size_t index3 = skel->getJoint("j_forearm_right")->getIndexInSkeleton(0); + std::size_t index0 = skel->getJoint("j_scapula_left")->getIndexInSkeleton(0); + std::size_t index1 = skel->getJoint("j_scapula_right")->getIndexInSkeleton(0); + std::size_t index2 = skel->getJoint("j_forearm_left")->getIndexInSkeleton(0); + std::size_t index3 = skel->getJoint("j_forearm_right")->getIndexInSkeleton(0); - size_t index6 = skel->getJoint("j_shin_left")->getIndexInSkeleton(0); - size_t index7 = skel->getJoint("j_shin_right")->getIndexInSkeleton(0); + std::size_t index6 = skel->getJoint("j_shin_left")->getIndexInSkeleton(0); + std::size_t index7 = skel->getJoint("j_shin_right")->getIndexInSkeleton(0); skel->setCommand(index0, 1.0 * std::sin(mWorld->getTime() * 4.0)); skel->setCommand(index1, -1.0 * std::sin(mWorld->getTime() * 4.0)); diff --git a/apps/jointConstraints/Controller.cpp b/apps/jointConstraints/Controller.cpp index e93b69cb7d4e1..44dd9f8892f5a 100644 --- a/apps/jointConstraints/Controller.cpp +++ b/apps/jointConstraints/Controller.cpp @@ -83,7 +83,7 @@ void Controller::computeTorques(const Eigen::VectorXd& _dof, const Eigen::VectorXd& _dofVel) { // SPD tracking - // size_t nDof = mSkel->getNumDofs(); + // std::size_t nDof = mSkel->getNumDofs(); Eigen::MatrixXd invM = (mSkel->getMassMatrix() + mKd * mTimestep).inverse(); Eigen::VectorXd p = -mKp * (_dof + _dofVel * mTimestep - mDesiredDofs); Eigen::VectorXd d = -mKd * _dofVel; diff --git a/apps/jointConstraints/Main.cpp b/apps/jointConstraints/Main.cpp index 91fb7df866ac2..45b316879d160 100644 --- a/apps/jointConstraints/Main.cpp +++ b/apps/jointConstraints/Main.cpp @@ -56,7 +56,7 @@ int main(int argc, char* argv[]) Eigen::Vector3d gravity(0.0, -9.81, 0.0); myWorld->setGravity(gravity); - std::vector genCoordIds; + std::vector genCoordIds; genCoordIds.push_back(1); // global orientation y genCoordIds.push_back(4); // global position y genCoordIds.push_back(6); // left hip diff --git a/apps/softBodies/Main.cpp b/apps/softBodies/Main.cpp index e309c58f2a2bd..9689782178f7e 100644 --- a/apps/softBodies/Main.cpp +++ b/apps/softBodies/Main.cpp @@ -55,10 +55,10 @@ int main(int argc, char* argv[]) DART_DATA_PATH"skel/softBodies.skel"); assert(myWorld != nullptr); - for(size_t i=0; igetNumSkeletons(); ++i) + for(std::size_t i=0; igetNumSkeletons(); ++i) { dart::dynamics::SkeletonPtr skel = myWorld->getSkeleton(i); - for(size_t j=0; jgetNumBodyNodes(); ++j) + for(std::size_t j=0; jgetNumBodyNodes(); ++j) { dart::dynamics::BodyNode* bn = skel->getBodyNode(j); Eigen::Vector3d color = dart::Color::Random(); diff --git a/apps/speedTest/Main.cpp b/apps/speedTest/Main.cpp index 39d11df62850b..8052d8acc4e66 100644 --- a/apps/speedTest/Main.cpp +++ b/apps/speedTest/Main.cpp @@ -45,7 +45,7 @@ double testForwardKinematicSpeed(dart::dynamics::SkeletonPtr skel, bool position=true, bool velocity=true, bool acceleration=true, - size_t numTests=100000) + std::size_t numTests=100000) { if(nullptr==skel) return 0; @@ -57,9 +57,9 @@ double testForwardKinematicSpeed(dart::dynamics::SkeletonPtr skel, std::chrono::time_point start, end; start = std::chrono::system_clock::now(); - for(size_t i=0; igetNumDofs(); ++i) + for(std::size_t i=0; igetNumDofs(); ++i) { dart::dynamics::DegreeOfFreedom* dof = skel->getDof(i); dof->setPosition( dart::math::random( @@ -67,7 +67,7 @@ double testForwardKinematicSpeed(dart::dynamics::SkeletonPtr skel, std::min(dof->getPositionUpperLimit(), 1.0)) ); } - for(size_t i=0; igetNumBodyNodes(); ++i) + for(std::size_t i=0; igetNumBodyNodes(); ++i) { if(position) skel->getBodyNode(i)->getWorldTransform(); @@ -102,7 +102,7 @@ void runKinematicsTest(std::vector& results, std::cout << "\n"; // Test for updating the whole skeleton - for(size_t i=0; igetSkeleton(0), @@ -113,12 +113,12 @@ void runKinematicsTest(std::vector& results, } double testDynamicsSpeed(dart::simulation::WorldPtr world, - size_t numIterations = 10000) + std::size_t numIterations = 10000) { if(nullptr==world) return 0; - for(size_t i=0; igetNumSkeletons(); ++i) + for(std::size_t i=0; igetNumSkeletons(); ++i) { dart::dynamics::SkeletonPtr skel = world->getSkeleton(i); skel->resetPositions(); @@ -129,7 +129,7 @@ double testDynamicsSpeed(dart::simulation::WorldPtr world, std::chrono::time_point start, end; start = std::chrono::system_clock::now(); - for(size_t i=0; istep(); } @@ -145,7 +145,7 @@ void runDynamicsTest(std::vector& results, { double totalTime = 0; - for(size_t i=0; i getWorlds() { std::vector sceneFiles = getSceneFiles(); std::vector worlds; - for(size_t i=0; i velocity_results; std::vector position_results; - for(size_t i=0; i<10; ++i) + for(std::size_t i=0; i<10; ++i) { std::cout << "\nTrial #" << i+1 << std::endl; runKinematicsTest(acceleration_results, worlds, true, true, true); @@ -245,7 +245,7 @@ int main(int argc, char* argv[]) std::cout << "Testing Dynamics" << std::endl; std::vector dynamics_results; - for(size_t i=0; i<10; ++i) + for(std::size_t i=0; i<10; ++i) { std::cout << "\nTrial #" << i+1 << std::endl; runDynamicsTest(dynamics_results, worlds); diff --git a/apps/vehicle/MyWindow.cpp b/apps/vehicle/MyWindow.cpp index 8f16ba1bf1acf..7fa753c886c47 100644 --- a/apps/vehicle/MyWindow.cpp +++ b/apps/vehicle/MyWindow.cpp @@ -51,7 +51,7 @@ void MyWindow::timeStepping() { dart::dynamics::SkeletonPtr vehicle = mWorld->getSkeleton("car_skeleton"); assert(vehicle != 0); - size_t dof = vehicle->getNumDofs(); + std::size_t dof = vehicle->getNumDofs(); Eigen::VectorXd q = vehicle->getPositions(); Eigen::VectorXd dq = vehicle->getVelocities(); diff --git a/dart/collision/CollisionGroup.cpp b/dart/collision/CollisionGroup.cpp index d2e3f8de617eb..732d532de81a9 100644 --- a/dart/collision/CollisionGroup.cpp +++ b/dart/collision/CollisionGroup.cpp @@ -149,7 +149,7 @@ bool CollisionGroup::hasShapeFrame( } //============================================================================== -size_t CollisionGroup::getNumShapeFrames() const +std::size_t CollisionGroup::getNumShapeFrames() const { return mShapeFrameMap.size(); } diff --git a/dart/collision/CollisionGroup.h b/dart/collision/CollisionGroup.h index a1aa234b20048..b6aadaa4bd06f 100644 --- a/dart/collision/CollisionGroup.h +++ b/dart/collision/CollisionGroup.h @@ -166,7 +166,7 @@ class CollisionGroup bool hasShapeFrame(const dynamics::ShapeFrame* shapeFrame) const; /// Return number of ShapeFrames added to this CollisionGroup - size_t getNumShapeFrames() const; + std::size_t getNumShapeFrames() const; /// Perform collision detection within this CollisionGroup. bool collide(const CollisionOption& option, CollisionResult& result); diff --git a/dart/collision/Option.cpp b/dart/collision/Option.cpp index 113652cec7880..9c31559bbcbdd 100644 --- a/dart/collision/Option.cpp +++ b/dart/collision/Option.cpp @@ -43,7 +43,7 @@ namespace collision { CollisionOption::CollisionOption( bool enableContact, bool binaryCheck, - size_t maxNumContacts, + std::size_t maxNumContacts, const std::shared_ptr& collisionFilter) : enableContact(enableContact), binaryCheck(binaryCheck), diff --git a/dart/collision/Option.h b/dart/collision/Option.h index 3371a6a78fa3d..9c59de7e35840 100644 --- a/dart/collision/Option.h +++ b/dart/collision/Option.h @@ -57,7 +57,7 @@ struct CollisionOption bool binaryCheck; /// Maximum number of contacts to detect - size_t maxNumContacts; + std::size_t maxNumContacts; /// CollisionFilter std::shared_ptr collisionFilter; @@ -65,7 +65,7 @@ struct CollisionOption /// Constructor CollisionOption(bool enableContact = true, bool binaryCheck = false, - size_t maxNumContacts = 100, + std::size_t maxNumContacts = 100, const std::shared_ptr& collisionFilter = nullptr); }; diff --git a/dart/collision/Result.cpp b/dart/collision/Result.cpp index e8e8d1ff65a3f..cfd2a88eadbd8 100644 --- a/dart/collision/Result.cpp +++ b/dart/collision/Result.cpp @@ -53,13 +53,13 @@ void CollisionResult::addContact(const Contact& contact) } //============================================================================== -size_t CollisionResult::getNumContacts() const +std::size_t CollisionResult::getNumContacts() const { return mContacts.size(); } //============================================================================== -Contact& CollisionResult::getContact(size_t index) +Contact& CollisionResult::getContact(std::size_t index) { assert(index < mContacts.size()); @@ -67,7 +67,7 @@ Contact& CollisionResult::getContact(size_t index) } //============================================================================== -const Contact& CollisionResult::getContact(size_t index) const +const Contact& CollisionResult::getContact(std::size_t index) const { assert(index < mContacts.size()); diff --git a/dart/collision/Result.h b/dart/collision/Result.h index aad8149a2c30e..ba7f7aec46da2 100644 --- a/dart/collision/Result.h +++ b/dart/collision/Result.h @@ -60,13 +60,13 @@ class CollisionResult void addContact(const Contact& contact); /// Return number of contacts - size_t getNumContacts() const; + std::size_t getNumContacts() const; /// Return the index-th contact - Contact& getContact(size_t index); + Contact& getContact(std::size_t index); /// Return (const) the index-th contact - const Contact& getContact(size_t index) const; + const Contact& getContact(std::size_t index) const; /// Return contacts const std::vector& getContacts() const; diff --git a/dart/collision/bullet/BulletCollisionDetector.h b/dart/collision/bullet/BulletCollisionDetector.h index bc6bc8dcb6e02..99382e65ee08b 100644 --- a/dart/collision/bullet/BulletCollisionDetector.h +++ b/dart/collision/bullet/BulletCollisionDetector.h @@ -107,7 +107,7 @@ class BulletCollisionDetector : public CollisionDetector private: std::map> mShapeMap; + std::pair> mShapeMap; }; diff --git a/dart/collision/fcl/FCLCollisionDetector.cpp b/dart/collision/fcl/FCLCollisionDetector.cpp index 18a634c2e833c..de0f572e895bb 100644 --- a/dart/collision/fcl/FCLCollisionDetector.cpp +++ b/dart/collision/fcl/FCLCollisionDetector.cpp @@ -149,7 +149,7 @@ struct FCLCollisionCallbackData { convertOption(mOption, mFclRequest); - mFclRequest.num_max_contacts = std::max(static_cast(100u), + mFclRequest.num_max_contacts = std::max(static_cast(100u), mOption.maxNumContacts); // Since some contact points can be filtered out in the post process, we ask // more than the demend. 100 is randomly picked. @@ -523,12 +523,12 @@ fcl::BVHModel* createMesh(float _scaleX, float _scaleY, float _scaleZ, assert(_mesh); fcl::BVHModel* model = new fcl::BVHModel; model->beginModel(); - for (size_t i = 0; i < _mesh->mNumMeshes; i++) + for (std::size_t i = 0; i < _mesh->mNumMeshes; i++) { - for (size_t j = 0; j < _mesh->mMeshes[i]->mNumFaces; j++) + for (std::size_t j = 0; j < _mesh->mMeshes[i]->mNumFaces; j++) { fcl::Vec3f vertices[3]; - for (size_t k = 0; k < 3; k++) + for (std::size_t k = 0; k < 3; k++) { const aiVector3D& vertex = _mesh->mMeshes[i]->mVertices[ @@ -554,10 +554,10 @@ fcl::BVHModel* createSoftMesh(const aiMesh* _mesh) fcl::BVHModel* model = new fcl::BVHModel; model->beginModel(); - for (size_t i = 0; i < _mesh->mNumFaces; i++) + for (std::size_t i = 0; i < _mesh->mNumFaces; i++) { fcl::Vec3f vertices[3]; - for (size_t j = 0; j < 3; j++) + for (std::size_t j = 0; j < 3; j++) { const aiVector3D& vertex = _mesh->mVertices[_mesh->mFaces[i].mIndices[j]]; vertices[j] = fcl::Vec3f(vertex.x, vertex.y, vertex.z); @@ -1071,7 +1071,7 @@ void postProcessFCL(const fcl::CollisionResult& fclResult, } } - for (size_t i = 0; i < numContacts; ++i) + for (std::size_t i = 0; i < numContacts; ++i) { if (!markForDeletion[i]) { diff --git a/dart/common/LocalResource.cpp b/dart/common/LocalResource.cpp index 99df39378100c..88cb9ede2187d 100644 --- a/dart/common/LocalResource.cpp +++ b/dart/common/LocalResource.cpp @@ -75,7 +75,7 @@ bool LocalResource::isGood() const } //============================================================================== -size_t LocalResource::getSize() +std::size_t LocalResource::getSize() { if(!mFile) return 0; @@ -131,7 +131,7 @@ size_t LocalResource::getSize() } //============================================================================== -size_t LocalResource::tell() +std::size_t LocalResource::tell() { if(!mFile) return 0; @@ -193,12 +193,12 @@ bool LocalResource::seek(ptrdiff_t _offset, SeekType _mode) } //============================================================================== -size_t LocalResource::read(void *_buffer, size_t _size, size_t _count) +std::size_t LocalResource::read(void *_buffer, std::size_t _size, std::size_t _count) { if (!mFile) return 0; - const size_t result = std::fread(_buffer, _size, _count, mFile); + const std::size_t result = std::fread(_buffer, _size, _count, mFile); if (std::ferror(mFile)) { dtwarn << "[LocalResource::read] Failed reading file: " diff --git a/dart/common/LocalResource.h b/dart/common/LocalResource.h index 276f87ea388b8..62b096d8aec5f 100644 --- a/dart/common/LocalResource.h +++ b/dart/common/LocalResource.h @@ -55,16 +55,16 @@ class LocalResource : public virtual Resource bool isGood() const; // Documentation inherited. - size_t getSize() override; + std::size_t getSize() override; // Documentation inherited. - size_t tell() override; + std::size_t tell() override; // Documentation inherited. bool seek(ptrdiff_t _origin, SeekType _mode) override; // Documentation inherited. - size_t read(void* _buffer, size_t _size, size_t _count) override; + std::size_t read(void* _buffer, std::size_t _size, std::size_t _count) override; private: std::FILE* mFile; diff --git a/dart/common/NameManager.h b/dart/common/NameManager.h index cb368da7b836e..bf1249e1af68c 100644 --- a/dart/common/NameManager.h +++ b/dart/common/NameManager.h @@ -115,7 +115,7 @@ class NameManager bool hasObject(const T& _obj) const; /// Get the number of the objects currently stored by the NameManager - size_t getCount() const; + std::size_t getCount() const; /// Get object by given name /// \param[in] _name diff --git a/dart/common/Resource.h b/dart/common/Resource.h index 47000f3d0a2b1..dc14f8d99a379 100644 --- a/dart/common/Resource.h +++ b/dart/common/Resource.h @@ -61,11 +61,11 @@ class Resource virtual ~Resource() = default; /// \brief Return the size of the resource, in bytes. - virtual size_t getSize() = 0; + virtual std::size_t getSize() = 0; /// \brief Return the current value of the position indicator. /// \note This method has the same API as the standard ftell function. - virtual size_t tell() = 0; + virtual std::size_t tell() = 0; /// \brief Set the position indicator to a new position. /// \param[in] _offset Offset, in bytes, relative to _origin. @@ -79,7 +79,7 @@ class Resource /// \param[in] _size Size, in bytes, of each element. /// \param[in] _count Number of elements, each of _size bytes. /// \note This method has the same API as the standard fread function. - virtual size_t read(void *_buffer, size_t _size, size_t _count) = 0; + virtual std::size_t read(void *_buffer, std::size_t _size, std::size_t _count) = 0; }; using ResourcePtr = std::shared_ptr; diff --git a/dart/common/Signal.h b/dart/common/Signal.h index cefb78b60f3d4..ed5b14347b655 100644 --- a/dart/common/Signal.h +++ b/dart/common/Signal.h @@ -145,7 +145,7 @@ class Signal<_Res(_ArgTypes...), Combiner> void cleanupConnections(); /// Get the number of connections - size_t getNumConnections() const; + std::size_t getNumConnections() const; /// Raise the signal template @@ -195,7 +195,7 @@ class Signal void cleanupConnections(); /// Get the number of connections - size_t getNumConnections() const; + std::size_t getNumConnections() const; /// Raise the signal template diff --git a/dart/common/StlHelpers.h b/dart/common/StlHelpers.h index ae1f276b3af85..d4e3a6404dcd2 100644 --- a/dart/common/StlHelpers.h +++ b/dart/common/StlHelpers.h @@ -61,7 +61,7 @@ std::unique_ptr make_unique(Args&&... args) //============================================================================== template -static T getVectorObjectIfAvailable(size_t index, const std::vector& vec) +static T getVectorObjectIfAvailable(std::size_t index, const std::vector& vec) { assert(index < vec.size()); if(index < vec.size()) diff --git a/dart/common/Uri.cpp b/dart/common/Uri.cpp index 80ee728d37af4..530543dde3050 100644 --- a/dart/common/Uri.cpp +++ b/dart/common/Uri.cpp @@ -226,11 +226,11 @@ bool Uri::fromString(const std::string& _input) static regex uriRegex( R"END(^(([^:/?#]+):)?(//([^/?#]*))?([^?#]*)(\?([^#]*))?(#(.*))?)END", regex::extended | regex::optimize); - static const size_t schemeIndex = 2; - static const size_t authorityIndex = 4; - static const size_t pathIndex = 5; - static const size_t queryIndex = 7; - static const size_t fragmentIndex = 9; + static const std::size_t schemeIndex = 2; + static const std::size_t authorityIndex = 4; + static const std::size_t pathIndex = 5; + static const std::size_t queryIndex = 7; + static const std::size_t fragmentIndex = 9; clear(); @@ -614,7 +614,7 @@ std::string Uri::mergePaths(const Uri& _base, const Uri& _relative) return "/" + *_relative.mPath; else { - const size_t index = _base.mPath->find_last_of('/'); + const std::size_t index = _base.mPath->find_last_of('/'); if(index != std::string::npos) return _base.mPath->substr(0, index + 1) + *_relative.mPath; else @@ -664,7 +664,7 @@ std::string Uri::removeDotSegments(const std::string& _path) { input = "/"; - size_t index = output.find_last_of('/'); + std::size_t index = output.find_last_of('/'); if(index != std::string::npos) output = output.substr(0, index); else @@ -674,7 +674,7 @@ std::string Uri::removeDotSegments(const std::string& _path) { input = "/" + input.substr(4); - size_t index = output.find_last_of('/'); + std::size_t index = output.find_last_of('/'); if(index != std::string::npos) output = output.substr(0, index); else @@ -693,7 +693,7 @@ std::string Uri::removeDotSegments(const std::string& _path) else { // Start at index one so we keep the leading '/'. - size_t index = input.find_first_of('/', 1); + std::size_t index = input.find_first_of('/', 1); output += input.substr(0, index); if(index != std::string::npos) diff --git a/dart/common/VersionCounter.cpp b/dart/common/VersionCounter.cpp index 44e5b3ed5fa2a..3495691122a46 100644 --- a/dart/common/VersionCounter.cpp +++ b/dart/common/VersionCounter.cpp @@ -52,7 +52,7 @@ VersionCounter::VersionCounter() } //============================================================================== -size_t VersionCounter::incrementVersion() +std::size_t VersionCounter::incrementVersion() { ++mVersion; if(mDependent) @@ -62,7 +62,7 @@ size_t VersionCounter::incrementVersion() } //============================================================================== -size_t VersionCounter::getVersion() const +std::size_t VersionCounter::getVersion() const { return mVersion; } diff --git a/dart/common/VersionCounter.h b/dart/common/VersionCounter.h index d3aa14ed4c37e..0d012191fe1bd 100644 --- a/dart/common/VersionCounter.h +++ b/dart/common/VersionCounter.h @@ -51,10 +51,10 @@ class VersionCounter VersionCounter(); /// Increment the version for this object - virtual size_t incrementVersion(); + virtual std::size_t incrementVersion(); /// Get the version number of this object - virtual size_t getVersion() const; + virtual std::size_t getVersion() const; virtual ~VersionCounter() = default; @@ -62,7 +62,7 @@ class VersionCounter void setVersionDependentObject(VersionCounter* dependent); - size_t mVersion; + std::size_t mVersion; private: VersionCounter* mDependent; diff --git a/dart/common/detail/AspectWithVersion.h b/dart/common/detail/AspectWithVersion.h index c7c6bf83cd894..84fb7e069114a 100644 --- a/dart/common/detail/AspectWithVersion.h +++ b/dart/common/detail/AspectWithVersion.h @@ -156,7 +156,7 @@ class AspectWithVersionedProperties : public BaseT Composite* newComposite) const override; /// Increment the version of this Aspect and its Composite - size_t incrementVersion(); + std::size_t incrementVersion(); /// Call UpdateProperties(this) and incrementVersion() void notifyPropertiesUpdate(); @@ -322,7 +322,7 @@ cloneAspect(Composite* newComposite) const //============================================================================== template -size_t AspectWithVersionedProperties::incrementVersion() { if(CompositeType* comp = this->getComposite()) diff --git a/dart/common/detail/Cloneable.h b/dart/common/detail/Cloneable.h index a2662fb0b4151..4913146f2aa13 100644 --- a/dart/common/detail/Cloneable.h +++ b/dart/common/detail/Cloneable.h @@ -543,7 +543,7 @@ void CloneableVector::copy(const CloneableVector& anotherVector) const std::vector& other = anotherVector.getVector(); mVector.resize(other.size()); - for(size_t i=0; i < other.size(); ++i) + for(std::size_t i=0; i < other.size(); ++i) { if(mVector[i] && other[i]) mVector[i]->copy(*other[i]); diff --git a/dart/common/detail/NameManager.h b/dart/common/detail/NameManager.h index e2b2bab769dd9..e7c45525e1932 100644 --- a/dart/common/detail/NameManager.h +++ b/dart/common/detail/NameManager.h @@ -62,8 +62,8 @@ NameManager::NameManager(const std::string& _managerName, template bool NameManager::setPattern(const std::string& _newPattern) { - size_t name_start = _newPattern.find("%s"); - size_t number_start = _newPattern.find("%d"); + std::size_t name_start = _newPattern.find("%s"); + std::size_t number_start = _newPattern.find("%d"); if(name_start == std::string::npos || number_start == std::string::npos) return false; @@ -73,8 +73,8 @@ bool NameManager::setPattern(const std::string& _newPattern) else mNameBeforeNumber = false; - size_t prefix_end = std::min(name_start, number_start); - size_t infix_end = std::max(name_start, number_start); + std::size_t prefix_end = std::min(name_start, number_start); + std::size_t infix_end = std::max(name_start, number_start); mPrefix = _newPattern.substr(0, prefix_end); mInfix = _newPattern.substr(prefix_end+2, infix_end-prefix_end-2); @@ -221,7 +221,7 @@ bool NameManager::hasObject(const T& _obj) const //============================================================================== template -size_t NameManager::getCount() const +std::size_t NameManager::getCount() const { return mMap.size(); } diff --git a/dart/common/detail/Signal.h b/dart/common/detail/Signal.h index a63e1361864aa..0c4a701f6fa0a 100644 --- a/dart/common/detail/Signal.h +++ b/dart/common/detail/Signal.h @@ -106,9 +106,9 @@ void Signal<_Res (_ArgTypes...), Combiner>::cleanupConnections() //============================================================================== template class Combiner> -size_t Signal<_Res (_ArgTypes...), Combiner>::getNumConnections() const +std::size_t Signal<_Res (_ArgTypes...), Combiner>::getNumConnections() const { - size_t numConnections = 0; + std::size_t numConnections = 0; // Counts all the connected conection bodies for (const auto& connectionBody : mConnectionBodies) @@ -216,9 +216,9 @@ void Signal::cleanupConnections() //============================================================================== template -size_t Signal::getNumConnections() const +std::size_t Signal::getNumConnections() const { - size_t numConnections = 0; + std::size_t numConnections = 0; // Counts all the connected conection bodies for (const auto& connectionBody : mConnectionBodies) diff --git a/dart/constraint/BalanceConstraint.cpp b/dart/constraint/BalanceConstraint.cpp index 3dd2db9c83b08..ce3bb80801af0 100644 --- a/dart/constraint/BalanceConstraint.cpp +++ b/dart/constraint/BalanceConstraint.cpp @@ -137,14 +137,14 @@ double BalanceConstraint::eval(const Eigen::VectorXd& _x) if(!zeroError) { - size_t closestIndex1, closestIndex2; + std::size_t closestIndex1, closestIndex2; const Eigen::Vector2d closestPoint = math::computeClosestPointOnSupportPolygon( closestIndex1, closestIndex2, projected_com, polygon); // Save the indices of the EndEffectors that are closest to the center of // mass - const std::vector& indexMap = skel->getSupportIndices(); + const std::vector& indexMap = skel->getSupportIndices(); mClosestEndEffector[0] = indexMap[closestIndex1]; mClosestEndEffector[1] = indexMap[closestIndex2]; @@ -191,7 +191,7 @@ void BalanceConstraint::evalGradient(const Eigen::VectorXd& _x, // If eval(_x) was non-zero, then the IK and Skeleton should still exist, so // we shouldn't need to test their existance. const dynamics::SkeletonPtr& skel = mIK.lock()->getSkeleton(); - const size_t nDofs = skel->getNumDofs(); + const std::size_t nDofs = skel->getNumDofs(); if(SHIFT_COM == mBalanceMethod) { @@ -200,9 +200,9 @@ void BalanceConstraint::evalGradient(const Eigen::VectorXd& _x, // locations mNullSpaceCache.setIdentity(nDofs, nDofs); - size_t numEE = skel->getNumEndEffectors(); + std::size_t numEE = skel->getNumEndEffectors(); // Build up the null space of the supporting end effectors - for(size_t i=0; i < numEE; ++i) + for(std::size_t i=0; i < numEE; ++i) { const dynamics::EndEffector* ee = skel->getEndEffector(i); @@ -258,8 +258,8 @@ void BalanceConstraint::evalGradient(const Eigen::VectorXd& _x, mNullSpaceCache.setZero(); } - size_t numEE = skel->getNumEndEffectors(); - for(size_t i=0; i < numEE; ++i) + std::size_t numEE = skel->getNumEndEffectors(); + for(std::size_t i=0; i < numEE; ++i) { const dynamics::EndEffector* ee = skel->getEndEffector(i); @@ -295,7 +295,7 @@ void BalanceConstraint::evalGradient(const Eigen::VectorXd& _x, mNullSpaceCache.setZero(); } - for(size_t i=0; i<2; ++i) + for(std::size_t i=0; i<2; ++i) { const dynamics::EndEffector* ee = skel->getEndEffector(mClosestEndEffector[i]); diff --git a/dart/constraint/BalanceConstraint.h b/dart/constraint/BalanceConstraint.h index 2a6180b57f833..2e81cef603460 100644 --- a/dart/constraint/BalanceConstraint.h +++ b/dart/constraint/BalanceConstraint.h @@ -163,7 +163,7 @@ class BalanceConstraint : public optimizer::Function, /// The indices of the supporting end effectors that are closest to the center /// of mass. These are used when using FROM_EDGE - size_t mClosestEndEffector[2]; + std::size_t mClosestEndEffector[2]; /// The error vector points away from the direction that the center of mass /// should move in order to reduce the balance error @@ -173,7 +173,7 @@ class BalanceConstraint : public optimizer::Function, Eigen::Vector3d mLastCOM; /// The last version of the support polygon that was computed - size_t mLastSupportVersion; + std::size_t mLastSupportVersion; /// Cache for the center of mass Jacobian so that the memory space does not /// need to be reallocated each loop diff --git a/dart/constraint/BallJointConstraint.cpp b/dart/constraint/BallJointConstraint.cpp index 190bd853d98a8..29d19f8729cd8 100644 --- a/dart/constraint/BallJointConstraint.cpp +++ b/dart/constraint/BallJointConstraint.cpp @@ -164,7 +164,7 @@ void BallJointConstraint::getInformation(ConstraintInfo* _lcp) } //============================================================================== -void BallJointConstraint::applyUnitImpulse(size_t _index) +void BallJointConstraint::applyUnitImpulse(std::size_t _index) { assert(_index < mDim && "Invalid Index."); assert(isActive()); @@ -244,7 +244,7 @@ void BallJointConstraint::getVelocityChange(double* _vel, bool _withCfm) { assert(_vel != nullptr && "Null pointer is not allowed."); - for (size_t i = 0; i < mDim; ++i) + for (std::size_t i = 0; i < mDim; ++i) _vel[i] = 0.0; if (mBodyNode1->getSkeleton()->isImpulseApplied() @@ -253,7 +253,7 @@ void BallJointConstraint::getVelocityChange(double* _vel, bool _withCfm) Eigen::Vector3d v1 = mJacobian1 * mBodyNode1->getBodyVelocityChange(); // std::cout << "velChange " << mBodyNode1->getBodyVelocityChange() << std::endl; // std::cout << "v1: " << v1 << std::endl; - for (size_t i = 0; i < mDim; ++i) + for (std::size_t i = 0; i < mDim; ++i) _vel[i] += v1[i]; } @@ -263,7 +263,7 @@ void BallJointConstraint::getVelocityChange(double* _vel, bool _withCfm) { Eigen::Vector3d v2 = mJacobian2 * mBodyNode2->getBodyVelocityChange(); // std::cout << "v2: " << v2 << std::endl; - for (size_t i = 0; i < mDim; ++i) + for (std::size_t i = 0; i < mDim; ++i) _vel[i] -= v2[i]; } diff --git a/dart/constraint/BallJointConstraint.h b/dart/constraint/BallJointConstraint.h index d555be87c17a2..ff97a75886c3d 100644 --- a/dart/constraint/BallJointConstraint.h +++ b/dart/constraint/BallJointConstraint.h @@ -78,7 +78,7 @@ class BallJointConstraint : public JointConstraint void getInformation(ConstraintInfo* _lcp) override; // Documentation inherited - void applyUnitImpulse(size_t _index) override; + void applyUnitImpulse(std::size_t _index) override; // Documentation inherited void getVelocityChange(double* _vel, bool _withCfm) override; @@ -123,7 +123,7 @@ class BallJointConstraint : public JointConstraint double mOldX[3]; /// Index of applied impulse - size_t mAppliedImpulseIndex; + std::size_t mAppliedImpulseIndex; public: // To get byte-aligned Eigen vectors diff --git a/dart/constraint/ConstrainedGroup.cpp b/dart/constraint/ConstrainedGroup.cpp index 79d72052517b4..d4b0752dabecd 100644 --- a/dart/constraint/ConstrainedGroup.cpp +++ b/dart/constraint/ConstrainedGroup.cpp @@ -69,13 +69,13 @@ void ConstrainedGroup::addConstraint(const ConstraintBasePtr& _constraint) } //============================================================================== -size_t ConstrainedGroup::getNumConstraints() const +std::size_t ConstrainedGroup::getNumConstraints() const { return mConstraints.size(); } //============================================================================== -ConstraintBasePtr ConstrainedGroup::getConstraint(size_t _index) const +ConstraintBasePtr ConstrainedGroup::getConstraint(std::size_t _index) const { assert(_index < mConstraints.size()); return mConstraints[_index]; @@ -110,11 +110,11 @@ bool ConstrainedGroup::containConstraint( #endif //============================================================================== -size_t ConstrainedGroup::getTotalDimension() const +std::size_t ConstrainedGroup::getTotalDimension() const { - size_t totalDim = 0; + std::size_t totalDim = 0; - for (size_t i = 0; i < mConstraints.size(); ++i) + for (std::size_t i = 0; i < mConstraints.size(); ++i) totalDim += mConstraints[i]->getDimension(); return totalDim; diff --git a/dart/constraint/ConstrainedGroup.h b/dart/constraint/ConstrainedGroup.h index 4c736d133f450..f252629cb8aae 100644 --- a/dart/constraint/ConstrainedGroup.h +++ b/dart/constraint/ConstrainedGroup.h @@ -79,10 +79,10 @@ class ConstrainedGroup void addConstraint(const ConstraintBasePtr& _constraint); /// Return number of constraints in this constrained group - size_t getNumConstraints() const; + std::size_t getNumConstraints() const; /// Return a constraint - ConstraintBasePtr getConstraint(size_t _index) const; + ConstraintBasePtr getConstraint(std::size_t _index) const; /// Remove constraint void removeConstraint(const ConstraintBasePtr& _constraint); @@ -91,7 +91,7 @@ class ConstrainedGroup void removeAllConstraints(); /// Get total dimension of contraints in this group - size_t getTotalDimension() const; + std::size_t getTotalDimension() const; //---------------------------------------------------------------------------- // Friendship diff --git a/dart/constraint/ConstraintBase.cpp b/dart/constraint/ConstraintBase.cpp index 591829489033a..3174bc383cb7c 100644 --- a/dart/constraint/ConstraintBase.cpp +++ b/dart/constraint/ConstraintBase.cpp @@ -58,7 +58,7 @@ ConstraintBase::~ConstraintBase() } //============================================================================== -size_t ConstraintBase::getDimension() const +std::size_t ConstraintBase::getDimension() const { return mDim; } diff --git a/dart/constraint/ConstraintBase.h b/dart/constraint/ConstraintBase.h index 20956a5302181..3e5fcf23f4a5f 100644 --- a/dart/constraint/ConstraintBase.h +++ b/dart/constraint/ConstraintBase.h @@ -79,7 +79,7 @@ class ConstraintBase { public: /// Return dimesion of this constranit - size_t getDimension() const; + std::size_t getDimension() const; /// Update constraint using updated Skeleton's states virtual void update() = 0; @@ -88,7 +88,7 @@ class ConstraintBase virtual void getInformation(ConstraintInfo* _info) = 0; /// Apply unit impulse to constraint space - virtual void applyUnitImpulse(size_t _index) = 0; + virtual void applyUnitImpulse(std::size_t _index) = 0; /// Get velocity change due to the uint impulse virtual void getVelocityChange(double* _vel, bool _withCfm) = 0; @@ -133,7 +133,7 @@ class ConstraintBase protected: /// Dimension of constraint - size_t mDim; + std::size_t mDim; }; } // namespace constraint diff --git a/dart/constraint/ConstraintSolver.cpp b/dart/constraint/ConstraintSolver.cpp index e4f666722e652..7448e5086b340 100644 --- a/dart/constraint/ConstraintSolver.cpp +++ b/dart/constraint/ConstraintSolver.cpp @@ -290,7 +290,7 @@ LCPSolver* ConstraintSolver::getLCPSolver() const //============================================================================== void ConstraintSolver::solve() { - for (size_t i = 0; i < mSkeletons.size(); ++i) + for (std::size_t i = 0; i < mSkeletons.size(); ++i) { mSkeletons[i]->clearConstraintImpulses(); DART_SUPPRESS_DEPRECATED_BEGIN @@ -451,16 +451,16 @@ DART_SUPPRESS_DEPRECATED_END // Create new joint constraints for (const auto& skel : mSkeletons) { - const size_t numJoints = skel->getNumJoints(); - for (size_t i = 0; i < numJoints; i++) + const std::size_t numJoints = skel->getNumJoints(); + for (std::size_t i = 0; i < numJoints; i++) { dynamics::Joint* joint = skel->getJoint(i); if (joint->isKinematic()) continue; - const size_t dof = joint->getNumDofs(); - for (size_t j = 0; j < dof; ++j) + const std::size_t dof = joint->getNumDofs(); + for (std::size_t j = 0; j < dof; ++j) { if (joint->getCoulombFriction(j) != 0.0) { diff --git a/dart/constraint/ContactConstraint.cpp b/dart/constraint/ContactConstraint.cpp index 6b8797d8a5144..6f6ed92cd8f51 100644 --- a/dart/constraint/ContactConstraint.cpp +++ b/dart/constraint/ContactConstraint.cpp @@ -125,7 +125,7 @@ ContactConstraint::ContactConstraint(collision::Contact& _contact, mJacobians2.resize(mDim); // Intermediate variables - size_t idx = 0; + std::size_t idx = 0; Eigen::Vector3d bodyDirection1; Eigen::Vector3d bodyDirection2; @@ -133,7 +133,7 @@ ContactConstraint::ContactConstraint(collision::Contact& _contact, Eigen::Vector3d bodyPoint1; Eigen::Vector3d bodyPoint2; - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { collision::Contact* ct = mContacts[i]; @@ -224,7 +224,7 @@ ContactConstraint::ContactConstraint(collision::Contact& _contact, Eigen::Vector3d bodyPoint1; Eigen::Vector3d bodyPoint2; - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { collision::Contact* ct = mContacts[i]; @@ -384,8 +384,8 @@ void ContactConstraint::getInformation(ConstraintInfo* _info) //---------------------------------------------------------------------------- if (mIsFrictionOn) { - size_t index = 0; - for (size_t i = 0; i < mContacts.size(); ++i) + std::size_t index = 0; + for (std::size_t i = 0; i < mContacts.size(); ++i) { // Bias term, w, should be zero assert(_info->w[index] == 0.0); @@ -470,7 +470,7 @@ void ContactConstraint::getInformation(ConstraintInfo* _info) //---------------------------------------------------------------------------- else { - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { // Bias term, w, should be zero _info->w[i] = 0.0; @@ -531,7 +531,7 @@ void ContactConstraint::getInformation(ConstraintInfo* _info) } //============================================================================== -void ContactConstraint::applyUnitImpulse(size_t _idx) +void ContactConstraint::applyUnitImpulse(std::size_t _idx) { assert(_idx < mDim && "Invalid Index."); assert(isActive()); @@ -602,7 +602,7 @@ void ContactConstraint::getVelocityChange(double* _vel, bool _withCfm) { assert(_vel != nullptr && "Null pointer is not allowed."); - for (size_t i = 0; i < mDim; ++i) + for (std::size_t i = 0; i < mDim; ++i) { _vel[i] = 0.0; @@ -656,9 +656,9 @@ void ContactConstraint::applyImpulse(double* _lambda) //---------------------------------------------------------------------------- if (mIsFrictionOn) { - size_t index = 0; + std::size_t index = 0; - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { // std::cout << "_lambda1: " << _lambda[index] << std::endl; // std::cout << "_lambda2: " << _lambda[index + 1] << std::endl; @@ -717,7 +717,7 @@ void ContactConstraint::applyImpulse(double* _lambda) //---------------------------------------------------------------------------- else { - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { // Normal impulsive force // pContactPts[i]->lambda[0] = _lambda[i]; @@ -738,7 +738,7 @@ void ContactConstraint::getRelVelocity(double* _relVel) { assert(_relVel != nullptr && "Null pointer is not allowed."); - for (size_t i = 0; i < mDim; ++i) + for (std::size_t i = 0; i < mDim; ++i) { _relVel[i] = 0.0; diff --git a/dart/constraint/ContactConstraint.h b/dart/constraint/ContactConstraint.h index 875d9761d51db..a8bfbd26b4419 100644 --- a/dart/constraint/ContactConstraint.h +++ b/dart/constraint/ContactConstraint.h @@ -114,7 +114,7 @@ class ContactConstraint : public ConstraintBase void getInformation(ConstraintInfo* _info) override; // Documentation inherited - void applyUnitImpulse(size_t _idx) override; + void applyUnitImpulse(std::size_t _idx) override; // Documentation inherited void getVelocityChange(double* _vel, bool _withCfm) override; @@ -181,7 +181,7 @@ class ContactConstraint : public ConstraintBase bool mIsFrictionOn; /// Index of applied impulse - size_t mAppliedImpulseIndex; + std::size_t mAppliedImpulseIndex; /// bool mIsBounceOn; diff --git a/dart/constraint/DantzigLCPSolver.cpp b/dart/constraint/DantzigLCPSolver.cpp index d0972eb5d106c..787e2f8148dbe 100644 --- a/dart/constraint/DantzigLCPSolver.cpp +++ b/dart/constraint/DantzigLCPSolver.cpp @@ -65,8 +65,8 @@ void DantzigLCPSolver::solve(ConstrainedGroup* _group) { // Build LCP terms by aggregating them from constraints - size_t numConstraints = _group->getNumConstraints(); - size_t n = _group->getTotalDimension(); + std::size_t numConstraints = _group->getNumConstraints(); + std::size_t n = _group->getTotalDimension(); // If there is no constraint, then just return. if (0u == n) @@ -89,10 +89,10 @@ void DantzigLCPSolver::solve(ConstrainedGroup* _group) std::memset(findex, -1, n * sizeof(int)); // Compute offset indices - size_t* offset = new size_t[n]; + std::size_t* offset = new std::size_t[n]; offset[0] = 0; // std::cout << "offset[" << 0 << "]: " << offset[0] << std::endl; - for (size_t i = 1; i < numConstraints; ++i) + for (std::size_t i = 1; i < numConstraints; ++i) { const ConstraintBasePtr& constraint = _group->getConstraint(i - 1); assert(constraint->getDimension() > 0); @@ -103,7 +103,7 @@ void DantzigLCPSolver::solve(ConstrainedGroup* _group) // For each constraint ConstraintInfo constInfo; constInfo.invTimeStep = 1.0 / mTimeStep; - for (size_t i = 0; i < numConstraints; ++i) + for (std::size_t i = 0; i < numConstraints; ++i) { const ConstraintBasePtr& constraint = _group->getConstraint(i); @@ -119,7 +119,7 @@ void DantzigLCPSolver::solve(ConstrainedGroup* _group) // Fill a matrix by impulse tests: A constraint->excite(); - for (size_t j = 0; j < constraint->getDimension(); ++j) + for (std::size_t j = 0; j < constraint->getDimension(); ++j) { // Adjust findex for global index if (findex[offset[i] + j] >= 0) @@ -131,16 +131,16 @@ void DantzigLCPSolver::solve(ConstrainedGroup* _group) // Fill upper triangle blocks of A matrix int index = nSkip * (offset[i] + j) + offset[i]; constraint->getVelocityChange(A + index, true); - for (size_t k = i + 1; k < numConstraints; ++k) + for (std::size_t k = i + 1; k < numConstraints; ++k) { index = nSkip * (offset[i] + j) + offset[k]; _group->getConstraint(k)->getVelocityChange(A + index, false); } // Filling symmetric part of A matrix - for (size_t k = 0; k < i; ++k) + for (std::size_t k = 0; k < i; ++k) { - for (size_t l = 0; l < _group->getConstraint(k)->getDimension(); ++l) + for (std::size_t l = 0; l < _group->getConstraint(k)->getDimension(); ++l) { int index1 = nSkip * (offset[i] + j) + offset[k] + l; int index2 = nSkip * (offset[k] + l) + offset[i] + j; @@ -172,7 +172,7 @@ void DantzigLCPSolver::solve(ConstrainedGroup* _group) // std::cout << std::endl; // Apply constraint impulses - for (size_t i = 0; i < numConstraints; ++i) + for (std::size_t i = 0; i < numConstraints; ++i) { const ConstraintBasePtr& constraint = _group->getConstraint(i); constraint->applyImpulse(x + offset[i]); @@ -192,19 +192,19 @@ void DantzigLCPSolver::solve(ConstrainedGroup* _group) //============================================================================== #ifndef NDEBUG -bool DantzigLCPSolver::isSymmetric(size_t _n, double* _A) +bool DantzigLCPSolver::isSymmetric(std::size_t _n, double* _A) { - size_t nSkip = dPAD(_n); - for (size_t i = 0; i < _n; ++i) + std::size_t nSkip = dPAD(_n); + for (std::size_t i = 0; i < _n; ++i) { - for (size_t j = 0; j < _n; ++j) + for (std::size_t j = 0; j < _n; ++j) { if (std::abs(_A[nSkip * i + j] - _A[nSkip * j + i]) > 1e-6) { std::cout << "A: " << std::endl; - for (size_t k = 0; k < _n; ++k) + for (std::size_t k = 0; k < _n; ++k) { - for (size_t l = 0; l < nSkip; ++l) + for (std::size_t l = 0; l < nSkip; ++l) { std::cout << std::setprecision(4) << _A[k * nSkip + l] << " "; } @@ -222,20 +222,20 @@ bool DantzigLCPSolver::isSymmetric(size_t _n, double* _A) } //============================================================================== -bool DantzigLCPSolver::isSymmetric(size_t _n, double* _A, - size_t _begin, size_t _end) +bool DantzigLCPSolver::isSymmetric(std::size_t _n, double* _A, + std::size_t _begin, std::size_t _end) { - size_t nSkip = dPAD(_n); - for (size_t i = _begin; i <= _end; ++i) + std::size_t nSkip = dPAD(_n); + for (std::size_t i = _begin; i <= _end; ++i) { - for (size_t j = _begin; j <= _end; ++j) + for (std::size_t j = _begin; j <= _end; ++j) { if (std::abs(_A[nSkip * i + j] - _A[nSkip * j + i]) > 1e-6) { std::cout << "A: " << std::endl; - for (size_t k = 0; k < _n; ++k) + for (std::size_t k = 0; k < _n; ++k) { - for (size_t l = 0; l < nSkip; ++l) + for (std::size_t l = 0; l < nSkip; ++l) { std::cout << std::setprecision(4) << _A[k * nSkip + l] << " "; } @@ -253,15 +253,15 @@ bool DantzigLCPSolver::isSymmetric(size_t _n, double* _A, } //============================================================================== -void DantzigLCPSolver::print(size_t _n, double* _A, double* _x, +void DantzigLCPSolver::print(std::size_t _n, double* _A, double* _x, double* /*lo*/, double* /*hi*/, double* b, double* w, int* findex) { - size_t nSkip = dPAD(_n); + std::size_t nSkip = dPAD(_n); std::cout << "A: " << std::endl; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { - for (size_t j = 0; j < nSkip; ++j) + for (std::size_t j = 0; j < nSkip; ++j) { std::cout << std::setprecision(4) << _A[i * nSkip + j] << " "; } @@ -269,21 +269,21 @@ void DantzigLCPSolver::print(size_t _n, double* _A, double* _x, } std::cout << "b: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << std::setprecision(4) << b[i] << " "; } std::cout << std::endl; std::cout << "w: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << w[i] << " "; } std::cout << std::endl; std::cout << "x: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << _x[i] << " "; } @@ -304,7 +304,7 @@ void DantzigLCPSolver::print(size_t _n, double* _A, double* _x, // std::cout << std::endl; std::cout << "frictionIndex: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << findex[i] << " "; } @@ -312,28 +312,28 @@ void DantzigLCPSolver::print(size_t _n, double* _A, double* _x, double* Ax = new double[_n]; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { Ax[i] = 0.0; } - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { - for (size_t j = 0; j < _n; ++j) + for (std::size_t j = 0; j < _n; ++j) { Ax[i] += _A[i * nSkip + j] * _x[j]; } } std::cout << "Ax : "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << Ax[i] << " "; } std::cout << std::endl; std::cout << "b + w: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << b[i] + w[i] << " "; } diff --git a/dart/constraint/DantzigLCPSolver.h b/dart/constraint/DantzigLCPSolver.h index 60e1e99623ff3..27fecc25b02be 100644 --- a/dart/constraint/DantzigLCPSolver.h +++ b/dart/constraint/DantzigLCPSolver.h @@ -62,13 +62,13 @@ class DantzigLCPSolver : public LCPSolver #ifndef NDEBUG private: /// Return true if the matrix is symmetric - bool isSymmetric(size_t _n, double* _A); + bool isSymmetric(std::size_t _n, double* _A); /// Return true if the diagonla block of matrix is symmetric - bool isSymmetric(size_t _n, double* _A, size_t _begin, size_t _end); + bool isSymmetric(std::size_t _n, double* _A, std::size_t _begin, std::size_t _end); /// Print debug information - void print(size_t _n, double* _A, double* _x, double* _lo, double* _hi, + void print(std::size_t _n, double* _A, double* _x, double* _lo, double* _hi, double* _b, double* w, int* _findex); #endif }; diff --git a/dart/constraint/JointCoulombFrictionConstraint.cpp b/dart/constraint/JointCoulombFrictionConstraint.cpp index c5aa3469877dd..7f9818100b727 100644 --- a/dart/constraint/JointCoulombFrictionConstraint.cpp +++ b/dart/constraint/JointCoulombFrictionConstraint.cpp @@ -114,8 +114,8 @@ void JointCoulombFrictionConstraint::update() // Reset dimention mDim = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof; ++i) + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof; ++i) { mNegativeVel[i] = -mJoint->getVelocity(i); @@ -156,9 +156,9 @@ void JointCoulombFrictionConstraint::update() //============================================================================== void JointCoulombFrictionConstraint::getInformation(ConstraintInfo* _lcp) { - size_t index = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof; ++i) + std::size_t index = 0; + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof; ++i) { if (mActive[i] == false) continue; @@ -181,15 +181,15 @@ void JointCoulombFrictionConstraint::getInformation(ConstraintInfo* _lcp) } //============================================================================== -void JointCoulombFrictionConstraint::applyUnitImpulse(size_t _index) +void JointCoulombFrictionConstraint::applyUnitImpulse(std::size_t _index) { assert(_index < mDim && "Invalid Index."); - size_t localIndex = 0; + std::size_t localIndex = 0; const dynamics::SkeletonPtr& skeleton = mJoint->getSkeleton(); - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof; ++i) + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof; ++i) { if (mActive[i] == false) continue; @@ -215,9 +215,9 @@ void JointCoulombFrictionConstraint::getVelocityChange(double* _delVel, { assert(_delVel != nullptr && "Null pointer is not allowed."); - size_t localIndex = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof ; ++i) + std::size_t localIndex = 0; + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof ; ++i) { if (mActive[i] == false) continue; @@ -256,9 +256,9 @@ void JointCoulombFrictionConstraint::unexcite() //============================================================================== void JointCoulombFrictionConstraint::applyImpulse(double* _lambda) { - size_t localIndex = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof ; ++i) + std::size_t localIndex = 0; + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof ; ++i) { if (mActive[i] == false) continue; @@ -281,7 +281,7 @@ dynamics::SkeletonPtr JointCoulombFrictionConstraint::getRootSkeleton() const //============================================================================== bool JointCoulombFrictionConstraint::isActive() const { - for (size_t i = 0; i < 6; ++i) + for (std::size_t i = 0; i < 6; ++i) { if (mActive[i]) return true; diff --git a/dart/constraint/JointCoulombFrictionConstraint.h b/dart/constraint/JointCoulombFrictionConstraint.h index 09e6103e6836b..48de5ac176583 100644 --- a/dart/constraint/JointCoulombFrictionConstraint.h +++ b/dart/constraint/JointCoulombFrictionConstraint.h @@ -87,7 +87,7 @@ class JointCoulombFrictionConstraint : public ConstraintBase void getInformation(ConstraintInfo* _lcp) override; // Documentation inherited - void applyUnitImpulse(size_t _index) override; + void applyUnitImpulse(std::size_t _index) override; // Documentation inherited void getVelocityChange(double* _delVel, bool _withCfm) override; @@ -115,10 +115,10 @@ class JointCoulombFrictionConstraint : public ConstraintBase dynamics::BodyNode* mBodyNode; /// Index of applied impulse - size_t mAppliedImpulseIndex; + std::size_t mAppliedImpulseIndex; /// - size_t mLifeTime[6]; + std::size_t mLifeTime[6]; /// bool mActive[6]; diff --git a/dart/constraint/JointLimitConstraint.cpp b/dart/constraint/JointLimitConstraint.cpp index 6ed396df609a2..938b084ddb48f 100644 --- a/dart/constraint/JointLimitConstraint.cpp +++ b/dart/constraint/JointLimitConstraint.cpp @@ -187,8 +187,8 @@ void JointLimitConstraint::update() // Reset dimention mDim = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof; ++i) + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof; ++i) { // Lower bound check mViolation[i] = mJoint->getPosition(i) - mJoint->getPositionLowerLimit(i); @@ -243,9 +243,9 @@ void JointLimitConstraint::update() //============================================================================== void JointLimitConstraint::getInformation(ConstraintInfo* _lcp) { - size_t index = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof; ++i) + std::size_t index = 0; + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof; ++i) { if (mActive[i] == false) continue; @@ -290,15 +290,15 @@ void JointLimitConstraint::getInformation(ConstraintInfo* _lcp) } //============================================================================== -void JointLimitConstraint::applyUnitImpulse(size_t _index) +void JointLimitConstraint::applyUnitImpulse(std::size_t _index) { assert(_index < mDim && "Invalid Index."); - size_t localIndex = 0; + std::size_t localIndex = 0; const dynamics::SkeletonPtr& skeleton = mJoint->getSkeleton(); - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof; ++i) + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof; ++i) { if (mActive[i] == false) continue; @@ -323,9 +323,9 @@ void JointLimitConstraint::getVelocityChange(double* _delVel, bool _withCfm) { assert(_delVel != nullptr && "Null pointer is not allowed."); - size_t localIndex = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof ; ++i) + std::size_t localIndex = 0; + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof ; ++i) { if (mActive[i] == false) continue; @@ -364,9 +364,9 @@ void JointLimitConstraint::unexcite() //============================================================================== void JointLimitConstraint::applyImpulse(double* _lambda) { - size_t localIndex = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof ; ++i) + std::size_t localIndex = 0; + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof ; ++i) { if (mActive[i] == false) continue; @@ -389,7 +389,7 @@ dynamics::SkeletonPtr JointLimitConstraint::getRootSkeleton() const //============================================================================== bool JointLimitConstraint::isActive() const { - for (size_t i = 0; i < 6; ++i) + for (std::size_t i = 0; i < 6; ++i) { if (mActive[i]) return true; diff --git a/dart/constraint/JointLimitConstraint.h b/dart/constraint/JointLimitConstraint.h index 6886ca7687220..cd9c347d45f3c 100644 --- a/dart/constraint/JointLimitConstraint.h +++ b/dart/constraint/JointLimitConstraint.h @@ -106,7 +106,7 @@ class JointLimitConstraint : public ConstraintBase void getInformation(ConstraintInfo* _lcp) override; // Documentation inherited - void applyUnitImpulse(size_t _index) override; + void applyUnitImpulse(std::size_t _index) override; // Documentation inherited void getVelocityChange(double* _delVel, bool _withCfm) override; @@ -134,10 +134,10 @@ class JointLimitConstraint : public ConstraintBase dynamics::BodyNode* mBodyNode; /// Index of applied impulse - size_t mAppliedImpulseIndex; + std::size_t mAppliedImpulseIndex; /// - size_t mLifeTime[6]; + std::size_t mLifeTime[6]; /// bool mActive[6]; diff --git a/dart/constraint/PGSLCPSolver.cpp b/dart/constraint/PGSLCPSolver.cpp index 1f9530ed2931d..9748bf9e23e41 100644 --- a/dart/constraint/PGSLCPSolver.cpp +++ b/dart/constraint/PGSLCPSolver.cpp @@ -64,12 +64,12 @@ PGSLCPSolver::~PGSLCPSolver() void PGSLCPSolver::solve(ConstrainedGroup* _group) { // If there is no constraint, then just return true. - size_t numConstraints = _group->getNumConstraints(); + std::size_t numConstraints = _group->getNumConstraints(); if (numConstraints == 0) return; // Build LCP terms by aggregating them from constraints - size_t n = _group->getTotalDimension(); + std::size_t n = _group->getTotalDimension(); int nSkip = dPAD(n); double* A = new double[n * nSkip]; double* x = new double[n]; @@ -87,10 +87,10 @@ void PGSLCPSolver::solve(ConstrainedGroup* _group) std::memset(findex, -1, n * sizeof(int)); // Compute offset indices - size_t* offset = new size_t[n]; + std::size_t* offset = new std::size_t[n]; offset[0] = 0; // std::cout << "offset[" << 0 << "]: " << offset[0] << std::endl; - for (size_t i = 1; i < numConstraints; ++i) + for (std::size_t i = 1; i < numConstraints; ++i) { const ConstraintBasePtr& constraint = _group->getConstraint(i - 1); assert(constraint->getDimension() > 0); @@ -101,7 +101,7 @@ void PGSLCPSolver::solve(ConstrainedGroup* _group) // For each constraint ConstraintInfo constInfo; constInfo.invTimeStep = 1.0 / mTimeStep; - for (size_t i = 0; i < numConstraints; ++i) + for (std::size_t i = 0; i < numConstraints; ++i) { const ConstraintBasePtr& constraint = _group->getConstraint(i); @@ -117,7 +117,7 @@ void PGSLCPSolver::solve(ConstrainedGroup* _group) // Fill a matrix by impulse tests: A constraint->excite(); - for (size_t j = 0; j < constraint->getDimension(); ++j) + for (std::size_t j = 0; j < constraint->getDimension(); ++j) { // Adjust findex for global index if (findex[offset[i] + j] >= 0) @@ -129,16 +129,16 @@ void PGSLCPSolver::solve(ConstrainedGroup* _group) // Fill upper triangle blocks of A matrix int index = nSkip * (offset[i] + j) + offset[i]; constraint->getVelocityChange(A + index, true); - for (size_t k = i + 1; k < numConstraints; ++k) + for (std::size_t k = i + 1; k < numConstraints; ++k) { index = nSkip * (offset[i] + j) + offset[k]; _group->getConstraint(k)->getVelocityChange(A + index, false); } // Filling symmetric part of A matrix - for (size_t k = 0; k < i; ++k) + for (std::size_t k = 0; k < i; ++k) { - for (size_t l = 0; l < _group->getConstraint(k)->getDimension(); ++l) + for (std::size_t l = 0; l < _group->getConstraint(k)->getDimension(); ++l) { int index1 = nSkip * (offset[i] + j) + offset[k] + l; int index2 = nSkip * (offset[k] + l) + offset[i] + j; @@ -173,7 +173,7 @@ void PGSLCPSolver::solve(ConstrainedGroup* _group) // std::cout << std::endl; // Apply constraint impulses - for (size_t i = 0; i < numConstraints; ++i) + for (std::size_t i = 0; i < numConstraints; ++i) { const ConstraintBasePtr& constraint = _group->getConstraint(i); constraint->applyImpulse(x + offset[i]); @@ -193,19 +193,19 @@ void PGSLCPSolver::solve(ConstrainedGroup* _group) //============================================================================== #ifndef NDEBUG -bool PGSLCPSolver::isSymmetric(size_t _n, double* _A) +bool PGSLCPSolver::isSymmetric(std::size_t _n, double* _A) { - size_t nSkip = dPAD(_n); - for (size_t i = 0; i < _n; ++i) + std::size_t nSkip = dPAD(_n); + for (std::size_t i = 0; i < _n; ++i) { - for (size_t j = 0; j < _n; ++j) + for (std::size_t j = 0; j < _n; ++j) { if (std::abs(_A[nSkip * i + j] - _A[nSkip * j + i]) > 1e-6) { std::cout << "A: " << std::endl; - for (size_t k = 0; k < _n; ++k) + for (std::size_t k = 0; k < _n; ++k) { - for (size_t l = 0; l < nSkip; ++l) + for (std::size_t l = 0; l < nSkip; ++l) { std::cout << std::setprecision(4) << _A[k * nSkip + l] << " "; } @@ -223,20 +223,20 @@ bool PGSLCPSolver::isSymmetric(size_t _n, double* _A) } //============================================================================== -bool PGSLCPSolver::isSymmetric(size_t _n, double* _A, - size_t _begin, size_t _end) +bool PGSLCPSolver::isSymmetric(std::size_t _n, double* _A, + std::size_t _begin, std::size_t _end) { - size_t nSkip = dPAD(_n); - for (size_t i = _begin; i <= _end; ++i) + std::size_t nSkip = dPAD(_n); + for (std::size_t i = _begin; i <= _end; ++i) { - for (size_t j = _begin; j <= _end; ++j) + for (std::size_t j = _begin; j <= _end; ++j) { if (std::abs(_A[nSkip * i + j] - _A[nSkip * j + i]) > 1e-6) { std::cout << "A: " << std::endl; - for (size_t k = 0; k < _n; ++k) + for (std::size_t k = 0; k < _n; ++k) { - for (size_t l = 0; l < nSkip; ++l) + for (std::size_t l = 0; l < nSkip; ++l) { std::cout << std::setprecision(4) << _A[k * nSkip + l] << " "; } @@ -254,15 +254,15 @@ bool PGSLCPSolver::isSymmetric(size_t _n, double* _A, } //============================================================================== -void PGSLCPSolver::print(size_t _n, double* _A, double* _x, +void PGSLCPSolver::print(std::size_t _n, double* _A, double* _x, double* /*lo*/, double* /*hi*/, double* b, double* w, int* findex) { - size_t nSkip = dPAD(_n); + std::size_t nSkip = dPAD(_n); std::cout << "A: " << std::endl; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { - for (size_t j = 0; j < nSkip; ++j) + for (std::size_t j = 0; j < nSkip; ++j) { std::cout << std::setprecision(4) << _A[i * nSkip + j] << " "; } @@ -270,21 +270,21 @@ void PGSLCPSolver::print(size_t _n, double* _A, double* _x, } std::cout << "b: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << std::setprecision(4) << b[i] << " "; } std::cout << std::endl; std::cout << "w: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << w[i] << " "; } std::cout << std::endl; std::cout << "x: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << _x[i] << " "; } @@ -305,7 +305,7 @@ void PGSLCPSolver::print(size_t _n, double* _A, double* _x, // std::cout << std::endl; std::cout << "frictionIndex: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << findex[i] << " "; } @@ -313,28 +313,28 @@ void PGSLCPSolver::print(size_t _n, double* _A, double* _x, double* Ax = new double[_n]; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { Ax[i] = 0.0; } - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { - for (size_t j = 0; j < _n; ++j) + for (std::size_t j = 0; j < _n; ++j) { Ax[i] += _A[i * nSkip + j] * _x[j]; } } std::cout << "Ax : "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << Ax[i] << " "; } std::cout << std::endl; std::cout << "b + w: "; - for (size_t i = 0; i < _n; ++i) + for (std::size_t i = 0; i < _n; ++i) { std::cout << b[i] + w[i] << " "; } diff --git a/dart/constraint/PGSLCPSolver.h b/dart/constraint/PGSLCPSolver.h index 64480092880c3..ae6887a5b53f6 100644 --- a/dart/constraint/PGSLCPSolver.h +++ b/dart/constraint/PGSLCPSolver.h @@ -61,13 +61,13 @@ class PGSLCPSolver : public LCPSolver #ifndef NDEBUG private: /// Return true if the matrix is symmetric - bool isSymmetric(size_t _n, double* _A); + bool isSymmetric(std::size_t _n, double* _A); /// Return true if the diagonla block of matrix is symmetric - bool isSymmetric(size_t _n, double* _A, size_t _begin, size_t _end); + bool isSymmetric(std::size_t _n, double* _A, std::size_t _begin, std::size_t _end); /// Print debug information - void print(size_t _n, double* _A, double* _x, double* _lo, double* _hi, + void print(std::size_t _n, double* _A, double* _x, double* _lo, double* _hi, double* _b, double* w, int* _findex); #endif }; diff --git a/dart/constraint/ServoMotorConstraint.cpp b/dart/constraint/ServoMotorConstraint.cpp index fabec0e26b690..a70bf0b56c023 100644 --- a/dart/constraint/ServoMotorConstraint.cpp +++ b/dart/constraint/ServoMotorConstraint.cpp @@ -115,8 +115,8 @@ void ServoMotorConstraint::update() // Reset dimention mDim = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof; ++i) + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof; ++i) { mNegativeVelocityError[i] = mJoint->getCommand(i) - mJoint->getVelocity(i); @@ -157,9 +157,9 @@ void ServoMotorConstraint::update() //============================================================================== void ServoMotorConstraint::getInformation(ConstraintInfo* lcp) { - size_t index = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof; ++i) + std::size_t index = 0; + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof; ++i) { if (mActive[i] == false) continue; @@ -182,15 +182,15 @@ void ServoMotorConstraint::getInformation(ConstraintInfo* lcp) } //============================================================================== -void ServoMotorConstraint::applyUnitImpulse(size_t index) +void ServoMotorConstraint::applyUnitImpulse(std::size_t index) { assert(index < mDim && "Invalid Index."); - size_t localIndex = 0; + std::size_t localIndex = 0; const dynamics::SkeletonPtr& skeleton = mJoint->getSkeleton(); - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof; ++i) + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof; ++i) { if (mActive[i] == false) continue; @@ -215,9 +215,9 @@ void ServoMotorConstraint::getVelocityChange(double* delVel, bool withCfm) { assert(delVel != nullptr && "Null pointer is not allowed."); - size_t localIndex = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof ; ++i) + std::size_t localIndex = 0; + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof ; ++i) { if (mActive[i] == false) continue; @@ -256,9 +256,9 @@ void ServoMotorConstraint::unexcite() //============================================================================== void ServoMotorConstraint::applyImpulse(double* lambda) { - size_t localIndex = 0; - size_t dof = mJoint->getNumDofs(); - for (size_t i = 0; i < dof ; ++i) + std::size_t localIndex = 0; + std::size_t dof = mJoint->getNumDofs(); + for (std::size_t i = 0; i < dof ; ++i) { if (mActive[i] == false) continue; diff --git a/dart/constraint/ServoMotorConstraint.h b/dart/constraint/ServoMotorConstraint.h index 8e9820ffc4225..1449741c6d298 100644 --- a/dart/constraint/ServoMotorConstraint.h +++ b/dart/constraint/ServoMotorConstraint.h @@ -87,7 +87,7 @@ class ServoMotorConstraint : public ConstraintBase void getInformation(ConstraintInfo* lcp) override; // Documentation inherited - void applyUnitImpulse(size_t index) override; + void applyUnitImpulse(std::size_t index) override; // Documentation inherited void getVelocityChange(double* delVel, bool withCfm) override; @@ -115,10 +115,10 @@ class ServoMotorConstraint : public ConstraintBase dynamics::BodyNode* mBodyNode; /// Index of applied impulse - size_t mAppliedImpulseIndex; + std::size_t mAppliedImpulseIndex; /// - size_t mLifeTime[6]; + std::size_t mLifeTime[6]; // TODO(JS): Lifetime should be considered only when we use iterative lcp // solver diff --git a/dart/constraint/SoftContactConstraint.cpp b/dart/constraint/SoftContactConstraint.cpp index 0bf2c25b8f6ea..b198e323a899b 100644 --- a/dart/constraint/SoftContactConstraint.cpp +++ b/dart/constraint/SoftContactConstraint.cpp @@ -92,12 +92,12 @@ SoftContactConstraint::SoftContactConstraint( // Set the colliding state of body nodes and point masses to false if (mSoftBodyNode1) { - for (size_t i = 0; i < mSoftBodyNode1->getNumPointMasses(); ++i) + for (std::size_t i = 0; i < mSoftBodyNode1->getNumPointMasses(); ++i) mSoftBodyNode1->getPointMass(i)->setColliding(false); } if (mSoftBodyNode2) { - for (size_t i = 0; i < mSoftBodyNode2->getNumPointMasses(); ++i) + for (std::size_t i = 0; i < mSoftBodyNode2->getNumPointMasses(); ++i) mSoftBodyNode2->getPointMass(i)->setColliding(false); } @@ -175,7 +175,7 @@ SoftContactConstraint::SoftContactConstraint( Eigen::Vector3d bodyPoint1; Eigen::Vector3d bodyPoint2; - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { collision::Contact* ct = mContacts[i]; @@ -266,7 +266,7 @@ SoftContactConstraint::SoftContactConstraint( Eigen::Vector3d bodyPoint1; Eigen::Vector3d bodyPoint2; - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { collision::Contact* ct = mContacts[i]; @@ -426,8 +426,8 @@ void SoftContactConstraint::getInformation(ConstraintInfo* _info) //---------------------------------------------------------------------------- if (mIsFrictionOn) { - size_t index = 0; - for (size_t i = 0; i < mContacts.size(); ++i) + std::size_t index = 0; + for (std::size_t i = 0; i < mContacts.size(); ++i) { // Bias term, w, should be zero assert(_info->w[index] == 0.0); @@ -512,7 +512,7 @@ void SoftContactConstraint::getInformation(ConstraintInfo* _info) //---------------------------------------------------------------------------- else { - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { // Bias term, w, should be zero _info->w[i] = 0.0; @@ -575,7 +575,7 @@ void SoftContactConstraint::getInformation(ConstraintInfo* _info) } //============================================================================== -void SoftContactConstraint::applyUnitImpulse(size_t _idx) +void SoftContactConstraint::applyUnitImpulse(std::size_t _idx) { assert(_idx < mDim && "Invalid Index."); assert(isActive()); @@ -664,7 +664,7 @@ void SoftContactConstraint::getVelocityChange(double* _vel, bool _withCfm) { assert(_vel != nullptr && "Null pointer is not allowed."); - for (size_t i = 0; i < mDim; ++i) + for (std::size_t i = 0; i < mDim; ++i) { _vel[i] = 0.0; @@ -736,9 +736,9 @@ void SoftContactConstraint::applyImpulse(double* _lambda) //---------------------------------------------------------------------------- if (mIsFrictionOn) { - size_t index = 0; + std::size_t index = 0; - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { // std::cout << "_lambda1: " << _lambda[_idx] << std::endl; // std::cout << "_lambda2: " << _lambda[_idx + 1] << std::endl; @@ -848,7 +848,7 @@ void SoftContactConstraint::applyImpulse(double* _lambda) //---------------------------------------------------------------------------- else { - for (size_t i = 0; i < mContacts.size(); ++i) + for (std::size_t i = 0; i < mContacts.size(); ++i) { // Normal impulsive force // pContactPts[i]->lambda[0] = _lambda[i]; @@ -886,7 +886,7 @@ void SoftContactConstraint::getRelVelocity(double* _vel) { assert(_vel != nullptr && "Null pointer is not allowed."); - for (size_t i = 0; i < mDim; ++i) + for (std::size_t i = 0; i < mDim; ++i) { _vel[i] = 0.0; diff --git a/dart/constraint/SoftContactConstraint.h b/dart/constraint/SoftContactConstraint.h index ca7839564b2f1..666694f134b16 100644 --- a/dart/constraint/SoftContactConstraint.h +++ b/dart/constraint/SoftContactConstraint.h @@ -120,7 +120,7 @@ class SoftContactConstraint : public ConstraintBase void getInformation(ConstraintInfo* _info) override; // Documentation inherited - void applyUnitImpulse(size_t _idx) override; + void applyUnitImpulse(std::size_t _idx) override; // Documentation inherited void getVelocityChange(double* _vel, bool _withCfm) override; @@ -224,7 +224,7 @@ class SoftContactConstraint : public ConstraintBase bool mIsFrictionOn; /// Index of applied impulse - size_t mAppliedImpulseIndex; + std::size_t mAppliedImpulseIndex; /// bool mIsBounceOn; diff --git a/dart/constraint/WeldJointConstraint.cpp b/dart/constraint/WeldJointConstraint.cpp index 5419659ff8439..0eaf61deb66ce 100644 --- a/dart/constraint/WeldJointConstraint.cpp +++ b/dart/constraint/WeldJointConstraint.cpp @@ -177,7 +177,7 @@ void WeldJointConstraint::getInformation(ConstraintInfo* _lcp) } //============================================================================== -void WeldJointConstraint::applyUnitImpulse(size_t _index) +void WeldJointConstraint::applyUnitImpulse(std::size_t _index) { assert(_index < mDim && "Invalid Index."); assert(isActive()); @@ -273,7 +273,7 @@ void WeldJointConstraint::getVelocityChange(double* _vel, bool _withCfm) velChange -= mJacobian2 * mBodyNode2->getBodyVelocityChange(); } - for (size_t i = 0; i < mDim; ++i) + for (std::size_t i = 0; i < mDim; ++i) _vel[i] = velChange[i]; // Add small values to diagnal to keep it away from singular, similar to cfm diff --git a/dart/constraint/WeldJointConstraint.h b/dart/constraint/WeldJointConstraint.h index 50b31f6b3f77d..bb77e58e9e256 100644 --- a/dart/constraint/WeldJointConstraint.h +++ b/dart/constraint/WeldJointConstraint.h @@ -71,7 +71,7 @@ class WeldJointConstraint : public JointConstraint void getInformation(ConstraintInfo* _lcp) override; // Documentation inherited - void applyUnitImpulse(size_t _index) override; + void applyUnitImpulse(std::size_t _index) override; // Documentation inherited void getVelocityChange(double* _vel, bool _withCfm) override; @@ -111,7 +111,7 @@ class WeldJointConstraint : public JointConstraint double mOldX[6]; /// Index of applied impulse - size_t mAppliedImpulseIndex; + std::size_t mAppliedImpulseIndex; public: // To get byte-aligned Eigen vectors diff --git a/dart/dynamics/ArrowShape.cpp b/dart/dynamics/ArrowShape.cpp index f8d43453d44a2..43113e2bc08d1 100644 --- a/dart/dynamics/ArrowShape.cpp +++ b/dart/dynamics/ArrowShape.cpp @@ -59,7 +59,7 @@ ArrowShape::ArrowShape(const Eigen::Vector3d& _tail, const Eigen::Vector3d& _head, const Properties& _properties, const Eigen::Vector4d& _color, - size_t _resolution) + std::size_t _resolution) : MeshShape(Eigen::Vector3d::Ones(), nullptr), mTail(_tail), mHead(_head), @@ -99,10 +99,10 @@ void ArrowShape::setProperties(const Properties& _properties) //============================================================================== void ArrowShape::notifyColorUpdate(const Eigen::Vector4d& _color) { - for(size_t i=0; imNumMeshes; ++i) + for(std::size_t i=0; imNumMeshes; ++i) { aiMesh* mesh = mMesh->mMeshes[i]; - for(size_t j=0; jmNumVertices; ++j) + for(std::size_t j=0; jmNumVertices; ++j) { mesh->mColors[0][j] = aiColor4D(_color[0], _color[1], _color[2], _color[3]); @@ -120,8 +120,8 @@ const ArrowShape::Properties& ArrowShape::getProperties() const static void constructArrowTip(aiMesh* mesh, double base, double tip, const ArrowShape::Properties& properties) { - size_t resolution = (mesh->mNumVertices-1)/2; - for(size_t i=0; imNumVertices-1)/2; + for(std::size_t i=0; imNumVertices/2; - for(size_t i=0; imNumVertices/2; + for(std::size_t i=0; imRootNode; - for(size_t i=0; i<4; ++i) - for(size_t j=0; j<4; ++j) + for(std::size_t i=0; i<4; ++i) + for(std::size_t j=0; j<4; ++j) node->mTransformation[i][j] = tf(i,j); _updateBoundingBoxDim(); @@ -240,12 +240,12 @@ void ArrowShape::configureArrow(const Eigen::Vector3d& _tail, } //============================================================================== -void ArrowShape::instantiate(size_t resolution) +void ArrowShape::instantiate(std::size_t resolution) { aiNode* node = new aiNode; node->mNumMeshes = 3; node->mMeshes = new unsigned int[3]; - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) node->mMeshes[i] = i; aiScene* scene = new aiScene; @@ -257,9 +257,9 @@ void ArrowShape::instantiate(size_t resolution) scene->mMaterials[0] = new aiMaterial; // allocate memory - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) { - size_t numVertices = (i==0 || i==2)? 2*resolution+1 : 2*resolution; + std::size_t numVertices = (i==0 || i==2)? 2*resolution+1 : 2*resolution; aiMesh* mesh = new aiMesh; mesh->mMaterialIndex = (unsigned int)(-1); @@ -269,10 +269,10 @@ void ArrowShape::instantiate(size_t resolution) mesh->mNormals = new aiVector3D[numVertices]; mesh->mColors[0] = new aiColor4D[numVertices]; - size_t numFaces = (i==0 || i==2)? 3*resolution : numVertices; + std::size_t numFaces = (i==0 || i==2)? 3*resolution : numVertices; mesh->mNumFaces = numFaces; mesh->mFaces = new aiFace[numFaces]; - for(size_t j=0; jmFaces[j].mNumIndices = 3; mesh->mFaces[j].mIndices = new unsigned int[3]; @@ -283,7 +283,7 @@ void ArrowShape::instantiate(size_t resolution) // set normals aiMesh* mesh = scene->mMeshes[0]; - for(size_t i=0; imNormals[2*i].Set(0.0f, 0.0f, 1.0f); @@ -293,7 +293,7 @@ void ArrowShape::instantiate(size_t resolution) mesh->mNormals[mesh->mNumVertices-1].Set(0.0f, 0.0f, -1.0f); mesh = scene->mMeshes[1]; - for(size_t i=0; imNormals[2*i].Set(cos(theta), sin(theta), 0.0f); @@ -301,7 +301,7 @@ void ArrowShape::instantiate(size_t resolution) } mesh = scene->mMeshes[2]; - for(size_t i=0; imNormals[2*i].Set(0.0f, 0.0f, -1.0f); @@ -313,7 +313,7 @@ void ArrowShape::instantiate(size_t resolution) // set faces mesh = scene->mMeshes[0]; aiFace* face; - for(size_t i=0; imFaces[3*i]; @@ -334,7 +334,7 @@ void ArrowShape::instantiate(size_t resolution) } mesh = scene->mMeshes[1]; - for(size_t i=0; imFaces[2*i]; face->mIndices[0] = 2*i; @@ -348,7 +348,7 @@ void ArrowShape::instantiate(size_t resolution) } mesh = scene->mMeshes[2]; - for(size_t i=0; imFaces[3*i]; diff --git a/dart/dynamics/ArrowShape.h b/dart/dynamics/ArrowShape.h index ba351900e2377..ad0141b127fbd 100644 --- a/dart/dynamics/ArrowShape.h +++ b/dart/dynamics/ArrowShape.h @@ -74,7 +74,7 @@ class ArrowShape : public MeshShape ArrowShape(const Eigen::Vector3d& _tail, const Eigen::Vector3d& _head, const Properties& _properties = Properties(), const Eigen::Vector4d& _color=Eigen::Vector4d(0.5,0.5,1.0,1.0), - size_t _resolution=10); + std::size_t _resolution=10); /// Set the positions of the tail and head of the arrow without changing any /// settings @@ -101,7 +101,7 @@ class ArrowShape : public MeshShape protected: - void instantiate(size_t resolution); + void instantiate(std::size_t resolution); Eigen::Vector3d mTail; Eigen::Vector3d mHead; diff --git a/dart/dynamics/AssimpInputResourceAdaptor.cpp b/dart/dynamics/AssimpInputResourceAdaptor.cpp index c665fc0ce3783..844c186d9a460 100644 --- a/dart/dynamics/AssimpInputResourceAdaptor.cpp +++ b/dart/dynamics/AssimpInputResourceAdaptor.cpp @@ -120,15 +120,15 @@ AssimpInputResourceAdaptor::~AssimpInputResourceAdaptor() } //============================================================================== -size_t AssimpInputResourceAdaptor::Read( - void* pvBuffer, size_t psize, size_t pCount) +std::size_t AssimpInputResourceAdaptor::Read( + void* pvBuffer, std::size_t psize, std::size_t pCount) { return mResource->read(pvBuffer, psize, pCount); } //============================================================================== -size_t AssimpInputResourceAdaptor::Write( - const void* /*pvBuffer*/, size_t /*pSize*/, size_t /*pCount*/) +std::size_t AssimpInputResourceAdaptor::Write( + const void* /*pvBuffer*/, std::size_t /*pSize*/, std::size_t /*pCount*/) { dtwarn << "[AssimpInputResourceAdaptor::Write] Write is not implemented." " This is a read-only stream.\n"; @@ -136,7 +136,7 @@ size_t AssimpInputResourceAdaptor::Write( } //============================================================================== -aiReturn AssimpInputResourceAdaptor::Seek(size_t pOffset, aiOrigin pOrigin) +aiReturn AssimpInputResourceAdaptor::Seek(std::size_t pOffset, aiOrigin pOrigin) { using common::Resource; @@ -168,13 +168,13 @@ aiReturn AssimpInputResourceAdaptor::Seek(size_t pOffset, aiOrigin pOrigin) } //============================================================================== -size_t AssimpInputResourceAdaptor::Tell() const +std::size_t AssimpInputResourceAdaptor::Tell() const { return mResource->tell(); } //============================================================================== -size_t AssimpInputResourceAdaptor::FileSize() const +std::size_t AssimpInputResourceAdaptor::FileSize() const { return mResource->getSize(); } @@ -211,32 +211,32 @@ void fileFlushProc(aiFile *_file) } //============================================================================== -size_t fileReadProc(aiFile *_file, char *_buffer, size_t _size, size_t _count) +std::size_t fileReadProc(aiFile *_file, char *_buffer, std::size_t _size, std::size_t _count) { return getIOStream(_file)->Read(_buffer, _size, _count); } //============================================================================== -aiReturn fileSeekProc(aiFile *_file, size_t _offset, aiOrigin _origin) +aiReturn fileSeekProc(aiFile *_file, std::size_t _offset, aiOrigin _origin) { return getIOStream(_file)->Seek(_offset, _origin); } //============================================================================== -size_t fileSizeProc(aiFile *_file) +std::size_t fileSizeProc(aiFile *_file) { return getIOStream(_file)->FileSize(); } //============================================================================== -size_t fileTellProc(aiFile *_file) +std::size_t fileTellProc(aiFile *_file) { return getIOStream(_file)->Tell(); } //============================================================================== -size_t fileWriteProc( - aiFile *_file, const char *_buffer, size_t _size, size_t _count) +std::size_t fileWriteProc( + aiFile *_file, const char *_buffer, std::size_t _size, std::size_t _count) { return getIOStream(_file)->Write(_buffer, _size, _count); } diff --git a/dart/dynamics/AssimpInputResourceAdaptor.h b/dart/dynamics/AssimpInputResourceAdaptor.h index bff110ac5a302..d8013de9f8cc9 100644 --- a/dart/dynamics/AssimpInputResourceAdaptor.h +++ b/dart/dynamics/AssimpInputResourceAdaptor.h @@ -94,26 +94,26 @@ class AssimpInputResourceAdaptor : public Assimp::IOStream /// \brief Read from the file /// /// See fread() for more details - size_t Read(void* pvBuffer, size_t pSize, size_t pCount) override; + std::size_t Read(void* pvBuffer, std::size_t pSize, std::size_t pCount) override; /// \brief Not implemented. This is a read-only stream. - size_t Write(const void* pvBuffer, size_t pSize, size_t pCount) override; + std::size_t Write(const void* pvBuffer, std::size_t pSize, std::size_t pCount) override; /// \brief Set the read/write cursor of the file /// /// Note that the offset is _negative_ for aiOrigin_END. /// See fseek() for more details - aiReturn Seek(size_t pOffset, aiOrigin pOrigin) override; + aiReturn Seek(std::size_t pOffset, aiOrigin pOrigin) override; /// \brief Get the current position of the read/write cursor /// /// See ftell() for more details - size_t Tell() const override; + std::size_t Tell() const override; /// \brief Returns filesize /// /// Returns the filesize. - size_t FileSize() const override; + std::size_t FileSize() const override; /// \brief Not implemented. This is a read-only stream. void Flush() override; diff --git a/dart/dynamics/BallJoint.cpp b/dart/dynamics/BallJoint.cpp index 1a7481b6446e6..2a4867d3301b7 100644 --- a/dart/dynamics/BallJoint.cpp +++ b/dart/dynamics/BallJoint.cpp @@ -71,7 +71,7 @@ const std::string& BallJoint::getStaticType() } //============================================================================== -bool BallJoint::isCyclic(size_t _index) const +bool BallJoint::isCyclic(std::size_t _index) const { return _index < 3 && !hasPositionLimit(0) && !hasPositionLimit(1) && !hasPositionLimit(2); diff --git a/dart/dynamics/BallJoint.h b/dart/dynamics/BallJoint.h index fd2475afb2a76..5114a73ddc340 100644 --- a/dart/dynamics/BallJoint.h +++ b/dart/dynamics/BallJoint.h @@ -68,7 +68,7 @@ class BallJoint : public MultiDofJoint<3> static const std::string& getStaticType(); // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; /// Get the Properties of this BallJoint Properties getBallJointProperties() const; diff --git a/dart/dynamics/BodyNode.cpp b/dart/dynamics/BodyNode.cpp index 5882a3569e210..30e015ed0bd1d 100644 --- a/dart/dynamics/BodyNode.cpp +++ b/dart/dynamics/BodyNode.cpp @@ -78,7 +78,7 @@ static void extractDataFromNodeTypeMap( data->getVector().resize(nodes.size()); - for(size_t i=0; i < nodes.size(); ++i) + for(std::size_t i=0; i < nodes.size(); ++i) { std::unique_ptr& datum = data->getVector()[i]; datum = (nodes[i]->*getData)(); @@ -182,7 +182,7 @@ ConstSkeletonPtr SkeletonRefCountingBase::getSkeleton() const typedef std::set EntityPtrSet; //============================================================================== -size_t BodyNode::msBodyNodeCount = 0; +std::size_t BodyNode::msBodyNodeCount = 0; namespace detail { @@ -675,19 +675,19 @@ double BodyNode::getRestitutionCoeff() const } //============================================================================== -size_t BodyNode::getIndexInSkeleton() const +std::size_t BodyNode::getIndexInSkeleton() const { return mIndexInSkeleton; } //============================================================================== -size_t BodyNode::getIndexInTree() const +std::size_t BodyNode::getIndexInTree() const { return mIndexInTree; } //============================================================================== -size_t BodyNode::getTreeIndex() const +std::size_t BodyNode::getTreeIndex() const { return mTreeIndex; } @@ -859,31 +859,31 @@ void BodyNode::addChildBodyNode(BodyNode* _body) } //============================================================================== -size_t BodyNode::getNumChildBodyNodes() const +std::size_t BodyNode::getNumChildBodyNodes() const { return mChildBodyNodes.size(); } //============================================================================== -BodyNode* BodyNode::getChildBodyNode(size_t _index) +BodyNode* BodyNode::getChildBodyNode(std::size_t _index) { return common::getVectorObjectIfAvailable(_index, mChildBodyNodes); } //============================================================================== -const BodyNode* BodyNode::getChildBodyNode(size_t _index) const +const BodyNode* BodyNode::getChildBodyNode(std::size_t _index) const { return common::getVectorObjectIfAvailable(_index, mChildBodyNodes); } //============================================================================== -size_t BodyNode::getNumChildJoints() const +std::size_t BodyNode::getNumChildJoints() const { return mChildBodyNodes.size(); } //============================================================================== -Joint* BodyNode::getChildJoint(size_t _index) +Joint* BodyNode::getChildJoint(std::size_t _index) { BodyNode* childBodyNode = getChildBodyNode(_index); @@ -894,7 +894,7 @@ Joint* BodyNode::getChildJoint(size_t _index) } //============================================================================== -const Joint* BodyNode::getChildJoint(size_t _index) const +const Joint* BodyNode::getChildJoint(std::size_t _index) const { return const_cast(this)->getChildJoint(_index); } @@ -926,19 +926,19 @@ ShapeNode* BodyNode::createShapeNode(const ShapePtr& shape, const char* name) } //============================================================================== -size_t BodyNode::getNumShapeNodes() const +std::size_t BodyNode::getNumShapeNodes() const { return getNumNodes(); } //============================================================================== -ShapeNode* BodyNode::getShapeNode(size_t index) +ShapeNode* BodyNode::getShapeNode(std::size_t index) { return getNode(index); } //============================================================================== -const ShapeNode* BodyNode::getShapeNode(size_t index) const +const ShapeNode* BodyNode::getShapeNode(std::size_t index) const { return getNode(index); } @@ -1002,25 +1002,25 @@ void BodyNode::addMarker(Marker* _marker) } //============================================================================== -size_t BodyNode::getNumMarkers() const +std::size_t BodyNode::getNumMarkers() const { return mMarkers.size(); } //============================================================================== -Marker* BodyNode::getMarker(size_t _index) +Marker* BodyNode::getMarker(std::size_t _index) { return common::getVectorObjectIfAvailable(_index, mMarkers); } //============================================================================== -const Marker* BodyNode::getMarker(size_t _index) const +const Marker* BodyNode::getMarker(std::size_t _index) const { return common::getVectorObjectIfAvailable(_index, mMarkers); } //============================================================================== -bool BodyNode::dependsOn(size_t _genCoordIndex) const +bool BodyNode::dependsOn(std::size_t _genCoordIndex) const { return std::binary_search(mDependentGenCoordIndices.begin(), mDependentGenCoordIndices.end(), @@ -1028,13 +1028,13 @@ bool BodyNode::dependsOn(size_t _genCoordIndex) const } //============================================================================== -size_t BodyNode::getNumDependentGenCoords() const +std::size_t BodyNode::getNumDependentGenCoords() const { return mDependentGenCoordIndices.size(); } //============================================================================== -size_t BodyNode::getDependentGenCoordIndex(size_t _arrayIndex) const +std::size_t BodyNode::getDependentGenCoordIndex(std::size_t _arrayIndex) const { assert(_arrayIndex < mDependentGenCoordIndices.size()); @@ -1042,26 +1042,26 @@ size_t BodyNode::getDependentGenCoordIndex(size_t _arrayIndex) const } //============================================================================== -const std::vector& BodyNode::getDependentGenCoordIndices() const +const std::vector& BodyNode::getDependentGenCoordIndices() const { return mDependentGenCoordIndices; } //============================================================================== -size_t BodyNode::getNumDependentDofs() const +std::size_t BodyNode::getNumDependentDofs() const { return mDependentDofs.size(); } //============================================================================== -DegreeOfFreedom* BodyNode::getDependentDof(size_t _index) +DegreeOfFreedom* BodyNode::getDependentDof(std::size_t _index) { return common::getVectorObjectIfAvailable( _index, mDependentDofs); } //============================================================================== -const DegreeOfFreedom* BodyNode::getDependentDof(size_t _index) const +const DegreeOfFreedom* BodyNode::getDependentDof(std::size_t _index) const { return common::getVectorObjectIfAvailable( _index, mDependentDofs); @@ -1093,8 +1093,8 @@ const std::vector BodyNode::getChainDofs() const for(std::vector::reverse_iterator rit = bn_chain.rbegin(); rit != bn_chain.rend(); ++rit) { - size_t nDofs = (*rit)->getParentJoint()->getNumDofs(); - for(size_t i=0; igetParentJoint()->getNumDofs(); + for(std::size_t i=0; igetParentJoint()->getDof(i) ); } @@ -1371,7 +1371,7 @@ void BodyNode::init(const SkeletonPtr& _skeleton) else mDependentGenCoordIndices.clear(); - for (size_t i = 0; i < mParentJoint->getNumDofs(); i++) + for (std::size_t i = 0; i < mParentJoint->getNumDofs(); i++) mDependentGenCoordIndices.push_back(mParentJoint->getIndexInSkeleton(i)); // Sort @@ -1381,7 +1381,7 @@ void BodyNode::init(const SkeletonPtr& _skeleton) mDependentDofs.reserve(mDependentGenCoordIndices.size()); mConstDependentDofs.clear(); mConstDependentDofs.reserve(mDependentGenCoordIndices.size()); - for(const size_t& index : mDependentGenCoordIndices) + for(const std::size_t& index : mDependentGenCoordIndices) { mDependentDofs.push_back(_skeleton->getDof(index)); mConstDependentDofs.push_back(_skeleton->getDof(index)); @@ -1389,10 +1389,10 @@ void BodyNode::init(const SkeletonPtr& _skeleton) #ifndef NDEBUG // Check whether there is duplicated indices. - size_t nDepGenCoordIndices = mDependentGenCoordIndices.size(); - for (size_t i = 0; i < nDepGenCoordIndices; ++i) + std::size_t nDepGenCoordIndices = mDependentGenCoordIndices.size(); + for (std::size_t i = 0; i < nDepGenCoordIndices; ++i) { - for (size_t j = i + 1; j < nDepGenCoordIndices; ++j) + for (std::size_t j = i + 1; j < nDepGenCoordIndices; ++j) { assert(mDependentGenCoordIndices[i] != mDependentGenCoordIndices[j] && @@ -1404,7 +1404,7 @@ void BodyNode::init(const SkeletonPtr& _skeleton) //-------------------------------------------------------------------------- // Set dimensions of dynamics matrices and vectors. //-------------------------------------------------------------------------- - size_t numDepGenCoords = getNumDependentGenCoords(); + std::size_t numDepGenCoords = getNumDependentGenCoords(); mBodyJacobian.setZero(6, numDepGenCoords); mWorldJacobian.setZero(6, numDepGenCoords); mBodyJacobianSpatialDeriv.setZero(6, numDepGenCoords); @@ -1489,7 +1489,7 @@ void BodyNode::notifyTransformUpdate() // Child BodyNodes and other generic Entities are notified separately to allow // some optimizations - for(size_t i=0; inotifyTransformUpdate(); for(Entity* entity : mNonBodyNodeEntities) @@ -1516,7 +1516,7 @@ void BodyNode::notifyVelocityUpdate() // Child BodyNodes and other generic Entities are notified separately to allow // some optimizations - for(size_t i=0; inotifyVelocityUpdate(); for(Entity* entity : mNonBodyNodeEntities) @@ -1532,7 +1532,7 @@ void BodyNode::notifyAccelerationUpdate() mNeedAccelerationUpdate = true; - for(size_t i=0; inotifyAccelerationUpdate(); for(Entity* entity : mNonBodyNodeEntities) @@ -2005,11 +2005,11 @@ void BodyNode::aggregateGravityForceVector(Eigen::VectorXd& _g, (*it)->mG_F); } - size_t nGenCoords = mParentJoint->getNumDofs(); + std::size_t nGenCoords = mParentJoint->getNumDofs(); if (nGenCoords > 0) { Eigen::VectorXd g = -(mParentJoint->getLocalJacobian().transpose() * mG_F); - size_t iStart = mParentJoint->getIndexInTree(0); + std::size_t iStart = mParentJoint->getIndexInTree(0); _g.segment(iStart, nGenCoords) = g; } } @@ -2051,12 +2051,12 @@ void BodyNode::aggregateCombinedVector(Eigen::VectorXd& _Cg, mCg_F += math::dAdInvT((*it)->getParentJoint()->mT, (*it)->mCg_F); } - size_t nGenCoords = mParentJoint->getNumDofs(); + std::size_t nGenCoords = mParentJoint->getNumDofs(); if (nGenCoords > 0) { Eigen::VectorXd Cg = mParentJoint->getLocalJacobian().transpose() * mCg_F; - size_t iStart = mParentJoint->getIndexInTree(0); + std::size_t iStart = mParentJoint->getIndexInTree(0); _Cg.segment(iStart, nGenCoords) = Cg; } } @@ -2073,11 +2073,11 @@ void BodyNode::aggregateExternalForces(Eigen::VectorXd& _Fext) (*it)->mFext_F); } - size_t nGenCoords = mParentJoint->getNumDofs(); + std::size_t nGenCoords = mParentJoint->getNumDofs(); if (nGenCoords > 0) { Eigen::VectorXd Fext = mParentJoint->getLocalJacobian().transpose()*mFext_F; - size_t iStart = mParentJoint->getIndexInTree(0); + std::size_t iStart = mParentJoint->getIndexInTree(0); _Fext.segment(iStart, nGenCoords) = Fext; } } @@ -2098,7 +2098,7 @@ void BodyNode::aggregateSpatialToGeneralized(Eigen::VectorXd& _generalized, } // Project the spatial quantity to generalized coordinates - size_t iStart = mParentJoint->getIndexInTree(0); + std::size_t iStart = mParentJoint->getIndexInTree(0); _generalized.segment(iStart, mParentJoint->getNumDofs()) = mParentJoint->getSpatialToGeneralized(mArbitrarySpatial); } @@ -2107,7 +2107,7 @@ void BodyNode::aggregateSpatialToGeneralized(Eigen::VectorXd& _generalized, void BodyNode::updateMassMatrix() { mM_dV.setZero(); - size_t dof = mParentJoint->getNumDofs(); + std::size_t dof = mParentJoint->getNumDofs(); if (dof > 0) { mM_dV.noalias() += mParentJoint->getLocalJacobian() @@ -2121,7 +2121,7 @@ void BodyNode::updateMassMatrix() } //============================================================================== -void BodyNode::aggregateMassMatrix(Eigen::MatrixXd& _MCol, size_t _col) +void BodyNode::aggregateMassMatrix(Eigen::MatrixXd& _MCol, std::size_t _col) { const Eigen::Matrix6d& mI = mAspectProperties.mInertia.getSpatialTensor(); // @@ -2142,17 +2142,17 @@ void BodyNode::aggregateMassMatrix(Eigen::MatrixXd& _MCol, size_t _col) assert(!math::isNan(mM_F)); // - size_t dof = mParentJoint->getNumDofs(); + std::size_t dof = mParentJoint->getNumDofs(); if (dof > 0) { - size_t iStart = mParentJoint->getIndexInTree(0); + std::size_t iStart = mParentJoint->getIndexInTree(0); _MCol.block(iStart, _col, dof, 1).noalias() = mParentJoint->getLocalJacobian().transpose() * mM_F; } } //============================================================================== -void BodyNode::aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, +void BodyNode::aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, std::size_t _col, double _timeStep) { // TODO(JS): Need to be reimplemented @@ -2176,18 +2176,18 @@ void BodyNode::aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, assert(!math::isNan(mM_F)); // - size_t dof = mParentJoint->getNumDofs(); + std::size_t dof = mParentJoint->getNumDofs(); if (dof > 0) { Eigen::MatrixXd K = Eigen::MatrixXd::Zero(dof, dof); Eigen::MatrixXd D = Eigen::MatrixXd::Zero(dof, dof); - for (size_t i = 0; i < dof; ++i) + for (std::size_t i = 0; i < dof; ++i) { K(i, i) = mParentJoint->getSpringStiffness(i); D(i, i) = mParentJoint->getDampingCoefficient(i); } - size_t iStart = mParentJoint->getIndexInTree(0); + std::size_t iStart = mParentJoint->getIndexInTree(0); _MCol.block(iStart, _col, dof, 1).noalias() = mParentJoint->getLocalJacobian().transpose() * mM_F @@ -2239,7 +2239,7 @@ void BodyNode::updateInvAugMassMatrix() } //============================================================================== -void BodyNode::aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col) +void BodyNode::aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, std::size_t _col) { if (mParentBodyNode) { @@ -2266,7 +2266,7 @@ void BodyNode::aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col) } //============================================================================== -void BodyNode::aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col, +void BodyNode::aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, std::size_t _col, double /*_timeStep*/) { if (mParentBodyNode) @@ -2313,16 +2313,16 @@ void BodyNode::updateBodyJacobian() const if(nullptr == mParentJoint) return; - const size_t localDof = mParentJoint->getNumDofs(); + const std::size_t localDof = mParentJoint->getNumDofs(); assert(getNumDependentGenCoords() >= localDof); - const size_t ascendantDof = getNumDependentGenCoords() - localDof; + const std::size_t ascendantDof = getNumDependentGenCoords() - localDof; // Parent Jacobian if (mParentBodyNode) { - assert(static_cast(mParentBodyNode->getJacobian().cols()) + assert(static_cast(mParentBodyNode->getJacobian().cols()) + mParentJoint->getNumDofs() - == static_cast(mBodyJacobian.cols())); + == static_cast(mBodyJacobian.cols())); assert(mParentJoint); mBodyJacobian.leftCols(ascendantDof) = @@ -2374,8 +2374,8 @@ void BodyNode::updateBodyJacobianSpatialDeriv() const { const auto& dJ_parent = mParentBodyNode->getJacobianSpatialDeriv(); - assert(static_cast(dJ_parent.cols()) + mParentJoint->getNumDofs() - == static_cast(mBodyJacobianSpatialDeriv.cols())); + assert(static_cast(dJ_parent.cols()) + mParentJoint->getNumDofs() + == static_cast(mBodyJacobianSpatialDeriv.cols())); mBodyJacobianSpatialDeriv.leftCols(numParentDOFs) = math::AdInvTJac(mParentJoint->getLocalTransform(), dJ_parent); @@ -2413,9 +2413,9 @@ void BodyNode::updateWorldJacobianClassicDeriv() const if(nullptr == mParentJoint) return; - const size_t numLocalDOFs = mParentJoint->getNumDofs(); + const std::size_t numLocalDOFs = mParentJoint->getNumDofs(); assert(getNumDependentGenCoords() >= numLocalDOFs); - const size_t numParentDOFs = getNumDependentGenCoords() - numLocalDOFs; + const std::size_t numParentDOFs = getNumDependentGenCoords() - numLocalDOFs; if(mParentBodyNode) @@ -2430,8 +2430,8 @@ void BodyNode::updateWorldJacobianClassicDeriv() const const Eigen::Vector3d& p = (getWorldTransform().translation() - mParentBodyNode->getWorldTransform().translation()).eval(); - assert(static_cast(dJ_parent.cols()) + mParentJoint->getNumDofs() - == static_cast(mWorldJacobianClassicDeriv.cols())); + assert(static_cast(dJ_parent.cols()) + mParentJoint->getNumDofs() + == static_cast(mWorldJacobianClassicDeriv.cols())); // dJr mWorldJacobianClassicDeriv.block(0,0,3,numParentDOFs) diff --git a/dart/dynamics/BodyNode.h b/dart/dynamics/BodyNode.h index df0d52db79194..08a429e42fdd0 100644 --- a/dart/dynamics/BodyNode.h +++ b/dart/dynamics/BodyNode.h @@ -268,13 +268,13 @@ class BodyNode : //-------------------------------------------------------------------------- /// Return the index of this BodyNode within its Skeleton - size_t getIndexInSkeleton() const; + std::size_t getIndexInSkeleton() const; /// Return the index of this BodyNode within its tree - size_t getIndexInTree() const; + std::size_t getIndexInTree() const; /// Return the index of the tree that this BodyNode belongs to - size_t getTreeIndex() const; + std::size_t getTreeIndex() const; /// Remove this BodyNode and all of its children (recursively) from their /// Skeleton. If a BodyNodePtr that references this BodyNode (or any of its @@ -514,22 +514,22 @@ class BodyNode : // default argument. Please see #487 for detail /// Return the number of child BodyNodes - size_t getNumChildBodyNodes() const; + std::size_t getNumChildBodyNodes() const; /// Return the _index-th child BodyNode of this BodyNode - BodyNode* getChildBodyNode(size_t _index); + BodyNode* getChildBodyNode(std::size_t _index); /// Return the (const) _index-th child BodyNode of this BodyNode - const BodyNode* getChildBodyNode(size_t _index) const; + const BodyNode* getChildBodyNode(std::size_t _index) const; /// Return the number of child Joints - size_t getNumChildJoints() const; + std::size_t getNumChildJoints() const; /// Return the _index-th child Joint of this BodyNode - Joint* getChildJoint(size_t _index); + Joint* getChildJoint(std::size_t _index); /// Return the (const) _index-th child Joint of this BodyNode - const Joint* getChildJoint(size_t _index) const; + const Joint* getChildJoint(std::size_t _index) const; /// Create some Node type and attach it to this BodyNode. template @@ -556,13 +556,13 @@ class BodyNode : ShapeNode* createShapeNode(const ShapePtr& shape, const char* name); /// Return the number of all the ShapeNodes in this BodyNode - size_t getNumShapeNodes() const; + std::size_t getNumShapeNodes() const; /// Return the index-th ShapeNode - ShapeNode* getShapeNode(size_t index); + ShapeNode* getShapeNode(std::size_t index); /// Return the index-th (const) ShapeNode - const ShapeNode* getShapeNode(size_t index) const; + const ShapeNode* getShapeNode(std::size_t index) const; /// Return the list of ShapeNodes const std::vector getShapeNodes(); @@ -585,7 +585,7 @@ class BodyNode : /// Return the number of ShapeNodes containing given Aspect in this BodyNode template - size_t getNumShapeNodesWith() const; + std::size_t getNumShapeNodesWith() const; /// Return the list of ShapeNodes containing given Aspect template @@ -614,34 +614,34 @@ class BodyNode : void addMarker(Marker* _marker); /// Return the number of markers of the bodynode - size_t getNumMarkers() const; + std::size_t getNumMarkers() const; /// Return _index-th marker of the bodynode - Marker* getMarker(size_t _index); + Marker* getMarker(std::size_t _index); /// Return (const) _index-th marker of the bodynode - const Marker* getMarker(size_t _index) const; + const Marker* getMarker(std::size_t _index) const; // Documentation inherited - bool dependsOn(size_t _genCoordIndex) const override; + bool dependsOn(std::size_t _genCoordIndex) const override; // Documentation inherited - size_t getNumDependentGenCoords() const override; + std::size_t getNumDependentGenCoords() const override; // Documentation inherited - size_t getDependentGenCoordIndex(size_t _arrayIndex) const override; + std::size_t getDependentGenCoordIndex(std::size_t _arrayIndex) const override; // Documentation inherited - const std::vector& getDependentGenCoordIndices() const override; + const std::vector& getDependentGenCoordIndices() const override; // Documentation inherited - size_t getNumDependentDofs() const override; + std::size_t getNumDependentDofs() const override; // Documentation inherited - DegreeOfFreedom* getDependentDof(size_t _index) override; + DegreeOfFreedom* getDependentDof(std::size_t _index) override; // Documentation inherited - const DegreeOfFreedom* getDependentDof(size_t _index) const override; + const DegreeOfFreedom* getDependentDof(std::size_t _index) const override; // Documentation inherited const std::vector& getDependentDofs() override; @@ -978,15 +978,15 @@ class BodyNode : /// virtual void updateMassMatrix(); - virtual void aggregateMassMatrix(Eigen::MatrixXd& _MCol, size_t _col); - virtual void aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, + virtual void aggregateMassMatrix(Eigen::MatrixXd& _MCol, std::size_t _col); + virtual void aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, std::size_t _col, double _timeStep); /// virtual void updateInvMassMatrix(); virtual void updateInvAugMassMatrix(); - virtual void aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col); - virtual void aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col, + virtual void aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, std::size_t _col); + virtual void aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, std::size_t _col, double _timeStep); /// @@ -1039,7 +1039,7 @@ class BodyNode : int mID; /// Counts the number of nodes globally. - static size_t msBodyNodeCount; + static std::size_t msBodyNodeCount; /// Whether the node is currently in collision with another node. /// \deprecated DEPRECATED(6.0) See #670 for more detail. @@ -1050,13 +1050,13 @@ class BodyNode : //-------------------------------------------------------------------------- /// Index of this BodyNode in its Skeleton - size_t mIndexInSkeleton; + std::size_t mIndexInSkeleton; /// Index of this BodyNode in its Tree - size_t mIndexInTree; + std::size_t mIndexInTree; /// Index of this BodyNode's tree - size_t mTreeIndex; + std::size_t mTreeIndex; /// Parent joint Joint* mParentJoint; @@ -1075,7 +1075,7 @@ class BodyNode : std::vector mMarkers; /// A increasingly sorted list of dependent dof indices. - std::vector mDependentGenCoordIndices; + std::vector mDependentGenCoordIndices; /// A version of mDependentGenCoordIndices that holds DegreeOfFreedom pointers /// instead of indices diff --git a/dart/dynamics/Branch.cpp b/dart/dynamics/Branch.cpp index 357a397fcb904..e93cfe35d1d8e 100644 --- a/dart/dynamics/Branch.cpp +++ b/dart/dynamics/Branch.cpp @@ -84,7 +84,7 @@ bool Branch::isStillBranch() const if(!isAssembled()) return false; - for(size_t i=0; igetNumChildBodyNodes() != mNumChildNodes[i]) @@ -108,7 +108,7 @@ void Branch::update() mNumChildNodes.clear(); mNumChildNodes.reserve(mBodyNodes.size()); - for(size_t i=0; igetNumChildBodyNodes()); } diff --git a/dart/dynamics/Branch.h b/dart/dynamics/Branch.h index 7d79ee3720ba4..6ad3f882ed095 100644 --- a/dart/dynamics/Branch.h +++ b/dart/dynamics/Branch.h @@ -88,7 +88,7 @@ class Branch : public Linkage void update() override; /// The original number of child nodes for each BodyNode of this Branch - std::vector mNumChildNodes; + std::vector mNumChildNodes; }; } // namespace dynamics diff --git a/dart/dynamics/Chain.cpp b/dart/dynamics/Chain.cpp index 12c5ee0d7bbd9..b7c6a98855c15 100644 --- a/dart/dynamics/Chain.cpp +++ b/dart/dynamics/Chain.cpp @@ -129,7 +129,7 @@ bool Chain::isStillChain() const // Make sure there are no Branches and no parent FreeJoints on the BodyNodes // on the inside of the chain - for(size_t i=1; igetNumChildBodyNodes() > 1) return false; diff --git a/dart/dynamics/DegreeOfFreedom.cpp b/dart/dynamics/DegreeOfFreedom.cpp index 03546c18a36fd..09c72c35820a0 100644 --- a/dart/dynamics/DegreeOfFreedom.cpp +++ b/dart/dynamics/DegreeOfFreedom.cpp @@ -67,25 +67,25 @@ bool DegreeOfFreedom::isNamePreserved() const } //============================================================================== -size_t DegreeOfFreedom::getIndexInSkeleton() const +std::size_t DegreeOfFreedom::getIndexInSkeleton() const { return mIndexInSkeleton; } //============================================================================== -size_t DegreeOfFreedom::getIndexInTree() const +std::size_t DegreeOfFreedom::getIndexInTree() const { return mIndexInTree; } //============================================================================== -size_t DegreeOfFreedom::getIndexInJoint() const +std::size_t DegreeOfFreedom::getIndexInJoint() const { return mIndexInJoint; } //============================================================================== -size_t DegreeOfFreedom::getTreeIndex() const +std::size_t DegreeOfFreedom::getTreeIndex() const { return mJoint->getTreeIndex(); } @@ -528,7 +528,7 @@ const BodyNode* DegreeOfFreedom::getParentBodyNode() const //============================================================================== DegreeOfFreedom::DegreeOfFreedom(Joint* _joint, - size_t _indexInJoint) + std::size_t _indexInJoint) : mIndexInJoint(_indexInJoint), mIndexInSkeleton(0), mIndexInTree(0), diff --git a/dart/dynamics/DegreeOfFreedom.h b/dart/dynamics/DegreeOfFreedom.h index e72035d4b18b3..744abc8e05409 100644 --- a/dart/dynamics/DegreeOfFreedom.h +++ b/dart/dynamics/DegreeOfFreedom.h @@ -51,7 +51,7 @@ class Skeleton; class Joint; class BodyNode; class SingleDofJoint; -template class MultiDofJoint; +template class MultiDofJoint; /// DegreeOfFreedom class is a proxy class for accessing single degrees of /// freedom (aka generalized coordinates) of the Skeleton. @@ -61,7 +61,7 @@ class DegreeOfFreedom : public virtual common::Subject friend class Joint; friend class SingleDofJoint; - template friend class MultiDofJoint; + template friend class MultiDofJoint; friend class Skeleton; DegreeOfFreedom(const DegreeOfFreedom&) = delete; @@ -101,16 +101,16 @@ class DegreeOfFreedom : public virtual common::Subject bool isNamePreserved() const; /// Get this DegreeOfFreedom's index within its Skeleton - size_t getIndexInSkeleton() const; + std::size_t getIndexInSkeleton() const; /// Get this DegreeOfFreedom's index within its tree - size_t getIndexInTree() const; + std::size_t getIndexInTree() const; /// Get this DegreeOfFreedom's index within its Joint - size_t getIndexInJoint() const; + std::size_t getIndexInJoint() const; /// Get the index of the tree that this DegreeOfFreedom belongs to - size_t getTreeIndex() const; + std::size_t getTreeIndex() const; //---------------------------------------------------------------------------- /// \{ \name Command @@ -387,19 +387,19 @@ class DegreeOfFreedom : public virtual common::Subject protected: /// The constructor is protected so that only Joints can create /// DegreeOfFreedom classes - DegreeOfFreedom(Joint* _joint, size_t _indexInJoint); + DegreeOfFreedom(Joint* _joint, std::size_t _indexInJoint); /// \brief Index of this DegreeOfFreedom within its Joint /// /// The index is determined when this DegreeOfFreedom is created by the Joint /// it belongs to. Note that the index should be unique within the Joint. - size_t mIndexInJoint; + std::size_t mIndexInJoint; /// Index of this DegreeOfFreedom within its Skeleton - size_t mIndexInSkeleton; + std::size_t mIndexInSkeleton; /// Index of this DegreeOfFreedom within its tree - size_t mIndexInTree; + std::size_t mIndexInTree; /// The joint that this DegreeOfFreedom belongs to Joint* mJoint; diff --git a/dart/dynamics/EulerJoint.cpp b/dart/dynamics/EulerJoint.cpp index 4a0a3f8911a24..b6e9aea1c3dd4 100644 --- a/dart/dynamics/EulerJoint.cpp +++ b/dart/dynamics/EulerJoint.cpp @@ -116,7 +116,7 @@ const std::string& EulerJoint::getStaticType() } //============================================================================== -bool EulerJoint::isCyclic(size_t _index) const +bool EulerJoint::isCyclic(std::size_t _index) const { return !hasPositionLimit(_index); } @@ -327,7 +327,7 @@ void EulerJoint::updateDegreeOfFreedomNames() if (affixes.size() == 3) { - for (size_t i = 0; i < 3; ++i) + for (std::size_t i = 0; i < 3; ++i) { if(!mDofs[i]->isNamePreserved()) mDofs[i]->setName(Joint::mAspectProperties.mName + affixes[i], false); diff --git a/dart/dynamics/EulerJoint.h b/dart/dynamics/EulerJoint.h index 43fd233d45f12..51b147c693e5f 100644 --- a/dart/dynamics/EulerJoint.h +++ b/dart/dynamics/EulerJoint.h @@ -88,7 +88,7 @@ class EulerJoint : public detail::EulerJointBase static const std::string& getStaticType(); // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; /// Set the axis order /// \param[in] _order Axis order diff --git a/dart/dynamics/FixedJacobianNode.cpp b/dart/dynamics/FixedJacobianNode.cpp index 1dd0ed1c92a80..0a87f5bc45dac 100644 --- a/dart/dynamics/FixedJacobianNode.cpp +++ b/dart/dynamics/FixedJacobianNode.cpp @@ -54,43 +54,43 @@ void FixedJacobianNode::setRelativeTransform( } //============================================================================== -bool FixedJacobianNode::dependsOn(size_t _genCoordIndex) const +bool FixedJacobianNode::dependsOn(std::size_t _genCoordIndex) const { return mBodyNode->dependsOn(_genCoordIndex); } //============================================================================== -size_t FixedJacobianNode::getNumDependentGenCoords() const +std::size_t FixedJacobianNode::getNumDependentGenCoords() const { return mBodyNode->getNumDependentGenCoords(); } //============================================================================== -size_t FixedJacobianNode::getDependentGenCoordIndex(size_t _arrayIndex) const +std::size_t FixedJacobianNode::getDependentGenCoordIndex(std::size_t _arrayIndex) const { return mBodyNode->getDependentGenCoordIndex(_arrayIndex); } //============================================================================== -const std::vector& FixedJacobianNode::getDependentGenCoordIndices() const +const std::vector& FixedJacobianNode::getDependentGenCoordIndices() const { return mBodyNode->getDependentGenCoordIndices(); } //============================================================================== -size_t FixedJacobianNode::getNumDependentDofs() const +std::size_t FixedJacobianNode::getNumDependentDofs() const { return mBodyNode->getNumDependentDofs(); } //============================================================================== -DegreeOfFreedom* FixedJacobianNode::getDependentDof(size_t _index) +DegreeOfFreedom* FixedJacobianNode::getDependentDof(std::size_t _index) { return mBodyNode->getDependentDof(_index); } //============================================================================== -const DegreeOfFreedom* FixedJacobianNode::getDependentDof(size_t _index) const +const DegreeOfFreedom* FixedJacobianNode::getDependentDof(std::size_t _index) const { return mBodyNode->getDependentDof(_index); } diff --git a/dart/dynamics/FixedJacobianNode.h b/dart/dynamics/FixedJacobianNode.h index 62fa30036ade9..9bf549422fb2e 100644 --- a/dart/dynamics/FixedJacobianNode.h +++ b/dart/dynamics/FixedJacobianNode.h @@ -65,25 +65,25 @@ class FixedJacobianNode : void setRelativeTransform(const Eigen::Isometry3d& newRelativeTf) override; // Documentation inherited - bool dependsOn(size_t _genCoordIndex) const override; + bool dependsOn(std::size_t _genCoordIndex) const override; // Documentation inherited - size_t getNumDependentGenCoords() const override; + std::size_t getNumDependentGenCoords() const override; // Documentation inherited - size_t getDependentGenCoordIndex(size_t _arrayIndex) const override; + std::size_t getDependentGenCoordIndex(std::size_t _arrayIndex) const override; // Documentation inherited - const std::vector& getDependentGenCoordIndices() const override; + const std::vector& getDependentGenCoordIndices() const override; // Documentation inherited - size_t getNumDependentDofs() const override; + std::size_t getNumDependentDofs() const override; // Documentation inherited - DegreeOfFreedom* getDependentDof(size_t _index) override; + DegreeOfFreedom* getDependentDof(std::size_t _index) override; // Documentation inherited - const DegreeOfFreedom* getDependentDof(size_t _index) const override; + const DegreeOfFreedom* getDependentDof(std::size_t _index) const override; // Documentation inherited const std::vector& getDependentDofs() override; diff --git a/dart/dynamics/Frame.cpp b/dart/dynamics/Frame.cpp index 244bdec6bbe64..d97c48e647504 100644 --- a/dart/dynamics/Frame.cpp +++ b/dart/dynamics/Frame.cpp @@ -404,7 +404,7 @@ const std::set Frame::getChildEntities() const } //============================================================================== -size_t Frame::getNumChildEntities() const +std::size_t Frame::getNumChildEntities() const { return mChildEntities.size(); } @@ -422,7 +422,7 @@ std::set Frame::getChildFrames() const } //============================================================================== -size_t Frame::getNumChildFrames() const +std::size_t Frame::getNumChildFrames() const { return mChildFrames.size(); } diff --git a/dart/dynamics/Frame.h b/dart/dynamics/Frame.h index 4bfadb683c9d1..d8178b700799c 100644 --- a/dart/dynamics/Frame.h +++ b/dart/dynamics/Frame.h @@ -214,7 +214,7 @@ class Frame : public virtual Entity const std::set getChildEntities() const; /// Get the number of Entities that are currently children of this Frame. - size_t getNumChildEntities() const; + std::size_t getNumChildEntities() const; /// Get a container with the Frames that are children of this Frame. /// std::set is used because Frames may be arbitrarily added and removed @@ -227,7 +227,7 @@ class Frame : public virtual Entity std::set getChildFrames() const; /// Get the number of Frames that are currently children of this Frame. - size_t getNumChildFrames() const; + std::size_t getNumChildFrames() const; /// Returns true if this Frame is a ShapeFrame bool isShapeFrame() const; diff --git a/dart/dynamics/FreeJoint.cpp b/dart/dynamics/FreeJoint.cpp index 8e74af8fdd5d2..a72c5cc85b4c1 100644 --- a/dart/dynamics/FreeJoint.cpp +++ b/dart/dynamics/FreeJoint.cpp @@ -124,7 +124,7 @@ void FreeJoint::setTransform(Skeleton* skeleton, if (nullptr == skeleton) return; - const size_t numTrees = skeleton->getNumTrees(); + const std::size_t numTrees = skeleton->getNumTrees(); if (0 == numTrees) return; @@ -135,7 +135,7 @@ void FreeJoint::setTransform(Skeleton* skeleton, return; } - for (size_t i = 0; i < numTrees; ++i) + for (std::size_t i = 0; i < numTrees; ++i) setTransform(skeleton->getRootBodyNode(i), tf, withRespectTo); } @@ -557,7 +557,7 @@ const std::string& FreeJoint::getStaticType() } //============================================================================== -bool FreeJoint::isCyclic(size_t _index) const +bool FreeJoint::isCyclic(std::size_t _index) const { return _index < 3 && !hasPositionLimit(0) && !hasPositionLimit(1) && !hasPositionLimit(2); diff --git a/dart/dynamics/FreeJoint.h b/dart/dynamics/FreeJoint.h index 7e1481122f9f2..8b20be0c8b3e1 100644 --- a/dart/dynamics/FreeJoint.h +++ b/dart/dynamics/FreeJoint.h @@ -76,7 +76,7 @@ class FreeJoint : public MultiDofJoint<6> static const std::string& getStaticType(); // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; /// Convert a transform into a 6D vector that can be used to set the positions /// of a FreeJoint. The positions returned by this function will result in a diff --git a/dart/dynamics/Group.cpp b/dart/dynamics/Group.cpp index 37e0f33a6c3d4..aff4fc6bd6a34 100644 --- a/dart/dynamics/Group.cpp +++ b/dart/dynamics/Group.cpp @@ -73,7 +73,7 @@ GroupPtr Group::create(const std::string& _name, } //============================================================================== -void Group::swapBodyNodeIndices(size_t _index1, size_t _index2) +void Group::swapBodyNodeIndices(std::size_t _index1, std::size_t _index2) { if(_index1 >= mBodyNodes.size() || _index2 >= mBodyNodes.size()) { @@ -123,7 +123,7 @@ void Group::swapBodyNodeIndices(size_t _index1, size_t _index2) } //============================================================================== -void Group::swapDofIndices(size_t _index1, size_t _index2) +void Group::swapDofIndices(std::size_t _index1, std::size_t _index2) { if(_index1 >= mDofs.size() || _index2 >= mDofs.size()) { @@ -164,8 +164,8 @@ void Group::swapDofIndices(size_t _index1, size_t _index2) return; } - size_t localIndex1 = dof1->getIndexInJoint(); - size_t localIndex2 = dof2->getIndexInJoint(); + std::size_t localIndex1 = dof1->getIndexInJoint(); + std::size_t localIndex2 = dof2->getIndexInJoint(); it1->second.mDofIndices[localIndex1] = _index2; it2->second.mDofIndices[localIndex2] = _index1; @@ -195,7 +195,7 @@ bool Group::addComponent(BodyNode* _bn, bool _warning) added |= addBodyNode(_bn, false); - for(size_t i=0; i < _bn->getParentJoint()->getNumDofs(); ++i) + for(std::size_t i=0; i < _bn->getParentJoint()->getNumDofs(); ++i) added |= addDof(_bn->getParentJoint()->getDof(i), false); if(_warning && !added) @@ -240,7 +240,7 @@ bool Group::removeComponent(BodyNode* _bn, bool _warning) removed |= removeBodyNode(_bn, false); - for(size_t i=0; i < _bn->getParentJoint()->getNumDofs(); ++i) + for(std::size_t i=0; i < _bn->getParentJoint()->getNumDofs(); ++i) removed |= removeDof(_bn->getParentJoint()->getDof(i), false); if(_warning && !removed) @@ -376,7 +376,7 @@ bool Group::addJoint(Joint* _joint, bool _addDofs, bool _warning) if(_addDofs) { - for(size_t i=0; i < _joint->getNumDofs(); ++i) + for(std::size_t i=0; i < _joint->getNumDofs(); ++i) added |= addDof(_joint->getDof(i), false, false); } @@ -439,7 +439,7 @@ bool Group::removeJoint(Joint* _joint, bool _removeDofs, bool _warning) if(_removeDofs) { - for(size_t i=0; i < _joint->getNumDofs(); ++i) + for(std::size_t i=0; i < _joint->getNumDofs(); ++i) removed |= removeDof(_joint->getDof(i), false, false); } @@ -553,7 +553,7 @@ bool Group::removeDof(DegreeOfFreedom* _dof, bool _cleanupJoint, bool _warning) // Check whether any DOFs belonging to the Joint are remaining in the Group bool performCleanup = true; Joint* joint = _dof->getJoint(); - for(size_t i=0; i < joint->getNumDofs(); ++i) + for(std::size_t i=0; i < joint->getNumDofs(); ++i) { if(getIndexOf(joint->getDof(i), false) == INVALID_INDEX) { @@ -609,7 +609,7 @@ Group::Group(const std::string& _name, if(_includeDofs || _includeJoints) { - for(size_t i=0; i < _bodyNodes.size(); ++i) + for(std::size_t i=0; i < _bodyNodes.size(); ++i) { Joint* joint = _bodyNodes[i]->getParentJoint(); @@ -618,7 +618,7 @@ Group::Group(const std::string& _name, if(_includeDofs) { - for(size_t j=0; j < joint->getNumDofs(); ++j) + for(std::size_t j=0; j < joint->getNumDofs(); ++j) addDof(joint->getDof(j)); } } @@ -635,7 +635,7 @@ Group::Group(const std::string& _name, if(_includeBodyNodes) { - for(size_t i=0; i < _dofs.size(); ++i) + for(std::size_t i=0; i < _dofs.size(); ++i) { DegreeOfFreedom* dof = _dofs[i]; addBodyNode(dof->getChildBodyNode(), false); @@ -651,13 +651,13 @@ Group::Group(const std::string& _name, if(_metaSkeleton) { - for(size_t i=0; i < _metaSkeleton->getNumBodyNodes(); ++i) + for(std::size_t i=0; i < _metaSkeleton->getNumBodyNodes(); ++i) addBodyNode(_metaSkeleton->getBodyNode(i)); - for(size_t i=0; i < _metaSkeleton->getNumJoints(); ++i) + for(std::size_t i=0; i < _metaSkeleton->getNumJoints(); ++i) addJoint(_metaSkeleton->getJoint(i), false); - for(size_t i=0; i < _metaSkeleton->getNumDofs(); ++i) + for(std::size_t i=0; i < _metaSkeleton->getNumDofs(); ++i) addDof(_metaSkeleton->getDof(i), false); } } diff --git a/dart/dynamics/Group.h b/dart/dynamics/Group.h index 41da9db5096ee..69112fa7fb287 100644 --- a/dart/dynamics/Group.h +++ b/dart/dynamics/Group.h @@ -75,10 +75,10 @@ class Group : public ReferentialSkeleton virtual ~Group() = default; /// Swap the index of BodyNode _index1 with _index2 - void swapBodyNodeIndices(size_t _index1, size_t _index2); + void swapBodyNodeIndices(std::size_t _index1, std::size_t _index2); /// Swap the index of DegreeOfFreedom _index1 with _index2 - void swapDofIndices(size_t _index1, size_t _index2); + void swapDofIndices(std::size_t _index1, std::size_t _index2); /// Add a BodyNode and its parent DegreesOfFreedom to this Group. If _warning /// is true, you will be warned when the BodyNode and all its DegreesOfFreedom diff --git a/dart/dynamics/HierarchicalIK.cpp b/dart/dynamics/HierarchicalIK.cpp index ab8e269b5076c..2ef782aac608b 100644 --- a/dart/dynamics/HierarchicalIK.cpp +++ b/dart/dynamics/HierarchicalIK.cpp @@ -74,17 +74,17 @@ bool HierarchicalIK::solve(bool _applySolution) return false; } - const size_t nDofs = skel->getNumDofs(); + const std::size_t nDofs = skel->getNumDofs(); mProblem->setDimension(nDofs); mProblem->setInitialGuess(skel->getPositions()); Eigen::VectorXd bounds(nDofs); - for(size_t i=0; i < nDofs; ++i) + for(std::size_t i=0; i < nDofs; ++i) bounds[i] = skel->getDof(i)->getPositionLowerLimit(); mProblem->setLowerBounds(bounds); - for(size_t i=0; i < nDofs; ++i) + for(std::size_t i=0; i < nDofs; ++i) bounds[i] = skel->getDof(i)->getPositionUpperLimit(); mProblem->setUpperBounds(bounds); @@ -218,14 +218,14 @@ const std::vector& HierarchicalIK::computeNullSpaces() const { bool recompute = false; const ConstSkeletonPtr& skel = getSkeleton(); - const size_t nDofs = skel->getNumDofs(); - if(static_cast(mLastPositions.size()) != nDofs) + const std::size_t nDofs = skel->getNumDofs(); + if(static_cast(mLastPositions.size()) != nDofs) { recompute = true; } else { - for(size_t i=0; i < nDofs; ++i) + for(std::size_t i=0; i < nDofs; ++i) { if(mLastPositions[i] != skel->getDof(i)->getPosition()) { @@ -247,7 +247,7 @@ const std::vector& HierarchicalIK::computeNullSpaces() const mNullSpaceCache.resize(hierarchy.size()); bool zeroedNullSpace = false; - for(size_t i=0; i < hierarchy.size(); ++i) + for(std::size_t i=0; i < hierarchy.size(); ++i) { const std::vector< std::shared_ptr >& level = hierarchy[i]; @@ -271,7 +271,7 @@ const std::vector& HierarchicalIK::computeNullSpaces() const } mJacCache.resize(6, nDofs); - for(size_t j=0; j < level.size(); ++j) + for(std::size_t j=0; j < level.size(); ++j) { const std::shared_ptr& ik = level[j]; @@ -279,12 +279,12 @@ const std::vector& HierarchicalIK::computeNullSpaces() const continue; const math::Jacobian& J = ik->computeJacobian(); - const std::vector& dofs = ik->getDofs(); + const std::vector& dofs = ik->getDofs(); mJacCache.setZero(); - for(size_t d=0; d < dofs.size(); ++d) + for(std::size_t d=0; d < dofs.size(); ++d) { - size_t k = dofs[d]; + std::size_t k = dofs[d]; mJacCache.block<6,1>(0,k) = J.block<6,1>(0,d); } @@ -460,21 +460,21 @@ double HierarchicalIK::Constraint::eval(const Eigen::VectorXd& _x) const IKHierarchy& hierarchy = hik->getIKHierarchy(); double cost = 0.0; - for(size_t i=0; i < hierarchy.size(); ++i) + for(std::size_t i=0; i < hierarchy.size(); ++i) { const std::vector< std::shared_ptr >& level = hierarchy[i]; - for(size_t j=0; j < level.size(); ++j) + for(std::size_t j=0; j < level.size(); ++j) { const std::shared_ptr& ik = level[j]; if(!ik->isActive()) continue; - const std::vector& dofs = ik->getDofs(); + const std::vector& dofs = ik->getDofs(); Eigen::VectorXd q(dofs.size()); - for(size_t k=0; k < dofs.size(); ++k) + for(std::size_t k=0; k < dofs.size(); ++k) q[k] = _x[dofs[k]]; InverseKinematics::ErrorMethod& method = ik->getErrorMethod(); @@ -495,17 +495,17 @@ void HierarchicalIK::Constraint::evalGradient( const IKHierarchy& hierarchy = hik->getIKHierarchy(); const SkeletonPtr& skel = hik->getSkeleton(); - const size_t nDofs = skel->getNumDofs(); + const std::size_t nDofs = skel->getNumDofs(); const std::vector& nullspaces = hik->computeNullSpaces(); _grad.setZero(); - for(size_t i=0; i < hierarchy.size(); ++i) + for(std::size_t i=0; i < hierarchy.size(); ++i) { const std::vector< std::shared_ptr >& level = hierarchy[i]; mLevelGradCache.setZero(nDofs); - for(size_t j=0; j < level.size(); ++j) + for(std::size_t j=0; j < level.size(); ++j) { const std::shared_ptr& ik = level[j]; @@ -513,9 +513,9 @@ void HierarchicalIK::Constraint::evalGradient( continue; // Grab only the dependent coordinates from q - const std::vector& dofs = ik->getDofs(); + const std::vector& dofs = ik->getDofs(); Eigen::VectorXd q(dofs.size()); - for(size_t k=0; k < dofs.size(); ++k) + for(std::size_t k=0; k < dofs.size(); ++k) q[k] = _x[dofs[k]]; // Compute the gradient of this specific error term @@ -527,7 +527,7 @@ void HierarchicalIK::Constraint::evalGradient( method.evalGradient(q, gradMap); // Add the components of this gradient into the gradient of this level - for(size_t k=0; k < dofs.size(); ++k) + for(std::size_t k=0; k < dofs.size(); ++k) mLevelGradCache[dofs[k]] += mTempGradCache[k]; } @@ -590,12 +590,12 @@ void HierarchicalIK::copyOverSetup( newProblem->setObjective( cloneIkFunc(mProblem->getObjective(), _otherIK) ); newProblem->removeAllEqConstraints(); - for(size_t i=0; i < mProblem->getNumEqConstraints(); ++i) + for(std::size_t i=0; i < mProblem->getNumEqConstraints(); ++i) newProblem->addEqConstraint( cloneIkFunc(mProblem->getEqConstraint(i), _otherIK)); newProblem->removeAllIneqConstraints(); - for(size_t i=0; i < mProblem->getNumIneqConstraints(); ++i) + for(std::size_t i=0; i < mProblem->getNumIneqConstraints(); ++i) newProblem->addIneqConstraint( cloneIkFunc(mProblem->getIneqConstraint(i), _otherIK)); @@ -748,7 +748,7 @@ void WholeBodyIK::refreshIKHierarchy() // JacobianNode types, and also make the code more DRY. int highestLevel = -1; - for(size_t i=0; i < skel->getNumBodyNodes(); ++i) + for(std::size_t i=0; i < skel->getNumBodyNodes(); ++i) { BodyNode* bn = skel->getBodyNode(i); const std::shared_ptr& ik = bn->getIK(); @@ -760,7 +760,7 @@ void WholeBodyIK::refreshIKHierarchy() } } - for(size_t i=0; i < skel->getNumEndEffectors(); ++i) + for(std::size_t i=0; i < skel->getNumEndEffectors(); ++i) { EndEffector* ee = skel->getEndEffector(i); const std::shared_ptr& ik = ee->getIK(); @@ -783,7 +783,7 @@ void WholeBodyIK::refreshIKHierarchy() for(auto& level : mHierarchy) level.clear(); - for(size_t i=0; i < skel->getNumBodyNodes(); ++i) + for(std::size_t i=0; i < skel->getNumBodyNodes(); ++i) { BodyNode* bn = skel->getBodyNode(i); const std::shared_ptr& ik = bn->getIK(); @@ -792,7 +792,7 @@ void WholeBodyIK::refreshIKHierarchy() mHierarchy[ik->getHierarchyLevel()].push_back(ik); } - for(size_t i=0; i < skel->getNumEndEffectors(); ++i) + for(std::size_t i=0; i < skel->getNumEndEffectors(); ++i) { EndEffector* ee = skel->getEndEffector(i); const std::shared_ptr& ik = ee->getIK(); diff --git a/dart/dynamics/Inertia.cpp b/dart/dynamics/Inertia.cpp index 0bbd1bc47e390..73da1231f1999 100644 --- a/dart/dynamics/Inertia.cpp +++ b/dart/dynamics/Inertia.cpp @@ -144,7 +144,7 @@ void Inertia::setMoment(const Eigen::Matrix3d& _moment) << "matrix. Results might not by physically accurate or " << "meaningful.\n"; - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) mMoment[i] = _moment(i,i); mMoment[I_XY-4] = _moment(0,1); @@ -243,7 +243,7 @@ bool Inertia::verifySpatialTensor(const Eigen::Matrix6d& _spatial, bool valid = true; - for(size_t i=0; i<6; ++i) + for(std::size_t i=0; i<6; ++i) { if(_spatial(i, i) <= 0) { @@ -260,9 +260,9 @@ bool Inertia::verifySpatialTensor(const Eigen::Matrix6d& _spatial, } // Off-diagonals of top left block - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) { - for(size_t j=i+1; j<3; ++j) + for(std::size_t j=i+1; j<3; ++j) { if(std::abs(_spatial(i,j) - _spatial(j,i)) > _tolerance) { @@ -276,9 +276,9 @@ bool Inertia::verifySpatialTensor(const Eigen::Matrix6d& _spatial, } // Off-diagonals of bottom right block - for(size_t i=3; i<6; ++i) + for(std::size_t i=3; i<6; ++i) { - for(size_t j=i+1; j<6; ++j) + for(std::size_t j=i+1; j<6; ++j) { if(_spatial(i,j) != 0) { @@ -301,12 +301,12 @@ bool Inertia::verifySpatialTensor(const Eigen::Matrix6d& _spatial, } // Diagonals of the bottom left and top right blocks - for(size_t k=0; k<2; ++k) + for(std::size_t k=0; k<2; ++k) { - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) { - size_t i1 = k==0? i+3 : i; - size_t i2 = k==0? i : i+3; + std::size_t i1 = k==0? i+3 : i; + std::size_t i2 = k==0? i : i+3; if(_spatial(i1,i2) != 0) { valid = false; @@ -319,17 +319,17 @@ bool Inertia::verifySpatialTensor(const Eigen::Matrix6d& _spatial, } // Check skew-symmetry in bottom left and top right - for(size_t k=0; k<2; ++k) + for(std::size_t k=0; k<2; ++k) { - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) { - for(size_t j=i+1; j<3; ++j) + for(std::size_t j=i+1; j<3; ++j) { - size_t i1 = k==0? i+3 : i; - size_t j1 = k==0? j : j+3; + std::size_t i1 = k==0? i+3 : i; + std::size_t j1 = k==0? j : j+3; - size_t i2 = k==0? j+3 : j; - size_t j2 = k==0? i : i+3; + std::size_t i2 = k==0? j+3 : j; + std::size_t j2 = k==0? i : i+3; if(std::abs(_spatial(i1,j1) + _spatial(i2,j2)) > _tolerance) { @@ -349,15 +349,15 @@ bool Inertia::verifySpatialTensor(const Eigen::Matrix6d& _spatial, // Note that we only need to check three of the components from each block, // because the last test ensures that both blocks are skew-symmetric // themselves - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) { - for(size_t j=i+1; j<3; ++j) + for(std::size_t j=i+1; j<3; ++j) { - size_t i1 = i; - size_t j1 = j+3; + std::size_t i1 = i; + std::size_t j1 = j+3; - size_t i2 = i+3; - size_t j2 = j; + std::size_t i2 = i+3; + std::size_t j2 = j; if(std::abs(_spatial(i1,j1) - _spatial(i2,j2)) > _tolerance) { @@ -418,7 +418,7 @@ void Inertia::computeParameters() mCenterOfMass[2] = -C(0,1); Eigen::Matrix3d I = mSpatialTensor.block<3,3>(0,0) + mMass*C*C; - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) mMoment[i] = I(i,i); mMoment[I_XY-4] = I(0,1); diff --git a/dart/dynamics/InvalidIndex.h b/dart/dynamics/InvalidIndex.h index 6d7df702a74c2..e7105f471f080 100644 --- a/dart/dynamics/InvalidIndex.h +++ b/dart/dynamics/InvalidIndex.h @@ -42,7 +42,7 @@ namespace dart { namespace dynamics { -constexpr size_t INVALID_INDEX = static_cast(-1); +constexpr std::size_t INVALID_INDEX = static_cast(-1); } // namespace dynamics } // namespace dart diff --git a/dart/dynamics/InverseKinematics.cpp b/dart/dynamics/InverseKinematics.cpp index 3ca8f49dd2587..9850cc5d12008 100644 --- a/dart/dynamics/InverseKinematics.cpp +++ b/dart/dynamics/InverseKinematics.cpp @@ -85,11 +85,11 @@ bool InverseKinematics::solve(bool _applySolution) const SkeletonPtr& skel = getNode()->getSkeleton(); Eigen::VectorXd bounds(mDofs.size()); - for(size_t i=0; i < mDofs.size(); ++i) + for(std::size_t i=0; i < mDofs.size(); ++i) bounds[i] = skel->getDof(mDofs[i])->getPositionLowerLimit(); mProblem->setLowerBounds(bounds); - for(size_t i=0; i < mDofs.size(); ++i) + for(std::size_t i=0; i < mDofs.size(); ++i) bounds[i] = skel->getDof(mDofs[i])->getPositionUpperLimit(); mProblem->setUpperBounds(bounds); @@ -160,12 +160,12 @@ InverseKinematicsPtr InverseKinematics::clone(JacobianNode* _newNode) const newProblem->setObjective( cloneIkFunc(mProblem->getObjective(),newIK.get()) ); newProblem->removeAllEqConstraints(); - for(size_t i=0; i < mProblem->getNumEqConstraints(); ++i) + for(std::size_t i=0; i < mProblem->getNumEqConstraints(); ++i) newProblem->addEqConstraint( cloneIkFunc(mProblem->getEqConstraint(i), newIK.get()) ); newProblem->removeAllIneqConstraints(); - for(size_t i=0; i < mProblem->getNumIneqConstraints(); ++i) + for(std::size_t i=0; i < mProblem->getNumIneqConstraints(); ++i) newProblem->addIneqConstraint( cloneIkFunc(mProblem->getIneqConstraint(i), newIK.get())); @@ -445,7 +445,7 @@ Eigen::Isometry3d InverseKinematics::TaskSpaceRegion::computeDesiredTransform( Eigen::Isometry3d tf(Eigen::Isometry3d::Identity()); tf.rotate(_currentTf.linear()); - for(size_t i=0; i < 3; ++i) + for(std::size_t i=0; i < 3; ++i) { const double angle = _error[i]; Eigen::Vector3d axis(Eigen::Vector3d::Zero()); @@ -678,9 +678,9 @@ double InverseKinematics::GradientMethod::getComponentWiseClamp() const void InverseKinematics::GradientMethod::applyWeights( Eigen::VectorXd& _grad) const { - size_t numComponents = + std::size_t numComponents = std::min(_grad.size(), mGradientP.mComponentWeights.size()); - for(size_t i = 0; i < numComponents; ++i) + for(std::size_t i = 0; i < numComponents; ++i) _grad[i] = mGradientP.mComponentWeights[i] * _grad[i]; } @@ -857,10 +857,10 @@ void InverseKinematics::Analytical::UniqueProperties::resetQualityComparisonFunc const Eigen::VectorXd& worse, const InverseKinematics* ik) { - const std::vector& dofs = ik->getAnalytical()->getDofs(); + const std::vector& dofs = ik->getAnalytical()->getDofs(); double biggestJump = 0.0; bool isBetter = true; - for(size_t i=0; i < dofs.size(); ++i) + for(std::size_t i=0; i < dofs.size(); ++i) { double q = ik->getNode()->getSkeleton()->getPosition(dofs[i]); const double& testBetter = std::abs(q - better[i]); @@ -950,7 +950,7 @@ const std::vector& IK::Analytical::getSolutions( mLimitViolationCache.clear(); mLimitViolationCache.reserve(mSolutions.size()); - for(size_t i=0; i < mSolutions.size(); ++i) + for(std::size_t i=0; i < mSolutions.size(); ++i) { const Solution& s = mSolutions[i]; if(s.mValidity == VALID) @@ -994,16 +994,16 @@ const std::vector& IK::Analytical::getSolutions( static void applyExtraDofGradient(Eigen::VectorXd& grad, const Eigen::Vector6d& error, const InverseKinematics* ik, - const std::vector& extraDofs, + const std::vector& extraDofs, const Eigen::VectorXd& compWeights, double compClamp) { const math::Jacobian& J = ik->computeJacobian(); const std::vector& gradMap = ik->getDofMap(); - for(size_t i=0; i < extraDofs.size(); ++i) + for(std::size_t i=0; i < extraDofs.size(); ++i) { - size_t depIndex = extraDofs[i]; + std::size_t depIndex = extraDofs[i]; int gradIndex = gradMap[depIndex]; if(gradIndex == -1) continue; @@ -1044,12 +1044,12 @@ void InverseKinematics::Analytical::computeGradient( mGradientP.mComponentWiseClamp); const std::vector& gradMap = mIK->getDofMap(); - for(size_t i=0; i < mExtraDofs.size(); ++i) + for(std::size_t i=0; i < mExtraDofs.size(); ++i) { - const size_t depIndex = mExtraDofs[i]; + const std::size_t depIndex = mExtraDofs[i]; DegreeOfFreedom* dof = mIK->getNode()->getDependentDof(depIndex); - const size_t gradIndex = gradMap[depIndex]; + const std::size_t gradIndex = gradMap[depIndex]; dof->setPosition(dof->getPosition() - _grad[gradIndex]); } } @@ -1066,7 +1066,7 @@ void InverseKinematics::Analytical::computeGradient( const std::vector& analyticalToDependent = mDofMap; const std::vector& dependentToGradient = mIK->getDofMap(); - for(size_t i=0; i < analyticalToDependent.size(); ++i) + for(std::size_t i=0; i < analyticalToDependent.size(); ++i) { if(analyticalToDependent[i] == -1) continue; @@ -1162,8 +1162,8 @@ InverseKinematics::Analytical::getAnalyticalProperties() const //============================================================================== void InverseKinematics::Analytical::constructDofMap() { - const std::vector& analyticalDofs = getDofs(); - const std::vector& nodeDofs = + const std::vector& analyticalDofs = getDofs(); + const std::vector& nodeDofs = mIK->getNode()->getDependentGenCoordIndices(); mDofMap.clear(); @@ -1172,10 +1172,10 @@ void InverseKinematics::Analytical::constructDofMap() std::vector isExtraDof; isExtraDof.resize(nodeDofs.size(), true); - for(size_t i=0; i < analyticalDofs.size(); ++i) + for(std::size_t i=0; i < analyticalDofs.size(); ++i) { mDofMap[i] = -1; - for(size_t j=0; j < nodeDofs.size(); ++j) + for(std::size_t j=0; j < nodeDofs.size(); ++j) { if(analyticalDofs[i] == nodeDofs[j]) { @@ -1203,7 +1203,7 @@ void InverseKinematics::Analytical::constructDofMap() mExtraDofs.reserve(isExtraDof.size()); const std::vector& gradDofMap = mIK->getDofMap(); - for(size_t i=0; i < isExtraDof.size(); ++i) + for(std::size_t i=0; i < isExtraDof.size(); ++i) { if( isExtraDof[i] && (gradDofMap[i] > -1) ) mExtraDofs.push_back(i); @@ -1213,13 +1213,13 @@ void InverseKinematics::Analytical::constructDofMap() //============================================================================== void InverseKinematics::Analytical::checkSolutionJointLimits() { - const std::vector& dofs = getDofs(); - for(size_t i=0; i < mSolutions.size(); ++i) + const std::vector& dofs = getDofs(); + for(std::size_t i=0; i < mSolutions.size(); ++i) { Solution& s = mSolutions[i]; const Eigen::VectorXd& q = s.mConfig; - for(size_t j=0; j < dofs.size(); ++j) + for(std::size_t j=0; j < dofs.size(); ++j) { DegreeOfFreedom* dof = mIK->getNode()->getSkeleton()->getDof(dofs[j]); if(q[j] < dof->getPositionLowerLimit() @@ -1251,13 +1251,13 @@ bool InverseKinematics::isActive() const } //============================================================================== -void InverseKinematics::setHierarchyLevel(size_t _level) +void InverseKinematics::setHierarchyLevel(std::size_t _level) { mHierarchyLevel = _level; } //============================================================================== -size_t InverseKinematics::getHierarchyLevel() const +std::size_t InverseKinematics::getHierarchyLevel() const { return mHierarchyLevel; } @@ -1283,17 +1283,17 @@ void InverseKinematics::useWholeBody() } //============================================================================== -void InverseKinematics::setDofs(const std::vector& _dofs) +void InverseKinematics::setDofs(const std::vector& _dofs) { mDofs = _dofs; - const std::vector& entityDependencies = + const std::vector& entityDependencies = mNode->getDependentGenCoordIndices(); mDofMap.resize(entityDependencies.size()); - for(size_t i=0; i& _dofs) } //============================================================================== -const std::vector& InverseKinematics::getDofs() const +const std::vector& InverseKinematics::getDofs() const { return mDofs; } diff --git a/dart/dynamics/InverseKinematics.h b/dart/dynamics/InverseKinematics.h index c1ddeb24aaef9..6e2464b6689d7 100644 --- a/dart/dynamics/InverseKinematics.h +++ b/dart/dynamics/InverseKinematics.h @@ -119,7 +119,7 @@ class InverseKinematics : public common::Subject /// By default, the max_attempts is 1, but this can be changed by calling /// InverseKinematics::getSolver() and casting the SolverPtr to an /// optimizer::GradientDescentSolver (unless you have changed the Solver type) - /// and then calling GradientDescentSolver::setMaxAttempts(size_t). + /// and then calling GradientDescentSolver::setMaxAttempts(std::size_t). /// /// By default, the list of seeds is empty, but they can be added by calling /// InverseKinematics::getProblem() and then using @@ -762,7 +762,7 @@ class InverseKinematics : public common::Subject /// the DOFs being used by the InverseKinematics module, but this might not /// always be possible, so this function ensures that solutions can be /// interpreted correctly. - virtual const std::vector& getDofs() const = 0; + virtual const std::vector& getDofs() const = 0; /// Set the configuration of the DOFs. The components of _config must /// correspond to the DOFs provided by getDofs(). @@ -839,7 +839,7 @@ class InverseKinematics : public common::Subject /// List of extra DOFs in the module which are not covered by the Analytical /// IK implementation. The index of each DOF is its dependency index in the /// JacobianNode (i.e. the column it applies to in the Node's Jacobian). - std::vector mExtraDofs; + std::vector mExtraDofs; /// A cache for the valid solutions. The valid and invalid solution caches /// are kept separate so that they can each be sorted by quality @@ -878,10 +878,10 @@ class InverseKinematics : public common::Subject /// value will be projected through the null spaces of all modules with a /// smaller hierarchy value. In other words, IK modules with a hierarchy level /// closer to 0 are given higher priority. - void setHierarchyLevel(size_t _level); + void setHierarchyLevel(std::size_t _level); /// Get the hierarchy level of this modle. - size_t getHierarchyLevel() const; + std::size_t getHierarchyLevel() const; /// When solving the IK for this module's Node, use the longest available /// dynamics::Chain that goes from this module's Node towards the root of the @@ -900,10 +900,10 @@ class InverseKinematics : public common::Subject /// Explicitly set which degrees of freedom should be used to solve the IK for /// this module. The values in the vector should correspond to the Skeleton /// indices of each DOF. - void setDofs(const std::vector& _dofs); + void setDofs(const std::vector& _dofs); /// Get the indices of the DOFs that this IK module will use when solving. - const std::vector& getDofs() const; + const std::vector& getDofs() const; /// When a Jacobian is computed for a JacobianNode, it will include a column /// for every DegreeOfFreedom that the node depends on. Given the column index @@ -1181,11 +1181,11 @@ class InverseKinematics : public common::Subject bool mActive; /// Hierarchy level for this IK module - size_t mHierarchyLevel; + std::size_t mHierarchyLevel; /// A list of the DegreeOfFreedom Skeleton indices that will be used by this /// IK module - std::vector mDofs; + std::vector mDofs; /// Map for the DOFs that are to be used by this IK module std::vector mDofMap; diff --git a/dart/dynamics/JacobianNode.h b/dart/dynamics/JacobianNode.h index c96036c588471..a0c56eb5311d5 100644 --- a/dart/dynamics/JacobianNode.h +++ b/dart/dynamics/JacobianNode.h @@ -91,26 +91,26 @@ class JacobianNode : public virtual Frame, public Node //---------------------------------------------------------------------------- /// Return true if _genCoordIndex-th generalized coordinate - virtual bool dependsOn(size_t _genCoordIndex) const = 0; + virtual bool dependsOn(std::size_t _genCoordIndex) const = 0; /// The number of the generalized coordinates which affect this JacobianNode - virtual size_t getNumDependentGenCoords() const = 0; + virtual std::size_t getNumDependentGenCoords() const = 0; /// Return a generalized coordinate index from the array index /// (< getNumDependentDofs) - virtual size_t getDependentGenCoordIndex(size_t _arrayIndex) const = 0; + virtual std::size_t getDependentGenCoordIndex(std::size_t _arrayIndex) const = 0; /// Indices of the generalized coordinates which affect this JacobianNode - virtual const std::vector& getDependentGenCoordIndices() const = 0; + virtual const std::vector& getDependentGenCoordIndices() const = 0; /// Same as getNumDependentGenCoords() - virtual size_t getNumDependentDofs() const = 0; + virtual std::size_t getNumDependentDofs() const = 0; /// Get a pointer to the _indexth dependent DegreeOfFreedom for this BodyNode - virtual DegreeOfFreedom* getDependentDof(size_t _index) = 0; + virtual DegreeOfFreedom* getDependentDof(std::size_t _index) = 0; /// Get a pointer to the _indexth dependent DegreeOfFreedom for this BodyNode - virtual const DegreeOfFreedom* getDependentDof(size_t _index) const = 0; + virtual const DegreeOfFreedom* getDependentDof(std::size_t _index) const = 0; /// Return a std::vector of DegreeOfFreedom pointers that this Node depends on virtual const std::vector& getDependentDofs() = 0; diff --git a/dart/dynamics/Joint.cpp b/dart/dynamics/Joint.cpp index a10e2d46e09ba..b0c30f6264421 100644 --- a/dart/dynamics/Joint.cpp +++ b/dart/dynamics/Joint.cpp @@ -326,19 +326,19 @@ bool Joint::isPositionLimitEnforced() const } //============================================================================== -size_t Joint::getJointIndexInSkeleton() const +std::size_t Joint::getJointIndexInSkeleton() const { return mChildBodyNode->getIndexInSkeleton(); } //============================================================================== -size_t Joint::getJointIndexInTree() const +std::size_t Joint::getJointIndexInTree() const { return mChildBodyNode->getIndexInTree(); } //============================================================================== -size_t Joint::getTreeIndex() const +std::size_t Joint::getTreeIndex() const { return mChildBodyNode->getTreeIndex(); } @@ -347,7 +347,7 @@ size_t Joint::getTreeIndex() const bool Joint::checkSanity(bool _printWarnings) const { bool sane = true; - for(size_t i=0; i < getNumDofs(); ++i) + for(std::size_t i=0; i < getNumDofs(); ++i) { if(getInitialPosition(i) < getPositionLowerLimit(i) || getPositionUpperLimit(i) < getInitialPosition(i)) @@ -440,7 +440,7 @@ Joint::Joint() } //============================================================================== -DegreeOfFreedom* Joint::createDofPointer(size_t _indexInJoint) +DegreeOfFreedom* Joint::createDofPointer(std::size_t _indexInJoint) { return new DegreeOfFreedom(this, _indexInJoint); } @@ -500,7 +500,7 @@ void Joint::notifyPositionUpdate() SkeletonPtr skel = getSkeleton(); if(skel) { - size_t tree = mChildBodyNode->mTreeIndex; + std::size_t tree = mChildBodyNode->mTreeIndex; skel->notifyArticulatedInertiaUpdate(tree); skel->mTreeCache[tree].mDirty.mExternalForces = true; skel->mSkelCache.mDirty.mExternalForces = true; diff --git a/dart/dynamics/Joint.h b/dart/dynamics/Joint.h index 5eb9a59cd3a86..b3e92f51e7a6a 100644 --- a/dart/dynamics/Joint.h +++ b/dart/dynamics/Joint.h @@ -197,55 +197,55 @@ class Joint : public virtual common::Subject, bool isPositionLimitEnforced() const; /// Get a unique index in skeleton of a generalized coordinate in this Joint - virtual size_t getIndexInSkeleton(size_t _index) const = 0; + virtual std::size_t getIndexInSkeleton(std::size_t _index) const = 0; /// Get a unique index in the kinematic tree of a generalized coordinate in /// this Joint - virtual size_t getIndexInTree(size_t _index) const = 0; + virtual std::size_t getIndexInTree(std::size_t _index) const = 0; /// Get the index of this Joint within its Skeleton - size_t getJointIndexInSkeleton() const; + std::size_t getJointIndexInSkeleton() const; /// Get the index of this Joint within its tree - size_t getJointIndexInTree() const; + std::size_t getJointIndexInTree() const; /// Get the index of the tree that this Joint belongs to - size_t getTreeIndex() const; + std::size_t getTreeIndex() const; /// Get an object to access the _index-th degree of freedom (generalized /// coordinate) of this Joint - virtual DegreeOfFreedom* getDof(size_t _index) = 0; + virtual DegreeOfFreedom* getDof(std::size_t _index) = 0; /// Get an object to access the _index-th degree of freedom (generalized /// coordinate) of this Joint - virtual const DegreeOfFreedom* getDof(size_t _index) const = 0; + virtual const DegreeOfFreedom* getDof(std::size_t _index) const = 0; /// Alternative to DegreeOfFreedom::setName() - virtual const std::string& setDofName(size_t _index, + virtual const std::string& setDofName(std::size_t _index, const std::string& _name, bool _preserveName=true) = 0; /// Alternative to DegreeOfFreedom::preserveName() - virtual void preserveDofName(size_t _index, bool _preserve) = 0; + virtual void preserveDofName(std::size_t _index, bool _preserve) = 0; /// Alternative to DegreeOfFreedom::isNamePreserved() - virtual bool isDofNamePreserved(size_t _index) const = 0; + virtual bool isDofNamePreserved(std::size_t _index) const = 0; /// Alternative to DegreeOfFreedom::getName() - virtual const std::string& getDofName(size_t _index) const = 0; + virtual const std::string& getDofName(std::size_t _index) const = 0; /// Get number of generalized coordinates - virtual size_t getNumDofs() const = 0; + virtual std::size_t getNumDofs() const = 0; //---------------------------------------------------------------------------- /// \{ \name Command //---------------------------------------------------------------------------- /// Set a single command - virtual void setCommand(size_t _index, double _command) = 0; + virtual void setCommand(std::size_t _index, double _command) = 0; /// Get a single command - virtual double getCommand(size_t _index) const = 0; + virtual double getCommand(std::size_t _index) const = 0; /// Set all commands for this Joint virtual void setCommands(const Eigen::VectorXd& _commands) = 0; @@ -263,10 +263,10 @@ class Joint : public virtual common::Subject, //---------------------------------------------------------------------------- /// Set the position of a single generalized coordinate - virtual void setPosition(size_t _index, double _position) = 0; + virtual void setPosition(std::size_t _index, double _position) = 0; /// Get the position of a single generalized coordinate - virtual double getPosition(size_t _index) const = 0; + virtual double getPosition(std::size_t _index) const = 0; /// Set the positions of all generalized coordinates in this Joint virtual void setPositions(const Eigen::VectorXd& _positions) = 0; @@ -275,39 +275,39 @@ class Joint : public virtual common::Subject, virtual Eigen::VectorXd getPositions() const = 0; /// Set lower limit for position - virtual void setPositionLowerLimit(size_t _index, double _position) = 0; + virtual void setPositionLowerLimit(std::size_t _index, double _position) = 0; /// Get lower limit for position - virtual double getPositionLowerLimit(size_t _index) const = 0; + virtual double getPositionLowerLimit(std::size_t _index) const = 0; /// Set upper limit for position - virtual void setPositionUpperLimit(size_t _index, double _position) = 0; + virtual void setPositionUpperLimit(std::size_t _index, double _position) = 0; /// Get upper limit for position - virtual double getPositionUpperLimit(size_t _index) const = 0; + virtual double getPositionUpperLimit(std::size_t _index) const = 0; /// Get whether a generalized coordinate is cyclic. Return true if and only /// if this generalized coordinate has an infinite number of positions that /// produce the same local transform. Note that, for a multi-DOF joint, /// producing a cycle may require altering the position of this Joint's other /// generalized coordinates. - virtual bool isCyclic(size_t _index) const = 0; + virtual bool isCyclic(std::size_t _index) const = 0; /// Get whether the position of a generalized coordinate has limits. - virtual bool hasPositionLimit(size_t _index) const = 0; + virtual bool hasPositionLimit(std::size_t _index) const = 0; /// Set the position of this generalized coordinate to its initial position - virtual void resetPosition(size_t _index) = 0; + virtual void resetPosition(std::size_t _index) = 0; /// Set the positions of all generalized coordinates in this Joint to their /// initial positions virtual void resetPositions() = 0; /// Change the position that resetPositions() will give to this coordinate - virtual void setInitialPosition(size_t _index, double _initial) = 0; + virtual void setInitialPosition(std::size_t _index, double _initial) = 0; /// Get the position that resetPosition() will give to this coordinate - virtual double getInitialPosition(size_t _index) const = 0; + virtual double getInitialPosition(std::size_t _index) const = 0; /// Change the positions that resetPositions() will give to this Joint's /// coordinates @@ -324,10 +324,10 @@ class Joint : public virtual common::Subject, //---------------------------------------------------------------------------- /// Set the velocity of a single generalized coordinate - virtual void setVelocity(size_t _index, double _velocity) = 0; + virtual void setVelocity(std::size_t _index, double _velocity) = 0; /// Get the velocity of a single generalized coordinate - virtual double getVelocity(size_t _index) const = 0; + virtual double getVelocity(std::size_t _index) const = 0; /// Set the velocities of all generalized coordinates in this Joint virtual void setVelocities(const Eigen::VectorXd& _velocities) = 0; @@ -336,30 +336,30 @@ class Joint : public virtual common::Subject, virtual Eigen::VectorXd getVelocities() const = 0; /// Set lower limit for velocity - virtual void setVelocityLowerLimit(size_t _index, double _velocity) = 0; + virtual void setVelocityLowerLimit(std::size_t _index, double _velocity) = 0; /// Get lower limit for velocity - virtual double getVelocityLowerLimit(size_t _index) const = 0; + virtual double getVelocityLowerLimit(std::size_t _index) const = 0; /// Set upper limit for velocity - virtual void setVelocityUpperLimit(size_t _index, double _velocity) = 0; + virtual void setVelocityUpperLimit(std::size_t _index, double _velocity) = 0; /// Get upper limit for velocity - virtual double getVelocityUpperLimit(size_t _index) const = 0; + virtual double getVelocityUpperLimit(std::size_t _index) const = 0; /// Set the velocity of a generalized coordinate in this Joint to its initial /// velocity - virtual void resetVelocity(size_t _index) = 0; + virtual void resetVelocity(std::size_t _index) = 0; /// Set the velocities of all generalized coordinates in this Joint to their /// initial velocities virtual void resetVelocities() = 0; /// Change the velocity that resetVelocity() will give to this coordinate - virtual void setInitialVelocity(size_t _index, double _initial) = 0; + virtual void setInitialVelocity(std::size_t _index, double _initial) = 0; /// Get the velocity that resetVelocity() will give to this coordinate - virtual double getInitialVelocity(size_t _index) const = 0; + virtual double getInitialVelocity(std::size_t _index) const = 0; /// Change the velocities that resetVelocities() will give to this Joint's /// coordinates @@ -376,10 +376,10 @@ class Joint : public virtual common::Subject, //---------------------------------------------------------------------------- /// Set the acceleration of a single generalized coordinate - virtual void setAcceleration(size_t _index, double _acceleration) = 0; + virtual void setAcceleration(std::size_t _index, double _acceleration) = 0; /// Get the acceleration of a single generalized coordinate - virtual double getAcceleration(size_t _index) const = 0; + virtual double getAcceleration(std::size_t _index) const = 0; /// Set the accelerations of all generalized coordinates in this Joint virtual void setAccelerations(const Eigen::VectorXd& _accelerations) = 0; @@ -391,16 +391,16 @@ class Joint : public virtual common::Subject, virtual void resetAccelerations() = 0; /// Set lower limit for acceleration - virtual void setAccelerationLowerLimit(size_t _index, double _acceleration) = 0; + virtual void setAccelerationLowerLimit(std::size_t _index, double _acceleration) = 0; /// Get lower limit for acceleration - virtual double getAccelerationLowerLimit(size_t _index) const = 0; + virtual double getAccelerationLowerLimit(std::size_t _index) const = 0; /// Set upper limit for acceleration - virtual void setAccelerationUpperLimit(size_t _index, double _acceleration) = 0; + virtual void setAccelerationUpperLimit(std::size_t _index, double _acceleration) = 0; /// Get upper limit for acceleration - virtual double getAccelerationUpperLimit(size_t _index) const = 0; + virtual double getAccelerationUpperLimit(std::size_t _index) const = 0; /// \} @@ -409,10 +409,10 @@ class Joint : public virtual common::Subject, //---------------------------------------------------------------------------- /// Set the force of a single generalized coordinate - virtual void setForce(size_t _index, double _force) = 0; + virtual void setForce(std::size_t _index, double _force) = 0; /// Get the force of a single generalized coordinate - virtual double getForce(size_t _index) = 0; + virtual double getForce(std::size_t _index) = 0; /// Set the forces of all generalized coordinates in this Joint virtual void setForces(const Eigen::VectorXd& _forces) = 0; @@ -424,16 +424,16 @@ class Joint : public virtual common::Subject, virtual void resetForces() = 0; /// Set lower limit for force - virtual void setForceLowerLimit(size_t _index, double _force) = 0; + virtual void setForceLowerLimit(std::size_t _index, double _force) = 0; /// Get lower limit for force - virtual double getForceLowerLimit(size_t _index) const = 0; + virtual double getForceLowerLimit(std::size_t _index) const = 0; /// Set upper limit for force - virtual void setForceUpperLimit(size_t _index, double _force) = 0; + virtual void setForceUpperLimit(std::size_t _index, double _force) = 0; /// Get upper limit for force - virtual double getForceUpperLimit(size_t _index) const = 0; + virtual double getForceUpperLimit(std::size_t _index) const = 0; /// \} @@ -451,10 +451,10 @@ class Joint : public virtual common::Subject, //---------------------------------------------------------------------------- /// Set a single velocity change - virtual void setVelocityChange(size_t _index, double _velocityChange) = 0; + virtual void setVelocityChange(std::size_t _index, double _velocityChange) = 0; /// Get a single velocity change - virtual double getVelocityChange(size_t _index) const = 0; + virtual double getVelocityChange(std::size_t _index) const = 0; /// Set zero all the velocity change virtual void resetVelocityChanges() = 0; @@ -466,10 +466,10 @@ class Joint : public virtual common::Subject, //---------------------------------------------------------------------------- /// Set a single constraint impulse - virtual void setConstraintImpulse(size_t _index, double _impulse) = 0; + virtual void setConstraintImpulse(std::size_t _index, double _impulse) = 0; /// Get a single constraint impulse - virtual double getConstraintImpulse(size_t _index) const = 0; + virtual double getConstraintImpulse(std::size_t _index) const = 0; /// Set zero all the constraint impulses virtual void resetConstraintImpulses() = 0; @@ -500,39 +500,39 @@ class Joint : public virtual common::Subject, /// Set stiffness of joint spring force. /// \param[in] _index Index of joint axis. /// \param[in] _k Spring stiffness. - virtual void setSpringStiffness(size_t _index, double _k) = 0; + virtual void setSpringStiffness(std::size_t _index, double _k) = 0; /// Get stiffness of joint spring force. /// \param[in] _index Index of joint axis. - virtual double getSpringStiffness(size_t _index) const = 0; + virtual double getSpringStiffness(std::size_t _index) const = 0; /// Set rest position of spring force. /// \param[in] _index Index of joint axis. /// \param[in] _q0 Rest position. - virtual void setRestPosition(size_t _index, double _q0) = 0; + virtual void setRestPosition(std::size_t _index, double _q0) = 0; /// Get rest position of spring force. /// \param[in] _index Index of joint axis. /// \return Rest position. - virtual double getRestPosition(size_t _index) const = 0; + virtual double getRestPosition(std::size_t _index) const = 0; /// Set coefficient of joint damping (viscous friction) force. /// \param[in] _index Index of joint axis. /// \param[in] _coeff Damping coefficient. - virtual void setDampingCoefficient(size_t _index, double _coeff) = 0; + virtual void setDampingCoefficient(std::size_t _index, double _coeff) = 0; /// Get coefficient of joint damping (viscous friction) force. /// \param[in] _index Index of joint axis. - virtual double getDampingCoefficient(size_t _index) const = 0; + virtual double getDampingCoefficient(std::size_t _index) const = 0; /// Set joint Coulomb friction froce. /// \param[in] _index Index of joint axis. /// \param[in] _friction Joint Coulomb friction froce given index. - virtual void setCoulombFriction(size_t _index, double _friction) = 0; + virtual void setCoulombFriction(std::size_t _index, double _friction) = 0; /// Get joint Coulomb friction froce. /// \param[in] _index Index of joint axis. - virtual double getCoulombFriction(size_t _index) const = 0; + virtual double getCoulombFriction(std::size_t _index) const = 0; /// \} @@ -652,7 +652,7 @@ class Joint : public virtual common::Subject, /// DegreeOfFreedom should be created by the Joint because the DegreeOfFreedom /// class has a protected constructor, and the Joint is responsible for memory /// management of the pointer which is returned. - DegreeOfFreedom* createDofPointer(size_t _indexInJoint); + DegreeOfFreedom* createDofPointer(std::size_t _indexInJoint); /// Update the names of the joint's degrees of freedom. Used when setName() is /// called with _renameDofs set to true. @@ -815,13 +815,13 @@ class Joint : public virtual common::Subject, /// virtual void getInvMassMatrixSegment(Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) = 0; /// virtual void getInvAugMassMatrixSegment(Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) = 0; diff --git a/dart/dynamics/LineSegmentShape.cpp b/dart/dynamics/LineSegmentShape.cpp index 6588047a7bfd0..8823284a939f9 100644 --- a/dart/dynamics/LineSegmentShape.cpp +++ b/dart/dynamics/LineSegmentShape.cpp @@ -101,9 +101,9 @@ float LineSegmentShape::getThickness() const } //============================================================================== -size_t LineSegmentShape::addVertex(const Eigen::Vector3d& _v) +std::size_t LineSegmentShape::addVertex(const Eigen::Vector3d& _v) { - size_t parent = mVertices.size(); + std::size_t parent = mVertices.size(); if(parent > 0) return addVertex(_v, parent-1); @@ -112,20 +112,20 @@ size_t LineSegmentShape::addVertex(const Eigen::Vector3d& _v) } //============================================================================== -size_t LineSegmentShape::addVertex(const Eigen::Vector3d& _v, size_t _parent) +std::size_t LineSegmentShape::addVertex(const Eigen::Vector3d& _v, std::size_t _parent) { - size_t index = mVertices.size(); + std::size_t index = mVertices.size(); mVertices.push_back(_v); if(_parent > mVertices.size()) { if(mVertices.size() == 0) - dtwarn << "[LineSegmentShape::addVertex(const Eigen::Vector3d&, size_t)] " + dtwarn << "[LineSegmentShape::addVertex(const Eigen::Vector3d&, std::size_t)] " << "Attempting to add a vertex to be a child of vertex #" << _parent << ", but no vertices exist yet. No connection will be " << "created for the new vertex yet.\n"; else - dtwarn << "[LineSegmentShape::addVertex(const Eigen::Vector3d&, size_t)] " + dtwarn << "[LineSegmentShape::addVertex(const Eigen::Vector3d&, std::size_t)] " << "Attempting to add a vertex to be a child of vertex #" << _parent << ", but the vertex indices only go up to " << mVertices.size()-1 << ". No connection will be created for the " @@ -140,7 +140,7 @@ size_t LineSegmentShape::addVertex(const Eigen::Vector3d& _v, size_t _parent) } //============================================================================== -void LineSegmentShape::removeVertex(size_t _idx) +void LineSegmentShape::removeVertex(std::size_t _idx) { if(_idx >= mVertices.size()) { @@ -162,7 +162,7 @@ void LineSegmentShape::removeVertex(size_t _idx) } //============================================================================== -void LineSegmentShape::setVertex(size_t _idx, const Eigen::Vector3d& _v) +void LineSegmentShape::setVertex(std::size_t _idx, const Eigen::Vector3d& _v) { if(_idx >= mVertices.size()) { @@ -182,7 +182,7 @@ void LineSegmentShape::setVertex(size_t _idx, const Eigen::Vector3d& _v) } //============================================================================== -const Eigen::Vector3d& LineSegmentShape::getVertex(size_t _idx) const +const Eigen::Vector3d& LineSegmentShape::getVertex(std::size_t _idx) const { if(_idx < mVertices.size()) return mVertices[_idx]; @@ -205,7 +205,7 @@ const std::vector& LineSegmentShape::getVertices() const } //============================================================================== -void LineSegmentShape::addConnection(size_t _idx1, size_t _idx2) +void LineSegmentShape::addConnection(std::size_t _idx1, std::size_t _idx2) { if(_idx1 >= mVertices.size() || _idx2 >= mVertices.size()) { @@ -227,7 +227,7 @@ void LineSegmentShape::addConnection(size_t _idx1, size_t _idx2) } //============================================================================== -void LineSegmentShape::removeConnection(size_t _vertexIdx1, size_t _vertexIdx2) +void LineSegmentShape::removeConnection(std::size_t _vertexIdx1, std::size_t _vertexIdx2) { // Search through all connections to remove any that match the request Eigen::aligned_vector::iterator it = mConnections.begin(); @@ -247,17 +247,17 @@ void LineSegmentShape::removeConnection(size_t _vertexIdx1, size_t _vertexIdx2) } //============================================================================== -void LineSegmentShape::removeConnection(size_t _connectionIdx) +void LineSegmentShape::removeConnection(std::size_t _connectionIdx) { if(_connectionIdx >= mConnections.size()) { if(mConnections.size() == 0) - dtwarn << "[LineSegmentShape::removeConnection(size_t)] Attempting to " + dtwarn << "[LineSegmentShape::removeConnection(std::size_t)] Attempting to " << "remove connection #" << _connectionIdx << ", but " << "no connections exist yet. " << "No connection will be removed.\n"; else - dtwarn << "[LineSegmentShape::removeConnection(size_t)] Attempting to " + dtwarn << "[LineSegmentShape::removeConnection(std::size_t)] Attempting to " << "remove connection #" << _connectionIdx << ", but " << "connection indices only go up to #" << mConnections.size()-1 << ". " << "No connection will be removed.\n"; diff --git a/dart/dynamics/LineSegmentShape.h b/dart/dynamics/LineSegmentShape.h index f1729c0ed65ad..d9e079401d02f 100644 --- a/dart/dynamics/LineSegmentShape.h +++ b/dart/dynamics/LineSegmentShape.h @@ -63,39 +63,39 @@ class LineSegmentShape : public Shape float getThickness() const; /// Add a vertex as a child to the last vertex that was added - size_t addVertex(const Eigen::Vector3d& _v); + std::size_t addVertex(const Eigen::Vector3d& _v); /// Add a vertex as a child to the specified vertex - size_t addVertex(const Eigen::Vector3d& _v, size_t _parent); + std::size_t addVertex(const Eigen::Vector3d& _v, std::size_t _parent); /// Remove a vertex from the list of vertices. IMPORTANT: Note that this /// alters the indices of all vertices that follow it in the list, which also /// clobbers the validity of the list of connections for all those vertices. /// A safer and more efficient method might be to recycle vertices by moving /// them around with setVertex() and/or altering their connections. - void removeVertex(size_t _idx); + void removeVertex(std::size_t _idx); /// Change the location of the specified vertex - void setVertex(size_t _idx, const Eigen::Vector3d& _v); + void setVertex(std::size_t _idx, const Eigen::Vector3d& _v); /// Get the location of the specified vertex. Returns a zero vector if an /// out-of-bounds vertex is requested. - const Eigen::Vector3d& getVertex(size_t _idx) const; + const Eigen::Vector3d& getVertex(std::size_t _idx) const; /// Get all the vertices const std::vector& getVertices() const; /// Create a connection between the two specified vertices - void addConnection(size_t _idx1, size_t _idx2); + void addConnection(std::size_t _idx1, std::size_t _idx2); /// Search for a connection between two vertices and break it if it exists. - /// This is less efficient but more robust than removeConnection(size_t). - void removeConnection(size_t _vertexIdx1, size_t _vertexIdx2); + /// This is less efficient but more robust than removeConnection(std::size_t). + void removeConnection(std::size_t _vertexIdx1, std::size_t _vertexIdx2); /// Remove the specified connection entry. Note that this will impact the /// indices of all connections that come after _connectionIdx. This is more - /// efficient but less robust than removeConnection(size_t,size_t) - void removeConnection(size_t _connectionIdx); + /// efficient but less robust than removeConnection(std::size_t,std::size_t) + void removeConnection(std::size_t _connectionIdx); /// Get all the connections const Eigen::aligned_vector& getConnections() const; diff --git a/dart/dynamics/Linkage.cpp b/dart/dynamics/Linkage.cpp index c2ef589a46711..1062fb5ef2973 100644 --- a/dart/dynamics/Linkage.cpp +++ b/dart/dynamics/Linkage.cpp @@ -58,7 +58,7 @@ std::vector Linkage::Criteria::satisfy() const // If a start node is not given, then we must treat the root node of each // target as if it is a start node. - for(size_t i=0; i Linkage::Criteria::satisfy() const Target start = mStart; start.mPolicy = INCLUDE; - size_t treeIndex = target_bn->getTreeIndex(); + std::size_t treeIndex = target_bn->getTreeIndex(); start.mNode = target_bn->getSkeleton()->getRootBodyNode(treeIndex); expandToTarget(start, target, bns); @@ -83,7 +83,7 @@ std::vector Linkage::Criteria::satisfy() const bns.push_back(mStart.mNode.lock()); expansionPolicy(mStart.mNode.lock(), mStart.mPolicy, bns); - for(size_t i=0; igetParentBodyNode() != mParentBodyNodes[i].lock()) @@ -505,7 +505,7 @@ bool Linkage::isAssembled() const //============================================================================== void Linkage::reassemble() { - for(size_t i=0; imoveTo(mParentBodyNodes[i].lock()); @@ -540,7 +540,7 @@ void Linkage::update() { mParentBodyNodes.clear(); mParentBodyNodes.reserve(mBodyNodes.size()); - for(size_t i=0; igetParentBodyNode()); } diff --git a/dart/dynamics/MeshShape.cpp b/dart/dynamics/MeshShape.cpp index 14d8ac7ab970d..38bd517b9f986 100644 --- a/dart/dynamics/MeshShape.cpp +++ b/dart/dynamics/MeshShape.cpp @@ -76,32 +76,32 @@ aiScene::~aiScene() delete mRootNode; if(mNumMeshes && mMeshes) - for(size_t a=0; amNumMeshes; ++i) + for(std::size_t i=0; imNumMeshes; ++i) { aiMesh* mesh = mMesh->mMeshes[i]; - for(size_t j=0; jmNumVertices; ++j) + for(std::size_t j=0; jmNumVertices; ++j) mesh->mColors[0][j][3] = alpha; } } @@ -356,7 +356,7 @@ const aiScene* MeshShape::loadMesh( // might miss files with an .xml file ending, which would need to be looked // into to figure out whether they are collada files. std::string extension; - const size_t extensionIndex = _uri.find_last_of('.'); + const std::size_t extensionIndex = _uri.find_last_of('.'); if(extensionIndex != std::string::npos) extension = _uri.substr(extensionIndex); diff --git a/dart/dynamics/MetaSkeleton.cpp b/dart/dynamics/MetaSkeleton.cpp index 827a2bcbdf49f..144a5cdf0a273 100644 --- a/dart/dynamics/MetaSkeleton.cpp +++ b/dart/dynamics/MetaSkeleton.cpp @@ -43,11 +43,11 @@ namespace dynamics { //============================================================================== static bool checkIndexArrayValidity(const MetaSkeleton* skel, - const std::vector& _indices, + const std::vector& _indices, const std::string& _fname) { - size_t dofs = skel->getNumDofs(); - for(size_t i=0; i<_indices.size(); ++i) + std::size_t dofs = skel->getNumDofs(); + for(std::size_t i=0; i<_indices.size(); ++i) { if(_indices[i] >= dofs) { @@ -73,7 +73,7 @@ static bool checkIndexArrayValidity(const MetaSkeleton* skel, //============================================================================== static bool checkIndexArrayAgreement(const MetaSkeleton* skel, - const std::vector& _indices, + const std::vector& _indices, const Eigen::VectorXd& _values, const std::string& _fname, const std::string& _vname) @@ -94,7 +94,7 @@ static bool checkIndexArrayAgreement(const MetaSkeleton* skel, //============================================================================== template static void setValuesFromVector(MetaSkeleton* skel, - const std::vector& _indices, + const std::vector& _indices, const Eigen::VectorXd& _values, const std::string& _fname, const std::string& _vname) @@ -102,7 +102,7 @@ static void setValuesFromVector(MetaSkeleton* skel, if(!checkIndexArrayAgreement(skel, _indices, _values, _fname, _vname)) return; - for (size_t i=0; i<_indices.size(); ++i) + for (std::size_t i=0; i<_indices.size(); ++i) { DegreeOfFreedom* dof = skel->getDof(_indices[i]); if(dof) @@ -128,7 +128,7 @@ static void setAllValuesFromVector(MetaSkeleton* skel, const std::string& _fname, const std::string& _vname) { - size_t nDofs = skel->getNumDofs(); + std::size_t nDofs = skel->getNumDofs(); if( _values.size() != static_cast(skel->getNumDofs()) ) { dterr << "[MetaSkeleton::" << _fname << "] Invalid number of entries (" @@ -139,7 +139,7 @@ static void setAllValuesFromVector(MetaSkeleton* skel, return; } - for(size_t i=0; i < nDofs; ++i) + for(std::size_t i=0; i < nDofs; ++i) { DegreeOfFreedom* dof = skel->getDof(i); if(dof) @@ -162,12 +162,12 @@ static void setAllValuesFromVector(MetaSkeleton* skel, //============================================================================== template static Eigen::VectorXd getValuesFromVector( - const MetaSkeleton* skel, const std::vector& _indices, + const MetaSkeleton* skel, const std::vector& _indices, const std::string& _fname) { Eigen::VectorXd values(_indices.size()); - for(size_t i=0; i<_indices.size(); ++i) + for(std::size_t i=0; i<_indices.size(); ++i) { const DegreeOfFreedom* dof = skel->getDof(_indices[i]); if(dof) @@ -206,10 +206,10 @@ template static Eigen::VectorXd getValuesFromAllDofs( const MetaSkeleton* skel, const std::string& _fname) { - size_t nDofs = skel->getNumDofs(); + std::size_t nDofs = skel->getNumDofs(); Eigen::VectorXd values(nDofs); - for(size_t i=0; igetDof(i); if(dof) @@ -234,8 +234,8 @@ static Eigen::VectorXd getValuesFromAllDofs( template static void applyToAllDofs(MetaSkeleton* skel) { - size_t nDofs = skel->getNumDofs(); - for(size_t i=0; igetNumDofs(); + for(std::size_t i=0; igetDof(i); if(dof) @@ -245,7 +245,7 @@ static void applyToAllDofs(MetaSkeleton* skel) //============================================================================== template -static void setValueFromIndex(MetaSkeleton* skel, size_t _index, double _value, +static void setValueFromIndex(MetaSkeleton* skel, std::size_t _index, double _value, const std::string& _fname) { if(_index >= skel->getNumDofs()) @@ -281,7 +281,7 @@ static void setValueFromIndex(MetaSkeleton* skel, size_t _index, double _value, //============================================================================== template -static double getValueFromIndex(const MetaSkeleton* skel, size_t _index, +static double getValueFromIndex(const MetaSkeleton* skel, std::size_t _index, const std::string& _fname) { if(_index >= skel->getNumDofs()) @@ -316,14 +316,14 @@ static double getValueFromIndex(const MetaSkeleton* skel, size_t _index, } //============================================================================== -void MetaSkeleton::setCommand(size_t _index, double _command) +void MetaSkeleton::setCommand(std::size_t _index, double _command) { setValueFromIndex<&DegreeOfFreedom::setCommand>( this, _index, _command, "setCommand"); } //============================================================================== -double MetaSkeleton::getCommand(size_t _index) const +double MetaSkeleton::getCommand(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getCommand>( this, _index, "getCommand"); @@ -337,7 +337,7 @@ void MetaSkeleton::setCommands(const Eigen::VectorXd& _commands) } //============================================================================== -void MetaSkeleton::setCommands(const std::vector& _indices, +void MetaSkeleton::setCommands(const std::vector& _indices, const Eigen::VectorXd& _commands) { setValuesFromVector<&DegreeOfFreedom::setCommand>( @@ -352,7 +352,7 @@ Eigen::VectorXd MetaSkeleton::getCommands() const } //============================================================================== -Eigen::VectorXd MetaSkeleton::getCommands(const std::vector& _indices) const +Eigen::VectorXd MetaSkeleton::getCommands(const std::vector& _indices) const { return getValuesFromVector<&DegreeOfFreedom::getCommand>( this, _indices, "getCommands"); @@ -365,14 +365,14 @@ void MetaSkeleton::resetCommands() } //============================================================================== -void MetaSkeleton::setPosition(size_t _index, double _position) +void MetaSkeleton::setPosition(std::size_t _index, double _position) { setValueFromIndex<&DegreeOfFreedom::setPosition>( this, _index, _position, "setPosition"); } //============================================================================== -double MetaSkeleton::getPosition(size_t _index) const +double MetaSkeleton::getPosition(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getPosition>( this, _index, "getPosition"); @@ -386,7 +386,7 @@ void MetaSkeleton::setPositions(const Eigen::VectorXd& _positions) } //============================================================================== -void MetaSkeleton::setPositions(const std::vector& _indices, +void MetaSkeleton::setPositions(const std::vector& _indices, const Eigen::VectorXd& _positions) { setValuesFromVector<&DegreeOfFreedom::setPosition>( @@ -401,7 +401,7 @@ Eigen::VectorXd MetaSkeleton::getPositions() const } //============================================================================== -Eigen::VectorXd MetaSkeleton::getPositions(const std::vector& _indices) const +Eigen::VectorXd MetaSkeleton::getPositions(const std::vector& _indices) const { return getValuesFromVector<&DegreeOfFreedom::getPosition>( this, _indices, "getPositions"); @@ -414,42 +414,42 @@ void MetaSkeleton::resetPositions() } //============================================================================== -void MetaSkeleton::setPositionLowerLimit(size_t _index, double _position) +void MetaSkeleton::setPositionLowerLimit(std::size_t _index, double _position) { setValueFromIndex<&DegreeOfFreedom::setPositionLowerLimit>( this, _index, _position, "setPositionLowerLimit"); } //============================================================================== -double MetaSkeleton::getPositionLowerLimit(size_t _index) const +double MetaSkeleton::getPositionLowerLimit(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getPositionLowerLimit>( this, _index, "getPositionLowerLimit"); } //============================================================================== -void MetaSkeleton::setPositionUpperLimit(size_t _index, double _position) +void MetaSkeleton::setPositionUpperLimit(std::size_t _index, double _position) { setValueFromIndex<&DegreeOfFreedom::setPositionUpperLimit>( this, _index, _position, "setPositionUpperLimit"); } //============================================================================== -double MetaSkeleton::getPositionUpperLimit(size_t _index) const +double MetaSkeleton::getPositionUpperLimit(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getPositionUpperLimit>( this, _index, "getPositionUpperLimit"); } //============================================================================== -void MetaSkeleton::setVelocity(size_t _index, double _velocity) +void MetaSkeleton::setVelocity(std::size_t _index, double _velocity) { setValueFromIndex<&DegreeOfFreedom::setVelocity>( this, _index, _velocity, "setVelocity"); } //============================================================================== -double MetaSkeleton::getVelocity(size_t _index) const +double MetaSkeleton::getVelocity(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getVelocity>( this, _index, "getVelocity"); @@ -463,7 +463,7 @@ void MetaSkeleton::setVelocities(const Eigen::VectorXd& _velocities) } //============================================================================== -void MetaSkeleton::setVelocities(const std::vector& _indices, +void MetaSkeleton::setVelocities(const std::vector& _indices, const Eigen::VectorXd& _velocities) { setValuesFromVector<&DegreeOfFreedom::setVelocity>( @@ -478,7 +478,7 @@ Eigen::VectorXd MetaSkeleton::getVelocities() const } //============================================================================== -Eigen::VectorXd MetaSkeleton::getVelocities(const std::vector& _indices) const +Eigen::VectorXd MetaSkeleton::getVelocities(const std::vector& _indices) const { return getValuesFromVector<&DegreeOfFreedom::getVelocity>( this, _indices, "getVelocities"); @@ -491,42 +491,42 @@ void MetaSkeleton::resetVelocities() } //============================================================================== -void MetaSkeleton::setVelocityLowerLimit(size_t _index, double _velocity) +void MetaSkeleton::setVelocityLowerLimit(std::size_t _index, double _velocity) { setValueFromIndex<&DegreeOfFreedom::setVelocityLowerLimit>( this, _index, _velocity, "setVelocityLowerLimit"); } //============================================================================== -double MetaSkeleton::getVelocityLowerLimit(size_t _index) +double MetaSkeleton::getVelocityLowerLimit(std::size_t _index) { return getValueFromIndex<&DegreeOfFreedom::getVelocityLowerLimit>( this, _index, "getVelocityLowerLimit"); } //============================================================================== -void MetaSkeleton::setVelocityUpperLimit(size_t _index, double _velocity) +void MetaSkeleton::setVelocityUpperLimit(std::size_t _index, double _velocity) { setValueFromIndex<&DegreeOfFreedom::setVelocityUpperLimit>( this, _index, _velocity, "setVelocityUpperLimit"); } //============================================================================== -double MetaSkeleton::getVelocityUpperLimit(size_t _index) +double MetaSkeleton::getVelocityUpperLimit(std::size_t _index) { return getValueFromIndex<&DegreeOfFreedom::getVelocityUpperLimit>( this, _index, "getVelocityUpperLimit"); } //============================================================================== -void MetaSkeleton::setAcceleration(size_t _index, double _acceleration) +void MetaSkeleton::setAcceleration(std::size_t _index, double _acceleration) { setValueFromIndex<&DegreeOfFreedom::setAcceleration>( this, _index, _acceleration, "setAcceleration"); } //============================================================================== -double MetaSkeleton::getAcceleration(size_t _index) const +double MetaSkeleton::getAcceleration(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getAcceleration>( this, _index, "getAcceleration"); @@ -540,7 +540,7 @@ void MetaSkeleton::setAccelerations(const Eigen::VectorXd& _accelerations) } //============================================================================== -void MetaSkeleton::setAccelerations(const std::vector& _indices, +void MetaSkeleton::setAccelerations(const std::vector& _indices, const Eigen::VectorXd& _accelerations) { setValuesFromVector<&DegreeOfFreedom::setAcceleration>( @@ -556,7 +556,7 @@ Eigen::VectorXd MetaSkeleton::getAccelerations() const //============================================================================== Eigen::VectorXd MetaSkeleton::getAccelerations( - const std::vector& _indices) const + const std::vector& _indices) const { return getValuesFromVector<&DegreeOfFreedom::getAcceleration>( this, _indices, "getAccelerations"); @@ -569,42 +569,42 @@ void MetaSkeleton::resetAccelerations() } //============================================================================== -void MetaSkeleton::setAccelerationLowerLimit(size_t _index, double _acceleration) +void MetaSkeleton::setAccelerationLowerLimit(std::size_t _index, double _acceleration) { setValueFromIndex<&DegreeOfFreedom::setAccelerationLowerLimit>( this, _index, _acceleration, "setAccelerationLowerLimit"); } //============================================================================== -double MetaSkeleton::getAccelerationLowerLimit(size_t _index) const +double MetaSkeleton::getAccelerationLowerLimit(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getAccelerationLowerLimit>( this, _index, "getAccelerationLowerLimit"); } //============================================================================== -void MetaSkeleton::setAccelerationUpperLimit(size_t _index, double _acceleration) +void MetaSkeleton::setAccelerationUpperLimit(std::size_t _index, double _acceleration) { setValueFromIndex<&DegreeOfFreedom::setAccelerationUpperLimit>( this, _index, _acceleration, "setAccelerationUpperLimit"); } //============================================================================== -double MetaSkeleton::getAccelerationUpperLimit(size_t _index) const +double MetaSkeleton::getAccelerationUpperLimit(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getAccelerationUpperLimit>( this, _index, "getAccelerationUpperLimit"); } //============================================================================== -void MetaSkeleton::setForce(size_t _index, double _force) +void MetaSkeleton::setForce(std::size_t _index, double _force) { setValueFromIndex<&DegreeOfFreedom::setForce>( this, _index, _force, "setForce"); } //============================================================================== -double MetaSkeleton::getForce(size_t _index) const +double MetaSkeleton::getForce(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getForce>( this, _index, "getForce"); @@ -618,7 +618,7 @@ void MetaSkeleton::setForces(const Eigen::VectorXd& _forces) } //============================================================================== -void MetaSkeleton::setForces(const std::vector& _indices, +void MetaSkeleton::setForces(const std::vector& _indices, const Eigen::VectorXd& _forces) { setValuesFromVector<&DegreeOfFreedom::setForce>( @@ -633,7 +633,7 @@ Eigen::VectorXd MetaSkeleton::getForces() const } //============================================================================== -Eigen::VectorXd MetaSkeleton::getForces(const std::vector& _indices) const +Eigen::VectorXd MetaSkeleton::getForces(const std::vector& _indices) const { return getValuesFromVector<&DegreeOfFreedom::getForce>( this, _indices, "getForces"); @@ -648,28 +648,28 @@ void MetaSkeleton::resetGeneralizedForces() } //============================================================================== -void MetaSkeleton::setForceLowerLimit(size_t _index, double _force) +void MetaSkeleton::setForceLowerLimit(std::size_t _index, double _force) { setValueFromIndex<&DegreeOfFreedom::setForceLowerLimit>( this, _index, _force, "setForceLowerLimit"); } //============================================================================== -double MetaSkeleton::getForceLowerLimit(size_t _index) const +double MetaSkeleton::getForceLowerLimit(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getForceLowerLimit>( this, _index, "getForceLowerLimit"); } //============================================================================== -void MetaSkeleton::setForceUpperLimit(size_t _index, double _force) +void MetaSkeleton::setForceUpperLimit(std::size_t _index, double _force) { setValueFromIndex<&DegreeOfFreedom::setForceUpperLimit>( this, _index, _force, "setForceUpperLimit"); } //============================================================================== -double MetaSkeleton::getForceUpperLimit(size_t _index) const +double MetaSkeleton::getForceUpperLimit(std::size_t _index) const { return getValueFromIndex<&DegreeOfFreedom::getForceUpperLimit>( this, _index, "getForceUpperLimit"); diff --git a/dart/dynamics/MetaSkeleton.h b/dart/dynamics/MetaSkeleton.h index 528ef9a08af0e..9cdf939952563 100644 --- a/dart/dynamics/MetaSkeleton.h +++ b/dart/dynamics/MetaSkeleton.h @@ -92,13 +92,13 @@ class MetaSkeleton : public common::Subject //---------------------------------------------------------------------------- /// Get number of body nodes - virtual size_t getNumBodyNodes() const = 0; + virtual std::size_t getNumBodyNodes() const = 0; /// Get BodyNode whose index is _idx - virtual BodyNode* getBodyNode(size_t _idx) = 0; + virtual BodyNode* getBodyNode(std::size_t _idx) = 0; /// Get const BodyNode whose index is _idx - virtual const BodyNode* getBodyNode(size_t _idx) const = 0; + virtual const BodyNode* getBodyNode(std::size_t _idx) const = 0; /// Get all the BodyNodes that are held by this MetaSkeleton virtual const std::vector& getBodyNodes() = 0; @@ -110,31 +110,31 @@ class MetaSkeleton : public common::Subject /// Returns INVALID_INDEX if it is not held in this ReferentialSkeleton. /// When _warning is true, a warning message will be printed if the BodyNode /// is not in the MetaSkeleton. - virtual size_t getIndexOf(const BodyNode* _bn, bool _warning=true) const = 0; + virtual std::size_t getIndexOf(const BodyNode* _bn, bool _warning=true) const = 0; /// Get number of Joints - virtual size_t getNumJoints() const = 0; + virtual std::size_t getNumJoints() const = 0; /// Get Joint whose index is _idx - virtual Joint* getJoint(size_t _idx) = 0; + virtual Joint* getJoint(std::size_t _idx) = 0; /// Get const Joint whose index is _idx - virtual const Joint* getJoint(size_t _idx) const = 0; + virtual const Joint* getJoint(std::size_t _idx) const = 0; /// Get the index of a specific Joint within this ReferentialSkeleton. Returns /// INVALID_INDEX if it is not held in this ReferentialSkeleton. /// When _warning is true, a warning message will be printed if the Joint is /// not in the MetaSkeleton. - virtual size_t getIndexOf(const Joint* _joint, bool _warning=true) const = 0; + virtual std::size_t getIndexOf(const Joint* _joint, bool _warning=true) const = 0; /// Return the number of degrees of freedom in this skeleton - virtual size_t getNumDofs() const = 0; + virtual std::size_t getNumDofs() const = 0; /// Get degree of freedom (aka generalized coordinate) whose index is _idx - virtual DegreeOfFreedom* getDof(size_t _idx) = 0; + virtual DegreeOfFreedom* getDof(std::size_t _idx) = 0; /// Get degree of freedom (aka generalized coordinate) whose index is _idx - virtual const DegreeOfFreedom* getDof(size_t _idx) const = 0; + virtual const DegreeOfFreedom* getDof(std::size_t _idx) const = 0; /// Get the vector of DegreesOfFreedom for this MetaSkeleton virtual const std::vector& getDofs() = 0; @@ -146,7 +146,7 @@ class MetaSkeleton : public common::Subject /// ReferentialSkeleton. Returns INVALID_INDEX if it is not held in this /// ReferentialSkeleton. When _warning is true, a warning message will be /// printed if the DegreeOfFreedom is not in the MetaSkeleton. - virtual size_t getIndexOf(const DegreeOfFreedom* _dof, + virtual std::size_t getIndexOf(const DegreeOfFreedom* _dof, bool _warning=true) const = 0; /// \} @@ -156,23 +156,23 @@ class MetaSkeleton : public common::Subject //---------------------------------------------------------------------------- /// Set a single command - void setCommand(size_t _index, double _command); + void setCommand(std::size_t _index, double _command); /// Get a single command - double getCommand(size_t _index) const; + double getCommand(std::size_t _index) const; /// Set commands for all generalized coordinates void setCommands(const Eigen::VectorXd& _commands); /// Set commands for a subset of the generalized coordinates - void setCommands(const std::vector& _indices, + void setCommands(const std::vector& _indices, const Eigen::VectorXd& _commands); /// Get commands for all generalized coordinates Eigen::VectorXd getCommands() const; /// Get commands for a subset of the generalized coordinates - Eigen::VectorXd getCommands(const std::vector& _indices) const; + Eigen::VectorXd getCommands(const std::vector& _indices) const; /// Set all commands to zero void resetCommands(); @@ -184,38 +184,38 @@ class MetaSkeleton : public common::Subject //---------------------------------------------------------------------------- /// Set the position of a single generalized coordinate - void setPosition(size_t index, double _position); + void setPosition(std::size_t index, double _position); /// Get the position of a single generalized coordinate - double getPosition(size_t _index) const; + double getPosition(std::size_t _index) const; /// Set the positions for all generalized coordinates void setPositions(const Eigen::VectorXd& _positions); /// Set the positions for a subset of the generalized coordinates - void setPositions(const std::vector& _indices, + void setPositions(const std::vector& _indices, const Eigen::VectorXd& _positions); /// Get the positions for all generalized coordinates Eigen::VectorXd getPositions() const; /// Get the positions for a subset of the generalized coordinates - Eigen::VectorXd getPositions(const std::vector& _indices) const; + Eigen::VectorXd getPositions(const std::vector& _indices) const; /// Set all positions to zero void resetPositions(); /// Set the lower limit of a generalized coordinate's position - void setPositionLowerLimit(size_t _index, double _position); + void setPositionLowerLimit(std::size_t _index, double _position); /// Get the lower limit of a generalized coordinate's position - double getPositionLowerLimit(size_t _index) const; + double getPositionLowerLimit(std::size_t _index) const; /// Set the upper limit of a generalized coordainte's position - void setPositionUpperLimit(size_t _index, double _position); + void setPositionUpperLimit(std::size_t _index, double _position); /// Get the upper limit of a generalized coordinate's position - double getPositionUpperLimit(size_t _index) const; + double getPositionUpperLimit(std::size_t _index) const; /// \} @@ -224,38 +224,38 @@ class MetaSkeleton : public common::Subject //---------------------------------------------------------------------------- /// Set the velocity of a single generalized coordinate - void setVelocity(size_t _index, double _velocity); + void setVelocity(std::size_t _index, double _velocity); /// Get the velocity of a single generalized coordinate - double getVelocity(size_t _index) const; + double getVelocity(std::size_t _index) const; /// Set the velocities of all generalized coordinates void setVelocities(const Eigen::VectorXd& _velocities); /// Set the velocities of a subset of the generalized coordinates - void setVelocities(const std::vector& _indices, + void setVelocities(const std::vector& _indices, const Eigen::VectorXd& _velocities); /// Get the velocities for all generalized coordinates Eigen::VectorXd getVelocities() const; /// Get the velocities for a subset of the generalized coordinates - Eigen::VectorXd getVelocities(const std::vector& _indices) const; + Eigen::VectorXd getVelocities(const std::vector& _indices) const; /// Set all velocities to zero void resetVelocities(); /// Set the lower limit of a generalized coordinate's velocity - void setVelocityLowerLimit(size_t _index, double _velocity); + void setVelocityLowerLimit(std::size_t _index, double _velocity); /// Get the lower limit of a generalized coordinate's velocity - double getVelocityLowerLimit(size_t _index); + double getVelocityLowerLimit(std::size_t _index); /// Set the upper limit of a generalized coordinate's velocity - void setVelocityUpperLimit(size_t _index, double _velocity); + void setVelocityUpperLimit(std::size_t _index, double _velocity); /// Get the upper limit of a generalized coordinate's velocity - double getVelocityUpperLimit(size_t _index); + double getVelocityUpperLimit(std::size_t _index); /// \} @@ -264,38 +264,38 @@ class MetaSkeleton : public common::Subject //---------------------------------------------------------------------------- /// Set the acceleration of a single generalized coordinate - void setAcceleration(size_t _index, double _acceleration); + void setAcceleration(std::size_t _index, double _acceleration); /// Get the acceleration of a single generalized coordinate - double getAcceleration(size_t _index) const; + double getAcceleration(std::size_t _index) const; /// Set the accelerations of all generalized coordinates void setAccelerations(const Eigen::VectorXd& _accelerations); /// Set the accelerations of a subset of the generalized coordinates - void setAccelerations(const std::vector& _indices, + void setAccelerations(const std::vector& _indices, const Eigen::VectorXd& _accelerations); /// Get the accelerations for all generalized coordinates Eigen::VectorXd getAccelerations() const; /// Get the accelerations for a subset of the generalized coordinates - Eigen::VectorXd getAccelerations(const std::vector& _indices) const; + Eigen::VectorXd getAccelerations(const std::vector& _indices) const; /// Set all accelerations to zero void resetAccelerations(); /// Set the lower limit of a generalized coordinate's acceleration - void setAccelerationLowerLimit(size_t _index, double _acceleration); + void setAccelerationLowerLimit(std::size_t _index, double _acceleration); /// Get the lower limit of a generalized coordinate's acceleration - double getAccelerationLowerLimit(size_t _index) const; + double getAccelerationLowerLimit(std::size_t _index) const; /// Set the upper limit of a generalized coordinate's acceleration - void setAccelerationUpperLimit(size_t _index, double _acceleration); + void setAccelerationUpperLimit(std::size_t _index, double _acceleration); /// Get the upper limit of a generalized coordinate's acceleration - double getAccelerationUpperLimit(size_t _index) const; + double getAccelerationUpperLimit(std::size_t _index) const; /// \} @@ -304,38 +304,38 @@ class MetaSkeleton : public common::Subject //---------------------------------------------------------------------------- /// Set the force of a single generalized coordinate - void setForce(size_t _index, double _force); + void setForce(std::size_t _index, double _force); /// Get the force of a single generalized coordinate - double getForce(size_t _index) const; + double getForce(std::size_t _index) const; /// Set the forces of all generalized coordinates void setForces(const Eigen::VectorXd& _forces); /// Set the forces of a subset of the generalized coordinates - void setForces(const std::vector& _index, + void setForces(const std::vector& _index, const Eigen::VectorXd& _forces); /// Get the forces for all generalized coordinates Eigen::VectorXd getForces() const; /// Get the forces for a subset of the generalized coordinates - Eigen::VectorXd getForces(const std::vector& _indices) const; + Eigen::VectorXd getForces(const std::vector& _indices) const; /// Set all forces of the generalized coordinates to zero void resetGeneralizedForces(); /// Set the lower limit of a generalized coordinate's force - void setForceLowerLimit(size_t _index, double _force); + void setForceLowerLimit(std::size_t _index, double _force); /// Get the lower limit of a generalized coordinate's force - double getForceLowerLimit(size_t _index) const; + double getForceLowerLimit(std::size_t _index) const; /// Set the upper limit of a generalized coordinate's force - void setForceUpperLimit(size_t _index, double _force); + void setForceUpperLimit(std::size_t _index, double _force); /// Get the upper limit of a generalized coordinate's force - double getForceUpperLimit(size_t _index) const; + double getForceUpperLimit(std::size_t _index) const; /// \} diff --git a/dart/dynamics/MultiDofJoint.h b/dart/dynamics/MultiDofJoint.h index c51cfefc93fd1..2b8157e891449 100644 --- a/dart/dynamics/MultiDofJoint.h +++ b/dart/dynamics/MultiDofJoint.h @@ -57,12 +57,12 @@ class BodyNode; class Skeleton; /// class MultiDofJoint -template +template class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF > { public: - constexpr static size_t NumDofs = DOF; + constexpr static std::size_t NumDofs = DOF; using Vector = Eigen::Matrix; using Base = detail::MultiDofJointBase, DOF>; using UniqueProperties = detail::MultiDofJointUniqueProperties; @@ -106,43 +106,43 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF //---------------------------------------------------------------------------- // Documentation inherited - DegreeOfFreedom* getDof(size_t index) override; + DegreeOfFreedom* getDof(std::size_t index) override; // Documentation inherited - const DegreeOfFreedom* getDof(size_t _index) const override; + const DegreeOfFreedom* getDof(std::size_t _index) const override; // Documentation inherited - size_t getNumDofs() const override; + std::size_t getNumDofs() const override; // Documentation inherited - const std::string& setDofName(size_t _index, + const std::string& setDofName(std::size_t _index, const std::string& _name, bool _preserveName=true) override; // Docuemntation inherited - void preserveDofName(size_t _index, bool _preserve) override; + void preserveDofName(std::size_t _index, bool _preserve) override; // Documentation inherited - bool isDofNamePreserved(size_t _index) const override; + bool isDofNamePreserved(std::size_t _index) const override; // Documentation inherited - const std::string& getDofName(size_t _index) const override; + const std::string& getDofName(std::size_t _index) const override; // Documentation inherited - size_t getIndexInSkeleton(size_t _index) const override; + std::size_t getIndexInSkeleton(std::size_t _index) const override; // Documentation inherited - size_t getIndexInTree(size_t _index) const override; + std::size_t getIndexInTree(std::size_t _index) const override; //---------------------------------------------------------------------------- // Command //---------------------------------------------------------------------------- // Documentation inherited - void setCommand(size_t _index, double command) override; + void setCommand(std::size_t _index, double command) override; // Documentation inherited - double getCommand(size_t _index) const override; + double getCommand(std::size_t _index) const override; // Documentation inherited void setCommands(const Eigen::VectorXd& _commands) override; @@ -158,10 +158,10 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF //---------------------------------------------------------------------------- // Documentation inherited - void setPosition(size_t _index, double _position) override; + void setPosition(std::size_t _index, double _position) override; // Documentation inherited - double getPosition(size_t _index) const override; + double getPosition(std::size_t _index) const override; // Documentation inherited void setPositions(const Eigen::VectorXd& _positions) override; @@ -170,31 +170,31 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF Eigen::VectorXd getPositions() const override; // Documentation inherited - void setPositionLowerLimit(size_t _index, double _position) override; + void setPositionLowerLimit(std::size_t _index, double _position) override; // Documentation inherited - double getPositionLowerLimit(size_t _index) const override; + double getPositionLowerLimit(std::size_t _index) const override; // Documentation inherited - void setPositionUpperLimit(size_t _index, double _position) override; + void setPositionUpperLimit(std::size_t _index, double _position) override; // Documentation inherited - double getPositionUpperLimit(size_t _index) const override; + double getPositionUpperLimit(std::size_t _index) const override; // Documentation inherited - bool hasPositionLimit(size_t _index) const override; + bool hasPositionLimit(std::size_t _index) const override; // Documentation inherited - void resetPosition(size_t _index) override; + void resetPosition(std::size_t _index) override; // Documentation inherited void resetPositions() override; // Documentation inherited - void setInitialPosition(size_t _index, double _initial) override; + void setInitialPosition(std::size_t _index, double _initial) override; // Documentation inherited - double getInitialPosition(size_t _index) const override; + double getInitialPosition(std::size_t _index) const override; // Documentation inherited void setInitialPositions(const Eigen::VectorXd& _initial) override; @@ -207,10 +207,10 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF //---------------------------------------------------------------------------- // Documentation inherited - void setVelocity(size_t _index, double _velocity) override; + void setVelocity(std::size_t _index, double _velocity) override; // Documentation inherited - double getVelocity(size_t _index) const override; + double getVelocity(std::size_t _index) const override; // Documentation inherited void setVelocities(const Eigen::VectorXd& _velocities) override; @@ -219,28 +219,28 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF Eigen::VectorXd getVelocities() const override; // Documentation inherited - void setVelocityLowerLimit(size_t _index, double _velocity) override; + void setVelocityLowerLimit(std::size_t _index, double _velocity) override; // Documentation inherited - double getVelocityLowerLimit(size_t _index) const override; + double getVelocityLowerLimit(std::size_t _index) const override; // Documentation inherited - void setVelocityUpperLimit(size_t _index, double _velocity) override; + void setVelocityUpperLimit(std::size_t _index, double _velocity) override; // Documentation inherited - double getVelocityUpperLimit(size_t _index) const override; + double getVelocityUpperLimit(std::size_t _index) const override; // Documentation inherited - void resetVelocity(size_t _index) override; + void resetVelocity(std::size_t _index) override; // Documentation inherited void resetVelocities() override; // Documentation inherited - void setInitialVelocity(size_t _index, double _initial) override; + void setInitialVelocity(std::size_t _index, double _initial) override; // Documentation inherited - double getInitialVelocity(size_t _index) const override; + double getInitialVelocity(std::size_t _index) const override; // Documentation inherited void setInitialVelocities(const Eigen::VectorXd& _initial) override; @@ -253,10 +253,10 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF //---------------------------------------------------------------------------- // Documentation inherited - void setAcceleration(size_t _index, double _acceleration) override; + void setAcceleration(std::size_t _index, double _acceleration) override; // Documentation inherited - double getAcceleration(size_t _index) const override; + double getAcceleration(std::size_t _index) const override; // Documentation inherited void setAccelerations(const Eigen::VectorXd& _accelerations) override; @@ -268,16 +268,16 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF void resetAccelerations() override; // Documentation inherited - void setAccelerationLowerLimit(size_t _index, double _acceleration) override; + void setAccelerationLowerLimit(std::size_t _index, double _acceleration) override; // Documentation inherited - double getAccelerationLowerLimit(size_t _index) const override; + double getAccelerationLowerLimit(std::size_t _index) const override; // Documentation inherited - void setAccelerationUpperLimit(size_t _index, double _acceleration) override; + void setAccelerationUpperLimit(std::size_t _index, double _acceleration) override; // Documentation inherited - double getAccelerationUpperLimit(size_t _index) const override; + double getAccelerationUpperLimit(std::size_t _index) const override; //---------------------------------------------------------------------------- // Fixed-size mutators and accessors @@ -312,10 +312,10 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF //---------------------------------------------------------------------------- // Documentation inherited - void setForce(size_t _index, double _force) override; + void setForce(std::size_t _index, double _force) override; // Documentation inherited - double getForce(size_t _index) override; + double getForce(std::size_t _index) override; // Documentation inherited void setForces(const Eigen::VectorXd& _forces) override; @@ -327,26 +327,26 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF void resetForces() override; // Documentation inherited - void setForceLowerLimit(size_t _index, double _force) override; + void setForceLowerLimit(std::size_t _index, double _force) override; // Documentation inherited - double getForceLowerLimit(size_t _index) const override; + double getForceLowerLimit(std::size_t _index) const override; // Documentation inherited - void setForceUpperLimit(size_t _index, double _force) override; + void setForceUpperLimit(std::size_t _index, double _force) override; // Documentation inherited - double getForceUpperLimit(size_t _index) const override; + double getForceUpperLimit(std::size_t _index) const override; //---------------------------------------------------------------------------- // Velocity change //---------------------------------------------------------------------------- // Documentation inherited - void setVelocityChange(size_t _index, double _velocityChange) override; + void setVelocityChange(std::size_t _index, double _velocityChange) override; // Documentation inherited - double getVelocityChange(size_t _index) const override; + double getVelocityChange(std::size_t _index) const override; // Documentation inherited void resetVelocityChanges() override; @@ -356,10 +356,10 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF //---------------------------------------------------------------------------- // Documentation inherited - void setConstraintImpulse(size_t _index, double _impulse) override; + void setConstraintImpulse(std::size_t _index, double _impulse) override; // Documentation inherited - double getConstraintImpulse(size_t _index) const override; + double getConstraintImpulse(std::size_t _index) const override; // Documentation inherited void resetConstraintImpulses() override; @@ -387,28 +387,28 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF //---------------------------------------------------------------------------- // Documentation inherited - void setSpringStiffness(size_t _index, double _k) override; + void setSpringStiffness(std::size_t _index, double _k) override; // Documentation inherited - double getSpringStiffness(size_t _index) const override; + double getSpringStiffness(std::size_t _index) const override; // Documentation inherited - void setRestPosition(size_t _index, double _q0) override; + void setRestPosition(std::size_t _index, double _q0) override; // Documentation inherited - double getRestPosition(size_t _index) const override; + double getRestPosition(std::size_t _index) const override; // Documentation inherited - void setDampingCoefficient(size_t _index, double _d) override; + void setDampingCoefficient(std::size_t _index, double _d) override; // Documentation inherited - double getDampingCoefficient(size_t _index) const override; + double getDampingCoefficient(std::size_t _index) const override; // Documentation inherited - void setCoulombFriction(size_t _index, double _friction) override; + void setCoulombFriction(std::size_t _index, double _friction) override; // Documentation inherited - double getCoulombFriction(size_t _index) const override; + double getCoulombFriction(std::size_t _index) const override; /// \} @@ -579,13 +579,13 @@ class MultiDofJoint : public detail::MultiDofJointBase< MultiDofJoint, DOF // Documentation inherited void getInvMassMatrixSegment(Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) override; // Documentation inherited void getInvAugMassMatrixSegment(Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) override; diff --git a/dart/dynamics/Node.cpp b/dart/dynamics/Node.cpp index 27bf29e6ac257..5c26beda2e248 100644 --- a/dart/dynamics/Node.cpp +++ b/dart/dynamics/Node.cpp @@ -280,7 +280,7 @@ void Node::stageForRemoval() destructors.erase(destructor_iter); // Reset all the Node indices that have been altered - for(size_t i=mIndexInBodyNode; i < nodes.size(); ++i) + for(std::size_t i=mIndexInBodyNode; i < nodes.size(); ++i) nodes[i]->mIndexInBodyNode = i; assert(std::find(nodes.begin(), nodes.end(), this) == nodes.end()); diff --git a/dart/dynamics/Node.h b/dart/dynamics/Node.h index 2d87d4b0c41fd..4a6aeb2b01604 100644 --- a/dart/dynamics/Node.h +++ b/dart/dynamics/Node.h @@ -222,13 +222,13 @@ class Node : bool mAmAttached; /// The index of this Node within its vector in its BodyNode's NodeMap - size_t mIndexInBodyNode; + std::size_t mIndexInBodyNode; /// The index of this Node within its vector in its Skeleton's NodeMap - size_t mIndexInSkeleton; + std::size_t mIndexInSkeleton; /// Index of this Node within its tree - size_t mIndexInTree; + std::size_t mIndexInTree; }; //============================================================================== @@ -244,16 +244,16 @@ class AccessoryNode virtual ~AccessoryNode() = default; /// Get the index of this Node within its BodyNode. - size_t getIndexInBodyNode() const; + std::size_t getIndexInBodyNode() const; /// Get the index of this Node within its Skeleton. - size_t getIndexInSkeleton() const; + std::size_t getIndexInSkeleton() const; /// Get the index of this Node within its tree. - size_t getIndexInTree() const; + std::size_t getIndexInTree() const; /// Get the index of this Node's tree within its Skeleton - size_t getTreeIndex() const; + std::size_t getTreeIndex() const; /// Stage the Node for removal. When all strong references to the Node expire, /// the Node will be removed from its BodyNode and deleted. diff --git a/dart/dynamics/NodeManagerJoiner.h b/dart/dynamics/NodeManagerJoiner.h index 6a3c46d7f03ce..e1faf7aca495c 100644 --- a/dart/dynamics/NodeManagerJoiner.h +++ b/dart/dynamics/NodeManagerJoiner.h @@ -83,13 +83,13 @@ class NodeManagerJoinerForBodyNode : public Base1, public Base2 NodeManagerJoinerForBodyNode(common::NoArgTag, Base2Args&&... args2); template - size_t getNumNodes() const; + std::size_t getNumNodes() const; template - NodeType* getNode(size_t index); + NodeType* getNode(std::size_t index); template - const NodeType* getNode(size_t index) const; + const NodeType* getNode(std::size_t index) const; template static constexpr bool isSpecializedForNode(); @@ -144,17 +144,17 @@ class NodeManagerJoinerForSkeleton : /// Get the number of Nodes of the specified type that are in the treeIndexth /// tree of this Skeleton template - size_t getNumNodes(size_t treeIndex) const; + std::size_t getNumNodes(std::size_t treeIndex) const; /// Get the nodeIndexth Node of the specified type within the tree of /// treeIndex. template - NodeType* getNode(size_t treeIndex, size_t nodeIndex); + NodeType* getNode(std::size_t treeIndex, std::size_t nodeIndex); /// Get the nodeIndexth Node of the specified type within the tree of /// treeIndex. template - const NodeType* getNode(size_t treeIndex, size_t nodeIndex) const; + const NodeType* getNode(std::size_t treeIndex, std::size_t nodeIndex) const; /// Get the Node of the specified type with the given name. template diff --git a/dart/dynamics/PlanarJoint.cpp b/dart/dynamics/PlanarJoint.cpp index 65905ffec8546..8ab3e65d11515 100644 --- a/dart/dynamics/PlanarJoint.cpp +++ b/dart/dynamics/PlanarJoint.cpp @@ -120,7 +120,7 @@ const std::string& PlanarJoint::getStaticType() } //============================================================================== -bool PlanarJoint::isCyclic(size_t _index) const +bool PlanarJoint::isCyclic(std::size_t _index) const { return _index == 2 && !hasPositionLimit(_index); } @@ -260,7 +260,7 @@ void PlanarJoint::updateDegreeOfFreedomNames() if (affixes.size() == 2) { - for (size_t i = 0; i < 2; ++i) + for (std::size_t i = 0; i < 2; ++i) { if (!mDofs[i]->isNamePreserved()) mDofs[i]->setName(Joint::mAspectProperties.mName + affixes[i], false); diff --git a/dart/dynamics/PlanarJoint.h b/dart/dynamics/PlanarJoint.h index 26bc0e63970dc..5956bba9cf093 100644 --- a/dart/dynamics/PlanarJoint.h +++ b/dart/dynamics/PlanarJoint.h @@ -93,7 +93,7 @@ class PlanarJoint : public detail::PlanarJointBase static const std::string& getStaticType(); // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; /// \brief Set plane type as XY-plane /// \param[in] _renameDofs If true, the names of dofs in this joint will be diff --git a/dart/dynamics/PointMass.cpp b/dart/dynamics/PointMass.cpp index 2cb2c8a2fe587..c56c2902eac77 100644 --- a/dart/dynamics/PointMass.cpp +++ b/dart/dynamics/PointMass.cpp @@ -80,7 +80,7 @@ bool PointMass::State::operator ==(const PointMass::State& other) const PointMass::Properties::Properties( const Vector3d& _X0, double _mass, - const std::vector& _connections, + const std::vector& _connections, const Vector3d& _positionLowerLimits, const Vector3d& _positionUpperLimits, const Vector3d& _velocityLowerLimits, @@ -143,7 +143,7 @@ bool PointMass::Properties::operator !=(const PointMass::Properties& other) cons //============================================================================== PointMass::PointMass(SoftBodyNode* _softBodyNode) - : // mIndexInSkeleton(Eigen::Matrix::Zero()), + : // mIndexInSkeleton(Eigen::Matrix::Zero()), mParentSoftBodyNode(_softBodyNode), mPositionDeriv(Eigen::Vector3d::Zero()), mVelocitiesDeriv(Eigen::Vector3d::Zero()), @@ -197,7 +197,7 @@ const PointMass::State& PointMass::getState() const } //============================================================================== -size_t PointMass::getIndexInSoftBodyNode() const +std::size_t PointMass::getIndexInSoftBodyNode() const { return mIndex; } @@ -259,14 +259,14 @@ void PointMass::addConnectedPointMass(PointMass* _pointMass) } //============================================================================== -size_t PointMass::getNumConnectedPointMasses() const +std::size_t PointMass::getNumConnectedPointMasses() const { return mParentSoftBodyNode->mAspectProperties.mPointProps[mIndex]. mConnectedPointMassIndices.size(); } //============================================================================== -PointMass* PointMass::getConnectedPointMass(size_t _idx) +PointMass* PointMass::getConnectedPointMass(std::size_t _idx) { assert(_idx < getNumConnectedPointMasses()); @@ -276,7 +276,7 @@ PointMass* PointMass::getConnectedPointMass(size_t _idx) } //============================================================================== -const PointMass* PointMass::getConnectedPointMass(size_t _idx) const +const PointMass* PointMass::getConnectedPointMass(std::size_t _idx) const { return const_cast(this)->getConnectedPointMass(_idx); } @@ -294,13 +294,13 @@ bool PointMass::isColliding() } //============================================================================== -size_t PointMass::getNumDofs() const +std::size_t PointMass::getNumDofs() const { return 3; } ////============================================================================== -//void PointMass::setIndexInSkeleton(size_t _index, size_t _indexInSkeleton) +//void PointMass::setIndexInSkeleton(std::size_t _index, std::size_t _indexInSkeleton) //{ // assert(_index < 3); @@ -308,7 +308,7 @@ size_t PointMass::getNumDofs() const //} ////============================================================================== -//size_t PointMass::getIndexInSkeleton(size_t _index) const +//std::size_t PointMass::getIndexInSkeleton(std::size_t _index) const //{ // assert(_index < 3); @@ -316,7 +316,7 @@ size_t PointMass::getNumDofs() const //} //============================================================================== -void PointMass::setPosition(size_t _index, double _position) +void PointMass::setPosition(std::size_t _index, double _position) { assert(_index < 3); @@ -325,7 +325,7 @@ void PointMass::setPosition(size_t _index, double _position) } //============================================================================== -double PointMass::getPosition(size_t _index) const +double PointMass::getPosition(std::size_t _index) const { assert(_index < 3); @@ -353,7 +353,7 @@ void PointMass::resetPositions() } //============================================================================== -void PointMass::setVelocity(size_t _index, double _velocity) +void PointMass::setVelocity(std::size_t _index, double _velocity) { assert(_index < 3); @@ -362,7 +362,7 @@ void PointMass::setVelocity(size_t _index, double _velocity) } //============================================================================== -double PointMass::getVelocity(size_t _index) const +double PointMass::getVelocity(std::size_t _index) const { assert(_index < 3); @@ -390,7 +390,7 @@ void PointMass::resetVelocities() } //============================================================================== -void PointMass::setAcceleration(size_t _index, double _acceleration) +void PointMass::setAcceleration(std::size_t _index, double _acceleration) { assert(_index < 3); @@ -399,7 +399,7 @@ void PointMass::setAcceleration(size_t _index, double _acceleration) } //============================================================================== -double PointMass::getAcceleration(size_t _index) const +double PointMass::getAcceleration(std::size_t _index) const { assert(_index < 3); @@ -435,7 +435,7 @@ void PointMass::resetAccelerations() } //============================================================================== -void PointMass::setForce(size_t _index, double _force) +void PointMass::setForce(std::size_t _index, double _force) { assert(_index < 3); @@ -443,7 +443,7 @@ void PointMass::setForce(size_t _index, double _force) } //============================================================================== -double PointMass::getForce(size_t _index) +double PointMass::getForce(std::size_t _index) { assert(_index < 3); @@ -469,7 +469,7 @@ void PointMass::resetForces() } //============================================================================== -void PointMass::setVelocityChange(size_t _index, double _velocityChange) +void PointMass::setVelocityChange(std::size_t _index, double _velocityChange) { assert(_index < 3); @@ -477,7 +477,7 @@ void PointMass::setVelocityChange(size_t _index, double _velocityChange) } //============================================================================== -double PointMass::getVelocityChange(size_t _index) +double PointMass::getVelocityChange(std::size_t _index) { assert(_index < 3); @@ -491,7 +491,7 @@ void PointMass::resetVelocityChanges() } //============================================================================== -void PointMass::setConstraintImpulse(size_t _index, double _impulse) +void PointMass::setConstraintImpulse(std::size_t _index, double _impulse) { assert(_index < 3); @@ -499,7 +499,7 @@ void PointMass::setConstraintImpulse(size_t _index, double _impulse) } //============================================================================== -double PointMass::getConstraintImpulse(size_t _index) +double PointMass::getConstraintImpulse(std::size_t _index) { assert(_index < 3); @@ -862,7 +862,7 @@ void PointMass::updateBiasForceFD(double _dt, const Eigen::Vector3d& _gravity) - (_dt * (kv + nN * ke) + kd) * getVelocities() - getMass() * getPartialAccelerations() - mB; - for (size_t i = 0; i < getNumConnectedPointMasses(); ++i) + for (std::size_t i = 0; i < getNumConnectedPointMasses(); ++i) { const State& i_state = getConnectedPointMass(i)->getState(); mAlpha += ke * (i_state.mPositions + _dt * i_state.mVelocities); diff --git a/dart/dynamics/PointMass.h b/dart/dynamics/PointMass.h index 2685708347f9e..fa3dd995d5dba 100644 --- a/dart/dynamics/PointMass.h +++ b/dart/dynamics/PointMass.h @@ -92,7 +92,7 @@ class PointMass : public common::Subject double mMass; /// Indices of connected Point Masses - std::vector mConnectedPointMassIndices; + std::vector mConnectedPointMassIndices; /// Lower limit of position Eigen::Vector3d mPositionLowerLimits; // Currently unused @@ -120,7 +120,7 @@ class PointMass : public common::Subject Properties(const Eigen::Vector3d& _X0 = Eigen::Vector3d::Zero(), double _mass = 0.0005, - const std::vector& _connections = std::vector(), + const std::vector& _connections = std::vector(), const Eigen::Vector3d& _positionLowerLimits = Eigen::Vector3d::Constant(-math::constantsd::inf()), const Eigen::Vector3d& _positionUpperLimits = @@ -163,7 +163,7 @@ class PointMass : public common::Subject const State& getState() const; /// - size_t getIndexInSoftBodyNode() const; + std::size_t getIndexInSoftBodyNode() const; /// void setMass(double _mass); @@ -187,13 +187,13 @@ class PointMass : public common::Subject void addConnectedPointMass(PointMass* _pointMass); /// - size_t getNumConnectedPointMasses() const; + std::size_t getNumConnectedPointMasses() const; /// - PointMass* getConnectedPointMass(size_t _idx); + PointMass* getConnectedPointMass(std::size_t _idx); /// - const PointMass* getConnectedPointMass(size_t _idx) const; + const PointMass* getConnectedPointMass(std::size_t _idx) const; /// Set whether this point mass is colliding with other objects. Note that @@ -209,23 +209,23 @@ class PointMass : public common::Subject //---------------------------------------------------------------------------- // Documentation inherited - size_t getNumDofs() const; + std::size_t getNumDofs() const; // // Documentation inherited -// void setIndexInSkeleton(size_t _index, size_t _indexInSkeleton); +// void setIndexInSkeleton(std::size_t _index, std::size_t _indexInSkeleton); // // Documentation inherited -// size_t getIndexInSkeleton(size_t _index) const; +// std::size_t getIndexInSkeleton(std::size_t _index) const; //---------------------------------------------------------------------------- // Position //---------------------------------------------------------------------------- // Documentation inherited - void setPosition(size_t _index, double _position); + void setPosition(std::size_t _index, double _position); // Documentation inherited - double getPosition(size_t _index) const; + double getPosition(std::size_t _index) const; // Documentation inherited void setPositions(const Eigen::Vector3d& _positions); @@ -241,10 +241,10 @@ class PointMass : public common::Subject //---------------------------------------------------------------------------- // Documentation inherited - void setVelocity(size_t _index, double _velocity); + void setVelocity(std::size_t _index, double _velocity); // Documentation inherited - double getVelocity(size_t _index) const; + double getVelocity(std::size_t _index) const; // Documentation inherited void setVelocities(const Eigen::Vector3d& _velocities); @@ -260,10 +260,10 @@ class PointMass : public common::Subject //---------------------------------------------------------------------------- // Documentation inherited - void setAcceleration(size_t _index, double _acceleration); + void setAcceleration(std::size_t _index, double _acceleration); // Documentation inherited - double getAcceleration(size_t _index) const; + double getAcceleration(std::size_t _index) const; // Documentation inherited void setAccelerations(const Eigen::Vector3d& _accelerations); @@ -282,10 +282,10 @@ class PointMass : public common::Subject //---------------------------------------------------------------------------- // Documentation inherited - void setForce(size_t _index, double _force); + void setForce(std::size_t _index, double _force); // Documentation inherited - double getForce(size_t _index); + double getForce(std::size_t _index); // Documentation inherited void setForces(const Eigen::Vector3d& _forces); @@ -301,10 +301,10 @@ class PointMass : public common::Subject //---------------------------------------------------------------------------- // Documentation inherited - void setVelocityChange(size_t _index, double _velocityChange); + void setVelocityChange(std::size_t _index, double _velocityChange); // Documentation inherited - double getVelocityChange(size_t _index); + double getVelocityChange(std::size_t _index); // Documentation inherited void resetVelocityChanges(); @@ -314,10 +314,10 @@ class PointMass : public common::Subject //---------------------------------------------------------------------------- // Documentation inherited - void setConstraintImpulse(size_t _index, double _impulse); + void setConstraintImpulse(std::size_t _index, double _impulse); // Documentation inherited - double getConstraintImpulse(size_t _index); + double getConstraintImpulse(std::size_t _index); // Documentation inherited void resetConstraintImpulses(); @@ -547,13 +547,13 @@ class PointMass : public common::Subject protected: // TODO(JS): Need? /// -// Eigen::Matrix mIndexInSkeleton; +// Eigen::Matrix mIndexInSkeleton; /// SoftBodyNode that this PointMass belongs to SoftBodyNode* mParentSoftBodyNode; /// Index of this PointMass within the SoftBodyNode - size_t mIndex; + std::size_t mIndex; //---------------------------------------------------------------------------- // Configuration @@ -642,7 +642,7 @@ class PointMass : public common::Subject Eigen::Vector3d mFext; /// A increasingly sorted list of dependent dof indices. - std::vector mDependentGenCoordIndices; + std::vector mDependentGenCoordIndices; /// Whether the node is currently in collision with another node. bool mIsColliding; diff --git a/dart/dynamics/PrismaticJoint.cpp b/dart/dynamics/PrismaticJoint.cpp index 099dd9b53f5ed..9117b6482503f 100644 --- a/dart/dynamics/PrismaticJoint.cpp +++ b/dart/dynamics/PrismaticJoint.cpp @@ -116,7 +116,7 @@ const std::string& PrismaticJoint::getStaticType() } //============================================================================== -bool PrismaticJoint::isCyclic(size_t /*_index*/) const +bool PrismaticJoint::isCyclic(std::size_t /*_index*/) const { return false; } diff --git a/dart/dynamics/PrismaticJoint.h b/dart/dynamics/PrismaticJoint.h index 5b257000b1160..1193894a9a949 100644 --- a/dart/dynamics/PrismaticJoint.h +++ b/dart/dynamics/PrismaticJoint.h @@ -86,7 +86,7 @@ class PrismaticJoint : public detail::PrismaticJointBase static const std::string& getStaticType(); // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; /// void setAxis(const Eigen::Vector3d& _axis); diff --git a/dart/dynamics/ReferentialSkeleton.cpp b/dart/dynamics/ReferentialSkeleton.cpp index 90f96d763d4df..eefd625cfe5f6 100644 --- a/dart/dynamics/ReferentialSkeleton.cpp +++ b/dart/dynamics/ReferentialSkeleton.cpp @@ -64,19 +64,19 @@ const std::string& ReferentialSkeleton::getName() const } //============================================================================== -size_t ReferentialSkeleton::getNumBodyNodes() const +std::size_t ReferentialSkeleton::getNumBodyNodes() const { return mBodyNodes.size(); } //============================================================================== -BodyNode* ReferentialSkeleton::getBodyNode(size_t _idx) +BodyNode* ReferentialSkeleton::getBodyNode(std::size_t _idx) { return common::getVectorObjectIfAvailable(_idx, mBodyNodes); } //============================================================================== -const BodyNode* ReferentialSkeleton::getBodyNode(size_t _idx) const +const BodyNode* ReferentialSkeleton::getBodyNode(std::size_t _idx) const { return common::getVectorObjectIfAvailable(_idx, mBodyNodes); } @@ -87,7 +87,7 @@ static std::vector& convertVector(const std::vector& t1_vec, std::vector& t2_vec) { t2_vec.resize(t1_vec.size()); - for(size_t i = 0; i < t1_vec.size(); ++i) + for(std::size_t i = 0; i < t1_vec.size(); ++i) t2_vec[i] = t1_vec[i]; return t2_vec; } @@ -109,7 +109,7 @@ const std::vector& ReferentialSkeleton::getBodyNodes() const } //============================================================================== -size_t ReferentialSkeleton::getIndexOf(const BodyNode* _bn, bool _warning) const +std::size_t ReferentialSkeleton::getIndexOf(const BodyNode* _bn, bool _warning) const { if(nullptr == _bn) { @@ -141,25 +141,25 @@ size_t ReferentialSkeleton::getIndexOf(const BodyNode* _bn, bool _warning) const } //============================================================================== -size_t ReferentialSkeleton::getNumJoints() const +std::size_t ReferentialSkeleton::getNumJoints() const { return mJoints.size(); } //============================================================================== -Joint* ReferentialSkeleton::getJoint(size_t _idx) +Joint* ReferentialSkeleton::getJoint(std::size_t _idx) { return common::getVectorObjectIfAvailable(_idx, mJoints); } //============================================================================== -const Joint* ReferentialSkeleton::getJoint(size_t _idx) const +const Joint* ReferentialSkeleton::getJoint(std::size_t _idx) const { return common::getVectorObjectIfAvailable(_idx, mJoints); } //============================================================================== -size_t ReferentialSkeleton::getIndexOf(const Joint* _joint, bool _warning) const +std::size_t ReferentialSkeleton::getIndexOf(const Joint* _joint, bool _warning) const { if(nullptr == _joint) { @@ -190,19 +190,19 @@ size_t ReferentialSkeleton::getIndexOf(const Joint* _joint, bool _warning) const } //============================================================================== -size_t ReferentialSkeleton::getNumDofs() const +std::size_t ReferentialSkeleton::getNumDofs() const { return mDofs.size(); } //============================================================================== -DegreeOfFreedom* ReferentialSkeleton::getDof(size_t _idx) +DegreeOfFreedom* ReferentialSkeleton::getDof(std::size_t _idx) { return common::getVectorObjectIfAvailable(_idx, mDofs); } //============================================================================== -const DegreeOfFreedom* ReferentialSkeleton::getDof(size_t _idx) const +const DegreeOfFreedom* ReferentialSkeleton::getDof(std::size_t _idx) const { return common::getVectorObjectIfAvailable(_idx, mDofs); } @@ -228,7 +228,7 @@ std::vector ReferentialSkeleton::getDofs() const } //============================================================================== -size_t ReferentialSkeleton::getIndexOf( +std::size_t ReferentialSkeleton::getIndexOf( const DegreeOfFreedom* _dof, bool _warning) const { if(nullptr == _dof) @@ -258,7 +258,7 @@ size_t ReferentialSkeleton::getIndexOf( return INVALID_INDEX; } - size_t localIndex = _dof->getIndexInJoint(); + std::size_t localIndex = _dof->getIndexInJoint(); if(it->second.mDofIndices.size() <= localIndex || it->second.mDofIndices[localIndex] == INVALID_INDEX ) { @@ -306,10 +306,10 @@ void assignJacobian(JacobianType& _J, { const std::vector& bn_dofs = _node->getDependentDofs(); - size_t nDofs = bn_dofs.size(); - for(size_t i=0; igetIndexOf(bn_dofs[i], false); + std::size_t refIndex = _refSkel->getIndexOf(bn_dofs[i], false); if(INVALID_INDEX == refIndex) continue; @@ -621,29 +621,29 @@ double ReferentialSkeleton::getMass() const } //============================================================================== -template +template const Eigen::MatrixXd& setMatrixFromSkeletonData( Eigen::MatrixXd& M, const std::vector& dofs) { - const size_t nDofs = dofs.size(); + const std::size_t nDofs = dofs.size(); M.setZero(); - for(size_t i=0; igetTreeIndex(); + const std::size_t tree_i = dof_i->getTreeIndex(); const ConstSkeletonPtr& skel_i = dof_i->getSkeleton(); - const size_t index_i = dof_i->getIndexInTree(); + const std::size_t index_i = dof_i->getIndexInTree(); const Eigen::MatrixXd& treeMatrix = (skel_i.get()->*getMatrix)(tree_i); M(i,i) = treeMatrix(index_i, index_i); - for(size_t j=i+1; jgetTreeIndex(); + const std::size_t tree_j = dof_j->getTreeIndex(); const ConstSkeletonPtr& skel_j = dof_j->getSkeleton(); // If the DegreesOfFreedom are in the same tree within the same @@ -651,7 +651,7 @@ const Eigen::MatrixXd& setMatrixFromSkeletonData( // Otherwise, leave the entry as zero. if(skel_i == skel_j && tree_i == tree_j) { - const size_t index_j = dof_j->getIndexInTree(); + const std::size_t index_j = dof_j->getIndexInTree(); M(i,j) = treeMatrix(index_i, index_j); M(j,i) = M(i,j); @@ -690,21 +690,21 @@ const Eigen::MatrixXd& ReferentialSkeleton::getInvAugMassMatrix() const } //============================================================================== -template +template const Eigen::VectorXd& setVectorFromSkeletonData( Eigen::VectorXd& V, const std::vector& dofs) { - const size_t nDofs = dofs.size(); + const std::size_t nDofs = dofs.size(); V.setZero(); - for(size_t i=0; igetTreeIndex(); + const std::size_t tree_i = dof_i->getTreeIndex(); const ConstSkeletonPtr& skel_i = dof_i->getSkeleton(); - const size_t index_i = dof_i->getIndexInTree(); + const std::size_t index_i = dof_i->getIndexInTree(); const Eigen::VectorXd& treeVector = (skel_i.get()->*getVector)(tree_i); V[i] = treeVector[index_i]; @@ -905,11 +905,11 @@ JacType getCOMJacobianTemplate(const ReferentialSkeleton* _refSkel, totalMass += bn->getMass(); const std::vector& dofs = bn->getDependentDofs(); - size_t nDofs = dofs.size(); - for(size_t i=0; igetIndexOf(dof, false); + std::size_t index = _refSkel->getIndexOf(dof, false); if(INVALID_INDEX == index) continue; @@ -965,8 +965,8 @@ void ReferentialSkeleton::registerComponent(BodyNode* _bn) registerBodyNode(_bn); registerJoint(_bn->getParentJoint()); - size_t nDofs = _bn->getParentJoint()->getNumDofs(); - for(size_t i=0; i < nDofs; ++i) + std::size_t nDofs = _bn->getParentJoint()->getNumDofs(); + for(std::size_t i=0; i < nDofs; ++i) registerDegreeOfFreedom(_bn->getParentJoint()->getDof(i)); } @@ -1041,7 +1041,7 @@ void ReferentialSkeleton::registerJoint(Joint* _joint) void ReferentialSkeleton::registerDegreeOfFreedom(DegreeOfFreedom* _dof) { BodyNode* bn = _dof->getChildBodyNode(); - size_t localIndex = _dof->getIndexInJoint(); + std::size_t localIndex = _dof->getIndexInJoint(); std::unordered_map::iterator it = mIndexMap.find(bn); @@ -1109,11 +1109,11 @@ void ReferentialSkeleton::unregisterBodyNode( } IndexMap& indexing = it->second; - size_t bnIndex = indexing.mBodyNodeIndex; + std::size_t bnIndex = indexing.mBodyNodeIndex; mBodyNodes.erase(mBodyNodes.begin() + bnIndex); indexing.mBodyNodeIndex = INVALID_INDEX; - for(size_t i=bnIndex; i < mBodyNodes.size(); ++i) + for(std::size_t i=bnIndex; i < mBodyNodes.size(); ++i) { // Re-index all the BodyNodes in this ReferentialSkeleton which came after // the one that was removed. @@ -1123,7 +1123,7 @@ void ReferentialSkeleton::unregisterBodyNode( if(_unregisterDofs) { - for(size_t i=0; i < indexing.mDofIndices.size(); ++i) + for(std::size_t i=0; i < indexing.mDofIndices.size(); ++i) { if(indexing.mDofIndices[i] != INVALID_INDEX) unregisterDegreeOfFreedom(_bn, i); @@ -1165,11 +1165,11 @@ void ReferentialSkeleton::unregisterJoint(BodyNode* _child) return; } - size_t jointIndex = it->second.mJointIndex; + std::size_t jointIndex = it->second.mJointIndex; mJoints.erase(mJoints.begin() + jointIndex); it->second.mJointIndex = INVALID_INDEX; - for(size_t i = jointIndex; i < mJoints.size(); ++i) + for(std::size_t i = jointIndex; i < mJoints.size(); ++i) { // Re-index all of the Joints in this ReferentialSkeleton which came after // the Joint that was removed. @@ -1189,7 +1189,7 @@ void ReferentialSkeleton::unregisterJoint(BodyNode* _child) //============================================================================== void ReferentialSkeleton::unregisterDegreeOfFreedom( - BodyNode* _bn, size_t _localIndex) + BodyNode* _bn, std::size_t _localIndex) { if(nullptr == _bn) { @@ -1216,11 +1216,11 @@ void ReferentialSkeleton::unregisterDegreeOfFreedom( return; } - size_t dofIndex = it->second.mDofIndices[_localIndex]; + std::size_t dofIndex = it->second.mDofIndices[_localIndex]; mDofs.erase(mDofs.begin() + dofIndex); it->second.mDofIndices[_localIndex] = INVALID_INDEX; - for(size_t i = dofIndex; i < mDofs.size(); ++i) + for(std::size_t i = dofIndex; i < mDofs.size(); ++i) { // Re-index all the DOFs in this ReferentialSkeleton which came after the // DOF that was removed. @@ -1265,7 +1265,7 @@ void ReferentialSkeleton::updateCaches() mRawConstDofs.push_back(dof); } - size_t nDofs = mDofs.size(); + std::size_t nDofs = mDofs.size(); mM = Eigen::MatrixXd::Zero(nDofs, nDofs); mAugM = Eigen::MatrixXd::Zero(nDofs, nDofs); mInvM = Eigen::MatrixXd::Zero(nDofs, nDofs); @@ -1294,7 +1294,7 @@ bool ReferentialSkeleton::IndexMap::isExpired() const if(INVALID_INDEX != mJointIndex) return false; - for(size_t i=0; i < mDofIndices.size(); ++i) + for(std::size_t i=0; i < mDofIndices.size(); ++i) { if(mDofIndices[i] != INVALID_INDEX) return false; diff --git a/dart/dynamics/ReferentialSkeleton.h b/dart/dynamics/ReferentialSkeleton.h index cf7a2a96542a8..905ed3bfc1cab 100644 --- a/dart/dynamics/ReferentialSkeleton.h +++ b/dart/dynamics/ReferentialSkeleton.h @@ -75,13 +75,13 @@ class ReferentialSkeleton : public MetaSkeleton //---------------------------------------------------------------------------- // Documentation inherited - size_t getNumBodyNodes() const override; + std::size_t getNumBodyNodes() const override; // Documentation inherited - BodyNode* getBodyNode(size_t _idx) override; + BodyNode* getBodyNode(std::size_t _idx) override; // Documentation inherited - const BodyNode* getBodyNode(size_t _idx) const override; + const BodyNode* getBodyNode(std::size_t _idx) const override; // Documentation inherited const std::vector& getBodyNodes() override; @@ -90,28 +90,28 @@ class ReferentialSkeleton : public MetaSkeleton const std::vector& getBodyNodes() const override; // Documentation inherited - size_t getIndexOf(const BodyNode* _bn, bool _warning=true) const override; + std::size_t getIndexOf(const BodyNode* _bn, bool _warning=true) const override; // Documentation inherited - size_t getNumJoints() const override; + std::size_t getNumJoints() const override; // Documentation inherited - Joint* getJoint(size_t _idx) override; + Joint* getJoint(std::size_t _idx) override; // Documentation inherited - const Joint* getJoint(size_t _idx) const override; + const Joint* getJoint(std::size_t _idx) const override; // Documentation inherited - size_t getIndexOf(const Joint* _joint, bool _warning=true) const override; + std::size_t getIndexOf(const Joint* _joint, bool _warning=true) const override; // Documentation inherited - size_t getNumDofs() const override; + std::size_t getNumDofs() const override; // Documentation inherited - DegreeOfFreedom* getDof(size_t _idx) override; + DegreeOfFreedom* getDof(std::size_t _idx) override; // Documentation inherited - const DegreeOfFreedom* getDof(size_t _idx) const override; + const DegreeOfFreedom* getDof(std::size_t _idx) const override; // Documentation inherited const std::vector& getDofs() override; @@ -120,7 +120,7 @@ class ReferentialSkeleton : public MetaSkeleton std::vector getDofs() const override; // Documentation inherited - size_t getIndexOf(const DegreeOfFreedom* _dof, + std::size_t getIndexOf(const DegreeOfFreedom* _dof, bool _warning=true) const override; /// \} @@ -361,7 +361,7 @@ class ReferentialSkeleton : public MetaSkeleton /// Remove a DegreeOfFreedom from this ReferentialSkeleton. This can only be /// used by derived classes. - void unregisterDegreeOfFreedom(BodyNode* _bn, size_t _localIndex); + void unregisterDegreeOfFreedom(BodyNode* _bn, std::size_t _localIndex); /// Update the caches to match any changes to the structure of this /// ReferentialSkeleton @@ -375,13 +375,13 @@ class ReferentialSkeleton : public MetaSkeleton struct IndexMap { /// Index of the BodyNode - size_t mBodyNodeIndex; + std::size_t mBodyNodeIndex; /// Index of the parent Joint - size_t mJointIndex; + std::size_t mJointIndex; /// Indices of the parent DegreesOfFreedom - std::vector mDofIndices; + std::vector mDofIndices; /// Default constructor. Initializes mBodyNodeIndex and mJointIndex to /// INVALID_INDEX diff --git a/dart/dynamics/RevoluteJoint.cpp b/dart/dynamics/RevoluteJoint.cpp index dae6771165ab9..e32fe841a1497 100644 --- a/dart/dynamics/RevoluteJoint.cpp +++ b/dart/dynamics/RevoluteJoint.cpp @@ -110,7 +110,7 @@ const std::string& RevoluteJoint::getType() const } //============================================================================== -bool RevoluteJoint::isCyclic(size_t _index) const +bool RevoluteJoint::isCyclic(std::size_t _index) const { return !hasPositionLimit(_index); } diff --git a/dart/dynamics/RevoluteJoint.h b/dart/dynamics/RevoluteJoint.h index bb633b0efc054..57973bb890d83 100644 --- a/dart/dynamics/RevoluteJoint.h +++ b/dart/dynamics/RevoluteJoint.h @@ -84,7 +84,7 @@ class RevoluteJoint : public detail::RevoluteJointBase const std::string& getType() const override; // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; /// Get joint type for this class static const std::string& getStaticType(); diff --git a/dart/dynamics/ScrewJoint.cpp b/dart/dynamics/ScrewJoint.cpp index cf14ec18fab8e..a4bf07299f179 100644 --- a/dart/dynamics/ScrewJoint.cpp +++ b/dart/dynamics/ScrewJoint.cpp @@ -117,7 +117,7 @@ const std::string& ScrewJoint::getStaticType() } //============================================================================== -bool ScrewJoint::isCyclic(size_t /*_index*/) const +bool ScrewJoint::isCyclic(std::size_t /*_index*/) const { return false; } diff --git a/dart/dynamics/ScrewJoint.h b/dart/dynamics/ScrewJoint.h index b6d7383b8ed73..179c2a5f4f7cd 100644 --- a/dart/dynamics/ScrewJoint.h +++ b/dart/dynamics/ScrewJoint.h @@ -87,7 +87,7 @@ class ScrewJoint : public detail::ScrewJointBase static const std::string& getStaticType(); // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; /// void setAxis(const Eigen::Vector3d& _axis); diff --git a/dart/dynamics/SingleDofJoint.cpp b/dart/dynamics/SingleDofJoint.cpp index 16c394e795fb3..1be6de6ed50fc 100644 --- a/dart/dynamics/SingleDofJoint.cpp +++ b/dart/dynamics/SingleDofJoint.cpp @@ -151,13 +151,13 @@ SingleDofJoint& SingleDofJoint::operator=(const SingleDofJoint& _otherJoint) } //============================================================================== -size_t SingleDofJoint::getNumDofs() const +std::size_t SingleDofJoint::getNumDofs() const { return 1; } //============================================================================== -size_t SingleDofJoint::getIndexInSkeleton(size_t _index) const +std::size_t SingleDofJoint::getIndexInSkeleton(std::size_t _index) const { if (_index != 0) { @@ -169,7 +169,7 @@ size_t SingleDofJoint::getIndexInSkeleton(size_t _index) const } //============================================================================== -size_t SingleDofJoint::getIndexInTree(size_t _index) const +std::size_t SingleDofJoint::getIndexInTree(std::size_t _index) const { if (_index != 0) { @@ -181,7 +181,7 @@ size_t SingleDofJoint::getIndexInTree(size_t _index) const } //============================================================================== -DegreeOfFreedom* SingleDofJoint::getDof(size_t _index) +DegreeOfFreedom* SingleDofJoint::getDof(std::size_t _index) { if (0 == _index) return mDof; @@ -191,7 +191,7 @@ DegreeOfFreedom* SingleDofJoint::getDof(size_t _index) } //============================================================================== -const DegreeOfFreedom* SingleDofJoint::getDof(size_t _index) const +const DegreeOfFreedom* SingleDofJoint::getDof(std::size_t _index) const { if (0 == _index) return mDof; @@ -201,7 +201,7 @@ const DegreeOfFreedom* SingleDofJoint::getDof(size_t _index) const } //============================================================================== -const std::string& SingleDofJoint::setDofName(size_t _index, +const std::string& SingleDofJoint::setDofName(std::size_t _index, const std::string& _name, bool _preserveName) { @@ -233,7 +233,7 @@ const std::string& SingleDofJoint::setDofName(size_t _index, } //============================================================================== -void SingleDofJoint::preserveDofName(size_t _index, bool _preserve) +void SingleDofJoint::preserveDofName(std::size_t _index, bool _preserve) { if (0 < _index) { @@ -245,7 +245,7 @@ void SingleDofJoint::preserveDofName(size_t _index, bool _preserve) } //============================================================================== -bool SingleDofJoint::isDofNamePreserved(size_t _index) const +bool SingleDofJoint::isDofNamePreserved(std::size_t _index) const { if (0 < _index) { @@ -256,7 +256,7 @@ bool SingleDofJoint::isDofNamePreserved(size_t _index) const } //============================================================================== -const std::string& SingleDofJoint::getDofName(size_t _index) const +const std::string& SingleDofJoint::getDofName(std::size_t _index) const { if (0 < _index) { @@ -270,7 +270,7 @@ const std::string& SingleDofJoint::getDofName(size_t _index) const } //============================================================================== -void SingleDofJoint::setCommand(size_t _index, double _command) +void SingleDofJoint::setCommand(std::size_t _index, double _command) { if (_index != 0) { @@ -326,7 +326,7 @@ void SingleDofJoint::setCommand(size_t _index, double _command) } //============================================================================== -double SingleDofJoint::getCommand(size_t _index) const +double SingleDofJoint::getCommand(std::size_t _index) const { if (_index != 0) { @@ -340,7 +340,7 @@ double SingleDofJoint::getCommand(size_t _index) const //============================================================================== void SingleDofJoint::setCommands(const Eigen::VectorXd& _commands) { - if (static_cast(_commands.size()) != getNumDofs()) + if (static_cast(_commands.size()) != getNumDofs()) { SINGLEDOFJOINT_REPORT_DIM_MISMATCH( setCommands, _commands ); return; @@ -362,7 +362,7 @@ void SingleDofJoint::resetCommands() } //============================================================================== -void SingleDofJoint::setPosition(size_t _index, double _position) +void SingleDofJoint::setPosition(std::size_t _index, double _position) { if (_index != 0) { @@ -374,7 +374,7 @@ void SingleDofJoint::setPosition(size_t _index, double _position) } //============================================================================== -double SingleDofJoint::getPosition(size_t _index) const +double SingleDofJoint::getPosition(std::size_t _index) const { if (_index != 0) { @@ -388,7 +388,7 @@ double SingleDofJoint::getPosition(size_t _index) const //============================================================================== void SingleDofJoint::setPositions(const Eigen::VectorXd& _positions) { - if (static_cast(_positions.size()) != getNumDofs()) + if (static_cast(_positions.size()) != getNumDofs()) { SINGLEDOFJOINT_REPORT_DIM_MISMATCH( setPositions, _positions ); return; @@ -404,7 +404,7 @@ Eigen::VectorXd SingleDofJoint::getPositions() const } //============================================================================== -void SingleDofJoint::setPositionLowerLimit(size_t _index, double _position) +void SingleDofJoint::setPositionLowerLimit(std::size_t _index, double _position) { if (_index != 0) { @@ -416,7 +416,7 @@ void SingleDofJoint::setPositionLowerLimit(size_t _index, double _position) } //============================================================================== -double SingleDofJoint::getPositionLowerLimit(size_t _index) const +double SingleDofJoint::getPositionLowerLimit(std::size_t _index) const { if (_index != 0) { @@ -428,7 +428,7 @@ double SingleDofJoint::getPositionLowerLimit(size_t _index) const } //============================================================================== -void SingleDofJoint::setPositionUpperLimit(size_t _index, double _position) +void SingleDofJoint::setPositionUpperLimit(std::size_t _index, double _position) { if (_index != 0) { @@ -440,7 +440,7 @@ void SingleDofJoint::setPositionUpperLimit(size_t _index, double _position) } //============================================================================== -double SingleDofJoint::getPositionUpperLimit(size_t _index) const +double SingleDofJoint::getPositionUpperLimit(std::size_t _index) const { if (_index != 0) { @@ -452,7 +452,7 @@ double SingleDofJoint::getPositionUpperLimit(size_t _index) const } //============================================================================== -bool SingleDofJoint::hasPositionLimit(size_t _index) const +bool SingleDofJoint::hasPositionLimit(std::size_t _index) const { if (_index != 0) { @@ -465,7 +465,7 @@ bool SingleDofJoint::hasPositionLimit(size_t _index) const } //============================================================================== -void SingleDofJoint::resetPosition(size_t _index) +void SingleDofJoint::resetPosition(std::size_t _index) { if (_index != 0) { @@ -483,7 +483,7 @@ void SingleDofJoint::resetPositions() } //============================================================================== -void SingleDofJoint::setInitialPosition(size_t _index, double _initial) +void SingleDofJoint::setInitialPosition(std::size_t _index, double _initial) { if (_index != 0) { @@ -495,7 +495,7 @@ void SingleDofJoint::setInitialPosition(size_t _index, double _initial) } //============================================================================== -double SingleDofJoint::getInitialPosition(size_t _index) const +double SingleDofJoint::getInitialPosition(std::size_t _index) const { if (_index != 0) { @@ -509,7 +509,7 @@ double SingleDofJoint::getInitialPosition(size_t _index) const //============================================================================== void SingleDofJoint::setInitialPositions(const Eigen::VectorXd& _initial) { - if( static_cast(_initial.size()) != getNumDofs() ) + if( static_cast(_initial.size()) != getNumDofs() ) { SINGLEDOFJOINT_REPORT_DIM_MISMATCH( setInitialPositions, _initial ); return; @@ -526,7 +526,7 @@ Eigen::VectorXd SingleDofJoint::getInitialPositions() const } //============================================================================== -void SingleDofJoint::setVelocity(size_t _index, double _velocity) +void SingleDofJoint::setVelocity(std::size_t _index, double _velocity) { if (_index != 0) { @@ -541,7 +541,7 @@ void SingleDofJoint::setVelocity(size_t _index, double _velocity) } //============================================================================== -double SingleDofJoint::getVelocity(size_t _index) const +double SingleDofJoint::getVelocity(std::size_t _index) const { if (_index != 0) { @@ -555,7 +555,7 @@ double SingleDofJoint::getVelocity(size_t _index) const //============================================================================== void SingleDofJoint::setVelocities(const Eigen::VectorXd& _velocities) { - if (static_cast(_velocities.size()) != getNumDofs()) + if (static_cast(_velocities.size()) != getNumDofs()) { SINGLEDOFJOINT_REPORT_DIM_MISMATCH( setVelocities, _velocities ); return; @@ -574,7 +574,7 @@ Eigen::VectorXd SingleDofJoint::getVelocities() const } //============================================================================== -void SingleDofJoint::setVelocityLowerLimit(size_t _index, double _velocity) +void SingleDofJoint::setVelocityLowerLimit(std::size_t _index, double _velocity) { if (_index != 0) { @@ -586,7 +586,7 @@ void SingleDofJoint::setVelocityLowerLimit(size_t _index, double _velocity) } //============================================================================== -double SingleDofJoint::getVelocityLowerLimit(size_t _index) const +double SingleDofJoint::getVelocityLowerLimit(std::size_t _index) const { if (_index != 0) { @@ -598,7 +598,7 @@ double SingleDofJoint::getVelocityLowerLimit(size_t _index) const } //============================================================================== -void SingleDofJoint::setVelocityUpperLimit(size_t _index, double _velocity) +void SingleDofJoint::setVelocityUpperLimit(std::size_t _index, double _velocity) { if (_index != 0) { @@ -610,7 +610,7 @@ void SingleDofJoint::setVelocityUpperLimit(size_t _index, double _velocity) } //============================================================================== -double SingleDofJoint::getVelocityUpperLimit(size_t _index) const +double SingleDofJoint::getVelocityUpperLimit(std::size_t _index) const { if (_index != 0) { @@ -622,7 +622,7 @@ double SingleDofJoint::getVelocityUpperLimit(size_t _index) const } //============================================================================== -void SingleDofJoint::resetVelocity(size_t _index) +void SingleDofJoint::resetVelocity(std::size_t _index) { if (_index != 0) { @@ -640,7 +640,7 @@ void SingleDofJoint::resetVelocities() } //============================================================================== -void SingleDofJoint::setInitialVelocity(size_t _index, double _initial) +void SingleDofJoint::setInitialVelocity(std::size_t _index, double _initial) { if (_index != 0) { @@ -652,7 +652,7 @@ void SingleDofJoint::setInitialVelocity(size_t _index, double _initial) } //============================================================================== -double SingleDofJoint::getInitialVelocity(size_t _index) const +double SingleDofJoint::getInitialVelocity(std::size_t _index) const { if (_index != 0) { @@ -666,7 +666,7 @@ double SingleDofJoint::getInitialVelocity(size_t _index) const //============================================================================== void SingleDofJoint::setInitialVelocities(const Eigen::VectorXd& _initial) { - if( static_cast(_initial.size()) != getNumDofs() ) + if( static_cast(_initial.size()) != getNumDofs() ) { SINGLEDOFJOINT_REPORT_DIM_MISMATCH( setInitialVelocities, _initial ); return; @@ -683,7 +683,7 @@ Eigen::VectorXd SingleDofJoint::getInitialVelocities() const } //============================================================================== -void SingleDofJoint::setAcceleration(size_t _index, double _acceleration) +void SingleDofJoint::setAcceleration(std::size_t _index, double _acceleration) { if (_index != 0) { @@ -698,7 +698,7 @@ void SingleDofJoint::setAcceleration(size_t _index, double _acceleration) } //============================================================================== -double SingleDofJoint::getAcceleration(size_t _index) const +double SingleDofJoint::getAcceleration(std::size_t _index) const { if (_index != 0) { @@ -712,7 +712,7 @@ double SingleDofJoint::getAcceleration(size_t _index) const //============================================================================== void SingleDofJoint::setAccelerations(const Eigen::VectorXd& _accelerations) { - if (static_cast(_accelerations.size()) != getNumDofs()) + if (static_cast(_accelerations.size()) != getNumDofs()) { SINGLEDOFJOINT_REPORT_DIM_MISMATCH( setAccelerations, _accelerations ); return; @@ -737,7 +737,7 @@ void SingleDofJoint::resetAccelerations() } //============================================================================== -void SingleDofJoint::setAccelerationLowerLimit(size_t _index, +void SingleDofJoint::setAccelerationLowerLimit(std::size_t _index, double _acceleration) { if (_index != 0) @@ -750,7 +750,7 @@ void SingleDofJoint::setAccelerationLowerLimit(size_t _index, } //============================================================================== -double SingleDofJoint::getAccelerationLowerLimit(size_t _index) const +double SingleDofJoint::getAccelerationLowerLimit(std::size_t _index) const { if (_index != 0) { @@ -762,7 +762,7 @@ double SingleDofJoint::getAccelerationLowerLimit(size_t _index) const } //============================================================================== -void SingleDofJoint::setAccelerationUpperLimit(size_t _index, +void SingleDofJoint::setAccelerationUpperLimit(std::size_t _index, double _acceleration) { if (_index != 0) @@ -775,7 +775,7 @@ void SingleDofJoint::setAccelerationUpperLimit(size_t _index, } //============================================================================== -double SingleDofJoint::getAccelerationUpperLimit(size_t _index) const +double SingleDofJoint::getAccelerationUpperLimit(std::size_t _index) const { if (_index != 0) { @@ -835,7 +835,7 @@ const double& SingleDofJoint::getAccelerationStatic() const } //============================================================================== -void SingleDofJoint::setForce(size_t _index, double _force) +void SingleDofJoint::setForce(std::size_t _index, double _force) { if (_index != 0) { @@ -850,7 +850,7 @@ void SingleDofJoint::setForce(size_t _index, double _force) } //============================================================================== -double SingleDofJoint::getForce(size_t _index) +double SingleDofJoint::getForce(std::size_t _index) { if (_index != 0) { @@ -864,7 +864,7 @@ double SingleDofJoint::getForce(size_t _index) //============================================================================== void SingleDofJoint::setForces(const Eigen::VectorXd& _forces) { - if (static_cast(_forces.size()) != getNumDofs()) + if (static_cast(_forces.size()) != getNumDofs()) { SINGLEDOFJOINT_REPORT_DIM_MISMATCH( setForces, _forces ); return; @@ -892,7 +892,7 @@ void SingleDofJoint::resetForces() } //============================================================================== -void SingleDofJoint::setForceLowerLimit(size_t _index, double _force) +void SingleDofJoint::setForceLowerLimit(std::size_t _index, double _force) { if (_index != 0) { @@ -904,7 +904,7 @@ void SingleDofJoint::setForceLowerLimit(size_t _index, double _force) } //============================================================================== -double SingleDofJoint::getForceLowerLimit(size_t _index) const +double SingleDofJoint::getForceLowerLimit(std::size_t _index) const { if (_index != 0) { @@ -916,7 +916,7 @@ double SingleDofJoint::getForceLowerLimit(size_t _index) const } //============================================================================== -void SingleDofJoint::setForceUpperLimit(size_t _index, double _force) +void SingleDofJoint::setForceUpperLimit(std::size_t _index, double _force) { if (_index != 0) { @@ -928,7 +928,7 @@ void SingleDofJoint::setForceUpperLimit(size_t _index, double _force) } //============================================================================== -double SingleDofJoint::getForceUpperLimit(size_t _index) const +double SingleDofJoint::getForceUpperLimit(std::size_t _index) const { if (_index != 0) { @@ -940,7 +940,7 @@ double SingleDofJoint::getForceUpperLimit(size_t _index) const } //============================================================================== -void SingleDofJoint::setVelocityChange(size_t _index, double _velocityChange) +void SingleDofJoint::setVelocityChange(std::size_t _index, double _velocityChange) { if (_index != 0) { @@ -952,7 +952,7 @@ void SingleDofJoint::setVelocityChange(size_t _index, double _velocityChange) } //============================================================================== -double SingleDofJoint::getVelocityChange(size_t _index) const +double SingleDofJoint::getVelocityChange(std::size_t _index) const { if (_index != 0) { @@ -970,7 +970,7 @@ void SingleDofJoint::resetVelocityChanges() } //============================================================================== -void SingleDofJoint::setConstraintImpulse(size_t _index, double _impulse) +void SingleDofJoint::setConstraintImpulse(std::size_t _index, double _impulse) { if (_index != 0) { @@ -982,7 +982,7 @@ void SingleDofJoint::setConstraintImpulse(size_t _index, double _impulse) } //============================================================================== -double SingleDofJoint::getConstraintImpulse(size_t _index) const +double SingleDofJoint::getConstraintImpulse(std::size_t _index) const { if (_index != 0) { @@ -1015,8 +1015,8 @@ void SingleDofJoint::integrateVelocities(double _dt) Eigen::VectorXd SingleDofJoint::getPositionDifferences( const Eigen::VectorXd& _q2, const Eigen::VectorXd& _q1) const { - if (static_cast(_q1.size()) != getNumDofs() - || static_cast(_q2.size()) != getNumDofs()) + if (static_cast(_q1.size()) != getNumDofs() + || static_cast(_q2.size()) != getNumDofs()) { dterr << "[SingleDofJoint::getPositionsDifference] q1's size [" << _q1.size() << "] and q2's size [" << _q2.size() << "] must both " @@ -1037,7 +1037,7 @@ double SingleDofJoint::getPositionDifferenceStatic(double _q2, } //============================================================================== -void SingleDofJoint::setSpringStiffness(size_t _index, double _k) +void SingleDofJoint::setSpringStiffness(std::size_t _index, double _k) { if (_index != 0) { @@ -1051,7 +1051,7 @@ void SingleDofJoint::setSpringStiffness(size_t _index, double _k) } //============================================================================== -double SingleDofJoint::getSpringStiffness(size_t _index) const +double SingleDofJoint::getSpringStiffness(std::size_t _index) const { if (_index != 0) { @@ -1063,7 +1063,7 @@ double SingleDofJoint::getSpringStiffness(size_t _index) const } //============================================================================== -void SingleDofJoint::setRestPosition(size_t _index, double _q0) +void SingleDofJoint::setRestPosition(std::size_t _index, double _q0) { if (_index != 0) { @@ -1087,7 +1087,7 @@ void SingleDofJoint::setRestPosition(size_t _index, double _q0) } //============================================================================== -double SingleDofJoint::getRestPosition(size_t _index) const +double SingleDofJoint::getRestPosition(std::size_t _index) const { if (_index != 0) { @@ -1099,7 +1099,7 @@ double SingleDofJoint::getRestPosition(size_t _index) const } //============================================================================== -void SingleDofJoint::setDampingCoefficient(size_t _index, double _d) +void SingleDofJoint::setDampingCoefficient(std::size_t _index, double _d) { if (_index != 0) { @@ -1113,7 +1113,7 @@ void SingleDofJoint::setDampingCoefficient(size_t _index, double _d) } //============================================================================== -double SingleDofJoint::getDampingCoefficient(size_t _index) const +double SingleDofJoint::getDampingCoefficient(std::size_t _index) const { if (_index != 0) { @@ -1125,7 +1125,7 @@ double SingleDofJoint::getDampingCoefficient(size_t _index) const } //============================================================================== -void SingleDofJoint::setCoulombFriction(size_t _index, double _friction) +void SingleDofJoint::setCoulombFriction(std::size_t _index, double _friction) { if (_index != 0) { @@ -1139,7 +1139,7 @@ void SingleDofJoint::setCoulombFriction(size_t _index, double _friction) } //============================================================================== -double SingleDofJoint::getCoulombFriction(size_t _index) const +double SingleDofJoint::getCoulombFriction(std::size_t _index) const { if (_index != 0) { @@ -2003,7 +2003,7 @@ void SingleDofJoint::updateTotalForceForInvMassMatrix( //============================================================================== void SingleDofJoint::getInvMassMatrixSegment(Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) { @@ -2017,7 +2017,7 @@ void SingleDofJoint::getInvMassMatrixSegment(Eigen::MatrixXd& _invMassMat, assert(!math::isNan(mInvMassMatrixSegment)); // Index - size_t iStart = mDof->mIndexInTree; + std::size_t iStart = mDof->mIndexInTree; // Assign _invMassMat(iStart, _col) = mInvMassMatrixSegment; @@ -2026,7 +2026,7 @@ void SingleDofJoint::getInvMassMatrixSegment(Eigen::MatrixXd& _invMassMat, //============================================================================== void SingleDofJoint::getInvAugMassMatrixSegment( Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) { @@ -2040,7 +2040,7 @@ void SingleDofJoint::getInvAugMassMatrixSegment( assert(!math::isNan(mInvMassMatrixSegment)); // Index - size_t iStart = mDof->mIndexInTree; + std::size_t iStart = mDof->mIndexInTree; // Assign _invMassMat(iStart, _col) = mInvMassMatrixSegment; diff --git a/dart/dynamics/SingleDofJoint.h b/dart/dynamics/SingleDofJoint.h index 5e88facb49fce..acfbdef90ccb6 100644 --- a/dart/dynamics/SingleDofJoint.h +++ b/dart/dynamics/SingleDofJoint.h @@ -87,43 +87,43 @@ class SingleDofJoint : public detail::SingleDofJointBase SingleDofJoint& operator=(const SingleDofJoint& _otherJoint); // Documentation inherited - DegreeOfFreedom* getDof(size_t _index) override; + DegreeOfFreedom* getDof(std::size_t _index) override; // Documentation inherited - const DegreeOfFreedom* getDof(size_t _index) const override; + const DegreeOfFreedom* getDof(std::size_t _index) const override; // Documentation inherted - const std::string& setDofName(size_t _index, + const std::string& setDofName(std::size_t _index, const std::string& _name, bool _preserveName=true) override; // Documentation inherited - void preserveDofName(size_t _index, bool _preserve) override; + void preserveDofName(std::size_t _index, bool _preserve) override; // Documentation inherited - bool isDofNamePreserved(size_t _index) const override; + bool isDofNamePreserved(std::size_t _index) const override; // Documentation inherited - const std::string& getDofName(size_t _index) const override; + const std::string& getDofName(std::size_t _index) const override; // Documentation inherited - size_t getNumDofs() const override; + std::size_t getNumDofs() const override; // Documentation inherited - size_t getIndexInSkeleton(size_t _index) const override; + std::size_t getIndexInSkeleton(std::size_t _index) const override; // Documentation inherited - size_t getIndexInTree(size_t _index) const override; + std::size_t getIndexInTree(std::size_t _index) const override; //---------------------------------------------------------------------------- // Command //---------------------------------------------------------------------------- // Documentation inherited - void setCommand(size_t _index, double _command) override; + void setCommand(std::size_t _index, double _command) override; // Documentation inherited - double getCommand(size_t _index) const override; + double getCommand(std::size_t _index) const override; // Documentation inherited void setCommands(const Eigen::VectorXd& _commands) override; @@ -141,10 +141,10 @@ class SingleDofJoint : public detail::SingleDofJointBase // TODO(JS): Not to use Eigen::VectorXd // Documentation inherited - void setPosition(size_t _index, double _position) override; + void setPosition(std::size_t _index, double _position) override; // Documentation inherited - double getPosition(size_t _index) const override; + double getPosition(std::size_t _index) const override; // Documentation inherited void setPositions(const Eigen::VectorXd& _positions) override; @@ -153,31 +153,31 @@ class SingleDofJoint : public detail::SingleDofJointBase Eigen::VectorXd getPositions() const override; // Documentation inherited - void setPositionLowerLimit(size_t _index, double _position) override; + void setPositionLowerLimit(std::size_t _index, double _position) override; // Documentation inherited - double getPositionLowerLimit(size_t _index) const override; + double getPositionLowerLimit(std::size_t _index) const override; // Documentation inherited - void setPositionUpperLimit(size_t _index, double _position) override; + void setPositionUpperLimit(std::size_t _index, double _position) override; // Documentation inherited - double getPositionUpperLimit(size_t _index) const override; + double getPositionUpperLimit(std::size_t _index) const override; // Documentation inherited - bool hasPositionLimit(size_t _index) const override; + bool hasPositionLimit(std::size_t _index) const override; // Documentation inherited - void resetPosition(size_t _index) override; + void resetPosition(std::size_t _index) override; // Documentation inherited void resetPositions() override; // Documentation inherited - void setInitialPosition(size_t _index, double _initial) override; + void setInitialPosition(std::size_t _index, double _initial) override; // Documentation inherited - double getInitialPosition(size_t _index) const override; + double getInitialPosition(std::size_t _index) const override; // Documentation inherited void setInitialPositions(const Eigen::VectorXd& _initial) override; @@ -190,10 +190,10 @@ class SingleDofJoint : public detail::SingleDofJointBase //---------------------------------------------------------------------------- // Documentation inherited - void setVelocity(size_t _index, double _velocity) override; + void setVelocity(std::size_t _index, double _velocity) override; // Documentation inherited - double getVelocity(size_t _index) const override; + double getVelocity(std::size_t _index) const override; // Documentation inherited void setVelocities(const Eigen::VectorXd& _velocities) override; @@ -202,28 +202,28 @@ class SingleDofJoint : public detail::SingleDofJointBase Eigen::VectorXd getVelocities() const override; // Documentation inherited - void setVelocityLowerLimit(size_t _index, double _velocity) override; + void setVelocityLowerLimit(std::size_t _index, double _velocity) override; // Documentation inherited - double getVelocityLowerLimit(size_t _index) const override; + double getVelocityLowerLimit(std::size_t _index) const override; // Documentation inherited - void setVelocityUpperLimit(size_t _index, double _velocity) override; + void setVelocityUpperLimit(std::size_t _index, double _velocity) override; // Documentation inherited - double getVelocityUpperLimit(size_t _index) const override; + double getVelocityUpperLimit(std::size_t _index) const override; // Documentation inherited - void resetVelocity(size_t _index) override; + void resetVelocity(std::size_t _index) override; // Documentation inherited void resetVelocities() override; // Documentation inherited - void setInitialVelocity(size_t _index, double _initial) override; + void setInitialVelocity(std::size_t _index, double _initial) override; // Documentation inherited - double getInitialVelocity(size_t _index) const override; + double getInitialVelocity(std::size_t _index) const override; // Documentation inherited void setInitialVelocities(const Eigen::VectorXd& _initial) override; @@ -236,10 +236,10 @@ class SingleDofJoint : public detail::SingleDofJointBase //---------------------------------------------------------------------------- // Documentation inherited - void setAcceleration(size_t _index, double _acceleration) override; + void setAcceleration(std::size_t _index, double _acceleration) override; // Documentation inherited - double getAcceleration(size_t _index) const override; + double getAcceleration(std::size_t _index) const override; // Documentation inherited void setAccelerations(const Eigen::VectorXd& _accelerations) override; @@ -251,16 +251,16 @@ class SingleDofJoint : public detail::SingleDofJointBase void resetAccelerations() override; // Documentation inherited - void setAccelerationLowerLimit(size_t _index, double _acceleration) override; + void setAccelerationLowerLimit(std::size_t _index, double _acceleration) override; // Documentation inherited - double getAccelerationLowerLimit(size_t _index) const override; + double getAccelerationLowerLimit(std::size_t _index) const override; // Documentation inherited - void setAccelerationUpperLimit(size_t _index, double _acceleration) override; + void setAccelerationUpperLimit(std::size_t _index, double _acceleration) override; // Documentation inherited - double getAccelerationUpperLimit(size_t _index) const override; + double getAccelerationUpperLimit(std::size_t _index) const override; //---------------------------------------------------------------------------- // Fixed-size mutators and accessors @@ -295,10 +295,10 @@ class SingleDofJoint : public detail::SingleDofJointBase //---------------------------------------------------------------------------- // Documentation inherited - void setForce(size_t _index, double _force) override; + void setForce(std::size_t _index, double _force) override; // Documentation inherited - double getForce(size_t _index) override; + double getForce(std::size_t _index) override; // Documentation inherited void setForces(const Eigen::VectorXd& _forces) override; @@ -310,26 +310,26 @@ class SingleDofJoint : public detail::SingleDofJointBase void resetForces() override; // Documentation inherited - void setForceLowerLimit(size_t _index, double _force) override; + void setForceLowerLimit(std::size_t _index, double _force) override; // Documentation inherited - double getForceLowerLimit(size_t _index) const override; + double getForceLowerLimit(std::size_t _index) const override; // Documentation inherited - void setForceUpperLimit(size_t _index, double _force) override; + void setForceUpperLimit(std::size_t _index, double _force) override; // Documentation inherited - double getForceUpperLimit(size_t _index) const override; + double getForceUpperLimit(std::size_t _index) const override; //---------------------------------------------------------------------------- // Velocity change //---------------------------------------------------------------------------- // Documentation inherited - void setVelocityChange(size_t _index, double _velocityChange) override; + void setVelocityChange(std::size_t _index, double _velocityChange) override; // Documentation inherited - double getVelocityChange(size_t _index) const override; + double getVelocityChange(std::size_t _index) const override; // Documentation inherited void resetVelocityChanges() override; @@ -339,10 +339,10 @@ class SingleDofJoint : public detail::SingleDofJointBase //---------------------------------------------------------------------------- // Documentation inherited - void setConstraintImpulse(size_t _index, double _impulse) override; + void setConstraintImpulse(std::size_t _index, double _impulse) override; // Documentation inherited - double getConstraintImpulse(size_t _index) const override; + double getConstraintImpulse(std::size_t _index) const override; // Documentation inherited void resetConstraintImpulses() override; @@ -369,28 +369,28 @@ class SingleDofJoint : public detail::SingleDofJointBase //---------------------------------------------------------------------------- // Documentation inherited - void setSpringStiffness(size_t _index, double _k) override; + void setSpringStiffness(std::size_t _index, double _k) override; // Documentation inherited - double getSpringStiffness(size_t _index) const override; + double getSpringStiffness(std::size_t _index) const override; // Documentation inherited - void setRestPosition(size_t _index, double _q0) override; + void setRestPosition(std::size_t _index, double _q0) override; // Documentation inherited - double getRestPosition(size_t _index) const override; + double getRestPosition(std::size_t _index) const override; // Documentation inherited - void setDampingCoefficient(size_t _index, double _d) override; + void setDampingCoefficient(std::size_t _index, double _d) override; // Documentation inherited - double getDampingCoefficient(size_t _index) const override; + double getDampingCoefficient(std::size_t _index) const override; // Documentation inherited - void setCoulombFriction(size_t _index, double _friction) override; + void setCoulombFriction(std::size_t _index, double _friction) override; // Documentation inherited - double getCoulombFriction(size_t _index) const override; + double getCoulombFriction(std::size_t _index) const override; /// \} @@ -565,14 +565,14 @@ class SingleDofJoint : public detail::SingleDofJointBase // Documentation inherited void getInvMassMatrixSegment( Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) override; // Documentation inherited void getInvAugMassMatrixSegment( Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) override; diff --git a/dart/dynamics/Skeleton.cpp b/dart/dynamics/Skeleton.cpp index 3c10a6ae9d2fc..84400c731f374 100644 --- a/dart/dynamics/Skeleton.cpp +++ b/dart/dynamics/Skeleton.cpp @@ -63,7 +63,7 @@ #define SET_FLAG( Y, X ) mTreeCache[ Y ].mDirty. X = true; \ mSkelCache.mDirty. X = true; -#define ON_ALL_TREES( X ) for(size_t i=0; i < mTreeCache.size(); ++i) X (i); +#define ON_ALL_TREES( X ) for(std::size_t i=0; i < mTreeCache.size(); ++i) X (i); #define CHECK_CONFIG_VECTOR_SIZE( V ) \ @@ -98,8 +98,8 @@ namespace detail { // TODO(MXG): Consider putting this in an accessible header if it might be // useful in other places. template void setAllMemberObjectData(Owner* owner, const std::vector& data) { @@ -113,7 +113,7 @@ void setAllMemberObjectData(Owner* owner, const std::vector& data) return; } - size_t numObjects = (owner->*getNumObjects)(); + std::size_t numObjects = (owner->*getNumObjects)(); if(data.size() != numObjects) { @@ -128,7 +128,7 @@ void setAllMemberObjectData(Owner* owner, const std::vector& data) numObjects = std::min(numObjects, data.size()); } - for(size_t i=0; i < numObjects; ++i) + for(std::size_t i=0; i < numObjects; ++i) ((owner->*getObject)(i)->*setData)(data[i]); } @@ -143,8 +143,8 @@ void setAllMemberObjectData(Owner* owner, const std::vector& data) // TODO(MXG): Consider putting this in an accessible header if it might be // useful in other places. template std::vector getAllMemberObjectData(const Owner* owner) { @@ -158,11 +158,11 @@ std::vector getAllMemberObjectData(const Owner* owner) return std::vector(); } - const size_t numObjects = (owner->*getNumObjects)(); + const std::size_t numObjects = (owner->*getNumObjects)(); std::vector data; data.reserve(numObjects); - for(size_t i=0; i < numObjects; ++i) + for(std::size_t i=0; i < numObjects; ++i) data.push_back(((owner->*getObject)(i)->*getData)()); return data; @@ -275,7 +275,7 @@ Skeleton::Configuration::Configuration( mForces(forces), mCommands(commands) { - size_t nonzero_size = INVALID_INDEX; + std::size_t nonzero_size = INVALID_INDEX; CHECK_CONFIG_VECTOR_SIZE(positions); CHECK_CONFIG_VECTOR_SIZE(velocities); @@ -285,14 +285,14 @@ Skeleton::Configuration::Configuration( if(nonzero_size != INVALID_INDEX) { - for(size_t i=0; i < nonzero_size; ++i) + for(std::size_t i=0; i < nonzero_size; ++i) mIndices.push_back(i); } } //============================================================================== Skeleton::Configuration::Configuration( - const std::vector& indices, + const std::vector& indices, const Eigen::VectorXd& positions, const Eigen::VectorXd& velocities, const Eigen::VectorXd& accelerations, @@ -305,7 +305,7 @@ Skeleton::Configuration::Configuration( mForces(forces), mCommands(commands) { - size_t nonzero_size = indices.size(); + std::size_t nonzero_size = indices.size(); CHECK_CONFIG_VECTOR_SIZE(positions); CHECK_CONFIG_VECTOR_SIZE(velocities); @@ -404,7 +404,7 @@ SkeletonPtr Skeleton::clone(const std::string& cloneName) const { SkeletonPtr skelClone = Skeleton::create(cloneName); - for(size_t i=0; iclone(); @@ -486,8 +486,8 @@ void Skeleton::setConfiguration(const Configuration& configuration) //============================================================================== Skeleton::Configuration Skeleton::getConfiguration(int flags) const { - std::vector indices; - for(size_t i=0; i < getNumDofs(); ++i) + std::vector indices; + for(std::size_t i=0; i < getNumDofs(); ++i) indices.push_back(i); return getConfiguration(indices, flags); @@ -495,7 +495,7 @@ Skeleton::Configuration Skeleton::getConfiguration(int flags) const //============================================================================== Skeleton::Configuration Skeleton::getConfiguration( - const std::vector& indices, int flags) const + const std::vector& indices, int flags) const { Configuration config(indices); if(flags == CONFIG_NOTHING) @@ -639,14 +639,14 @@ void Skeleton::addEntryToSoftBodyNodeNameMgr(SoftBodyNode* _newNode) //============================================================================== void Skeleton::addMarkersOfBodyNode(BodyNode* _node) { - for (size_t i=0; i<_node->getNumMarkers(); ++i) + for (std::size_t i=0; i<_node->getNumMarkers(); ++i) addEntryToMarkerNameMgr(_node->getMarker(i)); } //============================================================================== void Skeleton::removeMarkersOfBodyNode(BodyNode* _node) { - for (size_t i=0; i<_node->getNumMarkers(); ++i) + for (std::size_t i=0; i<_node->getNumMarkers(); ++i) mNameMgrForMarkers.removeName(_node->getMarker(i)->getName()); } @@ -702,7 +702,7 @@ void Skeleton::setTimeStep(double _timeStep) assert(_timeStep > 0.0); mAspectProperties.mTimeStep = _timeStep; - for(size_t i=0; i _treeIdx) return mTreeCache[_treeIdx].mBodyNodes[0]; @@ -775,34 +775,34 @@ BodyNode* Skeleton::getRootBodyNode(size_t _treeIdx) } //============================================================================== -const BodyNode* Skeleton::getRootBodyNode(size_t _treeIdx) const +const BodyNode* Skeleton::getRootBodyNode(std::size_t _treeIdx) const { return const_cast(this)->getRootBodyNode(_treeIdx); } //============================================================================== -BodyNode* Skeleton::getBodyNode(size_t _idx) +BodyNode* Skeleton::getBodyNode(std::size_t _idx) { return common::getVectorObjectIfAvailable( _idx, mSkelCache.mBodyNodes); } //============================================================================== -const BodyNode* Skeleton::getBodyNode(size_t _idx) const +const BodyNode* Skeleton::getBodyNode(std::size_t _idx) const { return common::getVectorObjectIfAvailable( _idx, mSkelCache.mBodyNodes); } //============================================================================== -SoftBodyNode* Skeleton::getSoftBodyNode(size_t _idx) +SoftBodyNode* Skeleton::getSoftBodyNode(std::size_t _idx) { return common::getVectorObjectIfAvailable( _idx, mSoftBodyNodes); } //============================================================================== -const SoftBodyNode* Skeleton::getSoftBodyNode(size_t _idx) const +const SoftBodyNode* Skeleton::getSoftBodyNode(std::size_t _idx) const { return common::getVectorObjectIfAvailable( _idx, mSoftBodyNodes); @@ -838,7 +838,7 @@ static std::vector& convertToConstPtrVector( const std::vector& vec, std::vector& const_vec) { const_vec.resize(vec.size()); - for(size_t i=0; i& Skeleton::getBodyNodes() const } //============================================================================== -template -static size_t templatedGetIndexOf(const Skeleton* _skel, const ObjectT* _obj, +template +static std::size_t templatedGetIndexOf(const Skeleton* _skel, const ObjectT* _obj, const std::string& _type, bool _warning) { if(nullptr == _obj) @@ -888,18 +888,18 @@ static size_t templatedGetIndexOf(const Skeleton* _skel, const ObjectT* _obj, } //============================================================================== -size_t Skeleton::getIndexOf(const BodyNode* _bn, bool _warning) const +std::size_t Skeleton::getIndexOf(const BodyNode* _bn, bool _warning) const { return templatedGetIndexOf( this, _bn, "BodyNode", _warning); } //============================================================================== -const std::vector& Skeleton::getTreeBodyNodes(size_t _treeIdx) +const std::vector& Skeleton::getTreeBodyNodes(std::size_t _treeIdx) { if(_treeIdx >= mTreeCache.size()) { - size_t count = mTreeCache.size(); + std::size_t count = mTreeCache.size(); dterr << "[Skeleton::getTreeBodyNodes] Requesting an invalid tree (" << _treeIdx << ") " << (count > 0? (std::string("when the max tree index is (") + std::to_string(count-1) + ")\n" ) : @@ -911,21 +911,21 @@ const std::vector& Skeleton::getTreeBodyNodes(size_t _treeIdx) } //============================================================================== -std::vector Skeleton::getTreeBodyNodes(size_t _treeIdx) const +std::vector Skeleton::getTreeBodyNodes(std::size_t _treeIdx) const { return convertToConstPtrVector( mTreeCache[_treeIdx].mBodyNodes, mTreeCache[_treeIdx].mConstBodyNodes); } //============================================================================== -size_t Skeleton::getNumJoints() const +std::size_t Skeleton::getNumJoints() const { // The number of joints and body nodes are identical return getNumBodyNodes(); } //============================================================================== -Joint* Skeleton::getJoint(size_t _idx) +Joint* Skeleton::getJoint(std::size_t _idx) { BodyNode* bn = common::getVectorObjectIfAvailable( _idx, mSkelCache.mBodyNodes); @@ -936,7 +936,7 @@ Joint* Skeleton::getJoint(size_t _idx) } //============================================================================== -const Joint* Skeleton::getJoint(size_t _idx) const +const Joint* Skeleton::getJoint(std::size_t _idx) const { return const_cast(this)->getJoint(_idx); } @@ -954,27 +954,27 @@ const Joint* Skeleton::getJoint(const std::string& _name) const } //============================================================================== -size_t Skeleton::getIndexOf(const Joint* _joint, bool _warning) const +std::size_t Skeleton::getIndexOf(const Joint* _joint, bool _warning) const { return templatedGetIndexOf( this, _joint, "Joint", _warning); } //============================================================================== -size_t Skeleton::getNumDofs() const +std::size_t Skeleton::getNumDofs() const { return mSkelCache.mDofs.size(); } //============================================================================== -DegreeOfFreedom* Skeleton::getDof(size_t _idx) +DegreeOfFreedom* Skeleton::getDof(std::size_t _idx) { return common::getVectorObjectIfAvailable( _idx, mSkelCache.mDofs); } //============================================================================== -const DegreeOfFreedom* Skeleton::getDof(size_t _idx) const +const DegreeOfFreedom* Skeleton::getDof(std::size_t _idx) const { return common::getVectorObjectIfAvailable( _idx, mSkelCache.mDofs); @@ -1006,7 +1006,7 @@ std::vector Skeleton::getDofs() const } //============================================================================== -size_t Skeleton::getIndexOf(const DegreeOfFreedom* _dof, bool _warning) const +std::size_t Skeleton::getIndexOf(const DegreeOfFreedom* _dof, bool _warning) const { return templatedGetIndexOf( @@ -1014,14 +1014,14 @@ size_t Skeleton::getIndexOf(const DegreeOfFreedom* _dof, bool _warning) const } //============================================================================== -const std::vector& Skeleton::getTreeDofs(size_t _treeIdx) +const std::vector& Skeleton::getTreeDofs(std::size_t _treeIdx) { return mTreeCache[_treeIdx].mDofs; } //============================================================================== const std::vector& Skeleton::getTreeDofs( - size_t _treeIdx) const + std::size_t _treeIdx) const { return convertToConstPtrVector( mTreeCache[_treeIdx].mDofs, mTreeCache[_treeIdx].mConstDofs); @@ -1033,7 +1033,7 @@ bool Skeleton::checkIndexingConsistency() const bool consistent = true; // Check each BodyNode in the Skeleton cache - for(size_t i=0; imIndexInSkeleton != i) @@ -1078,7 +1078,7 @@ bool Skeleton::checkIndexingConsistency() const for(const auto& nodeType : nodeMap) { const std::vector& nodes = nodeType.second; - for(size_t k=0; k < nodes.size(); ++k) + for(std::size_t k=0; k < nodes.size(); ++k) { const Node* node = nodes[k]; if(node->getBodyNodePtr() != bn) @@ -1111,7 +1111,7 @@ bool Skeleton::checkIndexingConsistency() const } // Check DegreesOfFreedom indexing - for(size_t i=0; i < getNumDofs(); ++i) + for(std::size_t i=0; i < getNumDofs(); ++i) { const DegreeOfFreedom* dof = getDof(i); if(dof->getIndexInSkeleton() != i) @@ -1145,7 +1145,7 @@ bool Skeleton::checkIndexingConsistency() const for(const auto& nodeType : nodeMap) { const std::vector& nodes = nodeType.second; - for(size_t k=0; k < nodes.size(); ++k) + for(std::size_t k=0; k < nodes.size(); ++k) { const Node* node = nodes[k]; if(node->getSkeleton().get() != this) @@ -1176,10 +1176,10 @@ bool Skeleton::checkIndexingConsistency() const } // Check each BodyNode in each Tree cache - for(size_t i=0; imTreeIndex != i) @@ -1205,7 +1205,7 @@ bool Skeleton::checkIndexingConsistency() const } } - for(size_t j=0; j < cache.mDofs.size(); ++j) + for(std::size_t j=0; j < cache.mDofs.size(); ++j) { const DegreeOfFreedom* dof = cache.mDofs[j]; if(dof->getTreeIndex() != i) @@ -1234,14 +1234,14 @@ bool Skeleton::checkIndexingConsistency() const } // Check each Node in the NodeMap of each Tree - for(size_t i=0; i < mTreeNodeMaps.size(); ++i) + for(std::size_t i=0; i < mTreeNodeMaps.size(); ++i) { const NodeMap& nodeMap = mTreeNodeMaps[i]; for(const auto& nodeType : nodeMap) { const std::vector& nodes = nodeType.second; - for(size_t k=0; k < nodes.size(); ++k) + for(std::size_t k=0; k < nodes.size(); ++k) { const Node* node = nodes[k]; if(node->getBodyNodePtr()->mTreeIndex != i) @@ -1309,7 +1309,7 @@ void Skeleton::clearIK() } //============================================================================== -size_t Skeleton::getNumMarkers() const +std::size_t Skeleton::getNumMarkers() const { return mNameMgrForMarkers.getCount(); } @@ -1335,12 +1335,12 @@ DART_BAKE_SPECIALIZED_NODE_SKEL_DEFINITIONS( Skeleton, EndEffector ) //============================================================================== void Skeleton::integratePositions(double _dt) { - for (size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) + for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) mSkelCache.mBodyNodes[i]->getParentJoint()->integratePositions(_dt); - for (size_t i = 0; i < mSoftBodyNodes.size(); ++i) + for (std::size_t i = 0; i < mSoftBodyNodes.size(); ++i) { - for (size_t j = 0; j < mSoftBodyNodes[i]->getNumPointMasses(); ++j) + for (std::size_t j = 0; j < mSoftBodyNodes[i]->getNumPointMasses(); ++j) mSoftBodyNodes[i]->getPointMass(j)->integratePositions(_dt); } } @@ -1348,12 +1348,12 @@ void Skeleton::integratePositions(double _dt) //============================================================================== void Skeleton::integrateVelocities(double _dt) { - for (size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) + for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) mSkelCache.mBodyNodes[i]->getParentJoint()->integrateVelocities(_dt); - for (size_t i = 0; i < mSoftBodyNodes.size(); ++i) + for (std::size_t i = 0; i < mSoftBodyNodes.size(); ++i) { - for (size_t j = 0; j < mSoftBodyNodes[i]->getNumPointMasses(); ++j) + for (std::size_t j = 0; j < mSoftBodyNodes[i]->getNumPointMasses(); ++j) mSoftBodyNodes[i]->getPointMass(j)->integrateVelocities(_dt); } } @@ -1362,8 +1362,8 @@ void Skeleton::integrateVelocities(double _dt) Eigen::VectorXd Skeleton::getPositionDifferences( const Eigen::VectorXd& _q2, const Eigen::VectorXd& _q1) const { - if (static_cast(_q2.size()) != getNumDofs() - || static_cast(_q1.size()) != getNumDofs()) + if (static_cast(_q2.size()) != getNumDofs() + || static_cast(_q1.size()) != getNumDofs()) { dterr << "Skeleton::getPositionsDifference: q1's size[" << _q1.size() << "] or q2's size[" << _q2.size() << "is different with the dof [" @@ -1376,11 +1376,11 @@ Eigen::VectorXd Skeleton::getPositionDifferences( for (const auto& bodyNode : mSkelCache.mBodyNodes) { const Joint* joint = bodyNode->getParentJoint(); - const size_t dof = joint->getNumDofs(); + const std::size_t dof = joint->getNumDofs(); if (dof) { - size_t index = joint->getDof(0)->getIndexInSkeleton(); + std::size_t index = joint->getDof(0)->getIndexInSkeleton(); const Eigen::VectorXd& q2Seg = _q2.segment(index, dof); const Eigen::VectorXd& q1Seg = _q1.segment(index, dof); dq.segment(index, dof) = joint->getPositionDifferences(q2Seg, q1Seg); @@ -1394,8 +1394,8 @@ Eigen::VectorXd Skeleton::getPositionDifferences( Eigen::VectorXd Skeleton::getVelocityDifferences( const Eigen::VectorXd& _dq2, const Eigen::VectorXd& _dq1) const { - if (static_cast(_dq2.size()) != getNumDofs() - || static_cast(_dq1.size()) != getNumDofs()) + if (static_cast(_dq2.size()) != getNumDofs() + || static_cast(_dq1.size()) != getNumDofs()) { dterr << "Skeleton::getPositionsDifference: dq1's size[" << _dq1.size() << "] or dq2's size[" << _dq2.size() << "is different with the dof [" @@ -1441,7 +1441,7 @@ void assignJacobian(JacobianType& _J, const JacobianType& _JBodyNode) { // Assign the BodyNode's Jacobian to the result Jacobian. - size_t localIndex = 0; + std::size_t localIndex = 0; const auto& indices = _node->getDependentGenCoordIndices(); for (const auto& index : indices) { @@ -1754,7 +1754,7 @@ double Skeleton::getMass() const } //============================================================================== -const Eigen::MatrixXd& Skeleton::getMassMatrix(size_t _treeIdx) const +const Eigen::MatrixXd& Skeleton::getMassMatrix(std::size_t _treeIdx) const { if (mTreeCache[_treeIdx].mDirty.mMassMatrix) updateMassMatrix(_treeIdx); @@ -1770,7 +1770,7 @@ const Eigen::MatrixXd& Skeleton::getMassMatrix() const } //============================================================================== -const Eigen::MatrixXd& Skeleton::getAugMassMatrix(size_t _treeIdx) const +const Eigen::MatrixXd& Skeleton::getAugMassMatrix(std::size_t _treeIdx) const { if (mTreeCache[_treeIdx].mDirty.mAugMassMatrix) updateAugMassMatrix(_treeIdx); @@ -1788,7 +1788,7 @@ const Eigen::MatrixXd& Skeleton::getAugMassMatrix() const } //============================================================================== -const Eigen::MatrixXd& Skeleton::getInvMassMatrix(size_t _treeIdx) const +const Eigen::MatrixXd& Skeleton::getInvMassMatrix(std::size_t _treeIdx) const { if (mTreeCache[_treeIdx].mDirty.mInvMassMatrix) updateInvMassMatrix(_treeIdx); @@ -1806,7 +1806,7 @@ const Eigen::MatrixXd& Skeleton::getInvMassMatrix() const } //============================================================================== -const Eigen::MatrixXd& Skeleton::getInvAugMassMatrix(size_t _treeIdx) const +const Eigen::MatrixXd& Skeleton::getInvAugMassMatrix(std::size_t _treeIdx) const { if (mTreeCache[_treeIdx].mDirty.mInvAugMassMatrix) updateInvAugMassMatrix(_treeIdx); @@ -1824,7 +1824,7 @@ const Eigen::MatrixXd& Skeleton::getInvAugMassMatrix() const } //============================================================================== -const Eigen::VectorXd& Skeleton::getCoriolisForces(size_t _treeIdx) const +const Eigen::VectorXd& Skeleton::getCoriolisForces(std::size_t _treeIdx) const { if (mTreeCache[_treeIdx].mDirty.mCoriolisForces) updateCoriolisForces(_treeIdx); @@ -1842,7 +1842,7 @@ const Eigen::VectorXd& Skeleton::getCoriolisForces() const } //============================================================================== -const Eigen::VectorXd& Skeleton::getGravityForces(size_t _treeIdx) const +const Eigen::VectorXd& Skeleton::getGravityForces(std::size_t _treeIdx) const { if (mTreeCache[_treeIdx].mDirty.mGravityForces) updateGravityForces(_treeIdx); @@ -1860,7 +1860,7 @@ const Eigen::VectorXd& Skeleton::getGravityForces() const } //============================================================================== -const Eigen::VectorXd& Skeleton::getCoriolisAndGravityForces(size_t _treeIdx) const +const Eigen::VectorXd& Skeleton::getCoriolisAndGravityForces(std::size_t _treeIdx) const { if (mTreeCache[_treeIdx].mDirty.mCoriolisAndGravityForces) updateCoriolisAndGravityForces(_treeIdx); @@ -1878,7 +1878,7 @@ const Eigen::VectorXd& Skeleton::getCoriolisAndGravityForces() const } //============================================================================== -const Eigen::VectorXd& Skeleton::getExternalForces(size_t _treeIdx) const +const Eigen::VectorXd& Skeleton::getExternalForces(std::size_t _treeIdx) const { if (mTreeCache[_treeIdx].mDirty.mExternalForces) updateExternalForces(_treeIdx); @@ -1896,7 +1896,7 @@ const Eigen::VectorXd& Skeleton::getExternalForces() const } //============================================================================== -const Eigen::VectorXd& Skeleton::getConstraintForces(size_t _treeIdx) const +const Eigen::VectorXd& Skeleton::getConstraintForces(std::size_t _treeIdx) const { return computeConstraintForces(mTreeCache[_treeIdx]); } @@ -1982,7 +1982,7 @@ void Skeleton::registerBodyNode(BodyNode* _newBodyNode) } else { - size_t tree = _newBodyNode->getParentBodyNode()->getTreeIndex(); + std::size_t tree = _newBodyNode->getParentBodyNode()->getTreeIndex(); _newBodyNode->mTreeIndex = tree; DataCache& cache = mTreeCache[tree]; cache.mBodyNodes.push_back(_newBodyNode); @@ -2012,7 +2012,7 @@ void Skeleton::registerBodyNode(BodyNode* _newBodyNode) updateCacheDimensions(_newBodyNode->mTreeIndex); #ifndef NDEBUG // Debug mode - for(size_t i=0; imIndexInSkeleton != i) { @@ -2025,10 +2025,10 @@ void Skeleton::registerBodyNode(BodyNode* _newBodyNode) } } - for(size_t i=0; imTreeIndex != i) @@ -2070,9 +2070,9 @@ void Skeleton::registerJoint(Joint* _newJoint) addEntryToJointNameMgr(_newJoint); _newJoint->registerDofs(); - size_t tree = _newJoint->getChildBodyNode()->getTreeIndex(); + std::size_t tree = _newJoint->getChildBodyNode()->getTreeIndex(); std::vector& treeDofs = mTreeCache[tree].mDofs; - for(size_t i = 0; i < _newJoint->getNumDofs(); ++i) + for(std::size_t i = 0; i < _newJoint->getNumDofs(); ++i) { mSkelCache.mDofs.push_back(_newJoint->getDof(i)); _newJoint->getDof(i)->mIndexInSkeleton = mSkelCache.mDofs.size()-1; @@ -2083,7 +2083,7 @@ void Skeleton::registerJoint(Joint* _newJoint) } //============================================================================== -void Skeleton::registerNode(NodeMap& nodeMap, Node* _newNode, size_t& _index) +void Skeleton::registerNode(NodeMap& nodeMap, Node* _newNode, std::size_t& _index) { NodeMap::iterator it = nodeMap.find(typeid(*_newNode)); @@ -2132,7 +2132,7 @@ void Skeleton::registerNode(Node* _newNode) } //============================================================================== -void Skeleton::destructOldTree(size_t tree) +void Skeleton::destructOldTree(std::size_t tree) { mTreeCache.erase(mTreeCache.begin() + tree); mTreeNodeMaps.erase(mTreeNodeMaps.begin() + tree); @@ -2140,10 +2140,10 @@ void Skeleton::destructOldTree(size_t tree) // Decrease the tree index of every BodyNode whose tree index is higher than // the one which is being removed. None of the BodyNodes that predate the // current one can have a higher tree index, so they can be ignored. - for(size_t i=tree; i < mTreeCache.size(); ++i) + for(std::size_t i=tree; i < mTreeCache.size(); ++i) { DataCache& loweredTree = mTreeCache[i]; - for(size_t j=0; j < loweredTree.mBodyNodes.size(); ++j) + for(std::size_t j=0; j < loweredTree.mBodyNodes.size(); ++j) loweredTree.mBodyNodes[j]->mTreeIndex = i; } @@ -2166,10 +2166,10 @@ void Skeleton::unregisterBodyNode(BodyNode* _oldBodyNode) mNameMgrForBodyNodes.removeName(_oldBodyNode->getName()); - size_t index = _oldBodyNode->getIndexInSkeleton(); + std::size_t index = _oldBodyNode->getIndexInSkeleton(); assert(mSkelCache.mBodyNodes[index] == _oldBodyNode); mSkelCache.mBodyNodes.erase(mSkelCache.mBodyNodes.begin()+index); - for(size_t i=index; i < mSkelCache.mBodyNodes.size(); ++i) + for(std::size_t i=index; i < mSkelCache.mBodyNodes.size(); ++i) { BodyNode* bn = mSkelCache.mBodyNodes[i]; bn->mIndexInSkeleton = i; @@ -2185,7 +2185,7 @@ void Skeleton::unregisterBodyNode(BodyNode* _oldBodyNode) // registered, because the BodyNodes always get unregistered from leaf to // root. - size_t tree = _oldBodyNode->getTreeIndex(); + std::size_t tree = _oldBodyNode->getTreeIndex(); assert(mTreeCache[tree].mBodyNodes.size() == 1); assert(mTreeCache[tree].mBodyNodes[0] == _oldBodyNode); @@ -2194,13 +2194,13 @@ void Skeleton::unregisterBodyNode(BodyNode* _oldBodyNode) } else { - size_t tree = _oldBodyNode->getTreeIndex(); - size_t indexInTree = _oldBodyNode->getIndexInTree(); + std::size_t tree = _oldBodyNode->getTreeIndex(); + std::size_t indexInTree = _oldBodyNode->getIndexInTree(); assert(mTreeCache[tree].mBodyNodes[indexInTree] == _oldBodyNode); mTreeCache[tree].mBodyNodes.erase( mTreeCache[tree].mBodyNodes.begin() + indexInTree); - for(size_t i=indexInTree; imIndexInTree = i; updateCacheDimensions(tree); @@ -2231,13 +2231,13 @@ void Skeleton::unregisterJoint(Joint* _oldJoint) mNameMgrForJoints.removeName(_oldJoint->getName()); - size_t tree = _oldJoint->getChildBodyNode()->getTreeIndex(); + std::size_t tree = _oldJoint->getChildBodyNode()->getTreeIndex(); std::vector& treeDofs = mTreeCache[tree].mDofs; std::vector& skelDofs = mSkelCache.mDofs; - size_t firstSkelIndex = INVALID_INDEX; - size_t firstTreeIndex = INVALID_INDEX; - for (size_t i = 0; i < _oldJoint->getNumDofs(); ++i) + std::size_t firstSkelIndex = INVALID_INDEX; + std::size_t firstTreeIndex = INVALID_INDEX; + for (std::size_t i = 0; i < _oldJoint->getNumDofs(); ++i) { DegreeOfFreedom* dof = _oldJoint->getDof(i); mNameMgrForDofs.removeObject(dof); @@ -2251,13 +2251,13 @@ void Skeleton::unregisterJoint(Joint* _oldJoint) std::remove(treeDofs.begin(), treeDofs.end(), dof), treeDofs.end()); } - for (size_t i = firstSkelIndex; i < skelDofs.size(); ++i) + for (std::size_t i = firstSkelIndex; i < skelDofs.size(); ++i) { DegreeOfFreedom* dof = skelDofs[i]; dof->mIndexInSkeleton = i; } - for (size_t i = firstTreeIndex; i < treeDofs.size(); ++i) + for (std::size_t i = firstTreeIndex; i < treeDofs.size(); ++i) { DegreeOfFreedom* dof = treeDofs[i]; dof->mIndexInTree = i; @@ -2265,7 +2265,7 @@ void Skeleton::unregisterJoint(Joint* _oldJoint) } //============================================================================== -void Skeleton::unregisterNode(NodeMap& nodeMap, Node* _oldNode, size_t& _index) +void Skeleton::unregisterNode(NodeMap& nodeMap, Node* _oldNode, std::size_t& _index) { NodeMap::iterator it = nodeMap.find(typeid(*_oldNode)); @@ -2288,18 +2288,18 @@ void Skeleton::unregisterNode(NodeMap& nodeMap, Node* _oldNode, size_t& _index) //============================================================================== void Skeleton::unregisterNode(Node* _oldNode) { - const size_t indexInSkel = _oldNode->mIndexInSkeleton; + const std::size_t indexInSkel = _oldNode->mIndexInSkeleton; unregisterNode(mNodeMap, _oldNode, _oldNode->mIndexInSkeleton); NodeMap::iterator node_it = mNodeMap.find(typeid(*_oldNode)); assert(mNodeMap.end() != node_it); const std::vector& skelNodes = node_it->second; - for(size_t i=indexInSkel; i < skelNodes.size(); ++i) + for(std::size_t i=indexInSkel; i < skelNodes.size(); ++i) skelNodes[i]->mIndexInSkeleton = i; - const size_t indexInTree = _oldNode->mIndexInTree; - const size_t treeIndex = _oldNode->getBodyNodePtr()->getTreeIndex(); + const std::size_t indexInTree = _oldNode->mIndexInTree; + const std::size_t treeIndex = _oldNode->getBodyNodePtr()->getTreeIndex(); NodeMap& treeNodeMap = mTreeNodeMaps[treeIndex]; unregisterNode(treeNodeMap, _oldNode, _oldNode->mIndexInTree); @@ -2307,7 +2307,7 @@ void Skeleton::unregisterNode(Node* _oldNode) assert(treeNodeMap.end() != node_it); const std::vector& treeNodes = node_it->second; - for(size_t i=indexInTree; i < treeNodes.size(); ++i) + for(std::size_t i=indexInTree; i < treeNodes.size(); ++i) treeNodes[i]->mIndexInTree = i; // Remove it from the NameManager, if a NameManager is being used for this @@ -2445,7 +2445,7 @@ std::pair Skeleton::cloneBodyNodeTree( std::vector clones; clones.reserve(tree.size()); - for(size_t i=0; i& tree, BodyNodeT* _currentBodyNode) { tree.push_back(_currentBodyNode); - for(size_t i=0; i<_currentBodyNode->getNumChildBodyNodes(); ++i) + for(std::size_t i=0; i<_currentBodyNode->getNumChildBodyNodes(); ++i) recursiveConstructBodyNodeTree(tree, _currentBodyNode->getChildBodyNode(i)); } @@ -2512,7 +2512,7 @@ std::vector Skeleton::extractBodyNodeTree(BodyNode* _bodyNode) for(rit = tree.rbegin(); rit != tree.rend(); ++rit) unregisterBodyNode(*rit); - for(size_t i=0; iinit(getPtr()); return tree; @@ -2529,14 +2529,14 @@ void Skeleton::receiveBodyNodeTree(const std::vector& _tree) void Skeleton::updateTotalMass() { mTotalMass = 0.0; - for(size_t i=0; igetMass(); } //============================================================================== void Skeleton::updateCacheDimensions(Skeleton::DataCache& _cache) { - size_t dof = _cache.mDofs.size(); + std::size_t dof = _cache.mDofs.size(); _cache.mM = Eigen::MatrixXd::Zero(dof, dof); _cache.mAugM = Eigen::MatrixXd::Zero(dof, dof); _cache.mInvM = Eigen::MatrixXd::Zero(dof, dof); @@ -2549,7 +2549,7 @@ void Skeleton::updateCacheDimensions(Skeleton::DataCache& _cache) } //============================================================================== -void Skeleton::updateCacheDimensions(size_t _treeIdx) +void Skeleton::updateCacheDimensions(std::size_t _treeIdx) { updateCacheDimensions(mTreeCache[_treeIdx]); updateCacheDimensions(mSkelCache); @@ -2558,7 +2558,7 @@ void Skeleton::updateCacheDimensions(size_t _treeIdx) } //============================================================================== -void Skeleton::updateArticulatedInertia(size_t _tree) const +void Skeleton::updateArticulatedInertia(std::size_t _tree) const { DataCache& cache = mTreeCache[_tree]; for (std::vector::const_reverse_iterator it = cache.mBodyNodes.rbegin(); @@ -2573,7 +2573,7 @@ void Skeleton::updateArticulatedInertia(size_t _tree) const //============================================================================== void Skeleton::updateArticulatedInertia() const { - for(size_t i=0; i(cache.mM.cols()) == dof - && static_cast(cache.mM.rows()) == dof); + std::size_t dof = cache.mDofs.size(); + assert(static_cast(cache.mM.cols()) == dof + && static_cast(cache.mM.rows()) == dof); if (dof == 0) { cache.mDirty.mMassMatrix = false; @@ -2603,10 +2603,10 @@ void Skeleton::updateMassMatrix(size_t _treeIdx) const // Clear out the accelerations of the dofs in this tree so that we can set // them to 1.0 one at a time to build up the mass matrix - for (size_t i = 0; i < dof; ++i) + for (std::size_t i = 0; i < dof; ++i) cache.mDofs[i]->setAcceleration(0.0); - for (size_t j = 0; j < dof; ++j) + for (std::size_t j = 0; j < dof; ++j) { // Set the acceleration of this DOF to 1.0 while all the rest are 0.0 cache.mDofs[j]->setAcceleration(1.0); @@ -2623,10 +2623,10 @@ void Skeleton::updateMassMatrix(size_t _treeIdx) const cache.mBodyNodes.rbegin(); it != cache.mBodyNodes.rend(); ++it) { (*it)->aggregateMassMatrix(cache.mM, j); - size_t localDof = (*it)->mParentJoint->getNumDofs(); + std::size_t localDof = (*it)->mParentJoint->getNumDofs(); if (localDof > 0) { - size_t iStart = (*it)->mParentJoint->getIndexInTree(0); + std::size_t iStart = (*it)->mParentJoint->getIndexInTree(0); if (iStart + localDof < j) break; @@ -2647,9 +2647,9 @@ void Skeleton::updateMassMatrix(size_t _treeIdx) const //============================================================================== void Skeleton::updateMassMatrix() const { - size_t dof = mSkelCache.mDofs.size(); - assert(static_cast(mSkelCache.mM.cols()) == dof - && static_cast(mSkelCache.mM.rows()) == dof); + std::size_t dof = mSkelCache.mDofs.size(); + assert(static_cast(mSkelCache.mM.cols()) == dof + && static_cast(mSkelCache.mM.rows()) == dof); if(dof == 0) { mSkelCache.mDirty.mMassMatrix = false; @@ -2658,17 +2658,17 @@ void Skeleton::updateMassMatrix() const mSkelCache.mM.setZero(); - for(size_t tree = 0; tree < mTreeCache.size(); ++tree) + for(std::size_t tree = 0; tree < mTreeCache.size(); ++tree) { const Eigen::MatrixXd& treeM = getMassMatrix(tree); const std::vector& treeDofs = mTreeCache[tree].mDofs; - size_t nTreeDofs = treeDofs.size(); - for(size_t i=0; igetIndexInSkeleton(); - size_t kj = treeDofs[j]->getIndexInSkeleton(); + std::size_t ki = treeDofs[i]->getIndexInSkeleton(); + std::size_t kj = treeDofs[j]->getIndexInSkeleton(); mSkelCache.mM(ki,kj) = treeM(i,j); } @@ -2679,12 +2679,12 @@ void Skeleton::updateMassMatrix() const } //============================================================================== -void Skeleton::updateAugMassMatrix(size_t _treeIdx) const +void Skeleton::updateAugMassMatrix(std::size_t _treeIdx) const { DataCache& cache = mTreeCache[_treeIdx]; - size_t dof = cache.mDofs.size(); - assert(static_cast(cache.mAugM.cols()) == dof - && static_cast(cache.mAugM.rows()) == dof); + std::size_t dof = cache.mDofs.size(); + assert(static_cast(cache.mAugM.cols()) == dof + && static_cast(cache.mAugM.rows()) == dof); if (dof == 0) { cache.mDirty.mAugMassMatrix = false; @@ -2698,10 +2698,10 @@ void Skeleton::updateAugMassMatrix(size_t _treeIdx) const // Clear out the accelerations of the DOFs in this tree so that we can set // them to 1.0 one at a time to build up the augmented mass matrix - for (size_t i = 0; i < dof; ++i) + for (std::size_t i = 0; i < dof; ++i) cache.mDofs[i]->setAcceleration(0.0); - for (size_t j = 0; j < dof; ++j) + for (std::size_t j = 0; j < dof; ++j) { // Set the acceleration of this DOF to 1.0 while all the rest are 0.0 cache.mDofs[j]->setAcceleration(1.0); @@ -2718,10 +2718,10 @@ void Skeleton::updateAugMassMatrix(size_t _treeIdx) const cache.mBodyNodes.rbegin(); it != cache.mBodyNodes.rend(); ++it) { (*it)->aggregateAugMassMatrix(cache.mAugM, j, mAspectProperties.mTimeStep); - size_t localDof = (*it)->mParentJoint->getNumDofs(); + std::size_t localDof = (*it)->mParentJoint->getNumDofs(); if (localDof > 0) { - size_t iStart = (*it)->mParentJoint->getIndexInTree(0); + std::size_t iStart = (*it)->mParentJoint->getIndexInTree(0); if (iStart + localDof < j) break; @@ -2742,9 +2742,9 @@ void Skeleton::updateAugMassMatrix(size_t _treeIdx) const //============================================================================== void Skeleton::updateAugMassMatrix() const { - size_t dof = mSkelCache.mDofs.size(); - assert(static_cast(mSkelCache.mAugM.cols()) == dof - && static_cast(mSkelCache.mAugM.rows()) == dof); + std::size_t dof = mSkelCache.mDofs.size(); + assert(static_cast(mSkelCache.mAugM.cols()) == dof + && static_cast(mSkelCache.mAugM.rows()) == dof); if(dof == 0) { mSkelCache.mDirty.mMassMatrix = false; @@ -2753,17 +2753,17 @@ void Skeleton::updateAugMassMatrix() const mSkelCache.mAugM.setZero(); - for(size_t tree = 0; tree < mTreeCache.size(); ++tree) + for(std::size_t tree = 0; tree < mTreeCache.size(); ++tree) { const Eigen::MatrixXd& treeAugM = getAugMassMatrix(tree); const std::vector& treeDofs = mTreeCache[tree].mDofs; - size_t nTreeDofs = treeDofs.size(); - for(size_t i=0; igetIndexInSkeleton(); - size_t kj = treeDofs[j]->getIndexInSkeleton(); + std::size_t ki = treeDofs[i]->getIndexInSkeleton(); + std::size_t kj = treeDofs[j]->getIndexInSkeleton(); mSkelCache.mAugM(ki,kj) = treeAugM(i,j); } @@ -2774,12 +2774,12 @@ void Skeleton::updateAugMassMatrix() const } //============================================================================== -void Skeleton::updateInvMassMatrix(size_t _treeIdx) const +void Skeleton::updateInvMassMatrix(std::size_t _treeIdx) const { DataCache& cache = mTreeCache[_treeIdx]; - size_t dof = cache.mDofs.size(); - assert(static_cast(cache.mInvM.cols()) == dof - && static_cast(cache.mInvM.rows()) == dof); + std::size_t dof = cache.mDofs.size(); + assert(static_cast(cache.mInvM.cols()) == dof + && static_cast(cache.mInvM.rows()) == dof); if (dof == 0) { cache.mDirty.mInvMassMatrix = false; @@ -2794,10 +2794,10 @@ void Skeleton::updateInvMassMatrix(size_t _treeIdx) const // Clear out the forces of the dofs in this tree so that we can set them to // 1.0 one at a time to build up the inverse mass matrix - for (size_t i = 0; i < dof; ++i) + for (std::size_t i = 0; i < dof; ++i) cache.mDofs[i]->setForce(0.0); - for (size_t j = 0; j < dof; ++j) + for (std::size_t j = 0; j < dof; ++j) { // Set the force of this DOF to 1.0 while all the rest are 0.0 cache.mDofs[j]->setForce(1.0); @@ -2814,10 +2814,10 @@ void Skeleton::updateInvMassMatrix(size_t _treeIdx) const it != cache.mBodyNodes.end(); ++it) { (*it)->aggregateInvMassMatrix(cache.mInvM, j); - size_t localDof = (*it)->mParentJoint->getNumDofs(); + std::size_t localDof = (*it)->mParentJoint->getNumDofs(); if (localDof > 0) { - size_t iStart = (*it)->mParentJoint->getIndexInTree(0); + std::size_t iStart = (*it)->mParentJoint->getIndexInTree(0); if (iStart + localDof > j) break; @@ -2838,9 +2838,9 @@ void Skeleton::updateInvMassMatrix(size_t _treeIdx) const //============================================================================== void Skeleton::updateInvMassMatrix() const { - size_t dof = mSkelCache.mDofs.size(); - assert(static_cast(mSkelCache.mInvM.cols()) == dof - && static_cast(mSkelCache.mInvM.rows()) == dof); + std::size_t dof = mSkelCache.mDofs.size(); + assert(static_cast(mSkelCache.mInvM.cols()) == dof + && static_cast(mSkelCache.mInvM.rows()) == dof); if(dof == 0) { mSkelCache.mDirty.mInvMassMatrix = false; @@ -2849,17 +2849,17 @@ void Skeleton::updateInvMassMatrix() const mSkelCache.mInvM.setZero(); - for(size_t tree = 0; tree < mTreeCache.size(); ++tree) + for(std::size_t tree = 0; tree < mTreeCache.size(); ++tree) { const Eigen::MatrixXd& treeInvM = getInvMassMatrix(tree); const std::vector& treeDofs = mTreeCache[tree].mDofs; - size_t nTreeDofs = treeDofs.size(); - for(size_t i=0; igetIndexInSkeleton(); - size_t kj = treeDofs[j]->getIndexInSkeleton(); + std::size_t ki = treeDofs[i]->getIndexInSkeleton(); + std::size_t kj = treeDofs[j]->getIndexInSkeleton(); mSkelCache.mInvM(ki,kj) = treeInvM(i,j); } @@ -2870,12 +2870,12 @@ void Skeleton::updateInvMassMatrix() const } //============================================================================== -void Skeleton::updateInvAugMassMatrix(size_t _treeIdx) const +void Skeleton::updateInvAugMassMatrix(std::size_t _treeIdx) const { DataCache& cache = mTreeCache[_treeIdx]; - size_t dof = cache.mDofs.size(); - assert(static_cast(cache.mInvAugM.cols()) == dof - && static_cast(cache.mInvAugM.rows()) == dof); + std::size_t dof = cache.mDofs.size(); + assert(static_cast(cache.mInvAugM.cols()) == dof + && static_cast(cache.mInvAugM.rows()) == dof); if (dof == 0) { cache.mDirty.mInvAugMassMatrix = false; @@ -2890,10 +2890,10 @@ void Skeleton::updateInvAugMassMatrix(size_t _treeIdx) const // Clear out the forces of the dofs in this tree so that we can set them to // 1.0 one at a time to build up the inverse augmented mass matrix - for (size_t i = 0; i < dof; ++i) + for (std::size_t i = 0; i < dof; ++i) cache.mDofs[i]->setForce(0.0); - for (size_t j = 0; j < dof; ++j) + for (std::size_t j = 0; j < dof; ++j) { // Set the force of this DOF to 1.0 while all the rest are 0.0 cache.mDofs[j]->setForce(1.0); @@ -2910,10 +2910,10 @@ void Skeleton::updateInvAugMassMatrix(size_t _treeIdx) const it != cache.mBodyNodes.end(); ++it) { (*it)->aggregateInvAugMassMatrix(cache.mInvAugM, j, mAspectProperties.mTimeStep); - size_t localDof = (*it)->mParentJoint->getNumDofs(); + std::size_t localDof = (*it)->mParentJoint->getNumDofs(); if (localDof > 0) { - size_t iStart = (*it)->mParentJoint->getIndexInTree(0); + std::size_t iStart = (*it)->mParentJoint->getIndexInTree(0); if (iStart + localDof > j) break; @@ -2935,9 +2935,9 @@ void Skeleton::updateInvAugMassMatrix(size_t _treeIdx) const //============================================================================== void Skeleton::updateInvAugMassMatrix() const { - size_t dof = mSkelCache.mDofs.size(); - assert(static_cast(mSkelCache.mInvAugM.cols()) == dof - && static_cast(mSkelCache.mInvAugM.rows()) == dof); + std::size_t dof = mSkelCache.mDofs.size(); + assert(static_cast(mSkelCache.mInvAugM.cols()) == dof + && static_cast(mSkelCache.mInvAugM.rows()) == dof); if(dof == 0) { mSkelCache.mDirty.mInvAugMassMatrix = false; @@ -2946,17 +2946,17 @@ void Skeleton::updateInvAugMassMatrix() const mSkelCache.mInvAugM.setZero(); - for(size_t tree = 0; tree < mTreeCache.size(); ++tree) + for(std::size_t tree = 0; tree < mTreeCache.size(); ++tree) { const Eigen::MatrixXd& treeInvAugM = getInvAugMassMatrix(tree); const std::vector& treeDofs = mTreeCache[tree].mDofs; - size_t nTreeDofs = treeDofs.size(); - for(size_t i=0; igetIndexInSkeleton(); - size_t kj = treeDofs[j]->getIndexInSkeleton(); + std::size_t ki = treeDofs[i]->getIndexInSkeleton(); + std::size_t kj = treeDofs[j]->getIndexInSkeleton(); mSkelCache.mInvAugM(ki,kj) = treeInvAugM(i,j); } @@ -2967,11 +2967,11 @@ void Skeleton::updateInvAugMassMatrix() const } //============================================================================== -void Skeleton::updateCoriolisForces(size_t _treeIdx) const +void Skeleton::updateCoriolisForces(std::size_t _treeIdx) const { DataCache& cache = mTreeCache[_treeIdx]; - size_t dof = cache.mDofs.size(); - assert(static_cast(cache.mCvec.size()) == dof); + std::size_t dof = cache.mDofs.size(); + assert(static_cast(cache.mCvec.size()) == dof); if (dof == 0) { cache.mDirty.mCoriolisForces = false; @@ -2998,8 +2998,8 @@ void Skeleton::updateCoriolisForces(size_t _treeIdx) const //============================================================================== void Skeleton::updateCoriolisForces() const { - size_t dof = mSkelCache.mDofs.size(); - assert(static_cast(mSkelCache.mCvec.size()) == dof); + std::size_t dof = mSkelCache.mDofs.size(); + assert(static_cast(mSkelCache.mCvec.size()) == dof); if(dof == 0) { mSkelCache.mDirty.mCoriolisForces = false; @@ -3008,14 +3008,14 @@ void Skeleton::updateCoriolisForces() const mSkelCache.mCvec.setZero(); - for(size_t tree = 0; tree < mTreeCache.size(); ++tree) + for(std::size_t tree = 0; tree < mTreeCache.size(); ++tree) { const Eigen::VectorXd& treeCvec = getCoriolisForces(tree); const std::vector& treeDofs = mTreeCache[tree].mDofs; - size_t nTreeDofs = treeDofs.size(); - for(size_t i=0; igetIndexInSkeleton(); + std::size_t k = treeDofs[i]->getIndexInSkeleton(); mSkelCache.mCvec[k] = treeCvec[i]; } } @@ -3024,11 +3024,11 @@ void Skeleton::updateCoriolisForces() const } //============================================================================== -void Skeleton::updateGravityForces(size_t _treeIdx) const +void Skeleton::updateGravityForces(std::size_t _treeIdx) const { DataCache& cache = mTreeCache[_treeIdx]; - size_t dof = cache.mDofs.size(); - assert(static_cast(cache.mG.size()) == dof); + std::size_t dof = cache.mDofs.size(); + assert(static_cast(cache.mG.size()) == dof); if (dof == 0) { cache.mDirty.mGravityForces = false; @@ -3049,8 +3049,8 @@ void Skeleton::updateGravityForces(size_t _treeIdx) const //============================================================================== void Skeleton::updateGravityForces() const { - size_t dof = mSkelCache.mDofs.size(); - assert(static_cast(mSkelCache.mG.size()) == dof); + std::size_t dof = mSkelCache.mDofs.size(); + assert(static_cast(mSkelCache.mG.size()) == dof); if(dof == 0) { mSkelCache.mDirty.mGravityForces = false; @@ -3059,14 +3059,14 @@ void Skeleton::updateGravityForces() const mSkelCache.mG.setZero(); - for(size_t tree = 0; tree < mTreeCache.size(); ++tree) + for(std::size_t tree = 0; tree < mTreeCache.size(); ++tree) { const Eigen::VectorXd& treeG = getGravityForces(tree); std::vector& treeDofs = mTreeCache[tree].mDofs; - size_t nTreeDofs = treeDofs.size(); - for(size_t i=0; igetIndexInSkeleton(); + std::size_t k = treeDofs[i]->getIndexInSkeleton(); mSkelCache.mG[k] = treeG[i]; } } @@ -3075,11 +3075,11 @@ void Skeleton::updateGravityForces() const } //============================================================================== -void Skeleton::updateCoriolisAndGravityForces(size_t _treeIdx) const +void Skeleton::updateCoriolisAndGravityForces(std::size_t _treeIdx) const { DataCache& cache = mTreeCache[_treeIdx]; - size_t dof = cache.mDofs.size(); - assert(static_cast(cache.mCg.size()) == dof); + std::size_t dof = cache.mDofs.size(); + assert(static_cast(cache.mCg.size()) == dof); if (dof == 0) { cache.mDirty.mCoriolisAndGravityForces = false; @@ -3106,8 +3106,8 @@ void Skeleton::updateCoriolisAndGravityForces(size_t _treeIdx) const //============================================================================== void Skeleton::updateCoriolisAndGravityForces() const { - size_t dof = mSkelCache.mDofs.size(); - assert(static_cast(mSkelCache.mCg.size()) == dof); + std::size_t dof = mSkelCache.mDofs.size(); + assert(static_cast(mSkelCache.mCg.size()) == dof); if (dof == 0) { mSkelCache.mDirty.mCoriolisAndGravityForces = false; @@ -3116,14 +3116,14 @@ void Skeleton::updateCoriolisAndGravityForces() const mSkelCache.mCg.setZero(); - for(size_t tree = 0; tree < mTreeCache.size(); ++tree) + for(std::size_t tree = 0; tree < mTreeCache.size(); ++tree) { const Eigen::VectorXd& treeCg = getCoriolisAndGravityForces(tree); const std::vector& treeDofs = mTreeCache[tree].mDofs; - size_t nTreeDofs = treeDofs.size(); - for(size_t i=0; igetIndexInSkeleton(); + std::size_t k = treeDofs[i]->getIndexInSkeleton(); mSkelCache.mCg[k] = treeCg[i]; } } @@ -3132,11 +3132,11 @@ void Skeleton::updateCoriolisAndGravityForces() const } //============================================================================== -void Skeleton::updateExternalForces(size_t _treeIdx) const +void Skeleton::updateExternalForces(std::size_t _treeIdx) const { DataCache& cache = mTreeCache[_treeIdx]; - size_t dof = cache.mDofs.size(); - assert(static_cast(cache.mFext.size()) == dof); + std::size_t dof = cache.mDofs.size(); + assert(static_cast(cache.mFext.size()) == dof); if (dof == 0) { cache.mDirty.mExternalForces = false; @@ -3188,8 +3188,8 @@ void Skeleton::updateExternalForces(size_t _treeIdx) const //============================================================================== void Skeleton::updateExternalForces() const { - size_t dof = mSkelCache.mDofs.size(); - assert(static_cast(mSkelCache.mFext.size()) == dof); + std::size_t dof = mSkelCache.mDofs.size(); + assert(static_cast(mSkelCache.mFext.size()) == dof); if(dof == 0) { mSkelCache.mDirty.mExternalForces = false; @@ -3198,14 +3198,14 @@ void Skeleton::updateExternalForces() const mSkelCache.mFext.setZero(); - for(size_t tree = 0; tree < mTreeCache.size(); ++tree) + for(std::size_t tree = 0; tree < mTreeCache.size(); ++tree) { const Eigen::VectorXd& treeFext = getExternalForces(tree); const std::vector& treeDofs = mTreeCache[tree].mDofs; - size_t nTreeDofs = treeDofs.size(); - for(size_t i=0; igetIndexInSkeleton(); + std::size_t k = treeDofs[i]->getIndexInSkeleton(); mSkelCache.mFext[k] = treeFext[i]; } } @@ -3216,8 +3216,8 @@ void Skeleton::updateExternalForces() const //============================================================================== const Eigen::VectorXd& Skeleton::computeConstraintForces(DataCache& cache) const { - const size_t dof = cache.mDofs.size(); - assert(static_cast(cache.mFc.size()) == dof); + const std::size_t dof = cache.mDofs.size(); + assert(static_cast(cache.mFc.size()) == dof); // Body constraint impulses for (std::vector::reverse_iterator it = @@ -3229,7 +3229,7 @@ const Eigen::VectorXd& Skeleton::computeConstraintForces(DataCache& cache) const } // Joint constraint impulses - for (size_t i = 0; i < dof; ++i) + for (std::size_t i = 0; i < dof; ++i) cache.mFc[i] += cache.mDofs[i]->getConstraintImpulse(); // Get force by dividing the impulse by the time step @@ -3241,9 +3241,9 @@ const Eigen::VectorXd& Skeleton::computeConstraintForces(DataCache& cache) const //============================================================================== static void computeSupportPolygon( const Skeleton* skel, math::SupportPolygon& polygon, - math::SupportGeometry& geometry, std::vector& ee_indices, + math::SupportGeometry& geometry, std::vector& ee_indices, Eigen::Vector3d& axis1, Eigen::Vector3d& axis2, Eigen::Vector2d& centroid, - size_t treeIndex) + std::size_t treeIndex) { polygon.clear(); geometry.clear(); @@ -3261,9 +3261,9 @@ static void computeSupportPolygon( return; } - std::vector originalEE_map; + std::vector originalEE_map; originalEE_map.reserve(skel->getNumEndEffectors()); - for(size_t i=0; i < skel->getNumEndEffectors(); ++i) + for(std::size_t i=0; i < skel->getNumEndEffectors(); ++i) { const EndEffector* ee = skel->getEndEffector(i); if(ee->getSupport() && ee->getSupport()->isActive() @@ -3286,11 +3286,11 @@ static void computeSupportPolygon( axis2 = up.normalized().cross(axis1); - std::vector vertex_indices; + std::vector vertex_indices; polygon = math::computeSupportPolgyon(vertex_indices, geometry, axis1, axis2); ee_indices.reserve(vertex_indices.size()); - for(size_t i=0; i < vertex_indices.size(); ++i) + for(std::size_t i=0; i < vertex_indices.size(); ++i) ee_indices[i] = originalEE_map[vertex_indices[i]]; if(polygon.size() > 0) @@ -3319,7 +3319,7 @@ const math::SupportPolygon& Skeleton::getSupportPolygon() const } //============================================================================== -const math::SupportPolygon& Skeleton::getSupportPolygon(size_t _treeIdx) const +const math::SupportPolygon& Skeleton::getSupportPolygon(std::size_t _treeIdx) const { math::SupportPolygon& polygon = mTreeCache[_treeIdx].mSupportPolygon; @@ -3338,14 +3338,14 @@ const math::SupportPolygon& Skeleton::getSupportPolygon(size_t _treeIdx) const } //============================================================================== -const std::vector& Skeleton::getSupportIndices() const +const std::vector& Skeleton::getSupportIndices() const { getSupportPolygon(); return mSkelCache.mSupportIndices; } //============================================================================== -const std::vector& Skeleton::getSupportIndices(size_t _treeIdx) const +const std::vector& Skeleton::getSupportIndices(std::size_t _treeIdx) const { getSupportPolygon(_treeIdx); return mTreeCache[_treeIdx].mSupportIndices; @@ -3361,7 +3361,7 @@ Skeleton::getSupportAxes() const //============================================================================== const std::pair& -Skeleton::getSupportAxes(size_t _treeIdx) const +Skeleton::getSupportAxes(std::size_t _treeIdx) const { getSupportPolygon(_treeIdx); return mTreeCache[_treeIdx].mSupportAxes; @@ -3375,14 +3375,14 @@ const Eigen::Vector2d& Skeleton::getSupportCentroid() const } //============================================================================== -const Eigen::Vector2d& Skeleton::getSupportCentroid(size_t _treeIdx) const +const Eigen::Vector2d& Skeleton::getSupportCentroid(std::size_t _treeIdx) const { getSupportPolygon(_treeIdx); return mTreeCache[_treeIdx].mSupportCentroid; } //============================================================================== -size_t Skeleton::getSupportVersion() const +std::size_t Skeleton::getSupportVersion() const { if(mSkelCache.mDirty.mSupport) return mSkelCache.mDirty.mSupportVersion + 1; @@ -3391,7 +3391,7 @@ size_t Skeleton::getSupportVersion() const } //============================================================================== -size_t Skeleton::getSupportVersion(size_t _treeIdx) const +std::size_t Skeleton::getSupportVersion(std::size_t _treeIdx) const { if(mTreeCache[_treeIdx].mDirty.mSupport) return mTreeCache[_treeIdx].mDirty.mSupportVersion + 1; @@ -3487,7 +3487,7 @@ void Skeleton::clearInternalForces() } //============================================================================== -void Skeleton::notifyArticulatedInertiaUpdate(size_t _treeIdx) +void Skeleton::notifyArticulatedInertiaUpdate(std::size_t _treeIdx) { SET_FLAG(_treeIdx, mArticulatedInertia); SET_FLAG(_treeIdx, mMassMatrix); @@ -3500,7 +3500,7 @@ void Skeleton::notifyArticulatedInertiaUpdate(size_t _treeIdx) } //============================================================================== -void Skeleton::notifySupportUpdate(size_t _treeIdx) +void Skeleton::notifySupportUpdate(std::size_t _treeIdx) { SET_FLAG(_treeIdx, mSupport); } @@ -3529,7 +3529,7 @@ void Skeleton::updateBiasImpulse(BodyNode* _bodyNode) #ifndef NDEBUG // All the constraint impulse should be zero - for (size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) + for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) assert(mSkelCache.mBodyNodes[i]->mConstraintImpulse == Eigen::Vector6d::Zero()); #endif @@ -3560,7 +3560,7 @@ void Skeleton::updateBiasImpulse(BodyNode* _bodyNode, #ifndef NDEBUG // All the constraint impulse should be zero - for (size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) + for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) assert(mSkelCache.mBodyNodes[i]->mConstraintImpulse == Eigen::Vector6d::Zero()); #endif @@ -3607,7 +3607,7 @@ void Skeleton::updateBiasImpulse(BodyNode* _bodyNode1, #ifndef NDEBUG // All the constraint impulse should be zero - for (size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) + for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) assert(mSkelCache.mBodyNodes[i]->mConstraintImpulse == Eigen::Vector6d::Zero()); #endif @@ -3617,10 +3617,10 @@ void Skeleton::updateBiasImpulse(BodyNode* _bodyNode1, _bodyNode2->mConstraintImpulse = _imp2; // Find which body is placed later in the list of body nodes in this skeleton - size_t index1 = _bodyNode1->getIndexInSkeleton(); - size_t index2 = _bodyNode2->getIndexInSkeleton(); + std::size_t index1 = _bodyNode1->getIndexInSkeleton(); + std::size_t index2 = _bodyNode2->getIndexInSkeleton(); - size_t index = std::max(index1, index2); + std::size_t index = std::max(index1, index2); // Prepare cache data for (int i = index; 0 <= i; --i) @@ -3645,7 +3645,7 @@ void Skeleton::updateBiasImpulse(SoftBodyNode* _softBodyNode, #ifndef NDEBUG // All the constraint impulse should be zero - for (size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) + for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) assert(mSkelCache.mBodyNodes[i]->mConstraintImpulse == Eigen::Vector6d::Zero()); #endif @@ -3767,8 +3767,8 @@ Eigen::Vector3d Skeleton::getCOM(const Frame* _withRespectTo) const { Eigen::Vector3d com = Eigen::Vector3d::Zero(); - const size_t numBodies = getNumBodyNodes(); - for (size_t i = 0; i < numBodies; ++i) + const std::size_t numBodies = getNumBodyNodes(); + for (std::size_t i = 0; i < numBodies; ++i) { const BodyNode* bodyNode = getBodyNode(i); com += bodyNode->getMass() * bodyNode->getCOM(_withRespectTo); @@ -3790,8 +3790,8 @@ PropertyType getCOMPropertyTemplate(const Skeleton* _skel, { PropertyType result(PropertyType::Zero()); - const size_t numBodies = _skel->getNumBodyNodes(); - for (size_t i = 0; i < numBodies; ++i) + const std::size_t numBodies = _skel->getNumBodyNodes(); + for (std::size_t i = 0; i < numBodies; ++i) { const BodyNode* bodyNode = _skel->getBodyNode(i); result += bodyNode->getMass() @@ -3849,8 +3849,8 @@ JacType getCOMJacobianTemplate(const Skeleton* _skel, JacType J = JacType::Zero(JacType::RowsAtCompileTime, _skel->getNumDofs()); // Iterate through each of the Skeleton's BodyNodes - const size_t numBodies = _skel->getNumBodyNodes(); - for (size_t i = 0; i < numBodies; ++i) + const std::size_t numBodies = _skel->getNumBodyNodes(); + for (std::size_t i = 0; i < numBodies; ++i) { const BodyNode* bn = _skel->getBodyNode(i); @@ -3862,9 +3862,9 @@ JacType getCOMJacobianTemplate(const Skeleton* _skel, // For each column in the Jacobian of this BodyNode, we add it to the // appropriate column of the overall BodyNode - for (size_t j=0, end=bn->getNumDependentGenCoords(); j < end; ++j) + for (std::size_t j=0, end=bn->getNumDependentGenCoords(); j < end; ++j) { - size_t idx = bn->getDependentGenCoordIndex(j); + std::size_t idx = bn->getDependentGenCoordIndex(j); J.col(idx) += bnJ.col(j); } } diff --git a/dart/dynamics/Skeleton.h b/dart/dynamics/Skeleton.h index 328b12bb87ee6..0f0f8f37f2445 100644 --- a/dart/dynamics/Skeleton.h +++ b/dart/dynamics/Skeleton.h @@ -95,7 +95,7 @@ class Skeleton : const Eigen::VectorXd& commands = Eigen::VectorXd()); Configuration( - const std::vector& indices, + const std::vector& indices, const Eigen::VectorXd& positions = Eigen::VectorXd(), const Eigen::VectorXd& velocities = Eigen::VectorXd(), const Eigen::VectorXd& accelerations = Eigen::VectorXd(), @@ -104,7 +104,7 @@ class Skeleton : /// A list of degree of freedom indices that each entry in the /// Eigen::VectorXd members correspond to. - std::vector mIndices; + std::vector mIndices; /// Joint positions Eigen::VectorXd mPositions; @@ -188,7 +188,7 @@ class Skeleton : Configuration getConfiguration(int flags = CONFIG_ALL) const; /// Get the configuration of the specified indices in this Skeleton - Configuration getConfiguration(const std::vector& indices, + Configuration getConfiguration(const std::vector& indices, int flags = CONFIG_ALL) const; /// \} @@ -308,35 +308,35 @@ class Skeleton : // default argument. Please see #487 for detail // Documentation inherited - size_t getNumBodyNodes() const override; + std::size_t getNumBodyNodes() const override; /// Get number of rigid body nodes. - size_t getNumRigidBodyNodes() const; + std::size_t getNumRigidBodyNodes() const; /// Get number of soft body nodes. - size_t getNumSoftBodyNodes() const; + std::size_t getNumSoftBodyNodes() const; /// Get the number of independent trees that this Skeleton contains - size_t getNumTrees() const; + std::size_t getNumTrees() const; /// Get the root BodyNode of the tree whose index in this Skeleton is _treeIdx - BodyNode* getRootBodyNode(size_t _treeIdx = 0); + BodyNode* getRootBodyNode(std::size_t _treeIdx = 0); /// Get the const root BodyNode of the tree whose index in this Skeleton is /// _treeIdx - const BodyNode* getRootBodyNode(size_t _treeIdx = 0) const; + const BodyNode* getRootBodyNode(std::size_t _treeIdx = 0) const; // Documentation inherited - BodyNode* getBodyNode(size_t _idx) override; + BodyNode* getBodyNode(std::size_t _idx) override; // Documentation inherited - const BodyNode* getBodyNode(size_t _idx) const override; + const BodyNode* getBodyNode(std::size_t _idx) const override; /// Get SoftBodyNode whose index is _idx - SoftBodyNode* getSoftBodyNode(size_t _idx); + SoftBodyNode* getSoftBodyNode(std::size_t _idx); /// Get const SoftBodyNode whose index is _idx - const SoftBodyNode* getSoftBodyNode(size_t _idx) const; + const SoftBodyNode* getSoftBodyNode(std::size_t _idx) const; /// Get body node whose name is _name BodyNode* getBodyNode(const std::string& _name); @@ -357,22 +357,22 @@ class Skeleton : const std::vector& getBodyNodes() const override; // Documentation inherited - size_t getIndexOf(const BodyNode* _bn, bool _warning=true) const override; + std::size_t getIndexOf(const BodyNode* _bn, bool _warning=true) const override; /// Get the BodyNodes belonging to a tree in this Skeleton - const std::vector& getTreeBodyNodes(size_t _treeIdx); + const std::vector& getTreeBodyNodes(std::size_t _treeIdx); /// Get the BodyNodes belonging to a tree in this Skeleton - std::vector getTreeBodyNodes(size_t _treeIdx) const; + std::vector getTreeBodyNodes(std::size_t _treeIdx) const; // Documentation inherited - size_t getNumJoints() const override; + std::size_t getNumJoints() const override; // Documentation inherited - Joint* getJoint(size_t _idx) override; + Joint* getJoint(std::size_t _idx) override; // Documentation inherited - const Joint* getJoint(size_t _idx) const override; + const Joint* getJoint(std::size_t _idx) const override; /// Get Joint whose name is _name Joint* getJoint(const std::string& _name); @@ -381,16 +381,16 @@ class Skeleton : const Joint* getJoint(const std::string& _name) const; // Documentation inherited - size_t getIndexOf(const Joint* _joint, bool _warning=true) const override; + std::size_t getIndexOf(const Joint* _joint, bool _warning=true) const override; // Documentation inherited - size_t getNumDofs() const override; + std::size_t getNumDofs() const override; // Documentation inherited - DegreeOfFreedom* getDof(size_t _idx) override; + DegreeOfFreedom* getDof(std::size_t _idx) override; // Documentation inherited - const DegreeOfFreedom* getDof(size_t _idx) const override; + const DegreeOfFreedom* getDof(std::size_t _idx) const override; /// Get degree of freedom (aka generalized coordinate) whose name is _name DegreeOfFreedom* getDof(const std::string& _name); @@ -405,14 +405,14 @@ class Skeleton : std::vector getDofs() const override; // Documentation inherited - size_t getIndexOf(const DegreeOfFreedom* _dof, + std::size_t getIndexOf(const DegreeOfFreedom* _dof, bool _warning=true) const override; /// Get the DegreesOfFreedom belonging to a tree in this Skeleton - const std::vector& getTreeDofs(size_t _treeIdx); + const std::vector& getTreeDofs(std::size_t _treeIdx); /// Get the DegreesOfFreedom belonging to a tree in this Skeleton - const std::vector& getTreeDofs(size_t _treeIdx) const; + const std::vector& getTreeDofs(std::size_t _treeIdx) const; /// This function is only meant for debugging purposes. It will verify that /// all objects held in the Skeleton have the correct information about their @@ -444,7 +444,7 @@ class Skeleton : void clearIK(); /// Get total number of markers in this Skeleton - size_t getNumMarkers() const; + std::size_t getNumMarkers() const; /// Get marker whose name is _name Marker* getMarker(const std::string& _name); @@ -492,15 +492,15 @@ class Skeleton : /// Same as getSupportPolygon(), but it will only use EndEffectors within the /// specified tree within this Skeleton - const math::SupportPolygon& getSupportPolygon(size_t _treeIdx) const; + const math::SupportPolygon& getSupportPolygon(std::size_t _treeIdx) const; /// Get a list of the EndEffector indices that correspond to each of the /// points in the support polygon. - const std::vector& getSupportIndices() const; + const std::vector& getSupportIndices() const; /// Same as getSupportIndices(), but it corresponds to the support polygon of /// the specified tree within this Skeleton - const std::vector& getSupportIndices(size_t _treeIdx) const; + const std::vector& getSupportIndices(std::size_t _treeIdx) const; /// Get the axes that correspond to each component in the support polygon. /// These axes are needed in order to map the points on a support polygon @@ -511,7 +511,7 @@ class Skeleton : /// Same as getSupportAxes(), but it corresponds to the support polygon of the /// specified tree within this Skeleton const std::pair& getSupportAxes( - size_t _treeIdx) const; + std::size_t _treeIdx) const; /// Get the centroid of the support polygon for this Skeleton. If the support /// polygon is an empty set, the components of this vector will be nan. @@ -520,18 +520,18 @@ class Skeleton : /// Get the centroid of the support polygon for a tree in this Skeleton. If /// the support polygon is an empty set, the components of this vector will be /// nan. - const Eigen::Vector2d& getSupportCentroid(size_t _treeIdx) const; + const Eigen::Vector2d& getSupportCentroid(std::size_t _treeIdx) const; /// The version number of a support polygon will be incremented each time the /// support polygon needs to be recomputed. This number can be used to /// immediately determine whether the support polygon has changed since the /// last time you asked for it, allowing you to be more efficient in how you /// handle the data. - size_t getSupportVersion() const; + std::size_t getSupportVersion() const; /// Same as getSupportVersion(), but it corresponds to the support polygon of /// the specified tree within this Skeleton - size_t getSupportVersion(size_t _treeIdx) const; + std::size_t getSupportVersion(std::size_t _treeIdx) const; /// \} @@ -739,49 +739,49 @@ class Skeleton : double getMass() const override; /// Get the mass matrix of a specific tree in the Skeleton - const Eigen::MatrixXd& getMassMatrix(size_t _treeIdx) const; + const Eigen::MatrixXd& getMassMatrix(std::size_t _treeIdx) const; // Documentation inherited const Eigen::MatrixXd& getMassMatrix() const override; /// Get the augmented mass matrix of a specific tree in the Skeleton - const Eigen::MatrixXd& getAugMassMatrix(size_t _treeIdx) const; + const Eigen::MatrixXd& getAugMassMatrix(std::size_t _treeIdx) const; // Documentation inherited const Eigen::MatrixXd& getAugMassMatrix() const override; /// Get the inverse mass matrix of a specific tree in the Skeleton - const Eigen::MatrixXd& getInvMassMatrix(size_t _treeIdx) const; + const Eigen::MatrixXd& getInvMassMatrix(std::size_t _treeIdx) const; // Documentation inherited const Eigen::MatrixXd& getInvMassMatrix() const override; /// Get the inverse augmented mass matrix of a tree - const Eigen::MatrixXd& getInvAugMassMatrix(size_t _treeIdx) const; + const Eigen::MatrixXd& getInvAugMassMatrix(std::size_t _treeIdx) const; // Documentation inherited const Eigen::MatrixXd& getInvAugMassMatrix() const override; /// Get the Coriolis force vector of a tree in this Skeleton - const Eigen::VectorXd& getCoriolisForces(size_t _treeIdx) const; + const Eigen::VectorXd& getCoriolisForces(std::size_t _treeIdx) const; // Documentation inherited const Eigen::VectorXd& getCoriolisForces() const override; /// Get the gravity forces for a tree in this Skeleton - const Eigen::VectorXd& getGravityForces(size_t _treeIdx) const; + const Eigen::VectorXd& getGravityForces(std::size_t _treeIdx) const; // Documentation inherited const Eigen::VectorXd& getGravityForces() const override; /// Get the combined vector of Coriolis force and gravity force of a tree - const Eigen::VectorXd& getCoriolisAndGravityForces(size_t _treeIdx) const; + const Eigen::VectorXd& getCoriolisAndGravityForces(std::size_t _treeIdx) const; // Documentation inherited const Eigen::VectorXd& getCoriolisAndGravityForces() const override; /// Get the external force vector of a tree in the Skeleton - const Eigen::VectorXd& getExternalForces(size_t _treeIdx) const; + const Eigen::VectorXd& getExternalForces(std::size_t _treeIdx) const; // Documentation inherited const Eigen::VectorXd& getExternalForces() const override; @@ -790,7 +790,7 @@ class Skeleton : // const Eigen::VectorXd& getDampingForceVector(); /// Get constraint force vector for a tree - const Eigen::VectorXd& getConstraintForces(size_t _treeIdx) const; + const Eigen::VectorXd& getConstraintForces(std::size_t _treeIdx) const; /// Get constraint force vector const Eigen::VectorXd& getConstraintForces() const override; @@ -803,10 +803,10 @@ class Skeleton : /// Notify that the articulated inertia and everything that depends on it /// needs to be updated - void notifyArticulatedInertiaUpdate(size_t _treeIdx); + void notifyArticulatedInertiaUpdate(std::size_t _treeIdx); /// Notify that the support polygon of a tree needs to be updated - void notifySupportUpdate(size_t _treeIdx); + void notifySupportUpdate(std::size_t _treeIdx); // Documentation inherited double getKineticEnergy() const override; @@ -889,7 +889,7 @@ class Skeleton : friend class SoftBodyNode; friend class Joint; friend class SingleDofJoint; - template friend class MultiDofJoint; + template friend class MultiDofJoint; friend class DegreeOfFreedom; friend class Node; friend class ShapeNode; @@ -914,13 +914,13 @@ class Skeleton : void registerJoint(Joint* _newJoint); /// Register a Node with the Skeleton. Internal use only. - void registerNode(NodeMap& nodeMap, Node* _newNode, size_t& _index); + void registerNode(NodeMap& nodeMap, Node* _newNode, std::size_t& _index); /// Register a Node with the Skeleton. Internal use only. void registerNode(Node* _newNode); /// Remove an old tree from the Skeleton - void destructOldTree(size_t tree); + void destructOldTree(std::size_t tree); /// Remove a BodyNode from the Skeleton. Internal use only. void unregisterBodyNode(BodyNode* _oldBodyNode); @@ -929,7 +929,7 @@ class Skeleton : void unregisterJoint(Joint* _oldJoint); /// Remove a Node from the Skeleton. Internal use only. - void unregisterNode(NodeMap& nodeMap, Node* _oldNode, size_t& _index); + void unregisterNode(NodeMap& nodeMap, Node* _oldNode, std::size_t& _index); /// Remove a Node from the Skeleton. Internal use only. void unregisterNode(Node* _oldNode); @@ -989,57 +989,57 @@ class Skeleton : void updateCacheDimensions(DataCache& _cache); /// Update the dimensions for a tree's cache - void updateCacheDimensions(size_t _treeIdx); + void updateCacheDimensions(std::size_t _treeIdx); /// Update the articulated inertia of a tree - void updateArticulatedInertia(size_t _tree) const; + void updateArticulatedInertia(std::size_t _tree) const; /// Update the articulated inertias of the skeleton void updateArticulatedInertia() const; /// Update the mass matrix of a tree - void updateMassMatrix(size_t _treeIdx) const; + void updateMassMatrix(std::size_t _treeIdx) const; /// Update mass matrix of the skeleton. void updateMassMatrix() const; - void updateAugMassMatrix(size_t _treeIdx) const; + void updateAugMassMatrix(std::size_t _treeIdx) const; /// Update augmented mass matrix of the skeleton. void updateAugMassMatrix() const; /// Update the inverse mass matrix of a tree - void updateInvMassMatrix(size_t _treeIdx) const; + void updateInvMassMatrix(std::size_t _treeIdx) const; /// Update inverse of mass matrix of the skeleton. void updateInvMassMatrix() const; /// Update the inverse augmented mass matrix of a tree - void updateInvAugMassMatrix(size_t _treeIdx) const; + void updateInvAugMassMatrix(std::size_t _treeIdx) const; /// Update inverse of augmented mass matrix of the skeleton. void updateInvAugMassMatrix() const; /// Update Coriolis force vector for a tree in the Skeleton - void updateCoriolisForces(size_t _treeIdx) const; + void updateCoriolisForces(std::size_t _treeIdx) const; /// Update Coriolis force vector of the skeleton. void updateCoriolisForces() const; /// Update the gravity force vector of a tree - void updateGravityForces(size_t _treeIdx) const; + void updateGravityForces(std::size_t _treeIdx) const; /// Update gravity force vector of the skeleton. void updateGravityForces() const; /// Update the combined vector for a tree in this Skeleton - void updateCoriolisAndGravityForces(size_t _treeIdx) const; + void updateCoriolisAndGravityForces(std::size_t _treeIdx) const; /// Update combined vector of the skeleton. void updateCoriolisAndGravityForces() const; /// Update external force vector to generalized forces for a tree - void updateExternalForces(size_t _treeIdx) const; + void updateExternalForces(std::size_t _treeIdx) const; // TODO(JS): Not implemented yet /// update external force vector to generalized forces. @@ -1135,7 +1135,7 @@ class Skeleton : /// Increments each time a new support polygon is computed to help keep /// track of changes in the support polygon - size_t mSupportVersion; + std::size_t mSupportVersion; }; struct DataCache @@ -1187,7 +1187,7 @@ class Skeleton : /// A map of which EndEffectors correspond to the individual points in the /// support polygon - std::vector mSupportIndices; + std::vector mSupportIndices; /// A pair of vectors which map the 2D coordinates of the support polygon /// into 3D space @@ -1235,10 +1235,10 @@ class Skeleton : std::weak_ptr mUnionRootSkeleton; /// - size_t mUnionSize; + std::size_t mUnionSize; /// - size_t mUnionIndex; + std::size_t mUnionIndex; public: // To get byte-aligned Eigen vectors diff --git a/dart/dynamics/SoftBodyNode.cpp b/dart/dynamics/SoftBodyNode.cpp index 83842dc89ac43..1833d530b35cb 100644 --- a/dart/dynamics/SoftBodyNode.cpp +++ b/dart/dynamics/SoftBodyNode.cpp @@ -76,7 +76,7 @@ void SoftBodyNodeUniqueProperties::addPointMass( } //============================================================================== -bool SoftBodyNodeUniqueProperties::connectPointMasses(size_t i1, size_t i2) +bool SoftBodyNodeUniqueProperties::connectPointMasses(std::size_t i1, std::size_t i2) { if(i1 >= mPointProps.size() || i2 >= mPointProps.size()) { @@ -104,9 +104,9 @@ void SoftBodyNodeUniqueProperties::addFace(const Eigen::Vector3i& _newFace) assert(_newFace[0] != _newFace[1]); assert(_newFace[1] != _newFace[2]); assert(_newFace[2] != _newFace[0]); - assert(0 <= _newFace[0] && static_cast(_newFace[0]) < mPointProps.size()); - assert(0 <= _newFace[1] && static_cast(_newFace[1]) < mPointProps.size()); - assert(0 <= _newFace[2] && static_cast(_newFace[2]) < mPointProps.size()); + assert(0 <= _newFace[0] && static_cast(_newFace[0]) < mPointProps.size()); + assert(0 <= _newFace[1] && static_cast(_newFace[1]) < mPointProps.size()); + assert(0 <= _newFace[2] && static_cast(_newFace[2]) < mPointProps.size()); mFaces.push_back(_newFace); } @@ -125,7 +125,7 @@ SoftBodyNodeProperties::SoftBodyNodeProperties( //============================================================================== SoftBodyNode::~SoftBodyNode() { - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) delete mPointMasses[i]; delete mNotifier; @@ -216,13 +216,13 @@ SoftBodyNode& SoftBodyNode::operator=(const SoftBodyNode& _otherSoftBodyNode) } //============================================================================== -size_t SoftBodyNode::getNumPointMasses() const +std::size_t SoftBodyNode::getNumPointMasses() const { return mPointMasses.size(); } //============================================================================== -PointMass* SoftBodyNode::getPointMass(size_t _idx) +PointMass* SoftBodyNode::getPointMass(std::size_t _idx) { assert(_idx < mPointMasses.size()); if(_idx < mPointMasses.size()) @@ -232,7 +232,7 @@ PointMass* SoftBodyNode::getPointMass(size_t _idx) } //============================================================================== -const PointMass* SoftBodyNode::getPointMass(size_t _idx) const +const PointMass* SoftBodyNode::getPointMass(std::size_t _idx) const { return const_cast(this)->getPointMass(_idx); } @@ -287,8 +287,8 @@ void SoftBodyNode::configurePointMasses(ShapeNode* softNode) { const UniqueProperties& softProperties = mAspectProperties; - size_t newCount = softProperties.mPointProps.size(); - size_t oldCount = mPointMasses.size(); + std::size_t newCount = softProperties.mPointProps.size(); + std::size_t oldCount = mPointMasses.size(); if(newCount == oldCount) return; @@ -296,14 +296,14 @@ void SoftBodyNode::configurePointMasses(ShapeNode* softNode) // Adjust the number of PointMass objects since that has changed if(newCount < oldCount) { - for(size_t i = newCount; i < oldCount; ++i) + for(std::size_t i = newCount; i < oldCount; ++i) delete mPointMasses[i]; mPointMasses.resize(newCount); } else if(oldCount < newCount) { mPointMasses.resize(newCount); - for(size_t i = oldCount; i < newCount; ++i) + for(std::size_t i = oldCount; i < newCount; ++i) { mPointMasses[i] = new PointMass(this); mPointMasses[i]->mIndex = i; @@ -333,7 +333,7 @@ void SoftBodyNode::configurePointMasses(ShapeNode* softNode) << "SoftMeshShape.\n"; std::cout << "ShapeNodes: " << std::endl; - for(size_t i=0; i < getNumShapeNodes(); ++i) + for(std::size_t i=0; i < getNumShapeNodes(); ++i) { std::cout << "- " << i << ") " << getShapeNode(i)->getName() << std::endl; } @@ -348,7 +348,7 @@ void SoftBodyNode::init(const SkeletonPtr& _skeleton) { BodyNode::init(_skeleton); - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses[i]->init(); // //---------------------------------------------------------------------------- @@ -377,7 +377,7 @@ void SoftBodyNode::init(const SkeletonPtr& _skeleton) //void SoftBodyNode::aggregatePointMassGenCoords( // std::vector* _genCoords) //{ -// for (size_t i = 0; i < getNumPointMasses(); ++i) +// for (std::size_t i = 0; i < getNumPointMasses(); ++i) // { // PointMass* pointMass = getPointMass(i); // for (int j = 0; j < pointMass->getNumDofs(); ++j) @@ -406,7 +406,7 @@ double SoftBodyNode::getMass() const { double totalMass = BodyNode::getMass(); - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) totalMass += mPointMasses.at(i)->getMass(); return totalMass; @@ -487,7 +487,7 @@ PointMass* SoftBodyNode::addPointMass(const PointMass::Properties& _properties) } //============================================================================== -void SoftBodyNode::connectPointMasses(size_t _idx1, size_t _idx2) +void SoftBodyNode::connectPointMasses(std::size_t _idx1, std::size_t _idx2) { assert(_idx1 != _idx2); assert(_idx1 < mPointMasses.size()); @@ -505,14 +505,14 @@ void SoftBodyNode::addFace(const Eigen::Vector3i& _face) } //============================================================================== -const Eigen::Vector3i& SoftBodyNode::getFace(size_t _idx) const +const Eigen::Vector3i& SoftBodyNode::getFace(std::size_t _idx) const { assert(_idx < mAspectProperties.mFaces.size()); return mAspectProperties.mFaces[_idx]; } //============================================================================== -size_t SoftBodyNode::getNumFaces() const +std::size_t SoftBodyNode::getNumFaces() const { return mAspectProperties.mFaces.size(); } @@ -522,7 +522,7 @@ void SoftBodyNode::clearConstraintImpulse() { BodyNode::clearConstraintImpulse(); - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->clearConstraintImpulse(); } @@ -539,7 +539,7 @@ void SoftBodyNode::updateTransform() { BodyNode::updateTransform(); - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->updateTransform(); mNotifier->clearTransformNotice(); @@ -550,7 +550,7 @@ void SoftBodyNode::updateVelocity() { BodyNode::updateVelocity(); - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->updateVelocity(); mNotifier->clearVelocityNotice(); @@ -561,7 +561,7 @@ void SoftBodyNode::updatePartialAcceleration() const { BodyNode::updatePartialAcceleration(); - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->updatePartialAcceleration(); mNotifier->clearPartialAccelerationNotice(); @@ -572,7 +572,7 @@ void SoftBodyNode::updateAccelerationID() { BodyNode::updateAccelerationID(); - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->updateAccelerationID(); mNotifier->clearAccelerationNotice(); @@ -634,7 +634,7 @@ void SoftBodyNode::updateJointForceID(double _timeStep, bool _withDampingForces, bool _withSpringForces) { - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->updateJointForceID(_timeStep, _withDampingForces, _withSpringForces); @@ -839,16 +839,16 @@ void SoftBodyNode::updateMassMatrix() { BodyNode::updateMassMatrix(); -// for (size_t i = 0; i < mPointMasses.size(); ++i) +// for (std::size_t i = 0; i < mPointMasses.size(); ++i) // mPointMasses.at(i)->updateMassMatrix(); } //============================================================================== -void SoftBodyNode::aggregateMassMatrix(Eigen::MatrixXd& _MCol, size_t _col) +void SoftBodyNode::aggregateMassMatrix(Eigen::MatrixXd& _MCol, std::size_t _col) { BodyNode::aggregateMassMatrix(_MCol, _col); // //------------------------ PointMass Part ------------------------------------ -// for (size_t i = 0; i < mPointMasses.size(); ++i) +// for (std::size_t i = 0; i < mPointMasses.size(); ++i) // mPointMasses.at(i)->aggregateMassMatrix(_MCol, _col); // //----------------------- SoftBodyNode Part ---------------------------------- @@ -888,7 +888,7 @@ void SoftBodyNode::aggregateMassMatrix(Eigen::MatrixXd& _MCol, size_t _col) } //============================================================================== -void SoftBodyNode::aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, +void SoftBodyNode::aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, std::size_t _col, double _timeStep) { // TODO(JS): Need to be reimplemented @@ -896,7 +896,7 @@ void SoftBodyNode::aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, const Eigen::Matrix6d& mI = BodyNode::mAspectProperties.mInertia.getSpatialTensor(); //------------------------ PointMass Part ------------------------------------ - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->aggregateAugMassMatrix(_MCol, _col, _timeStep); //----------------------- SoftBodyNode Part ---------------------------------- @@ -917,12 +917,12 @@ void SoftBodyNode::aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, } assert(!math::isNan(mM_F)); - size_t dof = mParentJoint->getNumDofs(); + std::size_t dof = mParentJoint->getNumDofs(); if (dof > 0) { Eigen::MatrixXd K = Eigen::MatrixXd::Zero(dof, dof); Eigen::MatrixXd D = Eigen::MatrixXd::Zero(dof, dof); - for (size_t i = 0; i < dof; ++i) + for (std::size_t i = 0; i < dof; ++i) { K(i, i) = mParentJoint->getSpringStiffness(i); D(i, i) = mParentJoint->getDampingCoefficient(i); @@ -941,7 +941,7 @@ void SoftBodyNode::aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, void SoftBodyNode::updateInvMassMatrix() { //------------------------ PointMass Part ------------------------------------ - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->updateInvMassMatrix(); //----------------------- SoftBodyNode Part ---------------------------------- @@ -977,7 +977,7 @@ void SoftBodyNode::updateInvAugMassMatrix() BodyNode::updateInvAugMassMatrix(); // //------------------------ PointMass Part ------------------------------------ -//// for (size_t i = 0; i < mPointMasses.size(); ++i) +//// for (std::size_t i = 0; i < mPointMasses.size(); ++i) //// mPointMasses.at(i)->updateInvAugMassMatrix(); // //----------------------- SoftBodyNode Part ---------------------------------- @@ -1008,7 +1008,7 @@ void SoftBodyNode::updateInvAugMassMatrix() } //============================================================================== -void SoftBodyNode::aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col) +void SoftBodyNode::aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, std::size_t _col) { if (mParentBodyNode) { @@ -1034,13 +1034,13 @@ void SoftBodyNode::aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col mParentJoint->addInvMassMatrixSegmentTo(mInvM_U); // - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->aggregateInvMassMatrix(_InvMCol, _col); } //============================================================================== void SoftBodyNode::aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, - size_t _col, + std::size_t _col, double _timeStep) { BodyNode::aggregateInvAugMassMatrix(_InvMCol, _col, _timeStep); @@ -1068,7 +1068,7 @@ void SoftBodyNode::aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, // mParentJoint->addInvMassMatrixSegmentTo(mInvM_U); // // -//// for (size_t i = 0; i < mPointMasses.size(); ++i) +//// for (std::size_t i = 0; i < mPointMasses.size(); ++i) //// mPointMasses.at(i)->aggregateInvAugMassMatrix(_InvMCol, _col, _timeStep); } @@ -1085,7 +1085,7 @@ void SoftBodyNode::aggregateGravityForceVector(Eigen::VectorXd& _g, const Eigen::Matrix6d& mI = BodyNode::mAspectProperties.mInertia.getSpatialTensor(); //------------------------ PointMass Part ------------------------------------ - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->aggregateGravityForceVector(_g, _gravity); //----------------------- SoftBodyNode Part ---------------------------------- @@ -1122,7 +1122,7 @@ void SoftBodyNode::updateCombinedVector() { BodyNode::updateCombinedVector(); -// for (size_t i = 0; i < mPointMasses.size(); ++i) +// for (std::size_t i = 0; i < mPointMasses.size(); ++i) // mPointMasses.at(i)->updateCombinedVector(); } @@ -1132,7 +1132,7 @@ void SoftBodyNode::aggregateCombinedVector(Eigen::VectorXd& _Cg, { BodyNode::aggregateCombinedVector(_Cg, _gravity); // //------------------------ PointMass Part ------------------------------------ -// for (size_t i = 0; i < mPointMasses.size(); ++i) +// for (std::size_t i = 0; i < mPointMasses.size(); ++i) // mPointMasses.at(i)->aggregateCombinedVector(_Cg, _gravity); // //----------------------- SoftBodyNode Part ---------------------------------- @@ -1174,7 +1174,7 @@ void SoftBodyNode::aggregateCombinedVector(Eigen::VectorXd& _Cg, void SoftBodyNode::aggregateExternalForces(Eigen::VectorXd& _Fext) { //------------------------ PointMass Part ------------------------------------ - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->aggregateExternalForces(_Fext); //----------------------- SoftBodyNode Part ---------------------------------- @@ -1209,7 +1209,7 @@ void SoftBodyNode::clearExternalForces() { BodyNode::clearExternalForces(); - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses.at(i)->clearExtForce(); } @@ -1218,7 +1218,7 @@ void SoftBodyNode::clearInternalForces() { BodyNode::clearInternalForces(); - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) mPointMasses[i]->resetForces(); } @@ -1260,7 +1260,7 @@ void SoftBodyNode::updateInertiaWithPointMass() BodyNode::mAspectProperties.mInertia.getSpatialTensor(); mI2 = mI; - for (size_t i = 0; i < mPointMasses.size(); ++i) + for (std::size_t i = 0; i < mPointMasses.size(); ++i) { } @@ -1282,7 +1282,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( // Point masses //---------------------------------------------------------------------------- // Number of point masses - size_t nPointMasses = 8; + std::size_t nPointMasses = 8; properties.mPointProps.resize(8); // Mass per vertices @@ -1301,7 +1301,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( restingPos[7] = _size.cwiseProduct(Eigen::Vector3d(+1.0, +1.0, +1.0)) * 0.5; // Point masses - for (size_t i = 0; i < nPointMasses; ++i) + for (std::size_t i = 0; i < nPointMasses; ++i) { properties.mPointProps[i].mX0 = _localTransform * restingPos[i]; properties.mPointProps[i].mMass = mass; @@ -1400,7 +1400,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } } - size_t id = 0; + std::size_t id = 0; SoftBodyNode::UniqueProperties properties( _vertexStiffness, _edgeStiffness, _dampingCoeff); @@ -1411,14 +1411,14 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( // Number of point masses assert(frags[0] > 1 && frags[1] > 1 && frags[2] > 1); - size_t nCorners = 8; - size_t nVerticesAtEdgeX = frags[0] - 2; - size_t nVerticesAtEdgeY = frags[1] - 2; - size_t nVerticesAtEdgeZ = frags[2] - 2; - size_t nVerticesAtSideX = nVerticesAtEdgeY*nVerticesAtEdgeZ; - size_t nVerticesAtSideY = nVerticesAtEdgeZ*nVerticesAtEdgeX; - size_t nVerticesAtSideZ = nVerticesAtEdgeX*nVerticesAtEdgeY; - size_t nVertices + std::size_t nCorners = 8; + std::size_t nVerticesAtEdgeX = frags[0] - 2; + std::size_t nVerticesAtEdgeY = frags[1] - 2; + std::size_t nVerticesAtEdgeZ = frags[2] - 2; + std::size_t nVerticesAtSideX = nVerticesAtEdgeY*nVerticesAtEdgeZ; + std::size_t nVerticesAtSideY = nVerticesAtEdgeZ*nVerticesAtEdgeX; + std::size_t nVerticesAtSideZ = nVerticesAtEdgeX*nVerticesAtEdgeY; + std::size_t nVertices = nCorners + 4*(nVerticesAtEdgeX + nVerticesAtEdgeY + nVerticesAtEdgeZ) + 2*(nVerticesAtSideX + nVerticesAtSideY + nVerticesAtSideZ); @@ -1430,7 +1430,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( _size[1]/(frags[1] - 1), _size[2]/(frags[2] - 1)); - typedef std::pair PointPair; + typedef std::pair PointPair; std::vector corners(nCorners); @@ -1479,7 +1479,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( beginPts[6] = x1y1z1; beginPts[7] = x0y1z1; - for (size_t i = 0; i < nCorners; ++i) + for (std::size_t i = 0; i < nCorners; ++i) { corners[i].first.setRestingPosition(_localTransform * beginPts[i]); corners[i].first.setMass(mass); @@ -1495,11 +1495,11 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( beginPts[2] = x0y1z1; beginPts[3] = x0y0z1; - for (size_t i = 0; i < 4; ++i) + for (std::size_t i = 0; i < 4; ++i) { restPos = beginPts[i]; - for (size_t j = 0; j < nVerticesAtEdgeX; ++j) + for (std::size_t j = 0; j < nVerticesAtEdgeX; ++j) { restPos[0] += segLength[0]; @@ -1517,11 +1517,11 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( beginPts[2] = x1y0z1; beginPts[3] = x1y0z0; - for (size_t i = 0; i < 4; ++i) + for (std::size_t i = 0; i < 4; ++i) { restPos = beginPts[i]; - for (size_t j = 0; j < nVerticesAtEdgeY; ++j) + for (std::size_t j = 0; j < nVerticesAtEdgeY; ++j) { restPos[1] += segLength[1]; @@ -1539,11 +1539,11 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( beginPts[2] = x1y1z0; beginPts[3] = x0y1z0; - for (size_t i = 0; i < 4; ++i) + for (std::size_t i = 0; i < 4; ++i) { restPos = beginPts[i]; - for (size_t j = 0; j < nVerticesAtEdgeZ; ++j) + for (std::size_t j = 0; j < nVerticesAtEdgeZ; ++j) { restPos[2] += segLength[2]; @@ -1558,12 +1558,12 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( // Negative X side restPos = x0y0z0; - for (size_t i = 0; i < nVerticesAtEdgeY; ++i) + for (std::size_t i = 0; i < nVerticesAtEdgeY; ++i) { restPos[2] = x0y0z0[2]; restPos[1] += segLength[1]; - for (size_t j = 0; j < nVerticesAtEdgeZ; ++j) + for (std::size_t j = 0; j < nVerticesAtEdgeZ; ++j) { restPos[2] += segLength[2]; @@ -1578,12 +1578,12 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( // Positive X side restPos = x1y0z0; - for (size_t i = 0; i < nVerticesAtEdgeY; ++i) + for (std::size_t i = 0; i < nVerticesAtEdgeY; ++i) { restPos[2] = x1y0z0[2]; restPos[1] += segLength[1]; - for (size_t j = 0; j < nVerticesAtEdgeZ; ++j) + for (std::size_t j = 0; j < nVerticesAtEdgeZ; ++j) { restPos[2] += segLength[2]; @@ -1598,12 +1598,12 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( // Negative Y side restPos = x0y0z0; - for (size_t i = 0; i < nVerticesAtEdgeZ; ++i) + for (std::size_t i = 0; i < nVerticesAtEdgeZ; ++i) { restPos[0] = x0y0z0[0]; restPos[2] += segLength[2]; - for (size_t j = 0; j < nVerticesAtEdgeX; ++j) + for (std::size_t j = 0; j < nVerticesAtEdgeX; ++j) { restPos[0] += segLength[0]; @@ -1618,12 +1618,12 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( // Positive Y side restPos = x0y1z0; - for (size_t i = 0; i < nVerticesAtEdgeZ; ++i) + for (std::size_t i = 0; i < nVerticesAtEdgeZ; ++i) { restPos[0] = x0y1z0[0]; restPos[2] += segLength[2]; - for (size_t j = 0; j < nVerticesAtEdgeX; ++j) + for (std::size_t j = 0; j < nVerticesAtEdgeX; ++j) { restPos[0] += segLength[0]; @@ -1638,12 +1638,12 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( // Negative Z side restPos = x0y0z0; - for (size_t i = 0; i < nVerticesAtEdgeX; ++i) + for (std::size_t i = 0; i < nVerticesAtEdgeX; ++i) { restPos[1] = x0y0z0[1]; restPos[0] += segLength[0]; - for (size_t j = 0; j < nVerticesAtEdgeY; ++j) + for (std::size_t j = 0; j < nVerticesAtEdgeY; ++j) { restPos[1] += segLength[1]; @@ -1658,12 +1658,12 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( // Positive Z side restPos = x0y0z1; - for (size_t i = 0; i < nVerticesAtEdgeX; ++i) + for (std::size_t i = 0; i < nVerticesAtEdgeX; ++i) { restPos[1] = x0y0z1[1]; restPos[0] += segLength[0]; - for (size_t j = 0; j < nVerticesAtEdgeY; ++j) + for (std::size_t j = 0; j < nVerticesAtEdgeY; ++j) { restPos[1] += segLength[1]; @@ -1678,10 +1678,10 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( //---------------------------------------------------------------------------- // Faces //---------------------------------------------------------------------------- - size_t nFacesX = 2*(frags[1] - 1)*(frags[2] - 1); - size_t nFacesY = 2*(frags[2] - 1)*(frags[0] - 1); - size_t nFacesZ = 2*(frags[0] - 1)*(frags[1] - 1); - size_t nFaces = 2*nFacesX + 2*nFacesY + 2*nFacesZ; + std::size_t nFacesX = 2*(frags[1] - 1)*(frags[2] - 1); + std::size_t nFacesY = 2*(frags[2] - 1)*(frags[0] - 1); + std::size_t nFacesZ = 2*(frags[0] - 1)*(frags[1] - 1); + std::size_t nFaces = 2*nFacesX + 2*nFacesY + 2*nFacesZ; std::vector faces(nFaces, Eigen::Vector3i::Zero()); @@ -1992,7 +1992,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( properties.addFace(faces[47]); // EdgeX[0] - for (size_t i = 0; i < edgeX[0].size() - 1; ++i) + for (std::size_t i = 0; i < edgeX[0].size() - 1; ++i) { faces[fIdx][0] = edgeX[0][i].second; faces[fIdx][1] = edgeX[0][i + 1].second; @@ -2020,7 +2020,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // EdgeX[1] - for (size_t i = 0; i < edgeX[1].size() - 1; ++i) + for (std::size_t i = 0; i < edgeX[1].size() - 1; ++i) { faces[fIdx][0] = edgeX[1][i].second; faces[fIdx][1] = sideYPos[0][i].second; @@ -2048,7 +2048,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // EdgeX[2] - for (size_t i = 0; i < edgeX[2].size() - 1; ++i) + for (std::size_t i = 0; i < edgeX[2].size() - 1; ++i) { faces[fIdx][0] = edgeX[2][i + 1].second; faces[fIdx][1] = sideYPos.back()[i + 1].second; @@ -2076,7 +2076,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // EdgeX[3] - for (size_t i = 0; i < edgeX[3].size() - 1; ++i) + for (std::size_t i = 0; i < edgeX[3].size() - 1; ++i) { faces[fIdx][0] = edgeX[3][i].second; faces[fIdx][1] = sideYNeg.back()[i].second; @@ -2104,7 +2104,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // edgeY[0] - for (size_t i = 0; i < edgeY[0].size() - 1; ++i) + for (std::size_t i = 0; i < edgeY[0].size() - 1; ++i) { faces[fIdx][0] = edgeY[0][i + 1].second; faces[fIdx][1] = sideZNeg[0][i + 1].second; @@ -2132,7 +2132,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // edgeY[1] - for (size_t i = 0; i < edgeY[1].size() - 1; ++i) + for (std::size_t i = 0; i < edgeY[1].size() - 1; ++i) { faces[fIdx][0] = edgeY[1][i].second; faces[fIdx][1] = sideZPos[0][i].second; @@ -2160,7 +2160,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // edgeY[2] - for (size_t i = 0; i < edgeY[2].size() - 1; ++i) + for (std::size_t i = 0; i < edgeY[2].size() - 1; ++i) { faces[fIdx][0] = edgeY[2][i + 1].second; faces[fIdx][1] = sideZPos.back()[i + 1].second; @@ -2188,7 +2188,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // edgeY[3] - for (size_t i = 0; i < edgeY[3].size() - 1; ++i) + for (std::size_t i = 0; i < edgeY[3].size() - 1; ++i) { faces[fIdx][0] = edgeY[3][i].second; faces[fIdx][1] = sideZNeg.back()[i].second; @@ -2216,7 +2216,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // edgeZ[0] - for (size_t i = 0; i < edgeZ[0].size() - 1; ++i) + for (std::size_t i = 0; i < edgeZ[0].size() - 1; ++i) { faces[fIdx][0] = edgeZ[0][i + 1].second; faces[fIdx][1] = sideXNeg[0][i + 1].second; @@ -2244,7 +2244,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // edgeZ[1] - for (size_t i = 0; i < edgeZ[1].size() - 1; ++i) + for (std::size_t i = 0; i < edgeZ[1].size() - 1; ++i) { faces[fIdx][0] = edgeZ[1][i].second; faces[fIdx][1] = sideXPos[0][i].second; @@ -2272,7 +2272,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // edgeZ[2] - for (size_t i = 0; i < edgeZ[2].size() - 1; ++i) + for (std::size_t i = 0; i < edgeZ[2].size() - 1; ++i) { faces[fIdx][0] = edgeZ[2][i + 1].second; faces[fIdx][1] = sideXPos.back()[i + 1].second; @@ -2300,7 +2300,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // edgeZ[3] - for (size_t i = 0; i < edgeZ[3].size() - 1; ++i) + for (std::size_t i = 0; i < edgeZ[3].size() - 1; ++i) { faces[fIdx][0] = edgeZ[3][i].second; faces[fIdx][1] = sideXNeg.back()[i].second; @@ -2328,9 +2328,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // -X side - for (size_t i = 0; i < sideXNeg.size() - 1; ++i) + for (std::size_t i = 0; i < sideXNeg.size() - 1; ++i) { - for (size_t j = 0; j < sideXNeg[i].size() - 1; ++j) + for (std::size_t j = 0; j < sideXNeg[i].size() - 1; ++j) { faces[fIdx][0] = sideXNeg[i + 0][j + 0].second; faces[fIdx][1] = sideXNeg[i + 0][j + 1].second; @@ -2347,9 +2347,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // +X side - for (size_t i = 0; i < sideXPos.size() - 1; ++i) + for (std::size_t i = 0; i < sideXPos.size() - 1; ++i) { - for (size_t j = 0; j < sideXPos[i].size() - 1; ++j) + for (std::size_t j = 0; j < sideXPos[i].size() - 1; ++j) { faces[fIdx][0] = sideXPos[i + 0][j + 0].second; faces[fIdx][1] = sideXPos[i + 1][j + 0].second; @@ -2366,9 +2366,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // -Y side - for (size_t i = 0; i < sideYNeg.size() - 1; ++i) + for (std::size_t i = 0; i < sideYNeg.size() - 1; ++i) { - for (size_t j = 0; j < sideYNeg[i].size() - 1; ++j) + for (std::size_t j = 0; j < sideYNeg[i].size() - 1; ++j) { faces[fIdx][0] = sideYNeg[i + 0][j + 0].second; faces[fIdx][1] = sideYNeg[i + 0][j + 1].second; @@ -2385,9 +2385,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // +Y side - for (size_t i = 0; i < sideYPos.size() - 1; ++i) + for (std::size_t i = 0; i < sideYPos.size() - 1; ++i) { - for (size_t j = 0; j < sideYPos[i].size() - 1; ++j) + for (std::size_t j = 0; j < sideYPos[i].size() - 1; ++j) { faces[fIdx][0] = sideYPos[i + 0][j + 0].second; faces[fIdx][1] = sideYPos[i + 1][j + 0].second; @@ -2404,9 +2404,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // -Z side - for (size_t i = 0; i < sideZNeg.size() - 1; ++i) + for (std::size_t i = 0; i < sideZNeg.size() - 1; ++i) { - for (size_t j = 0; j < sideZNeg[i].size() - 1; ++j) + for (std::size_t j = 0; j < sideZNeg[i].size() - 1; ++j) { faces[fIdx][0] = sideZNeg[i + 0][j + 0].second; faces[fIdx][1] = sideZNeg[i + 0][j + 1].second; @@ -2423,9 +2423,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeBoxProperties( } // +Z side - for (size_t i = 0; i < sideZPos.size() - 1; ++i) + for (std::size_t i = 0; i < sideZPos.size() - 1; ++i) { - for (size_t j = 0; j < sideZPos[i].size() - 1; ++j) + for (std::size_t j = 0; j < sideZPos[i].size() - 1; ++j) { faces[fIdx][0] = sideZPos[i + 0][j + 0].second; faces[fIdx][1] = sideZPos[i + 1][j + 0].second; @@ -2479,7 +2479,7 @@ SoftBodyNodeHelper::makeSinglePointMassProperties( // Point masses //---------------------------------------------------------------------------- // Number of point masses - size_t nPointMasses = 1; + std::size_t nPointMasses = 1; // Mass per vertices double mass = _totalMass / nPointMasses; @@ -2490,7 +2490,7 @@ SoftBodyNodeHelper::makeSinglePointMassProperties( restingPos[0] = Eigen::Vector3d(+0.1, +0.1, +0.1); // Point masses - for (size_t i = 0; i < nPointMasses; ++i) + for (std::size_t i = 0; i < nPointMasses; ++i) { PointMass::Properties point(restingPos[i], mass); properties.addPointMass(point); @@ -2517,8 +2517,8 @@ void SoftBodyNodeHelper::setSinglePointMass(SoftBodyNode* _softBodyNode, //============================================================================== SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeEllipsoidProperties( const Eigen::Vector3d& _size, - size_t _nSlices, - size_t _nStacks, + std::size_t _nSlices, + std::size_t _nStacks, double _totalMass, double _vertexStiffness, double _edgeStiffness, @@ -2547,13 +2547,13 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeEllipsoidProperties( // middle float drho = 1_pi / _nStacks; float dtheta = 2_pi / _nSlices; - for (size_t i = 1; i < _nStacks; i++) + for (std::size_t i = 1; i < _nStacks; i++) { float rho = i * drho; float srho = (sin(rho)); float crho = (cos(rho)); - for (size_t j = 0; j < _nSlices; j++) + for (std::size_t j = 0; j < _nSlices; j++) { float theta = (j == _nSlices) ? 0.0f : j * dtheta; float stheta = (-sin(theta)); @@ -2578,22 +2578,22 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeEllipsoidProperties( //---------------------------------------------------------------------------- // a) longitudinal // -- top - for (size_t i = 0; i < _nSlices; i++) + for (std::size_t i = 0; i < _nSlices; i++) properties.connectPointMasses(0, i + 1); // -- middle - for (size_t i = 0; i < _nStacks - 2; i++) - for (size_t j = 0; j < _nSlices; j++) + for (std::size_t i = 0; i < _nStacks - 2; i++) + for (std::size_t j = 0; j < _nSlices; j++) properties.connectPointMasses(i*_nSlices + j + 1, (i + 1)*_nSlices + j + 1); // -- bottom - for (size_t i = 0; i < _nSlices; i++) + for (std::size_t i = 0; i < _nSlices; i++) properties.connectPointMasses((_nStacks-1)*_nSlices + 1, (_nStacks-2)*_nSlices + i + 1); // b) latitudinal - for (size_t i = 0; i < _nStacks - 1; i++) + for (std::size_t i = 0; i < _nStacks - 1; i++) { - for (size_t j = 0; j < _nSlices - 1; j++) + for (std::size_t j = 0; j < _nSlices - 1; j++) { properties.connectPointMasses(i*_nSlices + j + 1, i*_nSlices + j + 2); } @@ -2601,9 +2601,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeEllipsoidProperties( } // c) cross (shear) - for (size_t i = 0; i < _nStacks - 2; i++) + for (std::size_t i = 0; i < _nStacks - 2; i++) { - for (size_t j = 0; j < _nSlices - 1; j++) + for (std::size_t j = 0; j < _nSlices - 1; j++) { properties.connectPointMasses(i * _nSlices + j + 1, (i + 1) * _nSlices + j + 2); @@ -2623,7 +2623,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeEllipsoidProperties( // top meshIdx1 = 0; - for (size_t i = 0; i < _nSlices - 1; i++) + for (std::size_t i = 0; i < _nSlices - 1; i++) { meshIdx2 = i + 1; meshIdx3 = i + 2; @@ -2634,9 +2634,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeEllipsoidProperties( properties.addFace(Eigen::Vector3i(meshIdx1, meshIdx2, meshIdx3)); // middle - for (size_t i = 0; i < _nStacks - 2; i++) + for (std::size_t i = 0; i < _nStacks - 2; i++) { - for (size_t j = 0; j < _nSlices - 1; j++) + for (std::size_t j = 0; j < _nSlices - 1; j++) { meshIdx1 = i*_nSlices + j + 1; meshIdx2 = (i + 1)*_nSlices + j + 1; @@ -2662,7 +2662,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeEllipsoidProperties( // bottom meshIdx1 = (_nStacks-1)*_nSlices + 1; - for (size_t i = 0; i < _nSlices - 1; i++) + for (std::size_t i = 0; i < _nSlices - 1; i++) { meshIdx2 = (_nStacks-2)*_nSlices + i + 2; meshIdx3 = (_nStacks-2)*_nSlices + i + 1; @@ -2678,8 +2678,8 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeEllipsoidProperties( //============================================================================== void SoftBodyNodeHelper::setEllipsoid(SoftBodyNode* _softBodyNode, const Eigen::Vector3d& _size, - size_t _nSlices, - size_t _nStacks, + std::size_t _nSlices, + std::size_t _nStacks, double _totalMass, double _vertexStiffness, double _edgeStiffness, @@ -2699,9 +2699,9 @@ void SoftBodyNodeHelper::setEllipsoid(SoftBodyNode* _softBodyNode, SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( double _radius, double _height, - size_t _nSlices, - size_t _nStacks, - size_t _nRings, + std::size_t _nSlices, + std::size_t _nStacks, + std::size_t _nRings, double _totalMass, double _vertexStiffness, double _edgeStiffness, @@ -2717,9 +2717,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( // Point masses //---------------------------------------------------------------------------- // Number of point masses - size_t nTopPointMasses = _nSlices * (_nRings - 1) + 1; - size_t nDrumPointMasses = (_nStacks + 1) * _nSlices; - size_t nTotalMasses = nDrumPointMasses + 2 * nTopPointMasses; + std::size_t nTopPointMasses = _nSlices * (_nRings - 1) + 1; + std::size_t nDrumPointMasses = (_nStacks + 1) * _nSlices; + std::size_t nTotalMasses = nDrumPointMasses + 2 * nTopPointMasses; // Mass per vertices double mass = _totalMass / nTotalMasses; @@ -2732,12 +2732,12 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( properties.addPointMass(PointMass::Properties( Eigen::Vector3d(0.0, 0.0, 0.5 * _height), mass)); - for (size_t i = 1; i < _nRings; ++i) + for (std::size_t i = 1; i < _nRings; ++i) { float z = 0.5; float radius = i * dradius; - for (size_t j = 0; j < _nSlices; j++) + for (std::size_t j = 0; j < _nSlices; j++) { float theta = (j == _nSlices) ? 0.0f : j * dtheta; float stheta = (-sin(theta)); @@ -2753,11 +2753,11 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( // -- middle float dz = -1.0 / static_cast(_nStacks); - for (size_t i = 0; i < _nStacks + 1; i++) + for (std::size_t i = 0; i < _nStacks + 1; i++) { float z = 0.5 + i * dz; - for (size_t j = 0; j < _nSlices; j++) + for (std::size_t j = 0; j < _nSlices; j++) { float theta = (j == _nSlices) ? 0.0f : j * dtheta; float stheta = (-sin(theta)); @@ -2772,12 +2772,12 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( } // -- bottom - for (size_t i = 1; i < _nRings; ++i) + for (std::size_t i = 1; i < _nRings; ++i) { float z = -0.5; float radius = _radius - i * dradius; - for (size_t j = 0; j < _nSlices; j++) + for (std::size_t j = 0; j < _nSlices; j++) { float theta = (j == _nSlices) ? 0.0f : j * dtheta; float stheta = (-sin(theta)); @@ -2801,11 +2801,11 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( // a) longitudinal // -- top - for (size_t i = 0; i < _nSlices; i++) + for (std::size_t i = 0; i < _nSlices; i++) properties.connectPointMasses(0, i + 1); - for (size_t i = 0; i < _nRings - 1; i++) + for (std::size_t i = 0; i < _nRings - 1; i++) { - for (size_t j = 0; j < _nSlices; j++) + for (std::size_t j = 0; j < _nSlices; j++) { properties.connectPointMasses( _nSlices + 1 + (i + 0) * _nSlices + j, @@ -2813,9 +2813,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( } } // -- middle - for (size_t i = 0; i < _nStacks - 1; i++) + for (std::size_t i = 0; i < _nStacks - 1; i++) { - for (size_t j = 0; j < _nSlices; j++) + for (std::size_t j = 0; j < _nSlices; j++) { properties.connectPointMasses( nTopPointMasses + (i + 0) * _nSlices + j, @@ -2823,9 +2823,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( } } // -- bottom - for (size_t i = 0; i < _nRings - 1; i++) + for (std::size_t i = 0; i < _nRings - 1; i++) { - for (size_t j = 0; j < _nSlices; j++) + for (std::size_t j = 0; j < _nSlices; j++) { properties.connectPointMasses( nTopPointMasses + (nDrumPointMasses - _nSlices) @@ -2834,14 +2834,14 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( + (i + 1) * _nSlices + j); } } - for (size_t i = 1; i < _nSlices; i++) + for (std::size_t i = 1; i < _nSlices; i++) properties.connectPointMasses(nTotalMasses - 1 - i, nTotalMasses - 1); // b) latitudinal - for (size_t i = 0; i < _nStacks; i++) + for (std::size_t i = 0; i < _nStacks; i++) { - for (size_t j = 0; j < _nSlices - 1; j++) + for (std::size_t j = 0; j < _nSlices - 1; j++) { properties.connectPointMasses( nTopPointMasses + i * _nSlices + j + 0, @@ -2857,9 +2857,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( // c) cross (shear) // -- drum part - for (size_t i = 0; i < _nStacks - 2; i++) + for (std::size_t i = 0; i < _nStacks - 2; i++) { - for (size_t j = 0; j < _nSlices - 1; j++) + for (std::size_t j = 0; j < _nSlices - 1; j++) { properties.connectPointMasses( nTopPointMasses + (i + 0) * _nSlices + j + 0, @@ -2887,9 +2887,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( int meshIdx3 = 0; // top - size_t nConePointMass = 1; + std::size_t nConePointMass = 1; meshIdx1 = 0; - for (size_t i = 0; i < _nSlices - 1; i++) + for (std::size_t i = 0; i < _nSlices - 1; i++) { meshIdx2 = i + 1; meshIdx3 = i + 2; @@ -2898,9 +2898,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( meshIdx2 = _nSlices; meshIdx3 = 1; properties.addFace(Eigen::Vector3i(meshIdx1, meshIdx2, meshIdx3)); - for (size_t i = 0; i < _nRings - 1; ++i) + for (std::size_t i = 0; i < _nRings - 1; ++i) { - for (size_t j = 0; j < _nSlices - 1; ++j) + for (std::size_t j = 0; j < _nSlices - 1; ++j) { meshIdx1 = (i + 0) * _nSlices + j; meshIdx2 = (i + 1) * _nSlices + j; @@ -2933,9 +2933,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( } // middle - for (size_t i = 0; i < _nStacks; i++) + for (std::size_t i = 0; i < _nStacks; i++) { - for (size_t j = 0; j < _nSlices - 1; j++) + for (std::size_t j = 0; j < _nSlices - 1; j++) { meshIdx1 = (i + 0) * _nSlices + j; meshIdx2 = (i + 1) * _nSlices + j; @@ -2968,9 +2968,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( } // bottom - for (size_t i = 0; i < _nRings - 1; ++i) + for (std::size_t i = 0; i < _nRings - 1; ++i) { - for (size_t j = 0; j < _nSlices - 1; ++j) + for (std::size_t j = 0; j < _nSlices - 1; ++j) { meshIdx1 = (i + 0) * _nSlices + j; meshIdx2 = (i + 1) * _nSlices + j; @@ -3010,7 +3010,7 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( nTopPointMasses + (nDrumPointMasses - _nSlices) + meshIdx3)); } meshIdx1 = 1; - for (size_t i = 0; i < _nSlices - 1; i++) + for (std::size_t i = 0; i < _nSlices - 1; i++) { meshIdx2 = i + 2; meshIdx3 = i + 3; @@ -3033,9 +3033,9 @@ SoftBodyNode::UniqueProperties SoftBodyNodeHelper::makeCylinderProperties( void SoftBodyNodeHelper::setCylinder(SoftBodyNode* _softBodyNode, double _radius, double _height, - size_t _nSlices, - size_t _nStacks, - size_t _nRings, + std::size_t _nSlices, + std::size_t _nStacks, + std::size_t _nRings, double _totalMass, double _vertexStiffness, double _edgeStiffness, diff --git a/dart/dynamics/SoftBodyNode.h b/dart/dynamics/SoftBodyNode.h index a0130ba62daef..f2e3311061397 100644 --- a/dart/dynamics/SoftBodyNode.h +++ b/dart/dynamics/SoftBodyNode.h @@ -129,28 +129,28 @@ class SoftBodyNode : public detail::SoftBodyNodeBase PointMass* addPointMass(const PointMass::Properties& _properties); /// \brief - size_t getNumPointMasses() const; + std::size_t getNumPointMasses() const; /// \brief - PointMass* getPointMass(size_t _idx); + PointMass* getPointMass(std::size_t _idx); /// \brief - const PointMass* getPointMass(size_t _idx) const; + const PointMass* getPointMass(std::size_t _idx) const; /// Return all the point masses in this SoftBodyNode const std::vector& getPointMasses() const; /// \brief - void connectPointMasses(size_t _idx1, size_t _idx2); + void connectPointMasses(std::size_t _idx1, std::size_t _idx2); /// \brief void addFace(const Eigen::Vector3i& _face); /// \brief - const Eigen::Vector3i& getFace(size_t _idx) const; + const Eigen::Vector3i& getFace(std::size_t _idx) const; /// \brief - size_t getNumFaces() const; + std::size_t getNumFaces() const; // Documentation inherited. void clearConstraintImpulse() override; @@ -254,10 +254,10 @@ class SoftBodyNode : public detail::SoftBodyNodeBase void updateMassMatrix() override; // Documentation inherited. - void aggregateMassMatrix(Eigen::MatrixXd& _MCol, size_t _col) override; + void aggregateMassMatrix(Eigen::MatrixXd& _MCol, std::size_t _col) override; // Documentation inherited. - void aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, size_t _col, + void aggregateAugMassMatrix(Eigen::MatrixXd& _MCol, std::size_t _col, double _timeStep) override; // Documentation inherited. @@ -267,10 +267,10 @@ class SoftBodyNode : public detail::SoftBodyNodeBase void updateInvAugMassMatrix() override; // Documentation inherited. - void aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col) override; + void aggregateInvMassMatrix(Eigen::MatrixXd& _InvMCol, std::size_t _col) override; // Documentation inherited. - void aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, size_t _col, + void aggregateInvAugMassMatrix(Eigen::MatrixXd& _InvMCol, std::size_t _col, double _timeStep) override; // Documentation inherited. @@ -401,8 +401,8 @@ class SoftBodyNodeHelper /// Create a Properties struct for an Ellipsoid-shaped SoftBodyNode static SoftBodyNode::UniqueProperties makeEllipsoidProperties( const Eigen::Vector3d& _size, - size_t _nSlices, - size_t _nStacks, + std::size_t _nSlices, + std::size_t _nStacks, double _totalMass, double _vertexStiffness = DART_DEFAULT_VERTEX_STIFFNESS, double _edgeStiffness = DART_DEFAULT_EDGE_STIFNESS, @@ -412,8 +412,8 @@ class SoftBodyNodeHelper /// This should be called before SoftBodyNode::init() is called static void setEllipsoid(SoftBodyNode* _softBodyNode, const Eigen::Vector3d& _size, - size_t _nSlices, - size_t _nStacks, + std::size_t _nSlices, + std::size_t _nStacks, double _totalMass, double _vertexStiffness = DART_DEFAULT_VERTEX_STIFFNESS, double _edgeStiffness = DART_DEFAULT_EDGE_STIFNESS, @@ -423,9 +423,9 @@ class SoftBodyNodeHelper static SoftBodyNode::UniqueProperties makeCylinderProperties( double _radius, double _height, - size_t _nSlices, - size_t _nStacks, - size_t _nRings, + std::size_t _nSlices, + std::size_t _nStacks, + std::size_t _nRings, double _totalMass, double _vertexStiffness = DART_DEFAULT_VERTEX_STIFFNESS, double _edgeStiffness = DART_DEFAULT_EDGE_STIFNESS, @@ -436,9 +436,9 @@ class SoftBodyNodeHelper static void setCylinder(SoftBodyNode* _softBodyNode, double _radius, double _height, - size_t _nSlices, - size_t _nStacks, - size_t _nRings, + std::size_t _nSlices, + std::size_t _nStacks, + std::size_t _nRings, double _totalMass, double _vertexStiffness = DART_DEFAULT_VERTEX_STIFFNESS, double _edgeStiffness = DART_DEFAULT_EDGE_STIFNESS, diff --git a/dart/dynamics/SoftMeshShape.cpp b/dart/dynamics/SoftMeshShape.cpp index f6f558c665018..dd81ee49cd4c2 100644 --- a/dart/dynamics/SoftMeshShape.cpp +++ b/dart/dynamics/SoftMeshShape.cpp @@ -124,10 +124,10 @@ void SoftMeshShape::_buildMesh() void SoftMeshShape::update() { - size_t nVertices = mSoftBodyNode->getNumPointMasses(); + std::size_t nVertices = mSoftBodyNode->getNumPointMasses(); aiVector3D itAIVector3d; - for (size_t i = 0; i < nVertices; ++i) + for (std::size_t i = 0; i < nVertices; ++i) { PointMass* itPointMass = mSoftBodyNode->getPointMass(i); const Eigen::Vector3d& vertex = itPointMass->getLocalPosition(); diff --git a/dart/dynamics/SpecializedNodeManager.h b/dart/dynamics/SpecializedNodeManager.h index 9c986ae8d20d3..df1df5e713193 100644 --- a/dart/dynamics/SpecializedNodeManager.h +++ b/dart/dynamics/SpecializedNodeManager.h @@ -66,15 +66,15 @@ class BodyNodeSpecializedFor : /// Get the number of Nodes corresponding to the specified type template - size_t getNumNodes() const; + std::size_t getNumNodes() const; /// Get the Node of the specified type and the specified index template - NodeType* getNode(size_t index); + NodeType* getNode(std::size_t index); /// Get the Node of the specified type and the specified index template - const NodeType* getNode(size_t index) const; + const NodeType* getNode(std::size_t index) const; /// Check if this Manager is specialized for a specific type of Node template @@ -84,17 +84,17 @@ class BodyNodeSpecializedFor : /// Redirect to BasicNodeManagerForBodyNode::getNumNodes() template - size_t _getNumNodes(type) const; + std::size_t _getNumNodes(type) const; /// Specialized implementation of getNumNodes() - size_t _getNumNodes(type) const; + std::size_t _getNumNodes(type) const; - /// Redirect to BasicNodeManagerForBodyNode::getNode(size_t) + /// Redirect to BasicNodeManagerForBodyNode::getNode(std::size_t) template - NodeType* _getNode(type, size_t index); + NodeType* _getNode(type, std::size_t index); - /// Specialized implementation of getNode(size_t) - SpecNode* _getNode(type, size_t index); + /// Specialized implementation of getNode(std::size_t) + SpecNode* _getNode(type, std::size_t index); /// Return false template @@ -142,17 +142,17 @@ class SkeletonSpecializedFor : /// Get the number of Nodes of the specified type that are in the treeIndexth /// tree of this Skeleton template - size_t getNumNodes(size_t treeIndex) const; + std::size_t getNumNodes(std::size_t treeIndex) const; /// Get the nodeIndexth Node of the specified type within the tree of /// treeIndex. template - NodeType* getNode(size_t treeIndex, size_t nodeIndex); + NodeType* getNode(std::size_t treeIndex, std::size_t nodeIndex); /// Get the nodeIndexth Node of the specified type within the tree of /// treeIndex. template - const NodeType* getNode(size_t treeIndex, size_t nodeIndex) const; + const NodeType* getNode(std::size_t treeIndex, std::size_t nodeIndex) const; /// Get the Node of the specified type with the given name. template @@ -168,19 +168,19 @@ class SkeletonSpecializedFor : protected: - /// Redirect to BasicNodeManagerForSkeleton::getNumNodes(size_t) + /// Redirect to BasicNodeManagerForSkeleton::getNumNodes(std::size_t) template - size_t _getNumNodes(type, size_t treeIndex) const; + std::size_t _getNumNodes(type, std::size_t treeIndex) const; - /// Specialized implementation of getNumNodes(size_t) - size_t _getNumNodes(type, size_t treeIndex) const; + /// Specialized implementation of getNumNodes(std::size_t) + std::size_t _getNumNodes(type, std::size_t treeIndex) const; - /// Redirect to BasicNodeManagerForSkeleton::getNode(size_t, size_t) + /// Redirect to BasicNodeManagerForSkeleton::getNode(std::size_t, std::size_t) template - NodeType* _getNode(type, size_t treeIndex, size_t nodeIndex); + NodeType* _getNode(type, std::size_t treeIndex, std::size_t nodeIndex); - /// Specialized implementation of getNode(size_t, size_t) - SpecNode* _getNode(type, size_t treeIndex, size_t nodeIndex); + /// Specialized implementation of getNode(std::size_t, std::size_t) + SpecNode* _getNode(type, std::size_t treeIndex, std::size_t nodeIndex); /// Redirect to BasicNodeManagerForSkeleton::getNode(const std::string&) template diff --git a/dart/dynamics/TranslationalJoint.cpp b/dart/dynamics/TranslationalJoint.cpp index 8ad1ae20a5fe8..39234a8d2bf7c 100644 --- a/dart/dynamics/TranslationalJoint.cpp +++ b/dart/dynamics/TranslationalJoint.cpp @@ -102,7 +102,7 @@ const std::string& TranslationalJoint::getStaticType() } //============================================================================== -bool TranslationalJoint::isCyclic(size_t /*_index*/) const +bool TranslationalJoint::isCyclic(std::size_t /*_index*/) const { return false; } diff --git a/dart/dynamics/TranslationalJoint.h b/dart/dynamics/TranslationalJoint.h index dc5254102a572..a10235116e9f9 100644 --- a/dart/dynamics/TranslationalJoint.h +++ b/dart/dynamics/TranslationalJoint.h @@ -74,7 +74,7 @@ class TranslationalJoint : public MultiDofJoint<3> static const std::string& getStaticType(); // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; Eigen::Matrix getLocalJacobianStatic( const Eigen::Vector3d& _positions) const override; diff --git a/dart/dynamics/UniversalJoint.cpp b/dart/dynamics/UniversalJoint.cpp index 9112fa0875e1b..00bb1668c9a7a 100644 --- a/dart/dynamics/UniversalJoint.cpp +++ b/dart/dynamics/UniversalJoint.cpp @@ -116,7 +116,7 @@ const std::string& UniversalJoint::getStaticType() } //============================================================================== -bool UniversalJoint::isCyclic(size_t _index) const +bool UniversalJoint::isCyclic(std::size_t _index) const { return !hasPositionLimit(_index); } diff --git a/dart/dynamics/UniversalJoint.h b/dart/dynamics/UniversalJoint.h index e04c8a830f94d..efa84853f9b44 100644 --- a/dart/dynamics/UniversalJoint.h +++ b/dart/dynamics/UniversalJoint.h @@ -87,7 +87,7 @@ class UniversalJoint : public detail::UniversalJointBase static const std::string& getStaticType(); // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; /// void setAxis1(const Eigen::Vector3d& _axis); diff --git a/dart/dynamics/WeldJoint.cpp b/dart/dynamics/WeldJoint.cpp index 7bb7f2274f1cc..3846bf1ff98f1 100644 --- a/dart/dynamics/WeldJoint.cpp +++ b/dart/dynamics/WeldJoint.cpp @@ -71,7 +71,7 @@ const std::string& WeldJoint::getStaticType() } //============================================================================== -bool WeldJoint::isCyclic(size_t /*_index*/) const +bool WeldJoint::isCyclic(std::size_t /*_index*/) const { return false; } diff --git a/dart/dynamics/WeldJoint.h b/dart/dynamics/WeldJoint.h index 998deb38b5e36..9204b91aaf301 100644 --- a/dart/dynamics/WeldJoint.h +++ b/dart/dynamics/WeldJoint.h @@ -74,7 +74,7 @@ class WeldJoint : public ZeroDofJoint static const std::string& getStaticType(); // Documentation inherited - bool isCyclic(size_t _index) const override; + bool isCyclic(std::size_t _index) const override; // Documentation inherited void setTransformFromParentBodyNode(const Eigen::Isometry3d& _T) override; diff --git a/dart/dynamics/ZeroDofJoint.cpp b/dart/dynamics/ZeroDofJoint.cpp index 85b40d4140b21..4c6c478847b2e 100644 --- a/dart/dynamics/ZeroDofJoint.cpp +++ b/dart/dynamics/ZeroDofJoint.cpp @@ -64,7 +64,7 @@ ZeroDofJoint::Properties ZeroDofJoint::getZeroDofJointProperties() const } //============================================================================== -DegreeOfFreedom* ZeroDofJoint::getDof(size_t) +DegreeOfFreedom* ZeroDofJoint::getDof(std::size_t) { dterr << "[ZeroDofJoint::getDof] Attempting to get a DegreeOfFreedom from a " << "ZeroDofJoint. This is not allowed!\n"; @@ -73,7 +73,7 @@ DegreeOfFreedom* ZeroDofJoint::getDof(size_t) } //============================================================================== -const DegreeOfFreedom* ZeroDofJoint::getDof(size_t) const +const DegreeOfFreedom* ZeroDofJoint::getDof(std::size_t) const { dterr << "[ZeroDofJoint::getDof] Attempting to get a DegreeOfFreedom from a " << "ZeroDofJoint. This is not allowed!\n"; @@ -82,37 +82,37 @@ const DegreeOfFreedom* ZeroDofJoint::getDof(size_t) const } //============================================================================== -const std::string& ZeroDofJoint::setDofName(size_t, const std::string &, bool) +const std::string& ZeroDofJoint::setDofName(std::size_t, const std::string &, bool) { return emptyString; } //============================================================================== -void ZeroDofJoint::preserveDofName(size_t, bool) +void ZeroDofJoint::preserveDofName(std::size_t, bool) { // Do nothing } //============================================================================== -bool ZeroDofJoint::isDofNamePreserved(size_t) const +bool ZeroDofJoint::isDofNamePreserved(std::size_t) const { return false; } //============================================================================== -const std::string& ZeroDofJoint::getDofName(size_t) const +const std::string& ZeroDofJoint::getDofName(std::size_t) const { return emptyString; } //============================================================================== -size_t ZeroDofJoint::getNumDofs() const +std::size_t ZeroDofJoint::getNumDofs() const { return 0; } //============================================================================== -size_t ZeroDofJoint::getIndexInSkeleton(size_t _index) const +std::size_t ZeroDofJoint::getIndexInSkeleton(std::size_t _index) const { dterr << "[ZeroDofJoint::getIndexInSkeleton] This function should never be " << "called (" << _index << ")!\n"; @@ -122,7 +122,7 @@ size_t ZeroDofJoint::getIndexInSkeleton(size_t _index) const } //============================================================================== -size_t ZeroDofJoint::getIndexInTree(size_t _index) const +std::size_t ZeroDofJoint::getIndexInTree(std::size_t _index) const { dterr << "ZeroDofJoint::getIndexInTree] This function should never be " << "called (" << _index << ")!\n"; @@ -132,13 +132,13 @@ size_t ZeroDofJoint::getIndexInTree(size_t _index) const } //============================================================================== -void ZeroDofJoint::setCommand(size_t /*_index*/, double /*_command*/) +void ZeroDofJoint::setCommand(std::size_t /*_index*/, double /*_command*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getCommand(size_t _index) const +double ZeroDofJoint::getCommand(std::size_t _index) const { dterr << "[ZeroDofJoint::getCommand]: index[" << _index << "] out of range" << std::endl; @@ -165,13 +165,13 @@ void ZeroDofJoint::resetCommands() } //============================================================================== -void ZeroDofJoint::setPosition(size_t, double) +void ZeroDofJoint::setPosition(std::size_t, double) { // Do nothing } //============================================================================== -double ZeroDofJoint::getPosition(size_t _index) const +double ZeroDofJoint::getPosition(std::size_t _index) const { dterr << "getPosition index[" << _index << "] out of range" << std::endl; @@ -192,39 +192,39 @@ Eigen::VectorXd ZeroDofJoint::getPositions() const } //============================================================================== -void ZeroDofJoint::setPositionLowerLimit(size_t /*_index*/, +void ZeroDofJoint::setPositionLowerLimit(std::size_t /*_index*/, double /*_position*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getPositionLowerLimit(size_t /*_index*/) const +double ZeroDofJoint::getPositionLowerLimit(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::setPositionUpperLimit(size_t /*_index*/, +void ZeroDofJoint::setPositionUpperLimit(std::size_t /*_index*/, double /*_position*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getPositionUpperLimit(size_t /*_index*/) const +double ZeroDofJoint::getPositionUpperLimit(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -bool ZeroDofJoint::hasPositionLimit(size_t /*_index*/) const +bool ZeroDofJoint::hasPositionLimit(std::size_t /*_index*/) const { return true; } //============================================================================== -void ZeroDofJoint::resetPosition(size_t /*_index*/) +void ZeroDofJoint::resetPosition(std::size_t /*_index*/) { // Do nothing } @@ -236,13 +236,13 @@ void ZeroDofJoint::resetPositions() } //============================================================================== -void ZeroDofJoint::setInitialPosition(size_t /*_index*/, double /*_initial*/) +void ZeroDofJoint::setInitialPosition(std::size_t /*_index*/, double /*_initial*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getInitialPosition(size_t /*_index*/) const +double ZeroDofJoint::getInitialPosition(std::size_t /*_index*/) const { return 0.0; } @@ -260,13 +260,13 @@ Eigen::VectorXd ZeroDofJoint::getInitialPositions() const } //============================================================================== -void ZeroDofJoint::setVelocity(size_t /*_index*/, double /*_velocity*/) +void ZeroDofJoint::setVelocity(std::size_t /*_index*/, double /*_velocity*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getVelocity(size_t /*_index*/) const +double ZeroDofJoint::getVelocity(std::size_t /*_index*/) const { return 0.0; } @@ -284,33 +284,33 @@ Eigen::VectorXd ZeroDofJoint::getVelocities() const } //============================================================================== -void ZeroDofJoint::setVelocityLowerLimit(size_t /*_index*/, +void ZeroDofJoint::setVelocityLowerLimit(std::size_t /*_index*/, double /*_velocity*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getVelocityLowerLimit(size_t /*_index*/) const +double ZeroDofJoint::getVelocityLowerLimit(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::setVelocityUpperLimit(size_t /*_index*/, +void ZeroDofJoint::setVelocityUpperLimit(std::size_t /*_index*/, double /*_velocity*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getVelocityUpperLimit(size_t /*_index*/) const +double ZeroDofJoint::getVelocityUpperLimit(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::resetVelocity(size_t /*_index*/) +void ZeroDofJoint::resetVelocity(std::size_t /*_index*/) { // Do nothing } @@ -322,13 +322,13 @@ void ZeroDofJoint::resetVelocities() } //============================================================================== -void ZeroDofJoint::setInitialVelocity(size_t /*_index*/, double /*_initial*/) +void ZeroDofJoint::setInitialVelocity(std::size_t /*_index*/, double /*_initial*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getInitialVelocity(size_t /*_index*/) const +double ZeroDofJoint::getInitialVelocity(std::size_t /*_index*/) const { return 0.0; } @@ -346,13 +346,13 @@ Eigen::VectorXd ZeroDofJoint::getInitialVelocities() const } //============================================================================== -void ZeroDofJoint::setAcceleration(size_t /*_index*/, double /*_acceleration*/) +void ZeroDofJoint::setAcceleration(std::size_t /*_index*/, double /*_acceleration*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getAcceleration(size_t /*_index*/) const +double ZeroDofJoint::getAcceleration(std::size_t /*_index*/) const { return 0.0; } @@ -376,39 +376,39 @@ void ZeroDofJoint::resetAccelerations() } //============================================================================== -void ZeroDofJoint::setAccelerationLowerLimit(size_t /*_index*/, +void ZeroDofJoint::setAccelerationLowerLimit(std::size_t /*_index*/, double /*_acceleration*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getAccelerationLowerLimit(size_t /*_index*/) const +double ZeroDofJoint::getAccelerationLowerLimit(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::setAccelerationUpperLimit(size_t /*_index*/, +void ZeroDofJoint::setAccelerationUpperLimit(std::size_t /*_index*/, double /*_acceleration*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getAccelerationUpperLimit(size_t /*_index*/) const +double ZeroDofJoint::getAccelerationUpperLimit(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::setForce(size_t /*_index*/, double /*_force*/) +void ZeroDofJoint::setForce(std::size_t /*_index*/, double /*_force*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getForce(size_t /*_index*/) +double ZeroDofJoint::getForce(std::size_t /*_index*/) { return 0.0; } @@ -432,38 +432,38 @@ void ZeroDofJoint::resetForces() } //============================================================================== -void ZeroDofJoint::setForceLowerLimit(size_t /*_index*/, double /*_force*/) +void ZeroDofJoint::setForceLowerLimit(std::size_t /*_index*/, double /*_force*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getForceLowerLimit(size_t /*_index*/) const +double ZeroDofJoint::getForceLowerLimit(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::setForceUpperLimit(size_t /*_index*/, double /*_force*/) +void ZeroDofJoint::setForceUpperLimit(std::size_t /*_index*/, double /*_force*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getForceUpperLimit(size_t /*_index*/) const +double ZeroDofJoint::getForceUpperLimit(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::setVelocityChange(size_t /*_index*/, +void ZeroDofJoint::setVelocityChange(std::size_t /*_index*/, double /*_velocityChange*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getVelocityChange(size_t /*_index*/) const +double ZeroDofJoint::getVelocityChange(std::size_t /*_index*/) const { return 0.0; } @@ -475,13 +475,13 @@ void ZeroDofJoint::resetVelocityChanges() } //============================================================================== -void ZeroDofJoint::setConstraintImpulse(size_t /*_index*/, double /*_impulse*/) +void ZeroDofJoint::setConstraintImpulse(std::size_t /*_index*/, double /*_impulse*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getConstraintImpulse(size_t /*_index*/) const +double ZeroDofJoint::getConstraintImpulse(std::size_t /*_index*/) const { return 0.0; } @@ -513,49 +513,49 @@ Eigen::VectorXd ZeroDofJoint::getPositionDifferences( } //============================================================================== -void ZeroDofJoint::setSpringStiffness(size_t /*_index*/, double /*_k*/) +void ZeroDofJoint::setSpringStiffness(std::size_t /*_index*/, double /*_k*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getSpringStiffness(size_t /*_index*/) const +double ZeroDofJoint::getSpringStiffness(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::setRestPosition(size_t /*_index*/, double /*_q0*/) +void ZeroDofJoint::setRestPosition(std::size_t /*_index*/, double /*_q0*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getRestPosition(size_t /*_index*/) const +double ZeroDofJoint::getRestPosition(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::setDampingCoefficient(size_t /*_index*/, double /*_d*/) +void ZeroDofJoint::setDampingCoefficient(std::size_t /*_index*/, double /*_d*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getDampingCoefficient(size_t /*_index*/) const +double ZeroDofJoint::getDampingCoefficient(std::size_t /*_index*/) const { return 0.0; } //============================================================================== -void ZeroDofJoint::setCoulombFriction(size_t /*_index*/, double /*_friction*/) +void ZeroDofJoint::setCoulombFriction(std::size_t /*_index*/, double /*_friction*/) { // Do nothing } //============================================================================== -double ZeroDofJoint::getCoulombFriction(size_t /*_index*/) const +double ZeroDofJoint::getCoulombFriction(std::size_t /*_index*/) const { return 0.0; } @@ -794,7 +794,7 @@ void ZeroDofJoint::updateTotalForceForInvMassMatrix( //============================================================================== void ZeroDofJoint::getInvMassMatrixSegment( Eigen::MatrixXd& /*_invMassMat*/, - const size_t /*_col*/, + const std::size_t /*_col*/, const Eigen::Matrix6d& /*_artInertia*/, const Eigen::Vector6d& /*_spatialAcc*/) { @@ -804,7 +804,7 @@ void ZeroDofJoint::getInvMassMatrixSegment( //============================================================================== void ZeroDofJoint::getInvAugMassMatrixSegment( Eigen::MatrixXd& /*_invMassMat*/, - const size_t /*_col*/, + const std::size_t /*_col*/, const Eigen::Matrix6d& /*_artInertia*/, const Eigen::Vector6d& /*_spatialAcc*/) { diff --git a/dart/dynamics/ZeroDofJoint.h b/dart/dynamics/ZeroDofJoint.h index ac24b0a196896..3b4adb3eaf3f0 100644 --- a/dart/dynamics/ZeroDofJoint.h +++ b/dart/dynamics/ZeroDofJoint.h @@ -71,40 +71,40 @@ class ZeroDofJoint : public Joint //---------------------------------------------------------------------------- // Documentation inherited - DegreeOfFreedom* getDof(size_t) override; + DegreeOfFreedom* getDof(std::size_t) override; // Documentation inherited - const DegreeOfFreedom* getDof(size_t) const override; + const DegreeOfFreedom* getDof(std::size_t) const override; // Documentation inherited - const std::string& setDofName(size_t, const std::string&, bool ) override; + const std::string& setDofName(std::size_t, const std::string&, bool ) override; // Documentation inherited - void preserveDofName(size_t, bool) override; + void preserveDofName(std::size_t, bool) override; // Documentation inherited - bool isDofNamePreserved(size_t) const override; + bool isDofNamePreserved(std::size_t) const override; - const std::string& getDofName(size_t) const override; + const std::string& getDofName(std::size_t) const override; // Documentation inherited - size_t getNumDofs() const override; + std::size_t getNumDofs() const override; // Documentation inherited - size_t getIndexInSkeleton(size_t _index) const override; + std::size_t getIndexInSkeleton(std::size_t _index) const override; // Documentation inherited - size_t getIndexInTree(size_t _index) const override; + std::size_t getIndexInTree(std::size_t _index) const override; //---------------------------------------------------------------------------- // Command //---------------------------------------------------------------------------- // Documentation inherited - void setCommand(size_t _index, double _command) override; + void setCommand(std::size_t _index, double _command) override; // Documentation inherited - double getCommand(size_t _index) const override; + double getCommand(std::size_t _index) const override; // Documentation inherited void setCommands(const Eigen::VectorXd& _commands) override; @@ -120,10 +120,10 @@ class ZeroDofJoint : public Joint //---------------------------------------------------------------------------- // Documentation inherited - void setPosition(size_t, double) override; + void setPosition(std::size_t, double) override; // Documentation inherited - double getPosition(size_t _index) const override; + double getPosition(std::size_t _index) const override; // Documentation inherited void setPositions(const Eigen::VectorXd& _positions) override; @@ -132,31 +132,31 @@ class ZeroDofJoint : public Joint Eigen::VectorXd getPositions() const override; // Documentation inherited - void setPositionLowerLimit(size_t _index, double _position) override; + void setPositionLowerLimit(std::size_t _index, double _position) override; // Documentation inherited - double getPositionLowerLimit(size_t _index) const override; + double getPositionLowerLimit(std::size_t _index) const override; // Documentation inherited - void setPositionUpperLimit(size_t _index, double _position) override; + void setPositionUpperLimit(std::size_t _index, double _position) override; // Documentation inherited - double getPositionUpperLimit(size_t _index) const override; + double getPositionUpperLimit(std::size_t _index) const override; // Documentation inherited - bool hasPositionLimit(size_t _index) const override; + bool hasPositionLimit(std::size_t _index) const override; // Documentation inherited - void resetPosition(size_t _index) override; + void resetPosition(std::size_t _index) override; // Documentation inherited void resetPositions() override; // Documentation inherited - void setInitialPosition(size_t _index, double _initial) override; + void setInitialPosition(std::size_t _index, double _initial) override; // Documentation inherited - double getInitialPosition(size_t _index) const override; + double getInitialPosition(std::size_t _index) const override; // Documentation inherited void setInitialPositions(const Eigen::VectorXd& _initial) override; @@ -169,10 +169,10 @@ class ZeroDofJoint : public Joint //---------------------------------------------------------------------------- // Documentation inherited - void setVelocity(size_t _index, double _velocity) override; + void setVelocity(std::size_t _index, double _velocity) override; // Documentation inherited - double getVelocity(size_t _index) const override; + double getVelocity(std::size_t _index) const override; // Documentation inherited void setVelocities(const Eigen::VectorXd& _velocities) override; @@ -181,28 +181,28 @@ class ZeroDofJoint : public Joint Eigen::VectorXd getVelocities() const override; // Documentation inherited - void setVelocityLowerLimit(size_t _index, double _velocity) override; + void setVelocityLowerLimit(std::size_t _index, double _velocity) override; // Documentation inherited - double getVelocityLowerLimit(size_t _index) const override; + double getVelocityLowerLimit(std::size_t _index) const override; // Documentation inherited - void setVelocityUpperLimit(size_t _index, double _velocity) override; + void setVelocityUpperLimit(std::size_t _index, double _velocity) override; // Documentation inherited - double getVelocityUpperLimit(size_t _index) const override; + double getVelocityUpperLimit(std::size_t _index) const override; // Documentation inherited - void resetVelocity(size_t _index) override; + void resetVelocity(std::size_t _index) override; // Documentation inherited void resetVelocities() override; // Documentation inherited - void setInitialVelocity(size_t _index, double _initial) override; + void setInitialVelocity(std::size_t _index, double _initial) override; // Documentation inherited - double getInitialVelocity(size_t _index) const override; + double getInitialVelocity(std::size_t _index) const override; // Documentation inherited void setInitialVelocities(const Eigen::VectorXd& _initial) override; @@ -215,10 +215,10 @@ class ZeroDofJoint : public Joint //---------------------------------------------------------------------------- // Documentation inherited - void setAcceleration(size_t _index, double _acceleration) override; + void setAcceleration(std::size_t _index, double _acceleration) override; // Documentation inherited - double getAcceleration(size_t _index) const override; + double getAcceleration(std::size_t _index) const override; // Documentation inherited void setAccelerations(const Eigen::VectorXd& _accelerations) override; @@ -230,26 +230,26 @@ class ZeroDofJoint : public Joint void resetAccelerations() override; // Documentation inherited - void setAccelerationLowerLimit(size_t _index, double _acceleration) override; + void setAccelerationLowerLimit(std::size_t _index, double _acceleration) override; // Documentation inherited - double getAccelerationLowerLimit(size_t _index) const override; + double getAccelerationLowerLimit(std::size_t _index) const override; // Documentation inherited - void setAccelerationUpperLimit(size_t _index, double _acceleration) override; + void setAccelerationUpperLimit(std::size_t _index, double _acceleration) override; // Documentation inherited - double getAccelerationUpperLimit(size_t _index) const override; + double getAccelerationUpperLimit(std::size_t _index) const override; //---------------------------------------------------------------------------- // Force //---------------------------------------------------------------------------- // Documentation inherited - void setForce(size_t _index, double _force) override; + void setForce(std::size_t _index, double _force) override; // Documentation inherited - double getForce(size_t _index) override; + double getForce(std::size_t _index) override; // Documentation inherited void setForces(const Eigen::VectorXd& _forces) override; @@ -261,26 +261,26 @@ class ZeroDofJoint : public Joint void resetForces() override; // Documentation inherited - void setForceLowerLimit(size_t _index, double _force) override; + void setForceLowerLimit(std::size_t _index, double _force) override; // Documentation inherited - double getForceLowerLimit(size_t _index) const override; + double getForceLowerLimit(std::size_t _index) const override; // Documentation inherited - void setForceUpperLimit(size_t _index, double _force) override; + void setForceUpperLimit(std::size_t _index, double _force) override; // Documentation inherited - double getForceUpperLimit(size_t _index) const override; + double getForceUpperLimit(std::size_t _index) const override; //---------------------------------------------------------------------------- // Velocity change //---------------------------------------------------------------------------- // Documentation inherited - void setVelocityChange(size_t _index, double _velocityChange) override; + void setVelocityChange(std::size_t _index, double _velocityChange) override; // Documentation inherited - double getVelocityChange(size_t _index) const override; + double getVelocityChange(std::size_t _index) const override; // Documentation inherited void resetVelocityChanges() override; @@ -290,10 +290,10 @@ class ZeroDofJoint : public Joint //---------------------------------------------------------------------------- // Documentation inherited - void setConstraintImpulse(size_t _index, double _impulse) override; + void setConstraintImpulse(std::size_t _index, double _impulse) override; // Documentation inherited - double getConstraintImpulse(size_t _index) const override; + double getConstraintImpulse(std::size_t _index) const override; // Documentation inherited void resetConstraintImpulses() override; @@ -317,28 +317,28 @@ class ZeroDofJoint : public Joint //---------------------------------------------------------------------------- // Documentation inherited - void setSpringStiffness(size_t _index, double _k) override; + void setSpringStiffness(std::size_t _index, double _k) override; // Documentation inherited - double getSpringStiffness(size_t _index) const override; + double getSpringStiffness(std::size_t _index) const override; // Documentation inherited - void setRestPosition(size_t _index, double _q0) override; + void setRestPosition(std::size_t _index, double _q0) override; // Documentation inherited - double getRestPosition(size_t _index) const override; + double getRestPosition(std::size_t _index) const override; // Documentation inherited - void setDampingCoefficient(size_t _index, double _d) override; + void setDampingCoefficient(std::size_t _index, double _d) override; // Documentation inherited - double getDampingCoefficient(size_t _index) const override; + double getDampingCoefficient(std::size_t _index) const override; // Documentation inherited - void setCoulombFriction(size_t _index, double _friction) override; + void setCoulombFriction(std::size_t _index, double _friction) override; // Documentation inherited - double getCoulombFriction(size_t _index) const override; + double getCoulombFriction(std::size_t _index) const override; /// \} @@ -487,13 +487,13 @@ class ZeroDofJoint : public Joint // Documentation inherited void getInvMassMatrixSegment(Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) override; // Documentation inherited void getInvAugMassMatrixSegment(Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) override; diff --git a/dart/dynamics/detail/BasicNodeManager.h b/dart/dynamics/detail/BasicNodeManager.h index ecff7b40a38cf..e860445ec1013 100644 --- a/dart/dynamics/detail/BasicNodeManager.h +++ b/dart/dynamics/detail/BasicNodeManager.h @@ -67,15 +67,15 @@ class BasicNodeManagerForBodyNode /// Get the number of Nodes corresponding to the specified type template - size_t getNumNodes() const; + std::size_t getNumNodes() const; /// Get the Node of the specified type and the specified index template - NodeType* getNode(size_t index); + NodeType* getNode(std::size_t index); /// Get the Node of the specified type and the specified index template - const NodeType* getNode(size_t index) const; + const NodeType* getNode(std::size_t index) const; /// Check if this Manager is specialized for a specific type of Node template @@ -103,17 +103,17 @@ class BasicNodeManagerForSkeleton : public virtual BasicNodeManagerForBodyNode /// Get the number of Nodes of the specified type that are in the treeIndexth /// tree of this Skeleton template - size_t getNumNodes(size_t treeIndex) const; + std::size_t getNumNodes(std::size_t treeIndex) const; /// Get the nodeIndexth Node of the specified type within the tree of /// treeIndex. template - NodeType* getNode(size_t treeIndex, size_t nodeIndex); + NodeType* getNode(std::size_t treeIndex, std::size_t nodeIndex); /// Get the nodeIndexth Node of the specified type within the tree of /// treeIndex. template - const NodeType* getNode(size_t treeIndex, size_t nodeIndex) const; + const NodeType* getNode(std::size_t treeIndex, std::size_t nodeIndex) const; /// Get the Node of the specified type with the given name. template @@ -143,7 +143,7 @@ class BasicNodeManagerForSkeleton : public virtual BasicNodeManagerForBodyNode //============================================================================== template -size_t BasicNodeManagerForBodyNode::getNumNodes() const +std::size_t BasicNodeManagerForBodyNode::getNumNodes() const { NodeMap::const_iterator it = mNodeMap.find(typeid(NodeType)); if(mNodeMap.end() == it) @@ -154,7 +154,7 @@ size_t BasicNodeManagerForBodyNode::getNumNodes() const //============================================================================== template -NodeType* BasicNodeManagerForBodyNode::getNode(size_t index) +NodeType* BasicNodeManagerForBodyNode::getNode(std::size_t index) { NodeMap::const_iterator it = mNodeMap.find(typeid(NodeType)); if(mNodeMap.end() == it) @@ -166,7 +166,7 @@ NodeType* BasicNodeManagerForBodyNode::getNode(size_t index) //============================================================================== template -const NodeType* BasicNodeManagerForBodyNode::getNode(size_t index) const +const NodeType* BasicNodeManagerForBodyNode::getNode(std::size_t index) const { return const_cast(this)->getNode(index); } @@ -181,7 +181,7 @@ constexpr bool BasicNodeManagerForBodyNode::isSpecializedForNode() //============================================================================== template -size_t BasicNodeManagerForSkeleton::getNumNodes(size_t treeIndex) const +std::size_t BasicNodeManagerForSkeleton::getNumNodes(std::size_t treeIndex) const { if(treeIndex >= mTreeNodeMaps.size()) { @@ -203,7 +203,7 @@ size_t BasicNodeManagerForSkeleton::getNumNodes(size_t treeIndex) const //============================================================================== template NodeType* BasicNodeManagerForSkeleton::getNode( - size_t treeIndex, size_t nodeIndex) + std::size_t treeIndex, std::size_t nodeIndex) { if(treeIndex >= mTreeNodeMaps.size()) { @@ -241,7 +241,7 @@ NodeType* BasicNodeManagerForSkeleton::getNode( //============================================================================== template const NodeType* BasicNodeManagerForSkeleton::getNode( - size_t treeIndex, size_t nodeIndex) const + std::size_t treeIndex, std::size_t nodeIndex) const { return const_cast(this)->getNode( treeIndex, nodeIndex); @@ -270,11 +270,11 @@ const NodeType* BasicNodeManagerForSkeleton::getNode( //============================================================================== #define DART_BAKE_SPECIALIZED_NODE_IRREGULAR( TypeName, AspectName, PluralAspectName )\ - inline size_t getNum ## PluralAspectName () const\ + inline std::size_t getNum ## PluralAspectName () const\ { return getNumNodes< TypeName >(); }\ - inline TypeName * get ## AspectName (size_t index)\ + inline TypeName * get ## AspectName (std::size_t index)\ { return getNode< TypeName >(index); }\ - inline const TypeName * get ## AspectName (size_t index) const\ + inline const TypeName * get ## AspectName (std::size_t index) const\ { return getNode< TypeName >(index); } //============================================================================== @@ -284,11 +284,11 @@ const NodeType* BasicNodeManagerForSkeleton::getNode( //============================================================================== #define DART_BAKE_SPECIALIZED_NODE_SKEL_IRREGULAR( TypeName, AspectName, PluralAspectName )\ DART_BAKE_SPECIALIZED_NODE_IRREGULAR( TypeName, AspectName, PluralAspectName )\ - inline size_t getNum ## PluralAspectName (size_t treeIndex) const\ + inline std::size_t getNum ## PluralAspectName (std::size_t treeIndex) const\ { return getNumNodes< TypeName >(treeIndex); }\ - inline TypeName * get ## AspectName (size_t treeIndex, size_t nodeIndex)\ + inline TypeName * get ## AspectName (std::size_t treeIndex, std::size_t nodeIndex)\ { return getNode< TypeName >(treeIndex, nodeIndex); }\ - inline const TypeName * get ## AspectName (size_t treeIndex, size_t nodeIndex) const\ + inline const TypeName * get ## AspectName (std::size_t treeIndex, std::size_t nodeIndex) const\ { return getNode< TypeName >(treeIndex, nodeIndex); }\ \ inline TypeName * get ## AspectName (const std::string& name)\ @@ -302,9 +302,9 @@ const NodeType* BasicNodeManagerForSkeleton::getNode( //============================================================================== #define DART_BAKE_SPECIALIZED_NODE_IRREGULAR_DECLARATIONS( TypeName, AspectName, PluralAspectName )\ - size_t getNum ## PluralAspectName () const;\ - TypeName * get ## AspectName (size_t index);\ - const TypeName * get ## AspectName (size_t index) const; + std::size_t getNum ## PluralAspectName () const;\ + TypeName * get ## AspectName (std::size_t index);\ + const TypeName * get ## AspectName (std::size_t index) const; //============================================================================== #define DART_BAKE_SPECIALIZED_NODE_DECLARATIONS( AspectName )\ @@ -313,9 +313,9 @@ const NodeType* BasicNodeManagerForSkeleton::getNode( //============================================================================== #define DART_BAKE_SPECIALIZED_NODE_SKEL_IRREGULAR_DECLARATIONS( TypeName, AspectName, PluralAspectName )\ DART_BAKE_SPECIALIZED_NODE_IRREGULAR_DECLARATIONS( TypeName, AspectName, PluralAspectName )\ - size_t getNum ## PluralAspectName (size_t treeIndex) const;\ - TypeName * get ## AspectName (size_t treeIndex, size_t nodeIndex);\ - const TypeName * get ## AspectName (size_t treeIndex, size_t nodeIndex) const;\ + std::size_t getNum ## PluralAspectName (std::size_t treeIndex) const;\ + TypeName * get ## AspectName (std::size_t treeIndex, std::size_t nodeIndex);\ + const TypeName * get ## AspectName (std::size_t treeIndex, std::size_t nodeIndex) const;\ \ TypeName * get ## AspectName (const std::string& name);\ const TypeName * get ## AspectName (const std::string& name) const; @@ -326,11 +326,11 @@ const NodeType* BasicNodeManagerForSkeleton::getNode( //============================================================================== #define DART_BAKE_SPECIALIZED_NODE_IRREGULAR_DEFINITIONS( ClassName, TypeName, AspectName, PluralAspectName )\ - size_t ClassName :: getNum ## PluralAspectName () const\ + std::size_t ClassName :: getNum ## PluralAspectName () const\ { return getNumNodes< TypeName >(); }\ - TypeName * ClassName :: get ## AspectName (size_t index)\ + TypeName * ClassName :: get ## AspectName (std::size_t index)\ { return getNode< TypeName >(index); }\ - const TypeName * ClassName :: get ## AspectName (size_t index) const\ + const TypeName * ClassName :: get ## AspectName (std::size_t index) const\ { return getNode< TypeName >(index); } //============================================================================== @@ -340,11 +340,11 @@ const NodeType* BasicNodeManagerForSkeleton::getNode( //============================================================================== #define DART_BAKE_SPECIALIZED_NODE_SKEL_IRREGULAR_DEFINITIONS( ClassName, TypeName, AspectName, PluralAspectName )\ DART_BAKE_SPECIALIZED_NODE_IRREGULAR_DEFINITIONS( ClassName, TypeName, AspectName, PluralAspectName )\ - size_t ClassName :: getNum ## PluralAspectName (size_t treeIndex) const\ + std::size_t ClassName :: getNum ## PluralAspectName (std::size_t treeIndex) const\ { return getNumNodes< TypeName >(treeIndex); }\ - TypeName * ClassName :: get ## AspectName (size_t treeIndex, size_t nodeIndex)\ + TypeName * ClassName :: get ## AspectName (std::size_t treeIndex, std::size_t nodeIndex)\ { return getNode< TypeName >(treeIndex, nodeIndex); }\ - const TypeName * ClassName :: get ## AspectName (size_t treeIndex, size_t nodeIndex) const\ + const TypeName * ClassName :: get ## AspectName (std::size_t treeIndex, std::size_t nodeIndex) const\ { return getNode< TypeName >(treeIndex, nodeIndex); }\ \ TypeName * ClassName :: get ## AspectName (const std::string& name)\ diff --git a/dart/dynamics/detail/BodyNode.h b/dart/dynamics/detail/BodyNode.h index 03af89aad5317..e24593e9a038b 100644 --- a/dart/dynamics/detail/BodyNode.h +++ b/dart/dynamics/detail/BodyNode.h @@ -179,7 +179,7 @@ ShapeNode* BodyNode::createShapeNodeWith( //============================================================================== template -size_t BodyNode::getNumShapeNodesWith() const +std::size_t BodyNode::getNumShapeNodesWith() const { auto count = 0u; auto numShapeNode = getNumShapeNodes(); diff --git a/dart/dynamics/detail/DegreeOfFreedomPtr.h b/dart/dynamics/detail/DegreeOfFreedomPtr.h index 406512aac3ea4..b5518b7d48f51 100644 --- a/dart/dynamics/detail/DegreeOfFreedomPtr.h +++ b/dart/dynamics/detail/DegreeOfFreedomPtr.h @@ -118,7 +118,7 @@ class TemplateDegreeOfFreedomPtr /// Get the local generalized coordinate index that this DegreeOfFreedomPtr is /// tied to - size_t getLocalIndex() const + std::size_t getLocalIndex() const { if(nullptr == mBodyNodePtr) return INVALID_INDEX; @@ -210,7 +210,7 @@ class TemplateDegreeOfFreedomPtr TemplateBodyNodePtr mBodyNodePtr; /// Local index of this DegreeOfFreedom within its Joint - size_t mIndex; + std::size_t mIndex; }; /// TemplateWeakDegreeOfFreedomPtr is a templated class that enables users to @@ -321,7 +321,7 @@ class TemplateWeakDegreeOfFreedomPtr TemplateWeakBodyNodePtr mWeakBodyNode; /// Local index of this DegreeOfFreedom within its Joint - size_t mIndex; + std::size_t mIndex; }; } // namespace dynamics diff --git a/dart/dynamics/detail/InverseKinematics.h b/dart/dynamics/detail/InverseKinematics.h index b5354001cce39..231206e31940b 100644 --- a/dart/dynamics/detail/InverseKinematics.h +++ b/dart/dynamics/detail/InverseKinematics.h @@ -73,7 +73,7 @@ IKGradientMethod& InverseKinematics::setGradientMethod(Args&&... args) template void InverseKinematics::setDofs(const std::vector& _dofs) { - std::vector indices; + std::vector indices; indices.reserve(_dofs.size()); for(const DegreeOfFreedomT* dof : _dofs) indices.push_back(dof->getIndexInSkeleton()); diff --git a/dart/dynamics/detail/MultiDofJoint.h b/dart/dynamics/detail/MultiDofJoint.h index 3c048f73575e9..3149ab94cdca8 100644 --- a/dart/dynamics/detail/MultiDofJoint.h +++ b/dart/dynamics/detail/MultiDofJoint.h @@ -74,19 +74,19 @@ namespace dynamics { // // See this StackOverflow answer: http://stackoverflow.com/a/14396189/111426 // -template -constexpr size_t MultiDofJoint::NumDofs; +template +constexpr std::size_t MultiDofJoint::NumDofs; //============================================================================== -template +template MultiDofJoint::~MultiDofJoint() { - for (size_t i = 0; i < DOF; ++i) + for (std::size_t i = 0; i < DOF; ++i) delete mDofs[i]; } //============================================================================== -template +template void MultiDofJoint::setProperties(const Properties& _properties) { Joint::setProperties(static_cast(_properties)); @@ -94,14 +94,14 @@ void MultiDofJoint::setProperties(const Properties& _properties) } //============================================================================== -template +template void MultiDofJoint::setProperties(const UniqueProperties& _properties) { setAspectProperties(_properties); } //============================================================================== -template +template void MultiDofJoint::setAspectState(const AspectState& state) { setCommands(state.mCommands); @@ -112,10 +112,10 @@ void MultiDofJoint::setAspectState(const AspectState& state) } //============================================================================== -template +template void MultiDofJoint::setAspectProperties(const AspectProperties& properties) { - for(size_t i=0; i::setAspectProperties(const AspectProperties& properties) } //============================================================================== -template +template typename MultiDofJoint::Properties MultiDofJoint::getMultiDofJointProperties() const { @@ -145,7 +145,7 @@ MultiDofJoint::getMultiDofJointProperties() const } //============================================================================== -template +template void MultiDofJoint::copy(const MultiDofJoint& _otherJoint) { if(this == &_otherJoint) @@ -155,7 +155,7 @@ void MultiDofJoint::copy(const MultiDofJoint& _otherJoint) } //============================================================================== -template +template void MultiDofJoint::copy(const MultiDofJoint* _otherJoint) { if(nullptr == _otherJoint) @@ -165,7 +165,7 @@ void MultiDofJoint::copy(const MultiDofJoint* _otherJoint) } //============================================================================== -template +template MultiDofJoint& MultiDofJoint::operator=( const MultiDofJoint& _otherJoint) { @@ -174,8 +174,8 @@ MultiDofJoint& MultiDofJoint::operator=( } //============================================================================== -template -DegreeOfFreedom* MultiDofJoint::getDof(size_t _index) +template +DegreeOfFreedom* MultiDofJoint::getDof(std::size_t _index) { if (_index < DOF) return mDofs[_index]; @@ -186,8 +186,8 @@ DegreeOfFreedom* MultiDofJoint::getDof(size_t _index) } //============================================================================== -template -const DegreeOfFreedom* MultiDofJoint::getDof(size_t _index) const +template +const DegreeOfFreedom* MultiDofJoint::getDof(std::size_t _index) const { if (_index < DOF) return mDofs[_index]; @@ -198,8 +198,8 @@ const DegreeOfFreedom* MultiDofJoint::getDof(size_t _index) const } //============================================================================== -template -const std::string& MultiDofJoint::setDofName(size_t _index, +template +const std::string& MultiDofJoint::setDofName(std::size_t _index, const std::string& _name, bool _preserveName) { @@ -231,8 +231,8 @@ const std::string& MultiDofJoint::setDofName(size_t _index, } //============================================================================== -template -void MultiDofJoint::preserveDofName(size_t _index, bool _preserve) +template +void MultiDofJoint::preserveDofName(std::size_t _index, bool _preserve) { if (DOF <= _index) { @@ -244,8 +244,8 @@ void MultiDofJoint::preserveDofName(size_t _index, bool _preserve) } //============================================================================== -template -bool MultiDofJoint::isDofNamePreserved(size_t _index) const +template +bool MultiDofJoint::isDofNamePreserved(std::size_t _index) const { if(DOF <= _index) { @@ -257,8 +257,8 @@ bool MultiDofJoint::isDofNamePreserved(size_t _index) const } //============================================================================== -template -const std::string& MultiDofJoint::getDofName(size_t _index) const +template +const std::string& MultiDofJoint::getDofName(std::size_t _index) const { if(DOF <= _index) { @@ -273,15 +273,15 @@ const std::string& MultiDofJoint::getDofName(size_t _index) const } //============================================================================== -template -size_t MultiDofJoint::getNumDofs() const +template +std::size_t MultiDofJoint::getNumDofs() const { return DOF; } //============================================================================== -template -size_t MultiDofJoint::getIndexInSkeleton(size_t _index) const +template +std::size_t MultiDofJoint::getIndexInSkeleton(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -293,8 +293,8 @@ size_t MultiDofJoint::getIndexInSkeleton(size_t _index) const } //============================================================================== -template -size_t MultiDofJoint::getIndexInTree(size_t _index) const +template +std::size_t MultiDofJoint::getIndexInTree(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -306,8 +306,8 @@ size_t MultiDofJoint::getIndexInTree(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setCommand(size_t _index, double command) +template +void MultiDofJoint::setCommand(std::size_t _index, double command) { if (_index >= getNumDofs()) { @@ -362,8 +362,8 @@ void MultiDofJoint::setCommand(size_t _index, double command) } //============================================================================== -template -double MultiDofJoint::getCommand(size_t _index) const +template +double MultiDofJoint::getCommand(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -375,10 +375,10 @@ double MultiDofJoint::getCommand(size_t _index) const } //============================================================================== -template +template void MultiDofJoint::setCommands(const Eigen::VectorXd& _commands) { - if (static_cast(_commands.size()) != getNumDofs()) + if (static_cast(_commands.size()) != getNumDofs()) { MULTIDOFJOINT_REPORT_DIM_MISMATCH(setCommands, _commands); return; @@ -432,22 +432,22 @@ void MultiDofJoint::setCommands(const Eigen::VectorXd& _commands) } //============================================================================== -template +template Eigen::VectorXd MultiDofJoint::getCommands() const { return this->mAspectState.mCommands; } //============================================================================== -template +template void MultiDofJoint::resetCommands() { this->mAspectState.mCommands.setZero(); } //============================================================================== -template -void MultiDofJoint::setPosition(size_t _index, double _position) +template +void MultiDofJoint::setPosition(std::size_t _index, double _position) { if (_index >= getNumDofs()) { @@ -464,8 +464,8 @@ void MultiDofJoint::setPosition(size_t _index, double _position) } //============================================================================== -template -double MultiDofJoint::getPosition(size_t _index) const +template +double MultiDofJoint::getPosition(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -477,10 +477,10 @@ double MultiDofJoint::getPosition(size_t _index) const } //============================================================================== -template +template void MultiDofJoint::setPositions(const Eigen::VectorXd& _positions) { - if (static_cast(_positions.size()) != getNumDofs()) + if (static_cast(_positions.size()) != getNumDofs()) { MULTIDOFJOINT_REPORT_DIM_MISMATCH(setPositions, _positions); return; @@ -490,15 +490,15 @@ void MultiDofJoint::setPositions(const Eigen::VectorXd& _positions) } //============================================================================== -template +template Eigen::VectorXd MultiDofJoint::getPositions() const { return getPositionsStatic(); } //============================================================================== -template -void MultiDofJoint::setPositionLowerLimit(size_t _index, double _position) +template +void MultiDofJoint::setPositionLowerLimit(std::size_t _index, double _position) { if (_index >= getNumDofs()) { @@ -510,8 +510,8 @@ void MultiDofJoint::setPositionLowerLimit(size_t _index, double _position) } //============================================================================== -template -double MultiDofJoint::getPositionLowerLimit(size_t _index) const +template +double MultiDofJoint::getPositionLowerLimit(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -523,8 +523,8 @@ double MultiDofJoint::getPositionLowerLimit(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setPositionUpperLimit(size_t _index, double _position) +template +void MultiDofJoint::setPositionUpperLimit(std::size_t _index, double _position) { if (_index >= getNumDofs()) { @@ -536,8 +536,8 @@ void MultiDofJoint::setPositionUpperLimit(size_t _index, double _position) } //============================================================================== -template -void MultiDofJoint::resetPosition(size_t _index) +template +void MultiDofJoint::resetPosition(std::size_t _index) { if (_index >= getNumDofs()) { @@ -549,15 +549,15 @@ void MultiDofJoint::resetPosition(size_t _index) } //============================================================================== -template +template void MultiDofJoint::resetPositions() { setPositionsStatic(Base::mAspectProperties.mInitialPositions); } //============================================================================== -template -void MultiDofJoint::setInitialPosition(size_t _index, double _initial) +template +void MultiDofJoint::setInitialPosition(std::size_t _index, double _initial) { if (_index >= getNumDofs()) { @@ -569,8 +569,8 @@ void MultiDofJoint::setInitialPosition(size_t _index, double _initial) } //============================================================================== -template -double MultiDofJoint::getInitialPosition(size_t _index) const +template +double MultiDofJoint::getInitialPosition(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -582,10 +582,10 @@ double MultiDofJoint::getInitialPosition(size_t _index) const } //============================================================================== -template +template void MultiDofJoint::setInitialPositions(const Eigen::VectorXd& _initial) { - if ( static_cast(_initial.size()) != getNumDofs() ) + if ( static_cast(_initial.size()) != getNumDofs() ) { MULTIDOFJOINT_REPORT_DIM_MISMATCH(setInitialPositions, _initial); return; @@ -595,15 +595,15 @@ void MultiDofJoint::setInitialPositions(const Eigen::VectorXd& _initial) } //============================================================================== -template +template Eigen::VectorXd MultiDofJoint::getInitialPositions() const { return Base::mAspectProperties.mInitialPositions; } //============================================================================== -template -double MultiDofJoint::getPositionUpperLimit(size_t _index) const +template +double MultiDofJoint::getPositionUpperLimit(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -615,8 +615,8 @@ double MultiDofJoint::getPositionUpperLimit(size_t _index) const } //============================================================================== -template -bool MultiDofJoint::hasPositionLimit(size_t _index) const +template +bool MultiDofJoint::hasPositionLimit(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -629,8 +629,8 @@ bool MultiDofJoint::hasPositionLimit(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setVelocity(size_t _index, double _velocity) +template +void MultiDofJoint::setVelocity(std::size_t _index, double _velocity) { if (_index >= getNumDofs()) { @@ -650,8 +650,8 @@ void MultiDofJoint::setVelocity(size_t _index, double _velocity) } //============================================================================== -template -double MultiDofJoint::getVelocity(size_t _index) const +template +double MultiDofJoint::getVelocity(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -663,10 +663,10 @@ double MultiDofJoint::getVelocity(size_t _index) const } //============================================================================== -template +template void MultiDofJoint::setVelocities(const Eigen::VectorXd& _velocities) { - if (static_cast(_velocities.size()) != getNumDofs()) + if (static_cast(_velocities.size()) != getNumDofs()) { MULTIDOFJOINT_REPORT_DIM_MISMATCH(setVelocities, _velocities); return; @@ -679,15 +679,15 @@ void MultiDofJoint::setVelocities(const Eigen::VectorXd& _velocities) } //============================================================================== -template +template Eigen::VectorXd MultiDofJoint::getVelocities() const { return getVelocitiesStatic(); } //============================================================================== -template -void MultiDofJoint::setVelocityLowerLimit(size_t _index, double _velocity) +template +void MultiDofJoint::setVelocityLowerLimit(std::size_t _index, double _velocity) { if (_index >= getNumDofs()) { @@ -699,8 +699,8 @@ void MultiDofJoint::setVelocityLowerLimit(size_t _index, double _velocity) } //============================================================================== -template -double MultiDofJoint::getVelocityLowerLimit(size_t _index) const +template +double MultiDofJoint::getVelocityLowerLimit(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -712,8 +712,8 @@ double MultiDofJoint::getVelocityLowerLimit(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setVelocityUpperLimit(size_t _index, double _velocity) +template +void MultiDofJoint::setVelocityUpperLimit(std::size_t _index, double _velocity) { if (_index >= getNumDofs()) { @@ -725,8 +725,8 @@ void MultiDofJoint::setVelocityUpperLimit(size_t _index, double _velocity) } //============================================================================== -template -double MultiDofJoint::getVelocityUpperLimit(size_t _index) const +template +double MultiDofJoint::getVelocityUpperLimit(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -738,8 +738,8 @@ double MultiDofJoint::getVelocityUpperLimit(size_t _index) const } //============================================================================== -template -void MultiDofJoint::resetVelocity(size_t _index) +template +void MultiDofJoint::resetVelocity(std::size_t _index) { if (_index >= getNumDofs()) { @@ -751,15 +751,15 @@ void MultiDofJoint::resetVelocity(size_t _index) } //============================================================================== -template +template void MultiDofJoint::resetVelocities() { setVelocitiesStatic(Base::mAspectProperties.mInitialVelocities); } //============================================================================== -template -void MultiDofJoint::setInitialVelocity(size_t _index, double _initial) +template +void MultiDofJoint::setInitialVelocity(std::size_t _index, double _initial) { if (_index >= getNumDofs()) { @@ -771,8 +771,8 @@ void MultiDofJoint::setInitialVelocity(size_t _index, double _initial) } //============================================================================== -template -double MultiDofJoint::getInitialVelocity(size_t _index) const +template +double MultiDofJoint::getInitialVelocity(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -784,10 +784,10 @@ double MultiDofJoint::getInitialVelocity(size_t _index) const } //============================================================================== -template +template void MultiDofJoint::setInitialVelocities(const Eigen::VectorXd& _initial) { - if ( static_cast(_initial.size()) != getNumDofs() ) + if ( static_cast(_initial.size()) != getNumDofs() ) { MULTIDOFJOINT_REPORT_DIM_MISMATCH( setInitialVelocities, _initial ); return; @@ -797,15 +797,15 @@ void MultiDofJoint::setInitialVelocities(const Eigen::VectorXd& _initial) } //============================================================================== -template +template Eigen::VectorXd MultiDofJoint::getInitialVelocities() const { return Base::mAspectProperties.mInitialVelocities; } //============================================================================== -template -void MultiDofJoint::setAcceleration(size_t _index, double _acceleration) +template +void MultiDofJoint::setAcceleration(std::size_t _index, double _acceleration) { if (_index >= getNumDofs()) { @@ -825,8 +825,8 @@ void MultiDofJoint::setAcceleration(size_t _index, double _acceleration) } //============================================================================== -template -double MultiDofJoint::getAcceleration(size_t _index) const +template +double MultiDofJoint::getAcceleration(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -838,10 +838,10 @@ double MultiDofJoint::getAcceleration(size_t _index) const } //============================================================================== -template +template void MultiDofJoint::setAccelerations(const Eigen::VectorXd& _accelerations) { - if (static_cast(_accelerations.size()) != getNumDofs()) + if (static_cast(_accelerations.size()) != getNumDofs()) { MULTIDOFJOINT_REPORT_DIM_MISMATCH( setAccelerations, _accelerations ); return; @@ -854,22 +854,22 @@ void MultiDofJoint::setAccelerations(const Eigen::VectorXd& _accelerations) } //============================================================================== -template +template Eigen::VectorXd MultiDofJoint::getAccelerations() const { return getAccelerationsStatic(); } //============================================================================== -template +template void MultiDofJoint::resetAccelerations() { setAccelerationsStatic(Eigen::Matrix::Zero()); } //============================================================================== -template -void MultiDofJoint::setAccelerationLowerLimit(size_t _index, +template +void MultiDofJoint::setAccelerationLowerLimit(std::size_t _index, double _acceleration) { if (_index >= getNumDofs()) @@ -883,8 +883,8 @@ void MultiDofJoint::setAccelerationLowerLimit(size_t _index, } //============================================================================== -template -double MultiDofJoint::getAccelerationLowerLimit(size_t _index) const +template +double MultiDofJoint::getAccelerationLowerLimit(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -896,8 +896,8 @@ double MultiDofJoint::getAccelerationLowerLimit(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setAccelerationUpperLimit(size_t _index, +template +void MultiDofJoint::setAccelerationUpperLimit(std::size_t _index, double _acceleration) { if (_index >= getNumDofs()) @@ -911,8 +911,8 @@ void MultiDofJoint::setAccelerationUpperLimit(size_t _index, } //============================================================================== -template -double MultiDofJoint::getAccelerationUpperLimit(size_t _index) const +template +double MultiDofJoint::getAccelerationUpperLimit(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -924,7 +924,7 @@ double MultiDofJoint::getAccelerationUpperLimit(size_t _index) const } //============================================================================== -template +template void MultiDofJoint::setPositionsStatic(const Vector& _positions) { if(this->mAspectState.mPositions == _positions) @@ -935,7 +935,7 @@ void MultiDofJoint::setPositionsStatic(const Vector& _positions) } //============================================================================== -template +template const typename MultiDofJoint::Vector& MultiDofJoint::getPositionsStatic() const { @@ -943,7 +943,7 @@ MultiDofJoint::getPositionsStatic() const } //============================================================================== -template +template void MultiDofJoint::setVelocitiesStatic(const Vector& _velocities) { if(this->mAspectState.mVelocities == _velocities) @@ -954,7 +954,7 @@ void MultiDofJoint::setVelocitiesStatic(const Vector& _velocities) } //============================================================================== -template +template const typename MultiDofJoint::Vector& MultiDofJoint::getVelocitiesStatic() const { @@ -962,7 +962,7 @@ MultiDofJoint::getVelocitiesStatic() const } //============================================================================== -template +template void MultiDofJoint::setAccelerationsStatic(const Vector& _accels) { if(this->mAspectState.mAccelerations == _accels) @@ -973,7 +973,7 @@ void MultiDofJoint::setAccelerationsStatic(const Vector& _accels) } //============================================================================== -template +template const typename MultiDofJoint::Vector& MultiDofJoint::getAccelerationsStatic() const { @@ -981,8 +981,8 @@ MultiDofJoint::getAccelerationsStatic() const } //============================================================================== -template -void MultiDofJoint::setForce(size_t _index, double _force) +template +void MultiDofJoint::setForce(std::size_t _index, double _force) { if (_index >= getNumDofs()) { @@ -997,8 +997,8 @@ void MultiDofJoint::setForce(size_t _index, double _force) } //============================================================================== -template -double MultiDofJoint::getForce(size_t _index) +template +double MultiDofJoint::getForce(std::size_t _index) { if (_index >= getNumDofs()) { @@ -1010,10 +1010,10 @@ double MultiDofJoint::getForce(size_t _index) } //============================================================================== -template +template void MultiDofJoint::setForces(const Eigen::VectorXd& _forces) { - if (static_cast(_forces.size()) != getNumDofs()) + if (static_cast(_forces.size()) != getNumDofs()) { MULTIDOFJOINT_REPORT_DIM_MISMATCH(setForces, _forces); return; @@ -1026,14 +1026,14 @@ void MultiDofJoint::setForces(const Eigen::VectorXd& _forces) } //============================================================================== -template +template Eigen::VectorXd MultiDofJoint::getForces() const { return this->mAspectState.mForces; } //============================================================================== -template +template void MultiDofJoint::resetForces() { this->mAspectState.mForces.setZero(); @@ -1043,8 +1043,8 @@ void MultiDofJoint::resetForces() } //============================================================================== -template -void MultiDofJoint::setForceLowerLimit(size_t _index, double _force) +template +void MultiDofJoint::setForceLowerLimit(std::size_t _index, double _force) { if (_index >= getNumDofs()) { @@ -1056,8 +1056,8 @@ void MultiDofJoint::setForceLowerLimit(size_t _index, double _force) } //============================================================================== -template -double MultiDofJoint::getForceLowerLimit(size_t _index) const +template +double MultiDofJoint::getForceLowerLimit(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -1069,8 +1069,8 @@ double MultiDofJoint::getForceLowerLimit(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setForceUpperLimit(size_t _index, double _force) +template +void MultiDofJoint::setForceUpperLimit(std::size_t _index, double _force) { if (_index >= getNumDofs()) { @@ -1082,8 +1082,8 @@ void MultiDofJoint::setForceUpperLimit(size_t _index, double _force) } //============================================================================== -template -double MultiDofJoint::getForceUpperLimit(size_t _index) const +template +double MultiDofJoint::getForceUpperLimit(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -1095,8 +1095,8 @@ double MultiDofJoint::getForceUpperLimit(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setVelocityChange(size_t _index, +template +void MultiDofJoint::setVelocityChange(std::size_t _index, double _velocityChange) { if (_index >= getNumDofs()) @@ -1109,8 +1109,8 @@ void MultiDofJoint::setVelocityChange(size_t _index, } //============================================================================== -template -double MultiDofJoint::getVelocityChange(size_t _index) const +template +double MultiDofJoint::getVelocityChange(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -1122,15 +1122,15 @@ double MultiDofJoint::getVelocityChange(size_t _index) const } //============================================================================== -template +template void MultiDofJoint::resetVelocityChanges() { mVelocityChanges.setZero(); } //============================================================================== -template -void MultiDofJoint::setConstraintImpulse(size_t _index, double _impulse) +template +void MultiDofJoint::setConstraintImpulse(std::size_t _index, double _impulse) { if (_index >= getNumDofs()) { @@ -1142,8 +1142,8 @@ void MultiDofJoint::setConstraintImpulse(size_t _index, double _impulse) } //============================================================================== -template -double MultiDofJoint::getConstraintImpulse(size_t _index) const +template +double MultiDofJoint::getConstraintImpulse(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -1155,33 +1155,33 @@ double MultiDofJoint::getConstraintImpulse(size_t _index) const } //============================================================================== -template +template void MultiDofJoint::resetConstraintImpulses() { mConstraintImpulses.setZero(); } //============================================================================== -template +template void MultiDofJoint::integratePositions(double _dt) { setPositionsStatic(getPositionsStatic() + getVelocitiesStatic() * _dt); } //============================================================================== -template +template void MultiDofJoint::integrateVelocities(double _dt) { setVelocitiesStatic(getVelocitiesStatic() + getAccelerationsStatic() * _dt); } //============================================================================== -template +template Eigen::VectorXd MultiDofJoint::getPositionDifferences( const Eigen::VectorXd& _q2, const Eigen::VectorXd& _q1) const { - if (static_cast(_q1.size()) != getNumDofs() - || static_cast(_q2.size()) != getNumDofs()) + if (static_cast(_q1.size()) != getNumDofs() + || static_cast(_q2.size()) != getNumDofs()) { dterr << "[MultiDofJoint::getPositionsDifference] q1's size [" << _q1.size() << "] or q2's size [" << _q2.size() << "] must both equal the dof [" @@ -1194,7 +1194,7 @@ Eigen::VectorXd MultiDofJoint::getPositionDifferences( } //============================================================================== -template +template Eigen::Matrix MultiDofJoint::getPositionDifferencesStatic( const Vector& _q2, const Vector& _q1) const { @@ -1202,8 +1202,8 @@ Eigen::Matrix MultiDofJoint::getPositionDifferencesStatic( } //============================================================================== -template -void MultiDofJoint::setSpringStiffness(size_t _index, double _k) +template +void MultiDofJoint::setSpringStiffness(std::size_t _index, double _k) { if (_index >= getNumDofs()) { @@ -1217,8 +1217,8 @@ void MultiDofJoint::setSpringStiffness(size_t _index, double _k) } //============================================================================== -template -double MultiDofJoint::getSpringStiffness(size_t _index) const +template +double MultiDofJoint::getSpringStiffness(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -1230,8 +1230,8 @@ double MultiDofJoint::getSpringStiffness(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setRestPosition(size_t _index, double _q0) +template +void MultiDofJoint::setRestPosition(std::size_t _index, double _q0) { if (_index >= getNumDofs()) { @@ -1255,8 +1255,8 @@ void MultiDofJoint::setRestPosition(size_t _index, double _q0) } //============================================================================== -template -double MultiDofJoint::getRestPosition(size_t _index) const +template +double MultiDofJoint::getRestPosition(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -1268,8 +1268,8 @@ double MultiDofJoint::getRestPosition(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setDampingCoefficient(size_t _index, double _d) +template +void MultiDofJoint::setDampingCoefficient(std::size_t _index, double _d) { if (_index >= getNumDofs()) { @@ -1283,8 +1283,8 @@ void MultiDofJoint::setDampingCoefficient(size_t _index, double _d) } //============================================================================== -template -double MultiDofJoint::getDampingCoefficient(size_t _index) const +template +double MultiDofJoint::getDampingCoefficient(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -1296,8 +1296,8 @@ double MultiDofJoint::getDampingCoefficient(size_t _index) const } //============================================================================== -template -void MultiDofJoint::setCoulombFriction(size_t _index, double _friction) +template +void MultiDofJoint::setCoulombFriction(std::size_t _index, double _friction) { if (_index >= getNumDofs()) { @@ -1311,8 +1311,8 @@ void MultiDofJoint::setCoulombFriction(size_t _index, double _friction) } //============================================================================== -template -double MultiDofJoint::getCoulombFriction(size_t _index) const +template +double MultiDofJoint::getCoulombFriction(std::size_t _index) const { if (_index >= getNumDofs()) { @@ -1324,7 +1324,7 @@ double MultiDofJoint::getCoulombFriction(size_t _index) const } //============================================================================== -template +template double MultiDofJoint::getPotentialEnergy() const { // Spring energy @@ -1338,7 +1338,7 @@ double MultiDofJoint::getPotentialEnergy() const } //============================================================================== -template +template Eigen::Vector6d MultiDofJoint::getBodyConstraintWrench() const { assert(this->mChildBodyNode); @@ -1347,7 +1347,7 @@ Eigen::Vector6d MultiDofJoint::getBodyConstraintWrench() const } //============================================================================== -template +template MultiDofJoint::MultiDofJoint(const Properties& properties) : mVelocityChanges(Vector::Zero()), mImpulses(Vector::Zero()), @@ -1359,7 +1359,7 @@ MultiDofJoint::MultiDofJoint(const Properties& properties) mTotalForce(Vector::Zero()), mTotalImpulse(Vector::Zero()) { - for (size_t i = 0; i < DOF; ++i) + for (std::size_t i = 0; i < DOF; ++i) mDofs[i] = this->createDofPointer(i); // Joint and MultiDofJoint Aspects must be created by the most derived class. @@ -1368,11 +1368,11 @@ MultiDofJoint::MultiDofJoint(const Properties& properties) } //============================================================================== -template +template void MultiDofJoint::registerDofs() { const SkeletonPtr& skel = this->mChildBodyNode->getSkeleton(); - for (size_t i = 0; i < DOF; ++i) + for (std::size_t i = 0; i < DOF; ++i) { Base::mAspectProperties.mDofNames[i] = skel->mNameMgrForDofs.issueNewNameAndAdd(mDofs[i]->getName(), mDofs[i]); @@ -1380,14 +1380,14 @@ void MultiDofJoint::registerDofs() } //============================================================================== -template +template const math::Jacobian MultiDofJoint::getLocalJacobian() const { return getLocalJacobianStatic(); } //============================================================================== -template +template const Eigen::Matrix& MultiDofJoint::getLocalJacobianStatic() const { @@ -1400,7 +1400,7 @@ MultiDofJoint::getLocalJacobianStatic() const } //============================================================================== -template +template math::Jacobian MultiDofJoint::getLocalJacobian( const Eigen::VectorXd& _positions) const { @@ -1408,7 +1408,7 @@ math::Jacobian MultiDofJoint::getLocalJacobian( } //============================================================================== -template +template const math::Jacobian MultiDofJoint::getLocalJacobianTimeDeriv() const { if(this->mIsLocalJacobianTimeDerivDirty) @@ -1420,7 +1420,7 @@ const math::Jacobian MultiDofJoint::getLocalJacobianTimeDeriv() const } //============================================================================== -template +template const Eigen::Matrix& MultiDofJoint::getLocalJacobianTimeDerivStatic() const { @@ -1433,7 +1433,7 @@ MultiDofJoint::getLocalJacobianTimeDerivStatic() const } //============================================================================== -template +template const Eigen::Matrix& MultiDofJoint::getInvProjArtInertia() const { @@ -1442,7 +1442,7 @@ MultiDofJoint::getInvProjArtInertia() const } //============================================================================== -template +template const Eigen::Matrix& MultiDofJoint::getInvProjArtInertiaImplicit() const { @@ -1451,7 +1451,7 @@ MultiDofJoint::getInvProjArtInertiaImplicit() const } //============================================================================== -template +template void MultiDofJoint::updateLocalSpatialVelocity() const { this->mSpatialVelocity = @@ -1459,7 +1459,7 @@ void MultiDofJoint::updateLocalSpatialVelocity() const } //============================================================================== -template +template void MultiDofJoint::updateLocalSpatialAcceleration() const { this->mSpatialAcceleration = @@ -1468,7 +1468,7 @@ void MultiDofJoint::updateLocalSpatialAcceleration() const } //============================================================================== -template +template void MultiDofJoint::updateLocalPrimaryAcceleration() const { this->mPrimaryAcceleration = @@ -1476,7 +1476,7 @@ void MultiDofJoint::updateLocalPrimaryAcceleration() const } //============================================================================== -template +template void MultiDofJoint::addVelocityTo(Eigen::Vector6d& _vel) { // Add joint velocity to _vel @@ -1487,7 +1487,7 @@ void MultiDofJoint::addVelocityTo(Eigen::Vector6d& _vel) } //============================================================================== -template +template void MultiDofJoint::setPartialAccelerationTo( Eigen::Vector6d& _partialAcceleration, const Eigen::Vector6d& _childVelocity) @@ -1501,7 +1501,7 @@ void MultiDofJoint::setPartialAccelerationTo( } //============================================================================== -template +template void MultiDofJoint::addAccelerationTo(Eigen::Vector6d& _acc) { // Add joint acceleration to _acc @@ -1512,7 +1512,7 @@ void MultiDofJoint::addAccelerationTo(Eigen::Vector6d& _acc) } //============================================================================== -template +template void MultiDofJoint::addVelocityChangeTo(Eigen::Vector6d& _velocityChange) { // Add joint velocity change to _velocityChange @@ -1523,7 +1523,7 @@ void MultiDofJoint::addVelocityChangeTo(Eigen::Vector6d& _velocityChange) } //============================================================================== -template +template void MultiDofJoint::addChildArtInertiaTo( Eigen::Matrix6d& _parentArtInertia, const Eigen::Matrix6d& _childArtInertia) @@ -1549,7 +1549,7 @@ void MultiDofJoint::addChildArtInertiaTo( } //============================================================================== -template +template void MultiDofJoint::addChildArtInertiaToDynamic( Eigen::Matrix6d& _parentArtInertia, const Eigen::Matrix6d& _childArtInertia) @@ -1567,7 +1567,7 @@ void MultiDofJoint::addChildArtInertiaToDynamic( } //============================================================================== -template +template void MultiDofJoint::addChildArtInertiaToKinematic( Eigen::Matrix6d& _parentArtInertia, const Eigen::Matrix6d& _childArtInertia) @@ -1579,7 +1579,7 @@ void MultiDofJoint::addChildArtInertiaToKinematic( } //============================================================================== -template +template void MultiDofJoint::addChildArtInertiaImplicitTo( Eigen::Matrix6d& _parentArtInertia, const Eigen::Matrix6d& _childArtInertia) @@ -1605,7 +1605,7 @@ void MultiDofJoint::addChildArtInertiaImplicitTo( } //============================================================================== -template +template void MultiDofJoint::addChildArtInertiaImplicitToDynamic( Eigen::Matrix6d& _parentArtInertia, const Eigen::Matrix6d& _childArtInertia) @@ -1623,7 +1623,7 @@ void MultiDofJoint::addChildArtInertiaImplicitToDynamic( } //============================================================================== -template +template void MultiDofJoint::addChildArtInertiaImplicitToKinematic( Eigen::Matrix6d& _parentArtInertia, const Eigen::Matrix6d& _childArtInertia) @@ -1635,7 +1635,7 @@ void MultiDofJoint::addChildArtInertiaImplicitToKinematic( } //============================================================================== -template +template void MultiDofJoint::updateInvProjArtInertia( const Eigen::Matrix6d& _artInertia) { @@ -1658,7 +1658,7 @@ void MultiDofJoint::updateInvProjArtInertia( } //============================================================================== -template +template void MultiDofJoint::updateInvProjArtInertiaDynamic( const Eigen::Matrix6d& _artInertia) { @@ -1677,7 +1677,7 @@ void MultiDofJoint::updateInvProjArtInertiaDynamic( } //============================================================================== -template +template void MultiDofJoint::updateInvProjArtInertiaKinematic( const Eigen::Matrix6d& /*_artInertia*/) { @@ -1685,7 +1685,7 @@ void MultiDofJoint::updateInvProjArtInertiaKinematic( } //============================================================================== -template +template void MultiDofJoint::updateInvProjArtInertiaImplicit( const Eigen::Matrix6d& _artInertia, double _timeStep) @@ -1710,7 +1710,7 @@ void MultiDofJoint::updateInvProjArtInertiaImplicit( } //============================================================================== -template +template void MultiDofJoint::updateInvProjArtInertiaImplicitDynamic( const Eigen::Matrix6d& _artInertia, double _timeStep) @@ -1721,7 +1721,7 @@ void MultiDofJoint::updateInvProjArtInertiaImplicitDynamic( = Jacobian.transpose() * _artInertia * Jacobian; // Add additional inertia for implicit damping and spring force - for (size_t i = 0; i < DOF; ++i) + for (std::size_t i = 0; i < DOF; ++i) { projAI(i, i) += _timeStep * Base::mAspectProperties.mDampingCoefficients[i] + _timeStep * _timeStep * Base::mAspectProperties.mSpringStiffnesses[i]; @@ -1737,7 +1737,7 @@ void MultiDofJoint::updateInvProjArtInertiaImplicitDynamic( } //============================================================================== -template +template void MultiDofJoint::updateInvProjArtInertiaImplicitKinematic( const Eigen::Matrix6d& /*_artInertia*/, double /*_timeStep*/) @@ -1746,7 +1746,7 @@ void MultiDofJoint::updateInvProjArtInertiaImplicitKinematic( } //============================================================================== -template +template void MultiDofJoint::addChildBiasForceTo( Eigen::Vector6d& _parentBiasForce, const Eigen::Matrix6d& _childArtInertia, @@ -1778,7 +1778,7 @@ void MultiDofJoint::addChildBiasForceTo( } //============================================================================== -template +template void MultiDofJoint::addChildBiasForceToDynamic( Eigen::Vector6d& _parentBiasForce, const Eigen::Matrix6d& _childArtInertia, @@ -1807,7 +1807,7 @@ void MultiDofJoint::addChildBiasForceToDynamic( } //============================================================================== -template +template void MultiDofJoint::addChildBiasForceToKinematic( Eigen::Vector6d& _parentBiasForce, const Eigen::Matrix6d& _childArtInertia, @@ -1834,7 +1834,7 @@ void MultiDofJoint::addChildBiasForceToKinematic( } //============================================================================== -template +template void MultiDofJoint::addChildBiasImpulseTo( Eigen::Vector6d& _parentBiasImpulse, const Eigen::Matrix6d& _childArtInertia, @@ -1863,7 +1863,7 @@ void MultiDofJoint::addChildBiasImpulseTo( } //============================================================================== -template +template void MultiDofJoint::addChildBiasImpulseToDynamic( Eigen::Vector6d& _parentBiasImpulse, const Eigen::Matrix6d& _childArtInertia, @@ -1884,7 +1884,7 @@ void MultiDofJoint::addChildBiasImpulseToDynamic( } //============================================================================== -template +template void MultiDofJoint::addChildBiasImpulseToKinematic( Eigen::Vector6d& _parentBiasImpulse, const Eigen::Matrix6d& /*_childArtInertia*/, @@ -1897,7 +1897,7 @@ void MultiDofJoint::addChildBiasImpulseToKinematic( } //============================================================================== -template +template void MultiDofJoint::updateTotalForce( const Eigen::Vector6d& _bodyForce, double _timeStep) @@ -1935,7 +1935,7 @@ void MultiDofJoint::updateTotalForce( } //============================================================================== -template +template void MultiDofJoint::updateTotalForceDynamic( const Eigen::Vector6d& _bodyForce, double _timeStep) @@ -1957,7 +1957,7 @@ void MultiDofJoint::updateTotalForceDynamic( } //============================================================================== -template +template void MultiDofJoint::updateTotalForceKinematic( const Eigen::Vector6d& /*_bodyForce*/, double /*_timeStep*/) @@ -1966,7 +1966,7 @@ void MultiDofJoint::updateTotalForceKinematic( } //============================================================================== -template +template void MultiDofJoint::updateTotalImpulse( const Eigen::Vector6d& _bodyImpulse) { @@ -1989,7 +1989,7 @@ void MultiDofJoint::updateTotalImpulse( } //============================================================================== -template +template void MultiDofJoint::updateTotalImpulseDynamic( const Eigen::Vector6d& _bodyImpulse) { @@ -1999,7 +1999,7 @@ void MultiDofJoint::updateTotalImpulseDynamic( } //============================================================================== -template +template void MultiDofJoint::updateTotalImpulseKinematic( const Eigen::Vector6d& /*_bodyImpulse*/) { @@ -2007,14 +2007,14 @@ void MultiDofJoint::updateTotalImpulseKinematic( } //============================================================================== -template +template void MultiDofJoint::resetTotalImpulses() { mTotalImpulse.setZero(); } //============================================================================== -template +template void MultiDofJoint::updateAcceleration( const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) @@ -2038,7 +2038,7 @@ void MultiDofJoint::updateAcceleration( } //============================================================================== -template +template void MultiDofJoint::updateAccelerationDynamic( const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) @@ -2053,7 +2053,7 @@ void MultiDofJoint::updateAccelerationDynamic( } //============================================================================== -template +template void MultiDofJoint::updateAccelerationKinematic( const Eigen::Matrix6d& /*_artInertia*/, const Eigen::Vector6d& /*_spatialAcc*/) @@ -2062,7 +2062,7 @@ void MultiDofJoint::updateAccelerationKinematic( } //============================================================================== -template +template void MultiDofJoint::updateVelocityChange( const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _velocityChange) @@ -2086,7 +2086,7 @@ void MultiDofJoint::updateVelocityChange( } //============================================================================== -template +template void MultiDofJoint::updateVelocityChangeDynamic( const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _velocityChange) @@ -2102,7 +2102,7 @@ void MultiDofJoint::updateVelocityChangeDynamic( } //============================================================================== -template +template void MultiDofJoint::updateVelocityChangeKinematic( const Eigen::Matrix6d& /*_artInertia*/, const Eigen::Vector6d& /*_velocityChange*/) @@ -2111,7 +2111,7 @@ void MultiDofJoint::updateVelocityChangeKinematic( } //============================================================================== -template +template void MultiDofJoint::updateForceID(const Eigen::Vector6d& _bodyForce, double _timeStep, bool _withDampingForces, @@ -2140,7 +2140,7 @@ void MultiDofJoint::updateForceID(const Eigen::Vector6d& _bodyForce, } //============================================================================== -template +template void MultiDofJoint::updateForceFD(const Eigen::Vector6d& _bodyForce, double _timeStep, bool _withDampingForces, @@ -2165,14 +2165,14 @@ void MultiDofJoint::updateForceFD(const Eigen::Vector6d& _bodyForce, } //============================================================================== -template +template void MultiDofJoint::updateImpulseID(const Eigen::Vector6d& _bodyImpulse) { mImpulses = getLocalJacobianStatic().transpose()*_bodyImpulse; } //============================================================================== -template +template void MultiDofJoint::updateImpulseFD(const Eigen::Vector6d& _bodyImpulse) { switch (Joint::mAspectProperties.mActuatorType) @@ -2193,7 +2193,7 @@ void MultiDofJoint::updateImpulseFD(const Eigen::Vector6d& _bodyImpulse) } //============================================================================== -template +template void MultiDofJoint::updateConstrainedTerms(double _timeStep) { switch (Joint::mAspectProperties.mActuatorType) @@ -2215,7 +2215,7 @@ void MultiDofJoint::updateConstrainedTerms(double _timeStep) } //============================================================================== -template +template void MultiDofJoint::updateConstrainedTermsDynamic(double _timeStep) { const double invTimeStep = 1.0 / _timeStep; @@ -2228,7 +2228,7 @@ void MultiDofJoint::updateConstrainedTermsDynamic(double _timeStep) } //============================================================================== -template +template void MultiDofJoint::updateConstrainedTermsKinematic( double _timeStep) { @@ -2236,7 +2236,7 @@ void MultiDofJoint::updateConstrainedTermsKinematic( } //============================================================================== -template +template void MultiDofJoint::addChildBiasForceForInvMassMatrix( Eigen::Vector6d& _parentBiasForce, const Eigen::Matrix6d& _childArtInertia, @@ -2256,7 +2256,7 @@ void MultiDofJoint::addChildBiasForceForInvMassMatrix( } //============================================================================== -template +template void MultiDofJoint::addChildBiasForceForInvAugMassMatrix( Eigen::Vector6d& _parentBiasForce, const Eigen::Matrix6d& _childArtInertia, @@ -2276,7 +2276,7 @@ void MultiDofJoint::addChildBiasForceForInvAugMassMatrix( } //============================================================================== -template +template void MultiDofJoint::updateTotalForceForInvMassMatrix( const Eigen::Vector6d& _bodyForce) { @@ -2286,10 +2286,10 @@ void MultiDofJoint::updateTotalForceForInvMassMatrix( } //============================================================================== -template +template void MultiDofJoint::getInvMassMatrixSegment( Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) { @@ -2303,17 +2303,17 @@ void MultiDofJoint::getInvMassMatrixSegment( assert(!math::isNan(mInvMassMatrixSegment)); // Index - size_t iStart = mDofs[0]->mIndexInTree; + std::size_t iStart = mDofs[0]->mIndexInTree; // Assign _invMassMat.block(iStart, _col) = mInvMassMatrixSegment; } //============================================================================== -template +template void MultiDofJoint::getInvAugMassMatrixSegment( Eigen::MatrixXd& _invMassMat, - const size_t _col, + const std::size_t _col, const Eigen::Matrix6d& _artInertia, const Eigen::Vector6d& _spatialAcc) { @@ -2327,14 +2327,14 @@ void MultiDofJoint::getInvAugMassMatrixSegment( assert(!math::isNan(mInvMassMatrixSegment)); // Index - size_t iStart = mDofs[0]->mIndexInTree; + std::size_t iStart = mDofs[0]->mIndexInTree; // Assign _invMassMat.block(iStart, _col) = mInvMassMatrixSegment; } //============================================================================== -template +template void MultiDofJoint::addInvMassMatrixSegmentTo(Eigen::Vector6d& _acc) { // @@ -2342,7 +2342,7 @@ void MultiDofJoint::addInvMassMatrixSegmentTo(Eigen::Vector6d& _acc) } //============================================================================== -template +template Eigen::VectorXd MultiDofJoint::getSpatialToGeneralized( const Eigen::Vector6d& _spatial) { diff --git a/dart/dynamics/detail/MultiDofJointAspect.h b/dart/dynamics/detail/MultiDofJointAspect.h index f1be847fa5fd0..559c2cca8781f 100644 --- a/dart/dynamics/detail/MultiDofJointAspect.h +++ b/dart/dynamics/detail/MultiDofJointAspect.h @@ -45,15 +45,15 @@ namespace dart { namespace dynamics { // Forward declare the MultiDofJoint class -template class MultiDofJoint; +template class MultiDofJoint; namespace detail { //============================================================================== -template +template struct MultiDofJointState { - constexpr static size_t NumDofs = DOF; + constexpr static std::size_t NumDofs = DOF; using Vector = Eigen::Matrix; /// Position @@ -85,10 +85,10 @@ struct MultiDofJointState }; //============================================================================== -template +template struct MultiDofJointUniqueProperties { - constexpr static size_t NumDofs = DOF; + constexpr static std::size_t NumDofs = DOF; using Vector = Eigen::Matrix; using BoolArray = std::array; using StringArray = std::array; @@ -173,7 +173,7 @@ struct MultiDofJointUniqueProperties }; //============================================================================== -template +template struct MultiDofJointProperties : Joint::Properties, MultiDofJointUniqueProperties @@ -197,14 +197,14 @@ struct MultiDofJointProperties : // // See this StackOverflow answer: http://stackoverflow.com/a/14396189/111426 // -template -constexpr size_t MultiDofJointState::NumDofs; +template +constexpr std::size_t MultiDofJointState::NumDofs; -template -constexpr size_t MultiDofJointUniqueProperties::NumDofs; +template +constexpr std::size_t MultiDofJointUniqueProperties::NumDofs; //============================================================================== -template +template MultiDofJointState::MultiDofJointState( const Vector& positions, const Vector& velocities, @@ -221,7 +221,7 @@ MultiDofJointState::MultiDofJointState( } //============================================================================== -template +template MultiDofJointUniqueProperties::MultiDofJointUniqueProperties( const Vector& _positionLowerLimits, const Vector& _positionUpperLimits, @@ -250,7 +250,7 @@ MultiDofJointUniqueProperties::MultiDofJointUniqueProperties( mDampingCoefficients(_dampingCoefficient), mFrictions(_coulombFrictions) { - for (size_t i = 0; i < DOF; ++i) + for (std::size_t i = 0; i < DOF; ++i) { mPreserveDofNames[i] = false; mDofNames[i] = std::string(); @@ -258,7 +258,7 @@ MultiDofJointUniqueProperties::MultiDofJointUniqueProperties( } //============================================================================== -template +template MultiDofJointUniqueProperties::MultiDofJointUniqueProperties( const MultiDofJointUniqueProperties& _other) : mPositionLowerLimits(_other.mPositionLowerLimits), @@ -276,7 +276,7 @@ MultiDofJointUniqueProperties::MultiDofJointUniqueProperties( mDampingCoefficients(_other.mDampingCoefficients), mFrictions(_other.mFrictions) { - for (size_t i = 0; i < DOF; ++i) + for (std::size_t i = 0; i < DOF; ++i) { mPreserveDofNames[i] = _other.mPreserveDofNames[i]; mDofNames[i] = _other.mDofNames[i]; @@ -284,7 +284,7 @@ MultiDofJointUniqueProperties::MultiDofJointUniqueProperties( } //============================================================================== -template +template MultiDofJointProperties::MultiDofJointProperties( const Joint::Properties& _jointProperties, const MultiDofJointUniqueProperties& _multiDofProperties) @@ -294,7 +294,7 @@ MultiDofJointProperties::MultiDofJointProperties( // Do nothing } -template +template using MultiDofJointBase = common::EmbedStateAndPropertiesOnTopOf< Derived, MultiDofJointState, MultiDofJointUniqueProperties, Joint>; diff --git a/dart/dynamics/detail/Node.h b/dart/dynamics/detail/Node.h index 2bd2f9a2feda2..3a17a17d7e1ed 100644 --- a/dart/dynamics/detail/Node.h +++ b/dart/dynamics/detail/Node.h @@ -48,28 +48,28 @@ namespace dynamics { //============================================================================== template -size_t AccessoryNode::getIndexInBodyNode() const +std::size_t AccessoryNode::getIndexInBodyNode() const { return static_cast(this)->mIndexInBodyNode; } //============================================================================== template -size_t AccessoryNode::getIndexInSkeleton() const +std::size_t AccessoryNode::getIndexInSkeleton() const { return static_cast(this)->mIndexInSkeleton; } //============================================================================== template -size_t AccessoryNode::getIndexInTree() const +std::size_t AccessoryNode::getIndexInTree() const { return static_cast(this)->mIndexInTree; } //============================================================================== template -size_t AccessoryNode::getTreeIndex() const +std::size_t AccessoryNode::getTreeIndex() const { return static_cast(this)->getBodyNodePtr()->getTreeIndex(); } @@ -96,9 +96,9 @@ void AccessoryNode::reattach() //============================================================================== #define DART_ENABLE_NODE_SPECIALIZATION() \ public: \ - template size_t getNumNodes() const { return dart::dynamics::BodyNode::getNumNodes(); } \ - template T* getNode(size_t index) { return dart::dynamics::BodyNode::getNode(index); } \ - template const T* getNode(size_t index) const { return dart::dynamics::BodyNode::getNode(index); } + template std::size_t getNumNodes() const { return dart::dynamics::BodyNode::getNumNodes(); } \ + template T* getNode(std::size_t index) { return dart::dynamics::BodyNode::getNode(index); } \ + template const T* getNode(std::size_t index) const { return dart::dynamics::BodyNode::getNode(index); } //============================================================================== #define DETAIL_DART_INSTANTIATE_SPECIALIZED_NODE( NodeName, it ) \ @@ -117,13 +117,13 @@ void AccessoryNode::reattach() #define DETAIL_DART_SPECIALIZED_NODE_INLINE( NodeName, PluralName, it ) \ private: dart::dynamics::BodyNode::NodeMap::iterator it ; public: \ \ - inline size_t getNum ## PluralName () const \ + inline std::size_t getNum ## PluralName () const \ { return it->second.size(); } \ \ - inline NodeName * get ## NodeName (size_t index) \ + inline NodeName * get ## NodeName (std::size_t index) \ { return static_cast< NodeName *>(getVectorObjectIfAvailable(index, it->second)); } \ \ - inline const NodeName * get ## NodeName (size_t index) const \ + inline const NodeName * get ## NodeName (std::size_t index) const \ { return static_cast(getVectorObjectIfAvailable(index, it->second)); } //============================================================================== @@ -137,9 +137,9 @@ void AccessoryNode::reattach() //============================================================================== #define DETAIL_DART_SPECIALIZED_NODE_DECLARE( NodeName, PluralName, it ) \ private: dart::dynamics::BodyNode::NodeMap::iterator it ; public:\ - size_t getNum ## PluralName() const;\ - NodeName * get ## NodeName (size_t index);\ - const NodeName * get ## NodeName(size_t index) const; + std::size_t getNum ## PluralName() const;\ + NodeName * get ## NodeName (std::size_t index);\ + const NodeName * get ## NodeName(std::size_t index) const; //============================================================================== #define DART_SPECIALIZED_NODE_DECLARE_IRREGULAR( NodeName, PluralName )\ @@ -151,13 +151,13 @@ void AccessoryNode::reattach() //============================================================================== #define DETAIL_DART_SPECIALIZED_NODE_DEFINE( BodyNodeType, NodeName, PluralName, it )\ - size_t BodyNodeType :: getNum ## PluralName () const\ + std::size_t BodyNodeType :: getNum ## PluralName () const\ { return it->second.size(); }\ \ - NodeName * BodyNodeType :: get ## NodeName (size_t index)\ + NodeName * BodyNodeType :: get ## NodeName (std::size_t index)\ { return static_cast(getVectorObjectIfAvailable(index, it->second)); }\ \ - const NodeName * BodyNodeType :: get ## NodeName (size_t index) const\ + const NodeName * BodyNodeType :: get ## NodeName (std::size_t index) const\ { return static_cast(getVectorObjectIfAvailable(index, it->second)); } //============================================================================== @@ -170,9 +170,9 @@ void AccessoryNode::reattach() //============================================================================== #define DETAIL_DART_SPECIALIZED_NODE_TEMPLATE( BodyNodeType, NodeName, PluralName ) \ - template <> inline size_t BodyNodeType :: getNumNodes< NodeName >() const { return getNum ## PluralName (); } \ - template <> inline NodeName * BodyNodeType :: getNode< NodeName >(size_t index) { return get ## NodeName (index); } \ - template <> inline const NodeName * BodyNodeType :: getNode< NodeName >(size_t index) const { return get ## NodeName (index); } + template <> inline std::size_t BodyNodeType :: getNumNodes< NodeName >() const { return getNum ## PluralName (); } \ + template <> inline NodeName * BodyNodeType :: getNode< NodeName >(std::size_t index) { return get ## NodeName (index); } \ + template <> inline const NodeName * BodyNodeType :: getNode< NodeName >(std::size_t index) const { return get ## NodeName (index); } //============================================================================== #define DART_SPECIALIZED_NODE_TEMPLATE_IRREGULAR( BodyNodeType, NodeName, PluralName ) \ @@ -187,12 +187,12 @@ void AccessoryNode::reattach() //============================================================================== #define DART_SKEL_ENABLE_NODE_SPECIALIZATION() \ public: \ - template size_t getNumNodes() const { return dart::dynamics::Skeleton::getNumNodes(); } \ - template size_t getNumNodes(size_t treeIndex) const { return dart::dynamics::Skeleton::getNumNodes(treeIndex); } \ - template T* getNode(size_t index) { return dart::dynamics::Skeleton::getNode(index); } \ - template T* getNode(size_t nodeIdx, size_t treeIndex) { return dart::dynamics::Skeleton::getNode(nodeIdx, treeIndex); } \ - template const T* getNode(size_t index) const { return dart::dynamics::Skeleton::getNode(index); } \ - template const T* getNode(size_t nodeIdx, size_t treeIndex) const { return dart::dynamics::Skeleton::getNode(nodeIdx, treeIndex); } \ + template std::size_t getNumNodes() const { return dart::dynamics::Skeleton::getNumNodes(); } \ + template std::size_t getNumNodes(std::size_t treeIndex) const { return dart::dynamics::Skeleton::getNumNodes(treeIndex); } \ + template T* getNode(std::size_t index) { return dart::dynamics::Skeleton::getNode(index); } \ + template T* getNode(std::size_t nodeIdx, std::size_t treeIndex) { return dart::dynamics::Skeleton::getNode(nodeIdx, treeIndex); } \ + template const T* getNode(std::size_t index) const { return dart::dynamics::Skeleton::getNode(index); } \ + template const T* getNode(std::size_t nodeIdx, std::size_t treeIndex) const { return dart::dynamics::Skeleton::getNode(nodeIdx, treeIndex); } \ template T* getNode(const std::string& name) { return dart::dynamics::Skeleton::getNode(name); } \ template const T* getNode(const std::string& name) const { return dart::dynamics::Skeleton::getNode(name); } @@ -223,21 +223,21 @@ void AccessoryNode::reattach() std::vector treeIts; \ dart::common::NameManager* NameMgr; \ public: \ - inline size_t getNum ## PluralName () const \ + inline std::size_t getNum ## PluralName () const \ { return skelIt->second.size(); } \ - inline size_t getNum ## PluralName (size_t treeIndex) const \ + inline std::size_t getNum ## PluralName (std::size_t treeIndex) const \ { DETAIL_DART_WARN_TREE_INDEX(treeIts, treeIndex, getNum ## PluralName); \ treeIts [treeIndex]->second.size(); } \ \ - inline NodeName * get ## NodeName (size_t index) \ + inline NodeName * get ## NodeName (std::size_t index) \ { return static_cast< NodeName *>(getVectorObjectIfAvailable(index, skelIt ->second)); } \ - inline NodeName * get ## NodeName (size_t treeIndex, size_t nodeIndex) \ + inline NodeName * get ## NodeName (std::size_t treeIndex, std::size_t nodeIndex) \ { DETAIL_DART_WARN_TREE_INDEX(treeIts, treeIndex, get ## NodeName); \ return static_cast< NodeName *>(getVectorObjectIfAvailable(nodeIndex, treeIts[treeIndex]->second)); } \ \ - inline const NodeName * get ## NodeName (size_t index) const \ + inline const NodeName * get ## NodeName (std::size_t index) const \ { return static_cast(getVectorObjectIfAvailable(index, skelIt ->second)); } \ - inline const NodeName * get ## NodeName (size_t treeIndex, size_t nodeIndex) const \ + inline const NodeName * get ## NodeName (std::size_t treeIndex, std::size_t nodeIndex) const \ { DETAIL_DART_WARN_TREE_INDEX(treeIts, treeIndex, get ## NodeName); \ return static_cast(getVectorObjectIfAvailable(nodeIndex, treeIts[treeIndex]->second)); } \ \ @@ -261,17 +261,17 @@ void AccessoryNode::reattach() std::vector treeIts; \ dart::common::NameManager* NameMgr; \ public: \ - size_t getNum ## PluralName () const; \ + std::size_t getNum ## PluralName () const; \ \ - size_t getNum ## PluralName (size_t treeIndex) const; \ + std::size_t getNum ## PluralName (std::size_t treeIndex) const; \ \ - NodeName * get ## NodeName (size_t index); \ + NodeName * get ## NodeName (std::size_t index); \ \ - NodeName * get ## NodeName (size_t treeIndex, size_t nodeIndex); \ + NodeName * get ## NodeName (std::size_t treeIndex, std::size_t nodeIndex); \ \ - const NodeName * get ## NodeName (size_t index) const; \ + const NodeName * get ## NodeName (std::size_t index) const; \ \ - const NodeName * get ## NodeName (size_t treeIndex, size_t nodeIndex) const; \ + const NodeName * get ## NodeName (std::size_t treeIndex, std::size_t nodeIndex) const; \ \ NodeName * get ## NodeName (const std::string& name); \ \ @@ -287,21 +287,21 @@ void AccessoryNode::reattach() //============================================================================== #define DETAIL_DART_SKEL_SPECIALIZED_NODE_DEFINE( SkeletonType, NodeName, PluralName, skelIt, treeIts, NameMgr )\ - size_t SkeletonType :: getNum ## PluralName () const \ + std::size_t SkeletonType :: getNum ## PluralName () const \ { return skelIt->second.size(); } \ - size_t SkeletonType :: getNum ## PluralName (size_t treeIndex) const \ + std::size_t SkeletonType :: getNum ## PluralName (std::size_t treeIndex) const \ { DETAIL_DART_WARN_TREE_INDEX(treeIts, treeIndex, getNum ## PluralName); \ return treeIts [treeIndex]->second.size(); } \ \ - NodeName * SkeletonType :: get ## NodeName (size_t index) \ + NodeName * SkeletonType :: get ## NodeName (std::size_t index) \ { return static_cast< NodeName *>(getVectorObjectIfAvailable(index, skelIt ->second)); } \ - NodeName * SkeletonType :: get ## NodeName (size_t treeIndex, size_t nodeIndex) \ + NodeName * SkeletonType :: get ## NodeName (std::size_t treeIndex, std::size_t nodeIndex) \ { DETAIL_DART_WARN_TREE_INDEX(treeIts, treeIndex, get ## NodeName); \ return static_cast< NodeName *>(getVectorObjectIfAvailable(nodeIndex, treeIts[treeIndex]->second)); } \ \ - const NodeName * SkeletonType :: get ## NodeName (size_t index) const \ + const NodeName * SkeletonType :: get ## NodeName (std::size_t index) const \ { return static_cast(getVectorObjectIfAvailable(index, skelIt ->second)); } \ - const NodeName * SkeletonType :: get ## NodeName (size_t treeIndex, size_t nodeIndex) const \ + const NodeName * SkeletonType :: get ## NodeName (std::size_t treeIndex, std::size_t nodeIndex) const \ { DETAIL_DART_WARN_TREE_INDEX(treeIts, treeIndex, get ## NodeName); \ return static_cast(getVectorObjectIfAvailable(nodeIndex, treeIts[treeIndex]->second)); } \ \ @@ -320,12 +320,12 @@ void AccessoryNode::reattach() //============================================================================== #define DETAIL_DART_SKEL_SPECIALIZED_NODE_TEMPLATE( SkelType, NodeName, PluralName ) \ - template <> inline size_t SkelType :: getNumNodes< NodeName >() const { return getNum ## PluralName (); } \ - template <> inline size_t SkelType :: getNumNodes< NodeName >(size_t index) const { return getNum ## PluralName(index); } \ - template <> inline NodeName* SkelType :: getNode< NodeName >(size_t index) { return get ## NodeName (index); } \ - template <> inline NodeName* SkelType :: getNode< NodeName >(size_t treeIndex, size_t nodeIndex) { return get ## NodeName(treeIndex, nodeIndex); } \ - template <> inline const NodeName* SkelType :: getNode< NodeName >(size_t index) const { return get ## NodeName (index); } \ - template <> inline const NodeName* SkelType :: getNode< NodeName >(size_t treeIndex, size_t nodeIndex) const { return get ## NodeName(treeIndex, nodeIndex); } \ + template <> inline std::size_t SkelType :: getNumNodes< NodeName >() const { return getNum ## PluralName (); } \ + template <> inline std::size_t SkelType :: getNumNodes< NodeName >(std::size_t index) const { return getNum ## PluralName(index); } \ + template <> inline NodeName* SkelType :: getNode< NodeName >(std::size_t index) { return get ## NodeName (index); } \ + template <> inline NodeName* SkelType :: getNode< NodeName >(std::size_t treeIndex, std::size_t nodeIndex) { return get ## NodeName(treeIndex, nodeIndex); } \ + template <> inline const NodeName* SkelType :: getNode< NodeName >(std::size_t index) const { return get ## NodeName (index); } \ + template <> inline const NodeName* SkelType :: getNode< NodeName >(std::size_t treeIndex, std::size_t nodeIndex) const { return get ## NodeName(treeIndex, nodeIndex); } \ template <> inline NodeName* SkelType::getNode< NodeName >(const std::string& name) { return get ## NodeName (name); } \ template <> inline const NodeName* SkelType::getNode< NodeName >(const std::string& name) const { return get ## NodeName (name); } diff --git a/dart/dynamics/detail/NodeManagerJoiner.h b/dart/dynamics/detail/NodeManagerJoiner.h index c25c591ee5a85..c463247164c85 100644 --- a/dart/dynamics/detail/NodeManagerJoiner.h +++ b/dart/dynamics/detail/NodeManagerJoiner.h @@ -77,9 +77,9 @@ NodeManagerJoinerForBodyNode::NodeManagerJoinerForBodyNode( } //============================================================================== -DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(size_t, NodeManagerJoinerForBodyNode, getNumNodes, () const, isSpecializedForNode, ()) -DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(T*, NodeManagerJoinerForBodyNode, getNode, (size_t index), isSpecializedForNode, (index)) -DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(const T*, NodeManagerJoinerForBodyNode, getNode, (size_t index) const, isSpecializedForNode, (index)) +DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(std::size_t, NodeManagerJoinerForBodyNode, getNumNodes, () const, isSpecializedForNode, ()) +DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(T*, NodeManagerJoinerForBodyNode, getNode, (std::size_t index), isSpecializedForNode, (index)) +DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(const T*, NodeManagerJoinerForBodyNode, getNode, (std::size_t index) const, isSpecializedForNode, (index)) //============================================================================== template @@ -112,9 +112,9 @@ NodeManagerJoinerForSkeleton::NodeManagerJoinerForSkeleton( } //============================================================================== -DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(size_t, NodeManagerJoinerForSkeleton, getNumNodes, (size_t treeIndex) const, isSpecializedForNode, (treeIndex)) -DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(T*, NodeManagerJoinerForSkeleton, getNode, (size_t treeIndex, size_t nodeIndex), isSpecializedForNode, (treeIndex, nodeIndex)) -DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(const T*, NodeManagerJoinerForSkeleton, getNode, (size_t treeIndex, size_t nodeIndex) const, isSpecializedForNode, (treeIndex, nodeIndex)) +DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(std::size_t, NodeManagerJoinerForSkeleton, getNumNodes, (std::size_t treeIndex) const, isSpecializedForNode, (treeIndex)) +DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(T*, NodeManagerJoinerForSkeleton, getNode, (std::size_t treeIndex, std::size_t nodeIndex), isSpecializedForNode, (treeIndex, nodeIndex)) +DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(const T*, NodeManagerJoinerForSkeleton, getNode, (std::size_t treeIndex, std::size_t nodeIndex) const, isSpecializedForNode, (treeIndex, nodeIndex)) DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(T*, NodeManagerJoinerForSkeleton, getNode, (const std::string& name), isSpecializedForNode, (name)) DETAIL_DART_COMMON_IRREGULAR_TEMPLATEJOINERDISPATCH_IMPL(const T*, NodeManagerJoinerForSkeleton, getNode, (const std::string& name) const, isSpecializedForNode, (name)) diff --git a/dart/dynamics/detail/SoftBodyNodeAspect.h b/dart/dynamics/detail/SoftBodyNodeAspect.h index c8bc5ba28cc71..f8123acbfaabe 100644 --- a/dart/dynamics/detail/SoftBodyNodeAspect.h +++ b/dart/dynamics/detail/SoftBodyNodeAspect.h @@ -101,7 +101,7 @@ struct SoftBodyNodeUniqueProperties void addPointMass(const PointMass::Properties& _properties); /// Connect two PointMasses together in this Properties struct - bool connectPointMasses(size_t i1, size_t i2); + bool connectPointMasses(std::size_t i1, std::size_t i2); /// Add a face to this Properties struct void addFace(const Eigen::Vector3i& _newFace); diff --git a/dart/dynamics/detail/SpecializedNodeManager.h b/dart/dynamics/detail/SpecializedNodeManager.h index 290e18dc36705..c87ece354b13f 100644 --- a/dart/dynamics/detail/SpecializedNodeManager.h +++ b/dart/dynamics/detail/SpecializedNodeManager.h @@ -60,7 +60,7 @@ BodyNodeSpecializedFor::BodyNodeSpecializedFor() //============================================================================== template template -size_t BodyNodeSpecializedFor::getNumNodes() const +std::size_t BodyNodeSpecializedFor::getNumNodes() const { return _getNumNodes(type()); } @@ -68,7 +68,7 @@ size_t BodyNodeSpecializedFor::getNumNodes() const //============================================================================== template template -NodeType* BodyNodeSpecializedFor::getNode(size_t index) +NodeType* BodyNodeSpecializedFor::getNode(std::size_t index) { return _getNode(type(), index); } @@ -76,7 +76,7 @@ NodeType* BodyNodeSpecializedFor::getNode(size_t index) //============================================================================== template template -const NodeType* BodyNodeSpecializedFor::getNode(size_t index) const +const NodeType* BodyNodeSpecializedFor::getNode(std::size_t index) const { return const_cast*>(this)-> _getNode(type(), index); @@ -93,14 +93,14 @@ constexpr bool BodyNodeSpecializedFor::isSpecializedForNode() //============================================================================== template template -size_t BodyNodeSpecializedFor::_getNumNodes(type) const +std::size_t BodyNodeSpecializedFor::_getNumNodes(type) const { return detail::BasicNodeManagerForBodyNode::getNumNodes(); } //============================================================================== template -size_t BodyNodeSpecializedFor::_getNumNodes(type) const +std::size_t BodyNodeSpecializedFor::_getNumNodes(type) const { #ifdef DART_UNITTEST_SPECIALIZED_NODE_ACCESS usedSpecializedNodeAccess = true; @@ -112,14 +112,14 @@ size_t BodyNodeSpecializedFor::_getNumNodes(type) const //============================================================================== template template -NodeType* BodyNodeSpecializedFor::_getNode(type, size_t index) +NodeType* BodyNodeSpecializedFor::_getNode(type, std::size_t index) { return detail::BasicNodeManagerForBodyNode::getNode(index); } //============================================================================== template -SpecNode* BodyNodeSpecializedFor::_getNode(type, size_t index) +SpecNode* BodyNodeSpecializedFor::_getNode(type, std::size_t index) { #ifdef DART_UNITTEST_SPECIALIZED_NODE_ACCESS usedSpecializedNodeAccess = true; @@ -157,8 +157,8 @@ SkeletonSpecializedFor::SkeletonSpecializedFor() //============================================================================== template template -size_t SkeletonSpecializedFor::getNumNodes( - size_t treeIndex) const +std::size_t SkeletonSpecializedFor::getNumNodes( + std::size_t treeIndex) const { return _getNumNodes(type(), treeIndex); } @@ -167,7 +167,7 @@ size_t SkeletonSpecializedFor::getNumNodes( template template NodeType* SkeletonSpecializedFor::getNode( - size_t treeIndex, size_t nodeIndex) + std::size_t treeIndex, std::size_t nodeIndex) { return _getNode(type(), treeIndex, nodeIndex); } @@ -176,7 +176,7 @@ NodeType* SkeletonSpecializedFor::getNode( template template const NodeType* SkeletonSpecializedFor::getNode( - size_t treeIndex, size_t nodeIndex) const + std::size_t treeIndex, std::size_t nodeIndex) const { return const_cast*>(this)-> _getNode(type(), treeIndex, nodeIndex); @@ -212,16 +212,16 @@ constexpr bool SkeletonSpecializedFor::isSpecializedForNode() //============================================================================== template template -size_t SkeletonSpecializedFor::_getNumNodes( - type, size_t treeIndex) const +std::size_t SkeletonSpecializedFor::_getNumNodes( + type, std::size_t treeIndex) const { return detail::BasicNodeManagerForSkeleton::getNumNodes(treeIndex); } //============================================================================== template -size_t SkeletonSpecializedFor::_getNumNodes( - type, size_t treeIndex) const +std::size_t SkeletonSpecializedFor::_getNumNodes( + type, std::size_t treeIndex) const { #ifdef DART_UNITTEST_SPECIALIZED_NODE_ACCESS usedSpecializedNodeAccess = true; @@ -243,7 +243,7 @@ size_t SkeletonSpecializedFor::_getNumNodes( template template NodeType* SkeletonSpecializedFor::_getNode( - type, size_t treeIndex, size_t nodeIndex) + type, std::size_t treeIndex, std::size_t nodeIndex) { return detail::BasicNodeManagerForSkeleton::getNode( treeIndex, nodeIndex); @@ -252,7 +252,7 @@ NodeType* SkeletonSpecializedFor::_getNode( //============================================================================== template SpecNode* SkeletonSpecializedFor::_getNode( - type, size_t treeIndex, size_t nodeIndex) + type, std::size_t treeIndex, std::size_t nodeIndex) { #ifdef DART_UNITTEST_SPECIALIZED_NODE_ACCESS usedSpecializedNodeAccess = true; diff --git a/dart/gui/OpenGLRenderInterface.cpp b/dart/gui/OpenGLRenderInterface.cpp index 6482293261515..1266714032b2a 100644 --- a/dart/gui/OpenGLRenderInterface.cpp +++ b/dart/gui/OpenGLRenderInterface.cpp @@ -442,7 +442,7 @@ void OpenGLRenderInterface::compileList(dynamics::Skeleton* _skel) if(_skel == 0) return; - for (size_t i = 0; i < _skel->getNumBodyNodes(); i++) { + for (std::size_t i = 0; i < _skel->getNumBodyNodes(); i++) { compileList(_skel->getBodyNode(i)); } } diff --git a/dart/gui/SimWindow.cpp b/dart/gui/SimWindow.cpp index d3e3f740c3ba7..35597276b5fb0 100644 --- a/dart/gui/SimWindow.cpp +++ b/dart/gui/SimWindow.cpp @@ -115,7 +115,7 @@ void SimWindow::drawSkels() //============================================================================== void SimWindow::drawEntities() { - for (size_t i = 0; i < mWorld->getNumSimpleFrames(); ++i) + for (std::size_t i = 0; i < mWorld->getNumSimpleFrames(); ++i) drawShapeFrame(mWorld->getSimpleFrame(i).get()); } @@ -140,14 +140,14 @@ void SimWindow::draw() { glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); if (!mSimulating) { if (mPlayFrame < mWorld->getRecording()->getNumFrames()) { - size_t nSkels = mWorld->getNumSkeletons(); - for (size_t i = 0; i < nSkels; i++) { - // size_t start = mWorld->getIndex(i); - // size_t size = mWorld->getSkeleton(i)->getNumDofs(); + std::size_t nSkels = mWorld->getNumSkeletons(); + for (std::size_t i = 0; i < nSkels; i++) { + // std::size_t start = mWorld->getIndex(i); + // std::size_t size = mWorld->getSkeleton(i)->getNumDofs(); mWorld->getSkeleton(i)->setPositions(mWorld->getRecording()->getConfig(mPlayFrame, i)); } if (mShowMarkers) { - // size_t sumDofs = mWorld->getIndex(nSkels); + // std::size_t sumDofs = mWorld->getIndex(nSkels); int nContact = mWorld->getRecording()->getNumContacts(mPlayFrame); for (int i = 0; i < nContact; i++) { Eigen::Vector3d v = mWorld->getRecording()->getContactPoint(mPlayFrame, i); diff --git a/dart/gui/osg/DefaultEventHandler.cpp b/dart/gui/osg/DefaultEventHandler.cpp index b627d030cf0cd..5801f731647e0 100644 --- a/dart/gui/osg/DefaultEventHandler.cpp +++ b/dart/gui/osg/DefaultEventHandler.cpp @@ -61,8 +61,8 @@ DefaultEventHandler::DefaultEventHandler(Viewer* _viewer) mViewer->addInstructionText("Spacebar: Turn simulation on/off for any active worlds\n"); mViewer->addInstructionText("Ctrl+H: Turn headlights on/off\n"); - for(size_t i=0; igetTool((InteractiveTool::Type)s, c)->resetAlpha(); mHighlighting = false; } @@ -438,9 +438,9 @@ class InteractiveFrameMouseEvent : public MouseEventHandler const PickInfo& pick = picks[0]; - for(size_t s=0; s < (size_t)InteractiveTool::NUM_TYPES; ++s) + for(std::size_t s=0; s < (std::size_t)InteractiveTool::NUM_TYPES; ++s) { - for(size_t c=0; c<3; ++c) + for(std::size_t c=0; c<3; ++c) { if(mFrame->getTool((InteractiveTool::Type)s, c) == pick.frame->getParentFrame()) @@ -457,11 +457,11 @@ class InteractiveFrameMouseEvent : public MouseEventHandler if(mHighlighting) { - for(size_t s=0; s < InteractiveTool::NUM_TYPES; ++s) + for(std::size_t s=0; s < InteractiveTool::NUM_TYPES; ++s) { - for(size_t c=0; c<3; ++c) + for(std::size_t c=0; c<3; ++c) { - if(s == (size_t)mTool && c == mCoordinate) + if(s == (std::size_t)mTool && c == mCoordinate) mFrame->getTool((InteractiveTool::Type)s, c)->setAlpha(1.0); else mFrame->getTool((InteractiveTool::Type)s, c)->setAlpha(0.3); @@ -488,7 +488,7 @@ class InteractiveFrameMouseEvent : public MouseEventHandler bool mHighlighting; int mTool; - size_t mCoordinate; + std::size_t mCoordinate; }; //============================================================================== @@ -566,12 +566,12 @@ InteractiveFrameDnD::InteractiveFrameDnD(Viewer* viewer, mViewer->getDefaultEventHandler()->addMouseEventHandler( new InteractiveFrameMouseEvent(frame)); - for(size_t i=0; igetTool((InteractiveTool::Type)i, j))); - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) { DragAndDrop* dnd = mDnDs[i]; dnd->setRotationOption(SimpleFrameDnD::RotationOption::ALWAYS_OFF); @@ -595,7 +595,7 @@ void InteractiveFrameDnD::update() { if(!mAmMoving) { - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) { DragAndDrop* dnd = mDnDs[i]; Eigen::Matrix3d R = mInteractiveFrame->getWorldTransform().linear(); @@ -610,7 +610,7 @@ void InteractiveFrameDnD::update() } mAmMoving = false; - for(size_t i=0; iupdate(); @@ -619,9 +619,9 @@ void InteractiveFrameDnD::update() if(mAmMoving) { - for(size_t i=0; iisMoving() && tool->getEnabled()) { const auto shapeFrames = tool->getShapeFrames(); - for(size_t s=0; sgetVisualAspect(true)->setHidden(true); } } @@ -637,16 +637,16 @@ void InteractiveFrameDnD::update() } else { - for(size_t i=0; igetTool((InteractiveTool::Type)i,j); if(tool->getEnabled()) { const auto shapeFrames = tool->getShapeFrames(); - for(size_t s=0; sgetVisualAspect(true)->setHidden(false); } } @@ -743,12 +743,12 @@ void BodyNodeDnD::move() if(restrictJoints) { - std::vector dofs; + std::vector dofs; dart::dynamics::Joint* joint = mBodyNode.lock()->getParentJoint(); - for(size_t count = 0; count <= mAdditionalBodyNodes; ++count) + for(std::size_t count = 0; count <= mAdditionalBodyNodes; ++count) { - for(size_t j=0; j < joint->getNumDofs(); ++j) + for(std::size_t j=0; j < joint->getNumDofs(); ++j) dofs.push_back(joint->getDof(j)->getIndexInSkeleton()); } diff --git a/dart/gui/osg/DragAndDrop.h b/dart/gui/osg/DragAndDrop.h index 341f45384a3bf..1692b8404a10f 100644 --- a/dart/gui/osg/DragAndDrop.h +++ b/dart/gui/osg/DragAndDrop.h @@ -357,7 +357,7 @@ class BodyNodeDnD : public DragAndDrop ::osgGA::GUIEventAdapter::ModKeyMask mJointRestrictionModKey; /// Currently unused, but this will change in the future - size_t mAdditionalBodyNodes; + std::size_t mAdditionalBodyNodes; }; } // namespace osg diff --git a/dart/gui/osg/InteractiveFrame.cpp b/dart/gui/osg/InteractiveFrame.cpp index 755bbad7a5ab0..a26b551353f9d 100644 --- a/dart/gui/osg/InteractiveFrame.cpp +++ b/dart/gui/osg/InteractiveFrame.cpp @@ -164,7 +164,7 @@ InteractiveFrame::InteractiveFrame( Frame(referenceFrame), SimpleFrame(referenceFrame, name, relativeTransform) { - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) { std::string affix = (i==0)? "x" : (i==1)? "y" : "z"; @@ -196,7 +196,7 @@ void InteractiveFrame::resizeStandardVisuals(double size_scale, //============================================================================== InteractiveTool* InteractiveFrame::getTool(InteractiveTool::Type tool, - size_t coordinate) + std::size_t coordinate) { if(InteractiveTool::NUM_TYPES <= tool) { @@ -214,12 +214,12 @@ InteractiveTool* InteractiveFrame::getTool(InteractiveTool::Type tool, return nullptr; } - return mTools[(size_t)tool][coordinate]; + return mTools[(std::size_t)tool][coordinate]; } //============================================================================== const InteractiveTool* InteractiveFrame::getTool( - InteractiveTool::Type tool, size_t coordinate) const + InteractiveTool::Type tool, std::size_t coordinate) const { return const_cast(this)->getTool(tool, coordinate); } @@ -273,14 +273,14 @@ void InteractiveFrame::createStandardVisualizationShapes(double size, double thickness) { thickness = std::min(10.0, std::max(0.0, thickness)); - size_t resolution = 72; + std::size_t resolution = 72; double ring_outer_scale = 0.7*size; double ring_inner_scale = ring_outer_scale*(1-0.1*thickness); double plane_corner = 0.9*ring_inner_scale; double plane_length = plane_corner/sqrt(2); // Create translation arrows - for(size_t a=0; a<3; ++a) + for(std::size_t a=0; a<3; ++a) { Eigen::Vector3d tail(Eigen::Vector3d::Zero()); // tail[a] = 1.2*plane_length; @@ -312,13 +312,13 @@ void InteractiveFrame::createStandardVisualizationShapes(double size, } // Create rotation rings - for(size_t r=0; r<3; ++r) + for(std::size_t r=0; r<3; ++r) { aiMesh* mesh = new aiMesh; mesh->mMaterialIndex = (unsigned int)(-1); - size_t numVertices = 8*resolution; - size_t R = 4*resolution; + std::size_t numVertices = 8*resolution; + std::size_t R = 4*resolution; mesh->mNumVertices = numVertices; mesh->mVertices = new aiVector3D[numVertices]; mesh->mNormals = new aiVector3D[numVertices]; @@ -327,9 +327,9 @@ void InteractiveFrame::createStandardVisualizationShapes(double size, aiVector3D normal; aiColor4D color1; aiColor4D color2; - for(size_t j=0; j<2; ++j) + for(std::size_t j=0; j<2; ++j) { - for(size_t i=0; imNormals[4*i+j+R] = normal; mesh->mNormals[4*i+2+j+R] = normal; - for(size_t c=0; c<3; ++c) + for(std::size_t c=0; c<3; ++c) { color1[c] = 0.0; color2[c] = 0.0; @@ -372,12 +372,12 @@ void InteractiveFrame::createStandardVisualizationShapes(double size, } } - size_t numFaces = 4*resolution; - size_t F = 2*resolution; - size_t H = resolution/2; + std::size_t numFaces = 4*resolution; + std::size_t F = 2*resolution; + std::size_t H = resolution/2; mesh->mNumFaces = numFaces; mesh->mFaces = new aiFace[numFaces]; - for(size_t i=0; imFaces[2*i]; @@ -469,19 +469,19 @@ void InteractiveFrame::createStandardVisualizationShapes(double size, } // Create translation planes - for(size_t p=0; p<3; ++p) + for(std::size_t p=0; p<3; ++p) { aiMesh* mesh = new aiMesh; mesh->mMaterialIndex = (unsigned int)(-1); - size_t numVertices = 8; + std::size_t numVertices = 8; mesh->mNumVertices = numVertices; mesh->mVertices = new aiVector3D[numVertices]; mesh->mNormals = new aiVector3D[numVertices]; mesh->mColors[0] = new aiColor4D[numVertices]; double L = plane_length; - for(size_t i=0; i<2; ++i) + for(std::size_t i=0; i<2; ++i) { mesh->mVertices[4*i+0] = aiVector3D(0, -L, -L); mesh->mVertices[4*i+1] = aiVector3D(0, L, -L); @@ -489,7 +489,7 @@ void InteractiveFrame::createStandardVisualizationShapes(double size, mesh->mVertices[4*i+3] = aiVector3D(0, L, L); } - for(size_t i=0; i<4; ++i) + for(std::size_t i=0; i<4; ++i) { mesh->mNormals[i] = aiVector3D(1, 0, 0); mesh->mNormals[i+4] = aiVector3D(-1, 0, 0); @@ -498,13 +498,13 @@ void InteractiveFrame::createStandardVisualizationShapes(double size, aiColor4D color(0.1, 0.1, 0.1, getTool(InteractiveTool::PLANAR,p)->getDefaultAlpha()); color[p] = 0.9; - for(size_t i=0; imColors[0][i] = color; - size_t numFaces = 4; + std::size_t numFaces = 4; mesh->mNumFaces = numFaces; mesh->mFaces = new aiFace[numFaces]; - for(size_t i=0; imFaces[i]; face->mNumIndices = 3; @@ -557,12 +557,12 @@ void InteractiveFrame::createStandardVisualizationShapes(double size, shapeFrame->setRelativeTransform(tf); } - for(size_t i=0; igetShapeFrames(); - for(size_t s=0; sgetShape()->setDataVariance( dart::dynamics::Shape::DYNAMIC_COLOR); @@ -571,7 +571,7 @@ void InteractiveFrame::createStandardVisualizationShapes(double size, } // Create axes - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) { std::shared_ptr line( new dart::dynamics::LineSegmentShape(3.0)); @@ -591,9 +591,9 @@ void InteractiveFrame::deleteAllVisualizationShapes() { removeAllShapeFrames(); - for(size_t i=0; iremoveAllShapeFrames(); @@ -604,8 +604,8 @@ void InteractiveFrame::deleteAllVisualizationShapes() //============================================================================== void InteractiveFrame::deleteAllTools() { - for(size_t i=0; iresize(poly.size()); mFaces->resize(poly.size()); - for(size_t i=0; i < poly.size(); ++i) + for(std::size_t i=0; i < poly.size(); ++i) { const Eigen::Vector3d& v = axes.first*poly[i][0] + axes.second*poly[i][1] + up*mElevation; @@ -309,7 +309,7 @@ void SupportPolygonVisual::refresh() skel->getTreeBodyNodes(mTreeIndex); double mass = 0.0; - for(size_t i=0; i < bns.size(); ++i) + for(std::size_t i=0; i < bns.size(); ++i) { dart::dynamics::BodyNode* bn = bns[i]; com += bn->getMass() * bn->getCOM(); diff --git a/dart/gui/osg/SupportPolygonVisual.h b/dart/gui/osg/SupportPolygonVisual.h index 617647c639982..0612a5432901e 100644 --- a/dart/gui/osg/SupportPolygonVisual.h +++ b/dart/gui/osg/SupportPolygonVisual.h @@ -59,7 +59,7 @@ class SupportPolygonVisual : public ViewerAttachment double elevation = 0.02); /// Visualize the support polygon of a specific tree in a Skeleton - SupportPolygonVisual(const dart::dynamics::SkeletonPtr& skeleton, size_t treeIndex, + SupportPolygonVisual(const dart::dynamics::SkeletonPtr& skeleton, std::size_t treeIndex, double elevation = 0.02); /// Change the Skeleton that is being visualized @@ -72,7 +72,7 @@ class SupportPolygonVisual : public ViewerAttachment void visualizeWholeSkeleton(); /// Visualize a specific tree in the Skeleton - void visualizeTree(size_t treeIndex); + void visualizeTree(std::size_t treeIndex); /// Change the elevation height at which the polygon is displayed void setDisplayElevation(double elevation); @@ -144,7 +144,7 @@ class SupportPolygonVisual : public ViewerAttachment dart::dynamics::WeakSkeletonPtr mSkeleton; /// Tree index for this visual - size_t mTreeIndex; + std::size_t mTreeIndex; /// Elevation that this visual should use double mElevation; diff --git a/dart/gui/osg/Viewer.cpp b/dart/gui/osg/Viewer.cpp index edba0b1affebf..cb2670b708b1a 100644 --- a/dart/gui/osg/Viewer.cpp +++ b/dart/gui/osg/Viewer.cpp @@ -257,7 +257,7 @@ void Viewer::captureScreen(const std::string& filename) //============================================================================== void Viewer::record(const std::string& directory, const std::string& prefix, - bool restart, size_t digits) + bool restart, std::size_t digits) { if(directory.empty()) { diff --git a/dart/gui/osg/Viewer.h b/dart/gui/osg/Viewer.h index 97bc70050a07d..60bb2e29ac377 100644 --- a/dart/gui/osg/Viewer.h +++ b/dart/gui/osg/Viewer.h @@ -147,7 +147,7 @@ class Viewer : public osgViewer::Viewer, public dart::common::Subject /// Set the restart argument to true if you want the sequence counter to /// restart from 0. void record(const std::string& directory, const std::string& prefix = "image", - bool restart = false, size_t digits=6); + bool restart = false, std::size_t digits=6); /// If the Viewer is recording, then pause the recording. The next time /// record() is called, the numbering of the images will resume from where it @@ -297,10 +297,10 @@ class Viewer : public osgViewer::Viewer, public dart::common::Subject friend class SaveScreen; /// Current number of the image sequence for screen recording - size_t mImageSequenceNum; + std::size_t mImageSequenceNum; /// Number of digits to use when saving an image sequence - size_t mImageDigits; + std::size_t mImageDigits; /// Whether or not the Viewer is currently recording bool mRecording; diff --git a/dart/gui/osg/WorldNode.cpp b/dart/gui/osg/WorldNode.cpp index a9253f42d0434..33bc44212726c 100644 --- a/dart/gui/osg/WorldNode.cpp +++ b/dart/gui/osg/WorldNode.cpp @@ -95,7 +95,7 @@ void WorldNode::refresh() if(mSimulating) { - for(size_t i=0; istep(); @@ -148,13 +148,13 @@ void WorldNode::simulate(bool _on) } //============================================================================== -void WorldNode::setNumStepsPerCycle(size_t _steps) +void WorldNode::setNumStepsPerCycle(std::size_t _steps) { mNumStepsPerCycle = _steps; } //============================================================================== -size_t WorldNode::getNumStepsPerCycle() const +std::size_t WorldNode::getNumStepsPerCycle() const { return mNumStepsPerCycle; } @@ -210,10 +210,10 @@ void WorldNode::refreshSkeletons() // Apply the recursive Frame refreshing functionality to the root BodyNode of // each Skeleton - for(size_t i=0; i < mWorld->getNumSkeletons(); ++i) + for(std::size_t i=0; i < mWorld->getNumSkeletons(); ++i) { const dart::dynamics::SkeletonPtr& skeleton = mWorld->getSkeleton(i); - for(size_t i=0; i < skeleton->getNumTrees(); ++i) + for(std::size_t i=0; i < skeleton->getNumTrees(); ++i) { refreshBaseFrameNode(skeleton->getRootBodyNode(i)); } @@ -226,7 +226,7 @@ void WorldNode::refreshSimpleFrames() if(!mWorld) return; - for(size_t i=0, end=mWorld->getNumSimpleFrames(); igetNumSimpleFrames(); igetSimpleFrame(i).get()); } diff --git a/dart/gui/osg/WorldNode.h b/dart/gui/osg/WorldNode.h index 893ef09a17a22..b1b79412afa6e 100644 --- a/dart/gui/osg/WorldNode.h +++ b/dart/gui/osg/WorldNode.h @@ -127,11 +127,11 @@ class WorldNode : public ::osg::Group /// Set the number of steps to take between each render cycle (only if the /// simulation is not paused) - void setNumStepsPerCycle(size_t _steps); + void setNumStepsPerCycle(std::size_t _steps); /// Get the number of steps that will be taken between each render cycle (only /// if the simulation is not paused) - size_t getNumStepsPerCycle() const; + std::size_t getNumStepsPerCycle() const; protected: @@ -172,7 +172,7 @@ class WorldNode : public ::osg::Group bool mSimulating; /// Number of steps to take between rendering cycles - size_t mNumStepsPerCycle; + std::size_t mNumStepsPerCycle; /// Viewer that this WorldNode is inside of Viewer* mViewer; diff --git a/dart/gui/osg/examples/osgAtlasPuppet.cpp b/dart/gui/osg/examples/osgAtlasPuppet.cpp index c635a4df5ac89..64cf71892ed0a 100644 --- a/dart/gui/osg/examples/osgAtlasPuppet.cpp +++ b/dart/gui/osg/examples/osgAtlasPuppet.cpp @@ -251,7 +251,7 @@ class TeleoperationWorld : public dart::gui::osg::WorldNode protected: SkeletonPtr mAtlas; - size_t iter; + std::size_t iter; EndEffectorPtr l_foot; EndEffectorPtr r_foot; @@ -282,7 +282,7 @@ class InputHandler : public ::osgGA::GUIEventHandler mRestConfig = mAtlas->getPositions(); mLegs.reserve(12); - for(size_t i=0; igetNumDofs(); ++i) + for(std::size_t i=0; igetNumDofs(); ++i) { if(mAtlas->getDof(i)->getName().substr(1, 5) == "_leg_") mLegs.push_back(mAtlas->getDof(i)->getIndexInSkeleton()); @@ -292,7 +292,7 @@ class InputHandler : public ::osgGA::GUIEventHandler mLegs.push_back(mAtlas->getDof("rootJoint_rot_y")->getIndexInSkeleton()); mLegs.push_back(mAtlas->getDof("rootJoint_pos_z")->getIndexInSkeleton()); - for(size_t i=0; i < mAtlas->getNumEndEffectors(); ++i) + for(std::size_t i=0; i < mAtlas->getNumEndEffectors(); ++i) { const InverseKinematicsPtr ik = mAtlas->getEndEffector(i)->getIK(); if(ik) @@ -327,7 +327,7 @@ class InputHandler : public ::osgGA::GUIEventHandler { if( ea.getKey() == 'p' ) { - for(size_t i=0; i < mAtlas->getNumDofs(); ++i) + for(std::size_t i=0; i < mAtlas->getNumDofs(); ++i) std::cout << mAtlas->getDof(i)->getName() << ": " << mAtlas->getDof(i)->getPosition() << std::endl; std::cout << " -- -- -- -- -- " << std::endl; @@ -337,7 +337,7 @@ class InputHandler : public ::osgGA::GUIEventHandler if( ea.getKey() == 't' ) { // Reset all the positions except for x, y, and yaw - for(size_t i=0; i < mAtlas->getNumDofs(); ++i) + for(std::size_t i=0; i < mAtlas->getNumDofs(); ++i) { if( i < 2 || 4 < i ) mAtlas->getDof(i)->setPosition(mRestConfig[i]); @@ -347,7 +347,7 @@ class InputHandler : public ::osgGA::GUIEventHandler if( '1' <= ea.getKey() && ea.getKey() <= '9' ) { - size_t index = ea.getKey() - '1'; + std::size_t index = ea.getKey() - '1'; if(index < mConstraintActive.size()) { EndEffector* ee = mAtlas->getEndEffector(mEndEffectorIndex[index]); @@ -472,11 +472,11 @@ class InputHandler : public ::osgGA::GUIEventHandler Eigen::VectorXd mRestConfig; - std::vector mLegs; + std::vector mLegs; std::vector mConstraintActive; - std::vector mEndEffectorIndex; + std::vector mEndEffectorIndex; std::vector< std::pair > mDefaultBounds; @@ -747,7 +747,7 @@ void setupWholeBodySolver(const SkeletonPtr& atlas) atlas->getIK(true)->getSolver()); solver->setNumMaxIterations(10); - size_t nDofs = atlas->getNumDofs(); + std::size_t nDofs = atlas->getNumDofs(); double default_weight = 0.01; Eigen::VectorXd weights = default_weight * Eigen::VectorXd::Ones(nDofs); @@ -822,10 +822,10 @@ void setupWholeBodySolver(const SkeletonPtr& atlas) void enableDragAndDrops(dart::gui::osg::Viewer& viewer, const SkeletonPtr& atlas) { // Turn on drag-and-drop for the whole Skeleton - for(size_t i=0; i < atlas->getNumBodyNodes(); ++i) + for(std::size_t i=0; i < atlas->getNumBodyNodes(); ++i) viewer.enableDragAndDrop(atlas->getBodyNode(i), false, false); - for(size_t i=0; i < atlas->getNumEndEffectors(); ++i) + for(std::size_t i=0; i < atlas->getNumEndEffectors(); ++i) { EndEffector* ee = atlas->getEndEffector(i); if(!ee->getIK()) diff --git a/dart/gui/osg/examples/osgHuboPuppet.cpp b/dart/gui/osg/examples/osgHuboPuppet.cpp index 708410e1b14be..340642f9a91bb 100644 --- a/dart/gui/osg/examples/osgHuboPuppet.cpp +++ b/dart/gui/osg/examples/osgHuboPuppet.cpp @@ -228,12 +228,12 @@ class HuboArmIK : public InverseKinematics::Analytical return mSolutions; } - const size_t SP = 0; - const size_t SR = 1; - const size_t SY = 2; - const size_t EP = 3; - const size_t WY = 4; - const size_t WP = 5; + const std::size_t SP = 0; + const std::size_t SR = 1; + const std::size_t SY = 2; + const std::size_t EP = 3; + const std::size_t WY = 4; + const std::size_t WP = 5; const SkeletonPtr& skel = base->getSkeleton(); @@ -259,7 +259,7 @@ class HuboArmIK : public InverseKinematics::Analytical double y = p.y(); double z = p.z(); - for(size_t i = 0; i < 8; ++i) + for(std::size_t i = 0; i < 8; ++i) { const int flipEP = alterantives(i,0); const int incWY = alterantives(i,1); @@ -334,7 +334,7 @@ class HuboArmIK : public InverseKinematics::Analytical testQ(SR) = euler[1]; testQ(SY) = euler[2]; - for(size_t j=0; j < 6; ++j) + for(std::size_t j=0; j < 6; ++j) { testQ[j] = dart::math::wrapToPi(testQ[j]); if(std::abs(testQ[j]) < zeroSize) @@ -350,7 +350,7 @@ class HuboArmIK : public InverseKinematics::Analytical return mSolutions; } - const std::vector& getDofs() const override + const std::vector& getDofs() const override { if(!configured) configure(); @@ -390,7 +390,7 @@ class HuboArmIK : public InverseKinematics::Analytical DegreeOfFreedom* dofs[6]; BodyNode* bn = base; - for(size_t i=0; i < 6; ++i) + for(std::size_t i=0; i < 6; ++i) { Joint* joint = bn->getParentJoint(); if(joint->getNumDofs() != 1) @@ -436,7 +436,7 @@ class HuboArmIK : public InverseKinematics::Analytical -1, 0, 1, -1, 0, 0; - for(size_t i=0; i < 6; ++i) + for(std::size_t i=0; i < 6; ++i) { dofs[i]->setPosition(saved_q[i]); mDofs.push_back(dofs[i]->getIndexInSkeleton()); @@ -454,7 +454,7 @@ class HuboArmIK : public InverseKinematics::Analytical mutable Eigen::Matrix alterantives; - mutable std::vector mDofs; + mutable std::vector mDofs; std::string mBaseLinkName; mutable WeakBodyNodePtr mBaseLink; @@ -529,7 +529,7 @@ class HuboLegIK : public InverseKinematics::Analytical ny = Binv(1,0); sy = Binv(1,1); ay = Binv(1,2); py = Binv(1,3); az = Binv(2,2); pz = Binv(2,3); - for(size_t i=0; i < 8; ++i) + for(std::size_t i=0; i < 8; ++i) { bool isValid = true; @@ -588,7 +588,7 @@ class HuboLegIK : public InverseKinematics::Analytical return mSolutions; } - const std::vector& getDofs() const override + const std::vector& getDofs() const override { if(!configured) configure(); @@ -628,7 +628,7 @@ class HuboLegIK : public InverseKinematics::Analytical DegreeOfFreedom* dofs[6]; BodyNode* bn = base; - for(size_t i=0; i < 6; ++i) + for(std::size_t i=0; i < 6; ++i) { Joint* joint = bn->getParentJoint(); if(joint->getNumDofs() != 1) @@ -680,7 +680,7 @@ class HuboLegIK : public InverseKinematics::Analytical -1, -1, 1, -1, -1, -1; - for(size_t i=0; i < 6; ++i) + for(std::size_t i=0; i < 6; ++i) { dofs[i]->setPosition(saved_q[i]); mDofs.push_back(dofs[i]->getIndexInSkeleton()); @@ -695,7 +695,7 @@ class HuboLegIK : public InverseKinematics::Analytical mutable Eigen::Isometry3d footTfInv; mutable Eigen::Matrix alternatives; - mutable std::vector mDofs; + mutable std::vector mDofs; mutable bool configured; @@ -824,7 +824,7 @@ class TeleoperationWorld : public dart::gui::osg::WorldNode protected: SkeletonPtr mHubo; - size_t iter; + std::size_t iter; EndEffectorPtr l_foot; EndEffectorPtr r_foot; @@ -860,7 +860,7 @@ class InputHandler : public ::osgGA::GUIEventHandler { mRestConfig = mHubo->getPositions(); - for(size_t i=0; i < mHubo->getNumEndEffectors(); ++i) + for(std::size_t i=0; i < mHubo->getNumEndEffectors(); ++i) { const InverseKinematicsPtr ik = mHubo->getEndEffector(i)->getIK(); if(ik) @@ -905,7 +905,7 @@ class InputHandler : public ::osgGA::GUIEventHandler if( ea.getKey() == 'p' ) { - for(size_t i=0; i < mHubo->getNumDofs(); ++i) + for(std::size_t i=0; i < mHubo->getNumDofs(); ++i) std::cout << mHubo->getDof(i)->getName() << ": " << mHubo->getDof(i)->getPosition() << std::endl; return true; @@ -914,7 +914,7 @@ class InputHandler : public ::osgGA::GUIEventHandler if( ea.getKey() == 't' ) { // Reset all the positions except for x, y, and yaw - for(size_t i=0; i < mHubo->getNumDofs(); ++i) + for(std::size_t i=0; i < mHubo->getNumDofs(); ++i) { if( i < 2 || 4 < i ) mHubo->getDof(i)->setPosition(mRestConfig[i]); @@ -924,7 +924,7 @@ class InputHandler : public ::osgGA::GUIEventHandler if( '1' <= ea.getKey() && ea.getKey() <= '9' ) { - size_t index = ea.getKey() - '1'; + std::size_t index = ea.getKey() - '1'; if(index < mConstraintActive.size()) { EndEffector* ee = mHubo->getEndEffector(mEndEffectorIndex[index]); @@ -1058,7 +1058,7 @@ class InputHandler : public ::osgGA::GUIEventHandler std::vector mConstraintActive; - std::vector mEndEffectorIndex; + std::vector mEndEffectorIndex; std::vector< std::pair > mDefaultBounds; @@ -1101,7 +1101,7 @@ SkeletonPtr createHubo() SkeletonPtr hubo = loader.parseSkeleton(DART_DATA_PATH"/urdf/drchubo/drchubo.urdf"); - for(size_t i = 0; i < hubo->getNumBodyNodes(); ++i) + for(std::size_t i = 0; i < hubo->getNumBodyNodes(); ++i) { BodyNode* bn = hubo->getBodyNode(i); if(bn->getName().substr(0, 7) == "Body_LF" @@ -1324,10 +1324,10 @@ void setupEndEffectors(const SkeletonPtr& hubo) void enableDragAndDrops(dart::gui::osg::Viewer& viewer, const SkeletonPtr& hubo) { // Turn on drag-and-drop for the whole Skeleton - for(size_t i=0; i < hubo->getNumBodyNodes(); ++i) + for(std::size_t i=0; i < hubo->getNumBodyNodes(); ++i) viewer.enableDragAndDrop(hubo->getBodyNode(i), false, false); - for(size_t i=0; i < hubo->getNumEndEffectors(); ++i) + for(std::size_t i=0; i < hubo->getNumEndEffectors(); ++i) { EndEffector* ee = hubo->getEndEffector(i); if(!ee->getIK()) @@ -1346,7 +1346,7 @@ void setupWholeBodySolver(const SkeletonPtr& hubo) std::dynamic_pointer_cast( hubo->getIK(true)->getSolver()); - size_t nDofs = hubo->getNumDofs(); + std::size_t nDofs = hubo->getNumDofs(); double default_weight = 0.01; Eigen::VectorXd weights = default_weight * Eigen::VectorXd::Ones(nDofs); diff --git a/dart/gui/osg/examples/osgOperationalSpaceControl.cpp b/dart/gui/osg/examples/osgOperationalSpaceControl.cpp index 348f864b29cd6..d8a6b242cbf9b 100644 --- a/dart/gui/osg/examples/osgOperationalSpaceControl.cpp +++ b/dart/gui/osg/examples/osgOperationalSpaceControl.cpp @@ -55,17 +55,17 @@ class OperationalSpaceControlWorld : public dart::gui::osg::WorldNode mEndEffector = mRobot->getBodyNode(mRobot->getNumBodyNodes()-1); // Setup gain matrices - size_t dofs = mEndEffector->getNumDependentGenCoords(); + std::size_t dofs = mEndEffector->getNumDependentGenCoords(); mKp.setZero(); - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) mKp(i,i) = 50.0; mKd.setZero(dofs,dofs); - for(size_t i=0; igetNumJoints(); ++i) + for(std::size_t i=0; igetNumJoints(); ++i) { mRobot->getJoint(i)->setPositionLimitEnforced(false); mRobot->getJoint(i)->setDampingCoefficient(0, 0.5); @@ -153,7 +153,7 @@ class ConstraintEventHandler : public ::osgGA::GUIEventHandler void clearConstraints() { - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) mConstrained[i] = false; } @@ -216,8 +216,8 @@ class ConstraintEventHandler : public ::osgGA::GUIEventHandler if(!handled) return handled; - size_t constraintDofs = 0; - for(size_t i=0; i<3; ++i) + std::size_t constraintDofs = 0; + for(std::size_t i=0; i<3; ++i) if(mConstrained[i]) ++constraintDofs; @@ -228,7 +228,7 @@ class ConstraintEventHandler : public ::osgGA::GUIEventHandler else if(constraintDofs == 1) { Eigen::Vector3d v(Eigen::Vector3d::Zero()); - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) if(mConstrained[i]) v[i] = 1.0; @@ -237,7 +237,7 @@ class ConstraintEventHandler : public ::osgGA::GUIEventHandler else if(constraintDofs == 2) { Eigen::Vector3d v(Eigen::Vector3d::Zero()); - for(size_t i=0; i<3; ++i) + for(std::size_t i=0; i<3; ++i) if(!mConstrained[i]) v[i] = 1.0; @@ -263,7 +263,7 @@ int main() world->addSkeleton(robot); // Set the colors of the models to obey the shape's color specification - for(size_t i=0; igetNumBodyNodes(); ++i) + for(std::size_t i=0; igetNumBodyNodes(); ++i) { BodyNode* bn = robot->getBodyNode(i); auto shapeNodes = bn->getShapeNodesWith(); diff --git a/dart/gui/osg/examples/osgSoftBodies.cpp b/dart/gui/osg/examples/osgSoftBodies.cpp index 95db54c82e7c8..3e61e6fe113e3 100644 --- a/dart/gui/osg/examples/osgSoftBodies.cpp +++ b/dart/gui/osg/examples/osgSoftBodies.cpp @@ -59,14 +59,14 @@ class RecordingWorld : public dart::gui::osg::WorldNode TimeSlice slice; slice.reserve(mWorld->getNumSkeletons()); - for(size_t i=0; i < mWorld->getNumSkeletons(); ++i) + for(std::size_t i=0; i < mWorld->getNumSkeletons(); ++i) { const SkeletonPtr& skeleton = mWorld->getSkeleton(i); State state; state.mConfig = skeleton->getConfiguration(); state.mAspectStates.reserve(skeleton->getNumBodyNodes()); - for(size_t j=0; j < skeleton->getNumBodyNodes(); ++j) + for(std::size_t j=0; j < skeleton->getNumBodyNodes(); ++j) { BodyNode* bn = skeleton->getBodyNode(j); state.mAspectStates.push_back(bn->getCompositeState()); @@ -87,7 +87,7 @@ class RecordingWorld : public dart::gui::osg::WorldNode ++mCurrentIndex; } - void moveTo(size_t index) + void moveTo(std::size_t index) { mViewer->simulate(false); @@ -100,14 +100,14 @@ class RecordingWorld : public dart::gui::osg::WorldNode std::cout << "Moving to time step #" << index << std::endl; const TimeSlice& slice = mHistory[index]; - for(size_t i=0; i < slice.size(); ++i) + for(std::size_t i=0; i < slice.size(); ++i) { const State& state = slice[i]; const SkeletonPtr& skeleton = mWorld->getSkeleton(i); skeleton->setConfiguration(state.mConfig); - for(size_t j=0; j < skeleton->getNumBodyNodes(); ++j) + for(std::size_t j=0; j < skeleton->getNumBodyNodes(); ++j) { BodyNode* bn = skeleton->getBodyNode(j); bn->setCompositeState(state.mAspectStates[j]); @@ -149,7 +149,7 @@ class RecordingWorld : public dart::gui::osg::WorldNode History mHistory; - size_t mCurrentIndex; + std::size_t mCurrentIndex; }; class RecordingEventHandler : public osgGA::GUIEventHandler diff --git a/dart/gui/osg/render/LineSegmentShapeNode.cpp b/dart/gui/osg/render/LineSegmentShapeNode.cpp index b070e63771186..bdd2218c4d480 100644 --- a/dart/gui/osg/render/LineSegmentShapeNode.cpp +++ b/dart/gui/osg/render/LineSegmentShapeNode.cpp @@ -219,7 +219,7 @@ void LineSegmentShapeDrawable::refresh(bool firstTime) new ::osg::DrawElementsUInt(GL_LINES); elements->reserve(2*connections.size()); - for(size_t i=0; i < connections.size(); ++i) + for(std::size_t i=0; i < connections.size(); ++i) { const Eigen::Vector2i& c = connections[i]; elements->push_back(c[0]); @@ -236,7 +236,7 @@ void LineSegmentShapeDrawable::refresh(bool firstTime) if(mVertices->size() != vertices.size()) mVertices->resize(vertices.size()); - for(size_t i=0; imNumMaterials); - for(size_t i=0; imNumMaterials; ++i) + for(std::size_t i=0; imNumMaterials; ++i) { aiMaterial* aiMat = scene->mMaterials[i]; ::osg::ref_ptr<::osg::Material> material = new ::osg::Material; @@ -272,7 +272,7 @@ void MeshShapeNode::extractData(bool firstTime) } //============================================================================== -::osg::Material* MeshShapeNode::getMaterial(size_t index) const +::osg::Material* MeshShapeNode::getMaterial(std::size_t index) const { if(index < mMaterials.size()) return mMaterials[index]; @@ -331,7 +331,7 @@ void osgAiNode::extractData(bool firstTime) setMatrix(::osg::Matrixf((float*)(&M))); } - for(size_t i=0; imNumChildren; ++i) + for(std::size_t i=0; imNumChildren; ++i) { aiNode* child = mAiNode->mChildren[i]; std::map::iterator it = mChildNodes.find(child); @@ -416,7 +416,7 @@ void MeshShapeGeode::extractData(bool) clearChildUtilizationFlags(); const aiScene* scene = mMeshShape->getMesh(); - for(size_t i=0; imNumMeshes; ++i) + for(std::size_t i=0; imNumMeshes; ++i) { aiMesh* mesh = scene->mMeshes[mAiNode->mMeshes[i]]; @@ -512,7 +512,7 @@ void MeshShapeGeometry::extractData(bool firstTime) elements[2] = new ::osg::DrawElementsUInt(GL_TRIANGLES); elements[3] = new ::osg::DrawElementsUInt(GL_QUADS); - for(size_t i=0; imNumFaces; ++i) + for(std::size_t i=0; imNumFaces; ++i) { const aiFace& face = mAiMesh->mFaces[i]; @@ -520,19 +520,19 @@ void MeshShapeGeometry::extractData(bool firstTime) { ::osg::ref_ptr<::osg::DrawElementsUInt> polygon = new ::osg::DrawElementsUInt(GL_POLYGON); - for(size_t j=0; jpush_back(face.mIndices[j]); addPrimitiveSet(polygon); } else if(face.mNumIndices > 0) { ::osg::DrawElementsUInt* elem = elements[face.mNumIndices-1]; - for(size_t j=0; jpush_back(face.mIndices[j]); } } - for(size_t i=0; i<4; ++i) + for(std::size_t i=0; i<4; ++i) if(elements[i]->size() > 0) addPrimitiveSet(elements[i]); } @@ -547,7 +547,7 @@ void MeshShapeGeometry::extractData(bool firstTime) if(mNormals->size() != mAiMesh->mNumVertices) mNormals->resize(mAiMesh->mNumVertices); - for(size_t i=0; imNumVertices; ++i) + for(std::size_t i=0; imNumVertices; ++i) { const aiVector3D& v = mAiMesh->mVertices[i]; (*mVertices)[i] = ::osg::Vec3(v.x, v.y, v.z); @@ -591,7 +591,7 @@ void MeshShapeGeometry::extractData(bool firstTime) if(mColors->size() != mVertices->size()) mColors->resize(mVertices->size()); - for(size_t i=0; imNumVertices; ++i) + for(std::size_t i=0; imNumVertices; ++i) { const aiColor4D& c = colors[i]; (*mColors)[i] = ::osg::Vec4(c.r, c.g, c.b, c.a); @@ -652,7 +652,7 @@ void MeshShapeGeometry::extractData(bool firstTime) { ::osg::ref_ptr<::osg::FloatArray> texture = new ::osg::FloatArray(mAiMesh->mNumVertices); - for(size_t i=0; imNumVertices; ++i) + for(std::size_t i=0; imNumVertices; ++i) (*texture)[i] = aiTexCoords[i].x; setTexCoordArray(unit, texture, ::osg::Array::BIND_PER_VERTEX); break; @@ -661,7 +661,7 @@ void MeshShapeGeometry::extractData(bool firstTime) { ::osg::ref_ptr<::osg::Vec2Array> texture = new ::osg::Vec2Array(mAiMesh->mNumVertices); - for(size_t i=0; imNumVertices; ++i) + for(std::size_t i=0; imNumVertices; ++i) { const aiVector3D& t = aiTexCoords[i]; (*texture)[i] = ::osg::Vec2(t.x, t.y); @@ -673,7 +673,7 @@ void MeshShapeGeometry::extractData(bool firstTime) { ::osg::ref_ptr<::osg::Vec3Array> texture = new ::osg::Vec3Array(mAiMesh->mNumVertices); - for(size_t i=0; imNumVertices; ++i) + for(std::size_t i=0; imNumVertices; ++i) { const aiVector3D& t = aiTexCoords[i]; (*texture)[i] = ::osg::Vec3(t.x, t.y, t.z); diff --git a/dart/gui/osg/render/MeshShapeNode.h b/dart/gui/osg/render/MeshShapeNode.h index ee8002e645da4..436de463758c7 100644 --- a/dart/gui/osg/render/MeshShapeNode.h +++ b/dart/gui/osg/render/MeshShapeNode.h @@ -71,7 +71,7 @@ class MeshShapeNode : public ShapeNode, public ::osg::MatrixTransform void refresh(); void extractData(bool firstTime); - ::osg::Material* getMaterial(size_t index) const; + ::osg::Material* getMaterial(std::size_t index) const; protected: diff --git a/dart/gui/osg/render/SoftMeshShapeNode.cpp b/dart/gui/osg/render/SoftMeshShapeNode.cpp index 69540eb417d54..d3d31434e1a79 100644 --- a/dart/gui/osg/render/SoftMeshShapeNode.cpp +++ b/dart/gui/osg/render/SoftMeshShapeNode.cpp @@ -196,7 +196,7 @@ SoftMeshShapeDrawable::SoftMeshShapeDrawable( static Eigen::Vector3d normalFromVertex(const dart::dynamics::SoftBodyNode* bn, const Eigen::Vector3i& face, - size_t v) + std::size_t v) { const Eigen::Vector3d& v0 = bn->getPointMass(face[v])->getLocalPosition(); const Eigen::Vector3d& v1 = bn->getPointMass(face[(v+1)%3])->getLocalPosition(); @@ -215,17 +215,17 @@ static Eigen::Vector3d normalFromVertex(const dart::dynamics::SoftBodyNode* bn, static void computeNormals(std::vector& normals, const dart::dynamics::SoftBodyNode* bn) { - for(size_t i=0; igetNumFaces(); ++i) + for(std::size_t i=0; igetNumFaces(); ++i) { const Eigen::Vector3i& face = bn->getFace(i); - for(size_t j=0; j<3; ++j) + for(std::size_t j=0; j<3; ++j) normals[face[j]] += normalFromVertex(bn, face, j); } - for(size_t i=0; ireserve(3*bn->getNumFaces()); - for(size_t i=0; i < bn->getNumFaces(); ++i) + for(std::size_t i=0; i < bn->getNumFaces(); ++i) { const Eigen::Vector3i& F = bn->getFace(i); - for(size_t j=0; j<3; ++j) + for(std::size_t j=0; j<3; ++j) elements->push_back(F[j]); } @@ -270,7 +270,7 @@ void SoftMeshShapeDrawable::refresh(bool firstTime) mEigNormals.resize(bn->getNumPointMasses()); computeNormals(mEigNormals, bn); - for(size_t i=0; igetNumPointMasses(); ++i) + for(std::size_t i=0; igetNumPointMasses(); ++i) { (*mVertices)[i] = eigToOsgVec3(bn->getPointMass(i)->getLocalPosition()); (*mNormals)[i] = eigToOsgVec3(mEigNormals[i]); diff --git a/dart/lcpsolver/Lemke.cpp b/dart/lcpsolver/Lemke.cpp index 96700c39f9bb6..2410e183a839a 100644 --- a/dart/lcpsolver/Lemke.cpp +++ b/dart/lcpsolver/Lemke.cpp @@ -121,7 +121,7 @@ int Lemke(const Eigen::MatrixXd& _M, const Eigen::VectorXd& _q, Eigen::MatrixXd B = -Eigen::MatrixXd::Identity(n, n); - for (size_t i = 0; i < bas.size(); ++i) { + for (std::size_t i = 0; i < bas.size(); ++i) { B.col(bas[i]) = _M.col(bas[i]); } @@ -167,16 +167,16 @@ int Lemke(const Eigen::MatrixXd& _M, const Eigen::VectorXd& _q, break; } - size_t jSize = j.size(); + std::size_t jSize = j.size(); Eigen::VectorXd minRatio(jSize); - for (size_t i = 0; i < jSize; ++i) { + for (std::size_t i = 0; i < jSize; ++i) { minRatio[i] = (x[j[i]] + zer_tol) / d[j[i]]; } double theta = minRatio.minCoeff(); std::vector tmpJ; std::vector tmpMinRatio; - for (size_t i = 0; i < jSize; ++i) { + for (std::size_t i = 0; i < jSize; ++i) { if (x[j[i]] / d[j[i]] <= theta) { tmpJ.push_back(j[i]); tmpMinRatio.push_back(minRatio[i]); @@ -201,7 +201,7 @@ int Lemke(const Eigen::MatrixXd& _M, const Eigen::VectorXd& _q, } lvindex = -1; - for (size_t i = 0; i < jSize; ++i) { + for (std::size_t i = 0; i < jSize; ++i) { if (bas[j[i]] == t) lvindex = i; } @@ -211,7 +211,7 @@ int Lemke(const Eigen::MatrixXd& _M, const Eigen::VectorXd& _q, theta = tmpMinRatio[0]; lvindex = 0; - for (size_t i = 0; i < jSize; ++i) { + for (std::size_t i = 0; i < jSize; ++i) { if (tmpMinRatio[i]-theta > piv_tol) { theta = tmpMinRatio[i]; lvindex = i; @@ -245,7 +245,7 @@ int Lemke(const Eigen::MatrixXd& _M, const Eigen::VectorXd& _q, err = 1; if (err == 0) { - for (size_t i = 0; i < bas.size(); ++i) { + for (std::size_t i = 0; i < bas.size(); ++i) { if (bas[i] < _z->size()) { (*_z)[bas[i]] = x[i]; } diff --git a/dart/math/Geometry.cpp b/dart/math/Geometry.cpp index b41d29f9294b5..f17ce90fbf8a1 100644 --- a/dart/math/Geometry.cpp +++ b/dart/math/Geometry.cpp @@ -1402,8 +1402,8 @@ Eigen::Matrix3d parallelAxisTheorem(const Eigen::Matrix3d& _original, { const Eigen::Vector3d& p = _comShift; Eigen::Matrix3d result(_original); - for(size_t i=0; i<3; ++i) - for(size_t j=0; j<3; ++j) + for(std::size_t i=0; i<3; ++i) + for(std::size_t j=0; j<3; ++j) result(i,j) += _mass * ( delta(i,j)*p.dot(p) - p(i)*p(j) ); return result; @@ -1505,13 +1505,13 @@ SupportPolygon computeSupportPolgyon(const SupportGeometry& _geometry, const Eigen::Vector3d& _axis1, const Eigen::Vector3d& _axis2) { - std::vector indices; + std::vector indices; indices.reserve(_geometry.size()); return computeSupportPolgyon(indices, _geometry, _axis1, _axis2); } //============================================================================== -SupportPolygon computeSupportPolgyon(std::vector& _originalIndices, +SupportPolygon computeSupportPolgyon(std::vector& _originalIndices, const SupportGeometry& _geometry, const Eigen::Vector3d& _axis1, const Eigen::Vector3d& _axis2) @@ -1529,7 +1529,7 @@ SupportPolygon computeSupportPolgyon(std::vector& _originalIndices, // convex hulls struct HullAngle { - HullAngle(double angle, double distance, size_t index) + HullAngle(double angle, double distance, std::size_t index) : mAngle(angle), mDistance(distance), mIndex(index) @@ -1539,7 +1539,7 @@ struct HullAngle double mAngle; double mDistance; - size_t mIndex; + std::size_t mIndex; }; //============================================================================== @@ -1552,7 +1552,7 @@ static bool HullAngleComparison(const HullAngle& a, const HullAngle& b) //============================================================================== SupportPolygon computeConvexHull(const SupportPolygon& _points) { - std::vector indices; + std::vector indices; indices.reserve(_points.size()); return computeConvexHull(indices, _points); } @@ -1580,7 +1580,7 @@ Eigen::Vector2d computeCentroidOfHull(const SupportPolygon& _convexHull) double area_i; Eigen::Vector2d midp12, midp01; - for(size_t i=2; i < _convexHull.size(); ++i) + for(std::size_t i=2; i < _convexHull.size(); ++i) { const Eigen::Vector2d& p0 = _convexHull[0]; const Eigen::Vector2d& p1 = _convexHull[i-1]; @@ -1635,7 +1635,7 @@ static bool isLeftTurn(const Eigen::Vector2d& p1, } //============================================================================== -SupportPolygon computeConvexHull(std::vector& _originalIndices, +SupportPolygon computeConvexHull(std::vector& _originalIndices, const SupportPolygon& _points) { _originalIndices.clear(); @@ -1643,16 +1643,16 @@ SupportPolygon computeConvexHull(std::vector& _originalIndices, if(_points.size() <= 3) { // Three or fewer points is already a convex hull - for(size_t i=0; i < _points.size(); ++i) + for(std::size_t i=0; i < _points.size(); ++i) _originalIndices.push_back(i); return _points; } // We'll use "Graham scan" to compute the convex hull in the general case - size_t lowestIndex = static_cast(-1); + std::size_t lowestIndex = static_cast(-1); double lowestY = std::numeric_limits::infinity(); - for(size_t i=0; i < _points.size(); ++i) + for(std::size_t i=0; i < _points.size(); ++i) { if(_points[i][1] < lowestY) { @@ -1670,7 +1670,7 @@ SupportPolygon computeConvexHull(std::vector& _originalIndices, std::vector angles; const Eigen::Vector2d& bottom = _points[lowestIndex]; - for(size_t i=0; i < _points.size(); ++i) + for(std::size_t i=0; i < _points.size(); ++i) { const Eigen::Vector2d& p = _points[i]; if( p != bottom ) @@ -1684,13 +1684,13 @@ SupportPolygon computeConvexHull(std::vector& _originalIndices, if(angles.size() > 1) { - for(size_t i=0; i& _originalIndices, // three or fewer unique points _originalIndices.reserve(angles.size()+1); _originalIndices.push_back(lowestIndex); - for(size_t i=0; i < angles.size(); ++i) + for(std::size_t i=0; i < angles.size(); ++i) _originalIndices.push_back(angles[i].mIndex); SupportPolygon polygon; polygon.reserve(_originalIndices.size()); - for(size_t index : _originalIndices) + for(std::size_t index : _originalIndices) polygon.push_back(_points[index]); return polygon; } - std::vector& edge = _originalIndices; - size_t lastIndex = lowestIndex; - size_t secondToLastIndex = angles[0].mIndex; + std::vector& edge = _originalIndices; + std::size_t lastIndex = lowestIndex; + std::size_t secondToLastIndex = angles[0].mIndex; edge.reserve(angles.size()+1); edge.push_back(lowestIndex); - for(size_t i=1; i < angles.size(); ++i) + for(std::size_t i=1; i < angles.size(); ++i) { - size_t currentIndex = angles[i].mIndex; + std::size_t currentIndex = angles[i].mIndex; const Eigen::Vector2d& p1 = _points[lastIndex]; const Eigen::Vector2d& p2 = _points[secondToLastIndex]; const Eigen::Vector2d& p3 = _points[currentIndex]; @@ -1753,7 +1753,7 @@ SupportPolygon computeConvexHull(std::vector& _originalIndices, SupportPolygon polygon; polygon.reserve(edge.size()); - for(size_t index : edge) + for(std::size_t index : edge) polygon.push_back(_points[index]); // Note that we do not need to fill in _originalIndices, because "edge" is a @@ -1792,7 +1792,7 @@ IntersectionResult computeIntersection(Eigen::Vector2d& _intersectionPoint, else point[1] = dy_b/dx_b*(point[0]-b1[0]) + b1[1]; - for(size_t i=0; i < 2; ++i) + for(std::size_t i=0; i < 2; ++i) { if( (point[i] < std::min(a1[i], a2[i])) || (std::max(a1[i], a2[i]) < point[i]) ) @@ -1852,7 +1852,7 @@ bool isInsideSupportPolygon(const Eigen::Vector2d& _p, return false; } - for(size_t i=0; i < _support.size(); ++i) + for(std::size_t i=0; i < _support.size(); ++i) { const Eigen::Vector2d& p1 = (i==0)? _support.back() : _support[i-1]; const Eigen::Vector2d& p2 = _support[i]; @@ -1926,19 +1926,19 @@ Eigen::Vector2d computeClosestPointOnLineSegment(const Eigen::Vector2d& _p, Eigen::Vector2d computeClosestPointOnSupportPolygon(const Eigen::Vector2d& _p, const SupportPolygon& _support) { - size_t _index1; - size_t _index2; + std::size_t _index1; + std::size_t _index2; return computeClosestPointOnSupportPolygon(_index1, _index2, _p, _support); } //============================================================================== -Eigen::Vector2d computeClosestPointOnSupportPolygon(size_t& _index1, size_t& _index2, +Eigen::Vector2d computeClosestPointOnSupportPolygon(std::size_t& _index1, std::size_t& _index2, const Eigen::Vector2d& _p, const SupportPolygon& _support) { if(_support.size() == 0) { - _index1 = static_cast(-1); + _index1 = static_cast(-1); _index2 = _index1; return _p; } @@ -1959,7 +1959,7 @@ Eigen::Vector2d computeClosestPointOnSupportPolygon(size_t& _index1, size_t& _in double best = std::numeric_limits::infinity(), check; Eigen::Vector2d test, result; - for(size_t i=0; i < _support.size(); ++i) + for(std::size_t i=0; i < _support.size(); ++i) { const Eigen::Vector2d& p1 = (i==0)? _support.back() : _support[i-1]; const Eigen::Vector2d& p2 = _support[i]; diff --git a/dart/math/Geometry.h b/dart/math/Geometry.h index 0bc363bfded2b..c99e528d9ea8d 100644 --- a/dart/math/Geometry.h +++ b/dart/math/Geometry.h @@ -496,11 +496,11 @@ SupportPolygon computeSupportPolgyon( const Eigen::Vector3d& _axis1 = Eigen::Vector3d::UnitX(), const Eigen::Vector3d& _axis2 = Eigen::Vector3d::UnitY()); -/// Same as computeSupportPolgyon, except you can pass in a std::vector +/// Same as computeSupportPolgyon, except you can pass in a std::vector /// which will have the same size as the returned SupportPolygon, and each entry /// will contain the original index of each point in the SupportPolygon SupportPolygon computeSupportPolgyon( - std::vector& _originalIndices, + std::vector& _originalIndices, const SupportGeometry& _geometry, const Eigen::Vector3d& _axis1 = Eigen::Vector3d::UnitX(), const Eigen::Vector3d& _axis2 = Eigen::Vector3d::UnitY()); @@ -510,7 +510,7 @@ SupportPolygon computeConvexHull(const SupportPolygon& _points); /// Computes the convex hull of a set of 2D points and fills in _originalIndices /// with the original index of each entry in the returned SupportPolygon -SupportPolygon computeConvexHull(std::vector& _originalIndices, +SupportPolygon computeConvexHull(std::vector& _originalIndices, const SupportPolygon& _points); /// Compute the centroid of a polygon, assuming the polygon is a convex hull @@ -558,8 +558,8 @@ Eigen::Vector2d computeClosestPointOnSupportPolygon( /// Same as closestPointOnSupportPolygon, but also fills in _index1 and _index2 /// with the indices of the line segment Eigen::Vector2d computeClosestPointOnSupportPolygon( - size_t& _index1, - size_t& _index2, + std::size_t& _index1, + std::size_t& _index2, const Eigen::Vector2d& _p, const SupportPolygon& _support); diff --git a/dart/math/Helpers.h b/dart/math/Helpers.h index 39d8f61c39a95..f2ab86b361eab 100644 --- a/dart/math/Helpers.h +++ b/dart/math/Helpers.h @@ -214,18 +214,18 @@ inline bool isInf(const Eigen::MatrixXd& _m) { /// \brief Returns whether _m is symmetric or not inline bool isSymmetric(const Eigen::MatrixXd& _m, double _tol = 1e-6) { - size_t rows = _m.rows(); - size_t cols = _m.cols(); + std::size_t rows = _m.rows(); + std::size_t cols = _m.cols(); if (rows != cols) return false; - for (size_t i = 0; i < rows; ++i) { - for (size_t j = i + 1; j < cols; ++j) { + for (std::size_t i = 0; i < rows; ++i) { + for (std::size_t j = i + 1; j < cols; ++j) { if (std::abs(_m(i, j) - _m(j, i)) > _tol) { std::cout << "A: " << std::endl; - for (size_t k = 0; k < rows; ++k) { - for (size_t l = 0; l < cols; ++l) + for (std::size_t k = 0; k < rows; ++k) { + for (std::size_t l = 0; l < cols; ++l) std::cout << std::setprecision(4) << _m(k, l) << " "; std::cout << std::endl; } @@ -244,7 +244,7 @@ inline unsigned seedRand() { time_t now = time(0); unsigned char* p = reinterpret_cast(&now); unsigned seed = 0; - size_t i; + std::size_t i; for (i = 0; i < sizeof(now); i++) seed = seed * (UCHAR_MAX + 2U) + p[i]; @@ -262,7 +262,7 @@ template Eigen::Matrix randomVector(double _min, double _max) { Eigen::Matrix v; - for(size_t i=0; i randomVector(double _limit) } //============================================================================== -inline Eigen::VectorXd randomVectorXd(size_t size, double min, double max) +inline Eigen::VectorXd randomVectorXd(std::size_t size, double min, double max) { Eigen::VectorXd v = Eigen::VectorXd::Zero(size); - for (size_t i = 0; i < size; ++i) + for (std::size_t i = 0; i < size; ++i) v[i] = random(min, max); return v; } //============================================================================== -inline Eigen::VectorXd randomVectorXd(size_t size, double limit) +inline Eigen::VectorXd randomVectorXd(std::size_t size, double limit) { return randomVectorXd(size, -std::abs(limit), std::abs(limit)); } diff --git a/dart/math/MathTypes.h b/dart/math/MathTypes.h index ead135e4bcb2b..40ff2b4a4e357 100644 --- a/dart/math/MathTypes.h +++ b/dart/math/MathTypes.h @@ -80,7 +80,7 @@ template class aligned_allocator_cpp11 : public std::allocator { public: - typedef size_t size_type; + typedef std::size_t std::size_type; typedef std::ptrdiff_t difference_type; typedef T* pointer; typedef const T* const_pointer; @@ -106,13 +106,13 @@ class aligned_allocator_cpp11 : public std::allocator ~aligned_allocator_cpp11() {} - pointer allocate(size_type num, const void* /*hint*/ = 0) + pointer allocate(std::size_type num, const void* /*hint*/ = 0) { internal::check_size_for_overflow(num); return static_cast( internal::aligned_malloc(num * sizeof(T)) ); } - void deallocate(pointer p, size_type /*num*/) + void deallocate(pointer p, std::size_type /*num*/) { internal::aligned_free(p); } diff --git a/dart/optimizer/GradientDescentSolver.cpp b/dart/optimizer/GradientDescentSolver.cpp index a0bd360f84446..01fe731aba5a0 100644 --- a/dart/optimizer/GradientDescentSolver.cpp +++ b/dart/optimizer/GradientDescentSolver.cpp @@ -50,8 +50,8 @@ const std::string GradientDescentSolver::Type = "GradientDescentSolver"; //============================================================================== GradientDescentSolver::UniqueProperties::UniqueProperties( double _stepMultiplier, - size_t _maxAttempts, - size_t _perturbationStep, + std::size_t _maxAttempts, + std::size_t _perturbationStep, double _maxPerturbationFactor, double _maxRandomizationStep, double _defaultConstraintWeight, @@ -122,7 +122,7 @@ bool GradientDescentSolver::solve() double tol = std::abs(mProperties.mTolerance); double gamma = mGradientP.mStepSize; - size_t dim = problem->getDimension(); + std::size_t dim = problem->getDimension(); if(dim == 0) { @@ -142,10 +142,10 @@ bool GradientDescentSolver::solve() mIneqConstraintCostCache.resize(problem->getNumIneqConstraints()); mLastNumIterations = 0; - size_t attemptCount = 0; + std::size_t attemptCount = 0; do { - size_t stepCount = 0; + std::size_t stepCount = 0; do { ++mLastNumIterations; @@ -166,7 +166,7 @@ bool GradientDescentSolver::solve() // Check if the equality constraints are satsified satisfied = true; - for(size_t i=0; igetNumEqConstraints(); ++i) + for(std::size_t i=0; igetNumEqConstraints(); ++i) { mEqConstraintCostCache[i] = problem->getEqConstraint(i)->eval(x); if(std::abs(mEqConstraintCostCache[i]) > tol) @@ -174,7 +174,7 @@ bool GradientDescentSolver::solve() } // Check if the inequality constraints are satisfied - for(size_t i=0; igetNumIneqConstraints(); ++i) + for(std::size_t i=0; igetNumIneqConstraints(); ++i) { mIneqConstraintCostCache[i] = problem->getIneqConstraint(i)->eval(x); if(mIneqConstraintCostCache[i] > std::abs(tol)) @@ -359,25 +359,25 @@ double GradientDescentSolver::getStepSize() const } //============================================================================== -void GradientDescentSolver::setMaxAttempts(size_t _maxAttempts) +void GradientDescentSolver::setMaxAttempts(std::size_t _maxAttempts) { mGradientP.mMaxAttempts = _maxAttempts; } //============================================================================== -size_t GradientDescentSolver::getMaxAttempts() const +std::size_t GradientDescentSolver::getMaxAttempts() const { return mGradientP.mMaxAttempts; } //============================================================================== -void GradientDescentSolver::setPerturbationStep(size_t _step) +void GradientDescentSolver::setPerturbationStep(std::size_t _step) { mGradientP.mPerturbationStep = _step; } //============================================================================== -size_t GradientDescentSolver::getPerturbationStep() const +std::size_t GradientDescentSolver::getPerturbationStep() const { return mGradientP.mPerturbationStep; } @@ -480,7 +480,7 @@ void GradientDescentSolver::clampToBoundary(Eigen::VectorXd& _x) } //============================================================================== -size_t GradientDescentSolver::getLastNumIterations() const +std::size_t GradientDescentSolver::getLastNumIterations() const { return mLastNumIterations; } diff --git a/dart/optimizer/GradientDescentSolver.h b/dart/optimizer/GradientDescentSolver.h index 89385c6f9fc51..0affad6c93be0 100644 --- a/dart/optimizer/GradientDescentSolver.h +++ b/dart/optimizer/GradientDescentSolver.h @@ -67,11 +67,11 @@ class GradientDescentSolver : public Solver /// /// Set this to 0 to keep trying until a solution is found (the program will /// need to be interrupted in order to stop if no solution is being found). - size_t mMaxAttempts; + std::size_t mMaxAttempts; /// The number of steps between random perturbations being applied to the /// configuration. Set this to 0 to never apply randomized perturbations. - size_t mPerturbationStep; + std::size_t mPerturbationStep; /// The random perturbation works as follows: A random point in the domain /// of the Problem is selected, and then a random step size between 0 and @@ -106,8 +106,8 @@ class GradientDescentSolver : public Solver UniqueProperties( double _stepMultiplier = 0.1, - size_t _maxAttempts = 1, - size_t _perturbationStep = 0, + std::size_t _maxAttempts = 1, + std::size_t _perturbationStep = 0, double _maxPerturbationFactor = 1.0, double _maxRandomizationStep = 1e10, double _defaultConstraintWeight = 1.0, @@ -168,17 +168,17 @@ class GradientDescentSolver : public Solver /// will use getNumMaxIterations() steps. When a new attempt is started, it /// will use the next seed in the list of seeds. If we've reached the end of /// the list of seeds, the attempt will start from a randomized configuration. - void setMaxAttempts(size_t _maxAttempts); + void setMaxAttempts(std::size_t _maxAttempts); /// Get the maximum number of solving attempts. - size_t getMaxAttempts() const; + std::size_t getMaxAttempts() const; /// Set the number of steps that will be taken before applying a randomized /// perturbation. - void setPerturbationStep(size_t _step); + void setPerturbationStep(std::size_t _step); /// Get UniqueProperties::mPerturbationStep - size_t getPerturbationStep() const; + std::size_t getPerturbationStep() const; /// Set UniqueProperties::mPerturbationFactor void setMaxPerturbationFactor(double _factor); @@ -211,7 +211,7 @@ class GradientDescentSolver : public Solver void clampToBoundary(Eigen::VectorXd& _x); /// Get the number of iterations used in the last attempt to solve the problem - size_t getLastNumIterations() const; + std::size_t getLastNumIterations() const; protected: @@ -219,7 +219,7 @@ class GradientDescentSolver : public Solver UniqueProperties mGradientP; /// The last number of iterations performed by this Solver - size_t mLastNumIterations; + std::size_t mLastNumIterations; /// Randomization device std::random_device mRD; diff --git a/dart/optimizer/Problem.cpp b/dart/optimizer/Problem.cpp index fd1b0216b508b..4538bfe50daad 100644 --- a/dart/optimizer/Problem.cpp +++ b/dart/optimizer/Problem.cpp @@ -49,7 +49,7 @@ namespace optimizer { //============================================================================== template -static T getVectorObjectIfAvailable(size_t _idx, const std::vector& _vec) +static T getVectorObjectIfAvailable(std::size_t _idx, const std::vector& _vec) { // TODO: Should we have an out-of-bounds assertion or throw here? if (_idx < _vec.size()) @@ -59,7 +59,7 @@ static T getVectorObjectIfAvailable(size_t _idx, const std::vector& _vec) } //============================================================================== -Problem::Problem(size_t _dim) +Problem::Problem(std::size_t _dim) : mDimension(0), mOptimumValue(0.0) { @@ -67,7 +67,7 @@ Problem::Problem(size_t _dim) } //============================================================================== -void Problem::setDimension(size_t _dim) +void Problem::setDimension(std::size_t _dim) { if(_dim != mDimension) { @@ -87,7 +87,7 @@ void Problem::setDimension(size_t _dim) } //============================================================================== -size_t Problem::getDimension() const +std::size_t Problem::getDimension() const { return mDimension; } @@ -95,7 +95,7 @@ size_t Problem::getDimension() const //============================================================================== void Problem::setInitialGuess(const Eigen::VectorXd& _initGuess) { - assert(static_cast(_initGuess.size()) == mDimension + assert(static_cast(_initGuess.size()) == mDimension && "Invalid size."); if(_initGuess.size() != static_cast(mDimension)) @@ -132,7 +132,7 @@ void Problem::addSeed(const Eigen::VectorXd& _seed) } //============================================================================== -Eigen::VectorXd& Problem::getSeed(size_t _index) +Eigen::VectorXd& Problem::getSeed(std::size_t _index) { if(_index < mSeeds.size()) return mSeeds[_index]; @@ -150,7 +150,7 @@ Eigen::VectorXd& Problem::getSeed(size_t _index) } //============================================================================== -const Eigen::VectorXd& Problem::getSeed(size_t _index) const +const Eigen::VectorXd& Problem::getSeed(std::size_t _index) const { return const_cast(this)->getSeed(_index); } @@ -176,7 +176,7 @@ void Problem::clearAllSeeds() //============================================================================== void Problem::setLowerBounds(const Eigen::VectorXd& _lb) { - assert(static_cast(_lb.size()) == mDimension && "Invalid size."); + assert(static_cast(_lb.size()) == mDimension && "Invalid size."); mLowerBounds = _lb; } @@ -189,7 +189,7 @@ const Eigen::VectorXd& Problem::getLowerBounds() const //============================================================================== void Problem::setUpperBounds(const Eigen::VectorXd& _ub) { - assert(static_cast(_ub.size()) == mDimension && "Invalid size."); + assert(static_cast(_ub.size()) == mDimension && "Invalid size."); mUpperBounds = _ub; } @@ -227,26 +227,26 @@ void Problem::addIneqConstraint(FunctionPtr _ineqConst) } //============================================================================== -size_t Problem::getNumEqConstraints() const +std::size_t Problem::getNumEqConstraints() const { return mEqConstraints.size(); } //============================================================================== -size_t Problem::getNumIneqConstraints() const +std::size_t Problem::getNumIneqConstraints() const { return mIneqConstraints.size(); } //============================================================================== -FunctionPtr Problem::getEqConstraint(size_t _idx) const +FunctionPtr Problem::getEqConstraint(std::size_t _idx) const { assert(_idx < mEqConstraints.size()); return getVectorObjectIfAvailable(_idx, mEqConstraints); } //============================================================================== -FunctionPtr Problem::getIneqConstraint(size_t _idx) const +FunctionPtr Problem::getIneqConstraint(std::size_t _idx) const { assert(_idx < mIneqConstraints.size()); return getVectorObjectIfAvailable(_idx, mIneqConstraints); @@ -301,7 +301,7 @@ double Problem::getOptimumValue() const //============================================================================== void Problem::setOptimalSolution(const Eigen::VectorXd& _optParam) { - assert(static_cast(_optParam.size()) == mDimension + assert(static_cast(_optParam.size()) == mDimension && "Invalid size."); mOptimalSolution = _optParam; } diff --git a/dart/optimizer/Problem.h b/dart/optimizer/Problem.h index 71bd57c9ca47d..21247b747acff 100644 --- a/dart/optimizer/Problem.h +++ b/dart/optimizer/Problem.h @@ -54,7 +54,7 @@ class Problem public: /// \brief Constructor - explicit Problem(size_t _dim = 0); + explicit Problem(std::size_t _dim = 0); /// \brief Destructor virtual ~Problem() = default; @@ -62,10 +62,10 @@ class Problem //--------------------------- Problem Setting -------------------------------- /// \brief Set dimension. Note: Changing the dimension will clear out the /// initial guess and any seeds that have been added. - void setDimension(size_t _dim); + void setDimension(std::size_t _dim); /// \brief Get dimension - size_t getDimension() const; + std::size_t getDimension() const; /// \brief Set initial guess for opimization parameters void setInitialGuess(const Eigen::VectorXd& _initGuess); @@ -80,10 +80,10 @@ class Problem /// \brief Get a mutable reference of the seed for the specified index. If an /// out-of-bounds index is provided a warning will print, and a reference to /// the initial guess will be returned instead. - Eigen::VectorXd& getSeed(size_t _index); + Eigen::VectorXd& getSeed(std::size_t _index); - /// \brief An immutable version of getSeed(size_t) - const Eigen::VectorXd& getSeed(size_t _index) const; + /// \brief An immutable version of getSeed(std::size_t) + const Eigen::VectorXd& getSeed(std::size_t _index) const; /// \brief Get a mutable reference to the full vector of seeds that this /// Problem currently contains @@ -121,16 +121,16 @@ class Problem void addIneqConstraint(FunctionPtr _ineqConst); /// \brief Get number of equality constraints - size_t getNumEqConstraints() const; + std::size_t getNumEqConstraints() const; /// \brief Get number of inequality constraints - size_t getNumIneqConstraints() const; + std::size_t getNumIneqConstraints() const; /// \brief Get equality constraint - FunctionPtr getEqConstraint(size_t _idx) const; + FunctionPtr getEqConstraint(std::size_t _idx) const; /// \brief Get inequality constraint - FunctionPtr getIneqConstraint(size_t _idx) const; + FunctionPtr getIneqConstraint(std::size_t _idx) const; /// \brief Remove equality constraint void removeEqConstraint(FunctionPtr _eqConst); @@ -160,7 +160,7 @@ class Problem protected: /// \brief Dimension of this problem - size_t mDimension; + std::size_t mDimension; /// \brief Initial guess for optimization parameters Eigen::VectorXd mInitialGuess; diff --git a/dart/optimizer/Solver.cpp b/dart/optimizer/Solver.cpp index 90e517d6e9a70..de87fdd170397 100644 --- a/dart/optimizer/Solver.cpp +++ b/dart/optimizer/Solver.cpp @@ -45,8 +45,8 @@ namespace optimizer { Solver::Properties::Properties( std::shared_ptr _problem, double _tolerance, - size_t _numMaxIterations, - size_t _iterationsPerPrint, + std::size_t _numMaxIterations, + std::size_t _iterationsPerPrint, std::ostream* _ostream, bool _printFinalResult, const std::string &_resultFile) @@ -133,19 +133,19 @@ double Solver::getTolerance() const } //============================================================================== -void Solver::setNumMaxIterations(size_t _newMax) +void Solver::setNumMaxIterations(std::size_t _newMax) { mProperties.mNumMaxIterations = _newMax; } //============================================================================== -size_t Solver::getNumMaxIterations() const +std::size_t Solver::getNumMaxIterations() const { return mProperties.mNumMaxIterations; } //============================================================================== -void Solver::setIterationsPerPrint(size_t _newRatio) +void Solver::setIterationsPerPrint(std::size_t _newRatio) { mProperties.mIterationsPerPrint = _newRatio; } @@ -163,7 +163,7 @@ std::ostream* Solver::getOutStream() const } //============================================================================== -size_t Solver::getIterationsPerPrint() const +std::size_t Solver::getIterationsPerPrint() const { return mProperties.mIterationsPerPrint; } diff --git a/dart/optimizer/Solver.h b/dart/optimizer/Solver.h index af02827521d38..b8cd230213de6 100644 --- a/dart/optimizer/Solver.h +++ b/dart/optimizer/Solver.h @@ -73,11 +73,11 @@ class Solver /// The maximum number of iterations that the solver should use. Use 0 for /// infinite iterations. - size_t mNumMaxIterations; + std::size_t mNumMaxIterations; /// How many iterations between printing the Solver's progress to the /// terminal. Use 0 for no printing. - size_t mIterationsPerPrint; + std::size_t mIterationsPerPrint; /// Stream for printing the Solver's progress. Default is std::cout. std::ostream* mOutStream; @@ -91,8 +91,8 @@ class Solver Properties(std::shared_ptr _problem = nullptr, double _tolerance = 1e-9, - size_t _numMaxIterations = 500, - size_t _iterationsPerPrint = 0, + std::size_t _numMaxIterations = 500, + std::size_t _iterationsPerPrint = 0, std::ostream* _ostream = &std::cout, bool _printFinalResult = false, const std::string& _resultFile = ""); @@ -143,18 +143,18 @@ class Solver double getTolerance() const; /// Set the maximum number of iterations that the Solver should use - virtual void setNumMaxIterations(size_t _newMax); + virtual void setNumMaxIterations(std::size_t _newMax); /// Get the maximum number of iterations that the Solver should use - size_t getNumMaxIterations() const; + std::size_t getNumMaxIterations() const; /// Set the number of iterations that should pass between printing progress to /// the terminal. Use 0 for no printing. - virtual void setIterationsPerPrint(size_t _newRatio); + virtual void setIterationsPerPrint(std::size_t _newRatio); /// Get the number of iterations that should pass between printing progress to /// the terminal. A value of 0 means there will be no printing. - size_t getIterationsPerPrint() const; + std::size_t getIterationsPerPrint() const; /// Set the output stream that prints the Solver's progress. virtual void setOutStream(std::ostream* _os); diff --git a/dart/optimizer/ipopt/IpoptSolver.cpp b/dart/optimizer/ipopt/IpoptSolver.cpp index 9ccd29e91cffa..20c5d411533ec 100644 --- a/dart/optimizer/ipopt/IpoptSolver.cpp +++ b/dart/optimizer/ipopt/IpoptSolver.cpp @@ -86,7 +86,7 @@ bool IpoptSolver::solve() mIpoptApp->Options()->SetNumericValue("tol", getTolerance()); mIpoptApp->Options()->SetStringValue("output_file", getResultFileName()); - size_t freq = mProperties.mIterationsPerPrint; + std::size_t freq = mProperties.mIterationsPerPrint; if(freq > 0) { mIpoptApp->Options()->SetNumericValue("print_frequency_iter", freq); @@ -203,8 +203,8 @@ bool DartTNLP::get_bounds_info(Ipopt::Index n, // here, the n and m we gave IPOPT in get_nlp_info are passed back to us. // If desired, we could assert to make sure they are what we think they are. - assert(static_cast(n) == problem->getDimension()); - assert(static_cast(m) == problem->getNumEqConstraints() + assert(static_cast(n) == problem->getDimension()); + assert(static_cast(m) == problem->getNumEqConstraints() + problem->getNumIneqConstraints()); DART_UNUSED(m); @@ -216,14 +216,14 @@ bool DartTNLP::get_bounds_info(Ipopt::Index n, } // Add inequality constraint functions - size_t idx = 0; - for (size_t i = 0; i < problem->getNumEqConstraints(); ++i) + std::size_t idx = 0; + for (std::size_t i = 0; i < problem->getNumEqConstraints(); ++i) { g_l[idx] = g_u[idx] = 0.0; ++idx; } - for (size_t i = 0; i < problem->getNumIneqConstraints(); ++i) + for (std::size_t i = 0; i < problem->getNumIneqConstraints(); ++i) { // Ipopt interprets any number greater than nlp_upper_bound_inf as // infinity. The default value of nlp_upper_bound_inf and @@ -321,7 +321,7 @@ bool DartTNLP::eval_g(Ipopt::Index _n, { const std::shared_ptr& problem = mSolver->getProblem(); - assert(static_cast(_m) == problem->getNumEqConstraints() + assert(static_cast(_m) == problem->getNumEqConstraints() + problem->getNumIneqConstraints()); DART_UNUSED(_m); @@ -331,10 +331,10 @@ bool DartTNLP::eval_g(Ipopt::Index _n, } Eigen::Map x(_x, _n); - size_t idx = 0; + std::size_t idx = 0; // Evaluate function values for equality constraints - for (size_t i = 0; i < problem->getNumEqConstraints(); ++i) + for (std::size_t i = 0; i < problem->getNumEqConstraints(); ++i) { _g[idx] = problem->getEqConstraint(i)->eval( static_cast(x)); @@ -342,7 +342,7 @@ bool DartTNLP::eval_g(Ipopt::Index _n, } // Evaluate function values for inequality constraints - for (size_t i = 0; i < problem->getNumIneqConstraints(); ++i) + for (std::size_t i = 0; i < problem->getNumIneqConstraints(); ++i) { _g[idx] = problem->getIneqConstraint(i)->eval( static_cast(x)); @@ -373,7 +373,7 @@ bool DartTNLP::eval_jac_g(Ipopt::Index _n, // return the structure of the Jacobian // Assume the gradient is dense - size_t idx = 0; + std::size_t idx = 0; for (int i = 0; i < _m; ++i) { for (int j = 0; j < _n; ++j) @@ -387,12 +387,12 @@ bool DartTNLP::eval_jac_g(Ipopt::Index _n, else { // return the values of the Jacobian of the constraints - size_t idx = 0; + std::size_t idx = 0; Eigen::Map x(_x, _n); Eigen::Map grad(nullptr, 0); // Evaluate function values for equality constraints - for (size_t i = 0; i < problem->getNumEqConstraints(); ++i) + for (std::size_t i = 0; i < problem->getNumEqConstraints(); ++i) { new (&grad)Eigen::Map(_values + idx, _n); problem->getEqConstraint(i)->evalGradient( @@ -401,7 +401,7 @@ bool DartTNLP::eval_jac_g(Ipopt::Index _n, } // Evaluate function values for inequality constraints - for (size_t i = 0; i < problem->getNumIneqConstraints(); ++i) + for (std::size_t i = 0; i < problem->getNumIneqConstraints(); ++i) { new (&grad)Eigen::Map(_values + idx, _n); problem->getIneqConstraint(i)->evalGradient( diff --git a/dart/optimizer/nlopt/NloptSolver.cpp b/dart/optimizer/nlopt/NloptSolver.cpp index f9fb8cbc770b4..029757d3a0620 100644 --- a/dart/optimizer/nlopt/NloptSolver.cpp +++ b/dart/optimizer/nlopt/NloptSolver.cpp @@ -86,7 +86,7 @@ static std::vector convertToStd(const Eigen::VectorXd& v) static Eigen::VectorXd convertToEigen(const std::vector& _v) { Eigen::VectorXd result(_v.size()); - for(size_t i=0; i<_v.size(); ++i) + for(std::size_t i=0; i<_v.size(); ++i) result[i] = _v[i]; return result; @@ -96,7 +96,7 @@ static Eigen::VectorXd convertToEigen(const std::vector& _v) bool NloptSolver::solve() { // Allocate a new nlopt::opt structure if needed - size_t dimension = mProperties.mProblem->getDimension(); + std::size_t dimension = mProperties.mProblem->getDimension(); if(nullptr == mOpt || mOpt->get_dimension() != dimension || mOpt->get_algorithm() != mAlg) @@ -120,7 +120,7 @@ bool NloptSolver::solve() mOpt->set_min_objective(NloptSolver::_nlopt_func, problem->getObjective().get()); - for(size_t i=0; igetNumEqConstraints(); ++i) + for(std::size_t i=0; igetNumEqConstraints(); ++i) { FunctionPtr fn = problem->getEqConstraint(i); try @@ -145,7 +145,7 @@ bool NloptSolver::solve() } } - for(size_t i=0; igetNumIneqConstraints(); ++i) + for(std::size_t i=0; igetNumIneqConstraints(); ++i) { FunctionPtr fn = problem->getIneqConstraint(i); try diff --git a/dart/planning/PathPlanner.h b/dart/planning/PathPlanner.h index 18aaba81369c8..9ecdf31972df0 100644 --- a/dart/planning/PathPlanner.h +++ b/dart/planning/PathPlanner.h @@ -70,7 +70,7 @@ class PathPlanner { bool bidirectional; ///< Whether two trees try to meet each other or one goes for the goal double stepSize; ///< Step size from a node in the tree to the random/goal node double goalBias; ///< Choose btw goal and random value (for goal-biased search) - size_t maxNodes; ///< Maximum number of iterations the sampling would continue + std::size_t maxNodes; ///< Maximum number of iterations the sampling would continue simulation::WorldPtr world; ///< The world that the robot is in (for obstacles and etc.) // NOTE: It is useful to keep the rrts around after planning for reuse, analysis, and etc. @@ -84,7 +84,7 @@ class PathPlanner { /// The desired constructor - you should use this one. PathPlanner(simulation::World& world, bool bidirectional_ = true, bool connect_ = true, double stepSize_ = 0.1, - size_t maxNodes_ = 1e6, double goalBias_ = 0.3) : world(&world), bidirectional(bidirectional_), + std::size_t maxNodes_ = 1e6, double goalBias_ = 0.3) : world(&world), bidirectional(bidirectional_), connect(connect_), stepSize(stepSize_), maxNodes(maxNodes_), goalBias(goalBias_) { } @@ -101,7 +101,7 @@ class PathPlanner { } /// Plan a path from a _set_ of start configurations to a _set_ of goals - bool planPath(dynamics::Skeleton* robot, const std::vector &dofs, const std::vector &start, + bool planPath(dynamics::Skeleton* robot, const std::vector &dofs, const std::vector &start, const std::vector &goal, std::list &path); private: @@ -124,7 +124,7 @@ class PathPlanner { /* ********************************************************************************************* */ template -bool PathPlanner::planPath(dynamics::Skeleton* robot, const std::vector &dofs, +bool PathPlanner::planPath(dynamics::Skeleton* robot, const std::vector &dofs, const std::vector &start, const std::vector &goal, std::list &path) { @@ -191,7 +191,7 @@ bool PathPlanner::planSingleTreeRrt(dynamics::Skeleton* robot, const std::vec // Expand the tree until the goal is reached or the max # nodes is passed typename R::StepResult result = R::STEP_PROGRESS; double smallestGap = std::numeric_limits::infinity(); - size_t numNodes = start_rrt->getSize(); + std::size_t numNodes = start_rrt->getSize(); while(numNodes <= maxNodes) { // Get the target node based on the bias @@ -240,7 +240,7 @@ bool PathPlanner::planBidirectionalRrt(dynamics::Skeleton* robot, const std:: // Expand the tree until the trees meet or the max # nodes is passed double smallestGap = std::numeric_limits::infinity(); - size_t numNodes = rrt1->getSize() + rrt2->getSize(); + std::size_t numNodes = rrt1->getSize() + rrt2->getSize(); while(numNodes < maxNodes) { // Swap the roles of the two RRTs. Remember, the first rrt reaches out to a target node and diff --git a/dart/planning/PathShortener.cpp b/dart/planning/PathShortener.cpp index b4317eeebfe7c..e5e39e9f039a0 100644 --- a/dart/planning/PathShortener.cpp +++ b/dart/planning/PathShortener.cpp @@ -54,7 +54,7 @@ namespace planning { PathShortener::PathShortener() {} -PathShortener::PathShortener(WorldPtr world, dynamics::SkeletonPtr robot, const vector &dofs, double stepSize) : +PathShortener::PathShortener(WorldPtr world, dynamics::SkeletonPtr robot, const vector &dofs, double stepSize) : world(world), robot(robot), dofs(dofs), diff --git a/dart/planning/PathShortener.h b/dart/planning/PathShortener.h index 785af0e7176d4..0c3424b8dd99e 100644 --- a/dart/planning/PathShortener.h +++ b/dart/planning/PathShortener.h @@ -50,14 +50,14 @@ class PathShortener { public: PathShortener(); - PathShortener(simulation::WorldPtr world, dynamics::SkeletonPtr robot, const std::vector& dofs, double stepSize = 0.1); + PathShortener(simulation::WorldPtr world, dynamics::SkeletonPtr robot, const std::vector& dofs, double stepSize = 0.1); ~PathShortener(); virtual void shortenPath(std::list &rawPath); bool segmentCollisionFree(std::list &waypoints, const Eigen::VectorXd &config1, const Eigen::VectorXd &config2); protected: simulation::WorldPtr world; dynamics::SkeletonPtr robot; - std::vector dofs; + std::vector dofs; double stepSize; virtual bool localPlanner(std::list &waypoints, std::list::const_iterator it1, std::list::const_iterator it2); }; diff --git a/dart/planning/RRT.cpp b/dart/planning/RRT.cpp index 731c1da630b4d..1f2eded46a947 100644 --- a/dart/planning/RRT.cpp +++ b/dart/planning/RRT.cpp @@ -56,7 +56,7 @@ namespace dart { namespace planning { /* ********************************************************************************************* */ -RRT::RRT(WorldPtr world, SkeletonPtr robot, const std::vector &dofs, +RRT::RRT(WorldPtr world, SkeletonPtr robot, const std::vector &dofs, const VectorXd &root, double stepSize) : ndim(dofs.size()), stepSize(stepSize), @@ -71,7 +71,7 @@ RRT::RRT(WorldPtr world, SkeletonPtr robot, const std::vector &dofs, } /* ********************************************************************************************* */ -RRT::RRT(WorldPtr world, SkeletonPtr robot, const std::vector &dofs, const vector &roots, double stepSize) : +RRT::RRT(WorldPtr world, SkeletonPtr robot, const std::vector &dofs, const vector &roots, double stepSize) : ndim(dofs.size()), stepSize(stepSize), world(world), @@ -81,7 +81,7 @@ RRT::RRT(WorldPtr world, SkeletonPtr robot, const std::vector &dofs, con { // Reset the random number generator and add the given start configurations to the flann structure srand(time(nullptr)); - for(size_t i = 0; i < roots.size(); i++) { + for(std::size_t i = 0; i < roots.size(); i++) { addNode(roots[i], -1); } } @@ -227,7 +227,7 @@ bool RRT::checkCollisions(const VectorXd &c) { } /* ********************************************************************************************* */ -size_t RRT::getSize() { +std::size_t RRT::getSize() { return configVector.size(); } diff --git a/dart/planning/RRT.h b/dart/planning/RRT.h index 10b505ad552ba..a13167c95ac61 100644 --- a/dart/planning/RRT.h +++ b/dart/planning/RRT.h @@ -93,11 +93,11 @@ class RRT { public: //// Constructor with a single root - RRT(dart::simulation::WorldPtr world, dart::dynamics::SkeletonPtr robot, const std::vector &dofs, const Eigen::VectorXd &root, + RRT(dart::simulation::WorldPtr world, dart::dynamics::SkeletonPtr robot, const std::vector &dofs, const Eigen::VectorXd &root, double stepSize = 0.02); /// Constructor with multiple roots (so, multiple trees) - RRT(simulation::WorldPtr world, dynamics::SkeletonPtr robot, const std::vector &dofs, + RRT(simulation::WorldPtr world, dynamics::SkeletonPtr robot, const std::vector &dofs, const std::vector &roots, double stepSize = 0.02); /// Destructor @@ -136,7 +136,7 @@ class RRT { void tracePath(int node, std::list &path, bool reverse = false); /// Returns the number of nodes in the tree. - size_t getSize(); + std::size_t getSize(); /// Implementation-specific function for checking collisions virtual bool checkCollisions(const Eigen::VectorXd &c); @@ -148,7 +148,7 @@ class RRT { simulation::WorldPtr world; ///< The world that the robot is in dynamics::SkeletonPtr robot; ///< The ID of the robot for which a plan is generated - std::vector dofs; ///< The dofs of the robot the planner can manipulate + std::vector dofs; ///< The dofs of the robot the planner can manipulate /// The underlying flann data structure for fast nearest neighbor searches flann::Index >* index; diff --git a/dart/simulation/Recording.cpp b/dart/simulation/Recording.cpp index bb87fa712283d..95995ba846186 100644 --- a/dart/simulation/Recording.cpp +++ b/dart/simulation/Recording.cpp @@ -52,14 +52,14 @@ namespace simulation { //============================================================================== Recording::Recording(const std::vector& _skeletons) { - for (size_t i = 0; i < _skeletons.size(); i++) + for (std::size_t i = 0; i < _skeletons.size(); i++) mNumGenCoordsForSkeletons.push_back(_skeletons[i]->getNumDofs()); } //============================================================================== Recording::Recording(const std::vector& _skelDofs) { - for (size_t i = 0; i < _skelDofs.size(); i++) + for (std::size_t i = 0; i < _skelDofs.size(); i++) mNumGenCoordsForSkeletons.push_back(_skelDofs[i]); } @@ -90,7 +90,7 @@ int Recording::getNumDofs(int _skelIdx) const int Recording::getNumContacts(int _frameIdx) const { int totalDofs = 0; - for (size_t i = 0; i < mNumGenCoordsForSkeletons.size(); i++) + for (std::size_t i = 0; i < mNumGenCoordsForSkeletons.size(); i++) totalDofs += mNumGenCoordsForSkeletons[i]; return (mBakedStates[_frameIdx].size() - totalDofs) / 6; } @@ -117,7 +117,7 @@ double Recording::getGenCoord(int _frameIdx, int _skelIdx, int _dofIdx) const Eigen::Vector3d Recording::getContactPoint(int _frameIdx, int _contactIdx) const { int totalDofs = 0; - for (size_t i = 0; i < mNumGenCoordsForSkeletons.size(); i++) + for (std::size_t i = 0; i < mNumGenCoordsForSkeletons.size(); i++) totalDofs += mNumGenCoordsForSkeletons[i]; return mBakedStates[_frameIdx].segment(totalDofs + _contactIdx * 6, 3); } @@ -126,7 +126,7 @@ Eigen::Vector3d Recording::getContactPoint(int _frameIdx, int _contactIdx) const Eigen::Vector3d Recording::getContactForce(int _frameIdx, int _contactIdx) const { int totalDofs = 0; - for (size_t i = 0; i < mNumGenCoordsForSkeletons.size(); i++) + for (std::size_t i = 0; i < mNumGenCoordsForSkeletons.size(); i++) totalDofs += mNumGenCoordsForSkeletons[i]; return mBakedStates[_frameIdx].segment(totalDofs + _contactIdx * 6 + 3, 3); } @@ -147,7 +147,7 @@ void Recording::updateNumGenCoords( const std::vector& _skeletons) { mNumGenCoordsForSkeletons.clear(); - for (size_t i = 0; i < _skeletons.size(); ++i) + for (std::size_t i = 0; i < _skeletons.size(); ++i) mNumGenCoordsForSkeletons.push_back(_skeletons[i]->getNumDofs()); } diff --git a/dart/simulation/World.cpp b/dart/simulation/World.cpp index 294727ca8acb9..b7feeff1ce126 100644 --- a/dart/simulation/World.cpp +++ b/dart/simulation/World.cpp @@ -97,13 +97,13 @@ WorldPtr World::clone() const cd->cloneWithoutCollisionObjects()); // Clone and add each Skeleton - for(size_t i=0; iaddSkeleton(mSkeletons[i]->clone()); } // Clone and add each SimpleFrame - for(size_t i=0; iaddSimpleFrame(mSimpleFrames[i]->clone(mSimpleFrames[i]->getParentFrame())); } @@ -111,7 +111,7 @@ WorldPtr World::clone() const // For each newly cloned SimpleFrame, try to make its parent Frame be one of // the new clones if there is a match. This is meant to minimize any possible // interdependencies between the kinematics of different worlds. - for(size_t i=0; igetNumSimpleFrames(); ++i) + for(std::size_t i=0; igetNumSimpleFrames(); ++i) { dynamics::Frame* current_parent = worldClone->getSimpleFrame(i)->getParentFrame(); @@ -258,7 +258,7 @@ const Eigen::Vector3d& World::getGravity() const } //============================================================================== -dynamics::SkeletonPtr World::getSkeleton(size_t _index) const +dynamics::SkeletonPtr World::getSkeleton(std::size_t _index) const { if(_index < mSkeletons.size()) return mSkeletons[_index]; @@ -273,7 +273,7 @@ dynamics::SkeletonPtr World::getSkeleton(const std::string& _name) const } //============================================================================== -size_t World::getNumSkeletons() const +std::size_t World::getNumSkeletons() const { return mSkeletons.size(); } @@ -332,7 +332,7 @@ void World::removeSkeleton(const dynamics::SkeletonPtr& _skeleton) } // Find index of _skeleton in mSkeleton. - size_t index = 0; + std::size_t index = 0; for (; index < mSkeletons.size(); ++index) { if (mSkeletons[index] == _skeleton) @@ -349,7 +349,7 @@ void World::removeSkeleton(const dynamics::SkeletonPtr& _skeleton) } // Update mIndices. - for (size_t i = index+1; i < mSkeletons.size() - 1; ++i) + for (std::size_t i = index+1; i < mSkeletons.size() - 1; ++i) mIndices[i] = mIndices[i+1] - _skeleton->getNumDofs(); mIndices.pop_back(); @@ -395,7 +395,7 @@ int World::getIndex(int _index) const } //============================================================================== -dynamics::SimpleFramePtr World::getSimpleFrame(size_t _index) const +dynamics::SimpleFramePtr World::getSimpleFrame(std::size_t _index) const { if(_index < mSimpleFrames.size()) return mSimpleFrames[_index]; @@ -410,7 +410,7 @@ dynamics::SimpleFramePtr World::getSimpleFrame(const std::string& _name) const } //============================================================================== -size_t World::getNumSimpleFrames() const +std::size_t World::getNumSimpleFrames() const { return mSimpleFrames.size(); } @@ -462,7 +462,7 @@ void World::removeSimpleFrame(const dynamics::SimpleFramePtr& _frame) return; } - size_t index = it - mSimpleFrames.begin(); + std::size_t index = it - mSimpleFrames.begin(); // Remove the frame mSimpleFrames.erase(mSimpleFrames.begin()+index); diff --git a/dart/simulation/World.h b/dart/simulation/World.h index 9cf0c3ad5c7ab..d5a86a4892525 100644 --- a/dart/simulation/World.h +++ b/dart/simulation/World.h @@ -129,7 +129,7 @@ class World : public virtual common::Subject //-------------------------------------------------------------------------- /// Get the indexed skeleton - dynamics::SkeletonPtr getSkeleton(size_t _index) const; + dynamics::SkeletonPtr getSkeleton(std::size_t _index) const; /// Find a Skeleton by name /// \param[in] The name of the Skeleton you are looking for. @@ -137,7 +137,7 @@ class World : public virtual common::Subject dynamics::SkeletonPtr getSkeleton(const std::string& _name) const; /// Get the number of skeletons - size_t getNumSkeletons() const; + std::size_t getNumSkeletons() const; /// Add a skeleton to this world std::string addSkeleton(const dynamics::SkeletonPtr& _skeleton); @@ -153,13 +153,13 @@ class World : public virtual common::Subject int getIndex(int _index) const; /// Get the indexed Entity - dynamics::SimpleFramePtr getSimpleFrame(size_t _index) const; + dynamics::SimpleFramePtr getSimpleFrame(std::size_t _index) const; /// Find an Entity by name dynamics::SimpleFramePtr getSimpleFrame(const std::string& _name) const; /// Get the number of Entities - size_t getNumSimpleFrames() const; + std::size_t getNumSimpleFrames() const; /// Add an Entity to this world std::string addSimpleFrame(const dynamics::SimpleFramePtr& _frame); diff --git a/dart/utils/FileInfoDof.cpp b/dart/utils/FileInfoDof.cpp index 41a6ce3825131..84899930bbeab 100644 --- a/dart/utils/FileInfoDof.cpp +++ b/dart/utils/FileInfoDof.cpp @@ -69,7 +69,7 @@ bool FileInfoDof::loadFile(const char* _fName) inFile.precision(20); char buffer[256]; - size_t nDof; + std::size_t nDof; // nFrames = inFile >> buffer; @@ -87,12 +87,12 @@ bool FileInfoDof::loadFile(const char* _fName) mDofs.resize(mNumFrames); // dof names - for (size_t i = 0; i < nDof; i++) + for (std::size_t i = 0; i < nDof; i++) inFile >> buffer; - for (size_t j = 0; j < mNumFrames; j++) + for (std::size_t j = 0; j < mNumFrames; j++) { mDofs[j].resize(nDof); - for (size_t i = 0; i < nDof; i++) + for (std::size_t i = 0; i < nDof; i++) { double val; inFile >> val; @@ -115,7 +115,7 @@ bool FileInfoDof::loadFile(const char* _fName) } //============================================================================== -bool FileInfoDof::saveFile(const char* _fName, size_t _start, size_t _end, +bool FileInfoDof::saveFile(const char* _fName, std::size_t _start, std::size_t _end, double /*_sampleRate*/ ) { if (_end < _start) return false; @@ -123,26 +123,26 @@ bool FileInfoDof::saveFile(const char* _fName, size_t _start, size_t _end, std::ofstream outFile(_fName, std::ios::out); if (outFile.fail()) return false; - size_t first = _start < mNumFrames ? _start : mNumFrames - 1; - size_t last = _end < mNumFrames ? _end : mNumFrames - 1; + std::size_t first = _start < mNumFrames ? _start : mNumFrames - 1; + std::size_t last = _end < mNumFrames ? _end : mNumFrames - 1; outFile.precision(20); outFile << "frames = " << last-first+1 << " dofs = " << mSkel->getNumDofs() << std::endl; - for (size_t i = 0; i < mSkel->getNumDofs(); i++) + for (std::size_t i = 0; i < mSkel->getNumDofs(); i++) { const dynamics::DegreeOfFreedom* dof = mSkel->getDof(i); const dynamics::Joint* joint = dof->getJoint(); - const size_t localIndex = dof->getIndexInJoint(); + const std::size_t localIndex = dof->getIndexInJoint(); outFile << joint->getName() << "." << localIndex << ' '; } outFile << std::endl; - for (size_t i = first; i <= last; i++) + for (std::size_t i = first; i <= last; i++) { - for (size_t j = 0; j < mSkel->getNumDofs(); j++) + for (std::size_t j = 0; j < mSkel->getNumDofs(); j++) outFile << mDofs[i][j] << ' '; outFile << std::endl; } @@ -152,7 +152,7 @@ bool FileInfoDof::saveFile(const char* _fName, size_t _start, size_t _end, outFile.close(); std::string text = _fName; - size_t lastSlash = text.find_last_of("/"); + std::size_t lastSlash = text.find_last_of("/"); text = text.substr(lastSlash + 1); std::strcpy(mFileName, text.c_str()); return true; @@ -165,7 +165,7 @@ void FileInfoDof::addDof(const Eigen::VectorXd& _dofs) } //============================================================================== -double FileInfoDof::getDofAt(size_t _frame, size_t _id) const +double FileInfoDof::getDofAt(std::size_t _frame, std::size_t _id) const { assert(_frameaddState(state); tempState.clear(); diff --git a/dart/utils/SkelParser.cpp b/dart/utils/SkelParser.cpp index 4421a3b313a92..c564f04158e1a 100644 --- a/dart/utils/SkelParser.cpp +++ b/dart/utils/SkelParser.cpp @@ -145,10 +145,10 @@ using BodyMap = Eigen::aligned_map; using JointMap = std::map; // first: Order that Joint appears in file | second: Child BodyNode name -using IndexToJoint = std::map; +using IndexToJoint = std::map; // first: Child BodyNode name | second: Order that Joint appears in file -using JointToIndex = std::map; +using JointToIndex = std::map; simulation::WorldPtr readWorld( tinyxml2::XMLElement* _worldElement, @@ -333,13 +333,13 @@ void getDofAttributeIfItExists( const std::string& _element_type, const tinyxml2::XMLElement* _xmlElement, const std::string& _jointName, - size_t _index); + std::size_t _index); void setDofLimitAttributes( tinyxml2::XMLElement* _dofElement, const std::string& _element_type, const std::string& _jointName, - size_t _index, + std::size_t _index, double* lower, double* upper, double* initial); template @@ -347,21 +347,21 @@ void readAllDegreesOfFreedom(tinyxml2::XMLElement* _jointElement, PropertyType& _properties, SkelJoint& _joint, const std::string& _jointName, - size_t _numDofs); + std::size_t _numDofs); template void readDegreeOfFreedom(tinyxml2::XMLElement* _dofElement, PropertyType& properties, SkelJoint& joint, const std::string& jointName, - size_t numDofs); + std::size_t numDofs); template void readJointDynamicsAndLimit(tinyxml2::XMLElement* _jointElement, PropertyType& _properties, SkelJoint& _joint, const std::string& _name, - size_t _numAxis); + std::size_t _numAxis); JointPropPtr readWeldJoint( tinyxml2::XMLElement* _jointElement, @@ -1512,7 +1512,7 @@ void readJoint(tinyxml2::XMLElement* _jointElement, _joints[joint.childName] = joint; // Keep track of when each joint appeared in the file - size_t nextIndex; + std::size_t nextIndex; IndexToJoint::reverse_iterator lastIndex = _order.rbegin(); if(lastIndex == _order.rend()) nextIndex = 0; @@ -1530,7 +1530,7 @@ void getDofAttributeIfItExists( const std::string& _element_type, const tinyxml2::XMLElement* _xmlElement, const std::string& _jointName, - size_t _index) + std::size_t _index) { if (_xmlElement->QueryDoubleAttribute(_attribute.c_str(), _value) == tinyxml2::XML_WRONG_ATTRIBUTE_TYPE) @@ -1546,7 +1546,7 @@ void getDofAttributeIfItExists( void setDofLimitAttributes(tinyxml2::XMLElement* _dofElement, const std::string& _element_type, const std::string& _jointName, - size_t _index, + std::size_t _index, double* lower, double* upper, double* initial) { const tinyxml2::XMLElement* xmlElement @@ -1562,7 +1562,7 @@ void setDofLimitAttributes(tinyxml2::XMLElement* _dofElement, // SingleDofJoint::Properties and MultiDofJoint::Properties struct DofProxy { - size_t index; + std::size_t index; bool valid; double* lowerPosition; @@ -1590,7 +1590,7 @@ struct DofProxy std::string* name; DofProxy(dynamics::SingleDofJoint::Properties& properties, - SkelJoint& joint, size_t _index, + SkelJoint& joint, std::size_t _index, const std::string& jointName) : index(_index), valid(true), @@ -1629,7 +1629,7 @@ struct DofProxy template DofProxy(PropertyType& properties, - SkelJoint& joint, size_t _index, + SkelJoint& joint, std::size_t _index, const std::string& jointName) : index(_index), valid(true), @@ -1674,7 +1674,7 @@ void readAllDegreesOfFreedom(tinyxml2::XMLElement* _jointElement, PropertyType& _properties, SkelJoint& _joint, const std::string& _jointName, - size_t _numDofs) + std::size_t _numDofs) { if(_joint.position.size() < (int)_numDofs) { @@ -1712,7 +1712,7 @@ void readDegreeOfFreedom(tinyxml2::XMLElement* _dofElement, PropertyType& properties, SkelJoint& joint, const std::string& jointName, - size_t numDofs) + std::size_t numDofs) { int localIndex = -1; int xml_err = _dofElement->QueryIntAttribute("local_index", &localIndex); @@ -1811,7 +1811,7 @@ void readJointDynamicsAndLimit(tinyxml2::XMLElement* _jointElement, PropertyType& _properties, SkelJoint& _joint, const std::string& _name, - size_t _numAxis) + std::size_t _numAxis) { // TODO(MXG): Consider printing warnings for these tags that recommends using // the dof tag instead, because all functionality of these tags have been @@ -1823,7 +1823,7 @@ void readJointDynamicsAndLimit(tinyxml2::XMLElement* _jointElement, std::string axisName = "axis"; // axis - for (size_t i = 0; i < _numAxis; ++i) + for (std::size_t i = 0; i < _numAxis; ++i) { if (i != 0) axisName = "axis" + std::to_string(i + 1); diff --git a/dart/utils/VskParser.cpp b/dart/utils/VskParser.cpp index eeaea52805250..dc962728cc3c8 100644 --- a/dart/utils/VskParser.cpp +++ b/dart/utils/VskParser.cpp @@ -342,7 +342,7 @@ double getParameter(const ParameterMap& ParameterMap, } //============================================================================== -template +template Eigen::Matrix getParameters( const ParameterMap& ParameterMap, const std::string& paramNamesOrValues) @@ -354,14 +354,14 @@ Eigen::Matrix getParameters( Eigen::Matrix result; - for (size_t i = 0; i < NumParams; ++i) + for (std::size_t i = 0; i < NumParams; ++i) result[i] = getParameter(ParameterMap, tokens[i]); return result; } //============================================================================== -template +template Eigen::Matrix readAttributeVector( const tinyxml2::XMLElement* element, const std::string& name, @@ -889,7 +889,7 @@ bool readStick(const tinyxml2::XMLElement* /*stickEle*/, void generateShapes(const dynamics::SkeletonPtr& skel, VskData& vskData) { // Generate shapes for bodies that have their parents - for (size_t i = 0; i < skel->getNumBodyNodes(); ++i) + for (std::size_t i = 0; i < skel->getNumBodyNodes(); ++i) { dynamics::BodyNode* bodyNode = skel->getBodyNode(i); dynamics::Joint* joint = skel->getJoint(i); @@ -935,7 +935,7 @@ void generateShapes(const dynamics::SkeletonPtr& skel, VskData& vskData) if (vskData.options.removeEndBodyNodes) { std::vector emptynodes; - for (size_t i = 0; i < skel->getNumBodyNodes(); ++i) + for (std::size_t i = 0; i < skel->getNumBodyNodes(); ++i) { dynamics::BodyNode* bodyNode = skel->getBodyNode(i); @@ -952,7 +952,7 @@ void generateShapes(const dynamics::SkeletonPtr& skel, VskData& vskData) // Update mass and moments of inertia of the bodies based on the their shapes const double& density = vskData.options.density; - for (size_t i = 0; i < skel->getNumBodyNodes(); ++i) + for (std::size_t i = 0; i < skel->getNumBodyNodes(); ++i) { dynamics::BodyNode* bodyNode = skel->getBodyNode(i); @@ -1003,10 +1003,10 @@ void tokenize(const std::string& str, const std::string& delimiters) { // Skip delimiters at beginning. - std::string::size_type lastPos = str.find_first_not_of(delimiters, 0); + std::string::std::size_type lastPos = str.find_first_not_of(delimiters, 0); // Find first "non-delimiter". - std::string::size_type pos = str.find_first_of(delimiters, lastPos); + std::string::std::size_type pos = str.find_first_of(delimiters, lastPos); while (std::string::npos != pos || std::string::npos != lastPos) { diff --git a/dart/utils/XmlHelpers.cpp b/dart/utils/XmlHelpers.cpp index 2aa6260433f93..8b492c220ac11 100644 --- a/dart/utils/XmlHelpers.cpp +++ b/dart/utils/XmlHelpers.cpp @@ -188,7 +188,7 @@ Eigen::Vector2d toVector2d(const std::string& str) boost::token_compress_on); assert(pieces.size() == 2); - for (size_t i = 0; i < pieces.size(); ++i) + for (std::size_t i = 0; i < pieces.size(); ++i) { if (pieces[i] != "") { @@ -221,7 +221,7 @@ Eigen::Vector3d toVector3d(const std::string& str) boost::token_compress_on); assert(pieces.size() == 3); - for (size_t i = 0; i < pieces.size(); ++i) + for (std::size_t i = 0; i < pieces.size(); ++i) { if (pieces[i] != "") { @@ -255,7 +255,7 @@ Eigen::Vector3i toVector3i(const std::string& str) boost::token_compress_on); assert(pieces.size() == 3); - for (size_t i = 0; i < pieces.size(); ++i) + for (std::size_t i = 0; i < pieces.size(); ++i) { if (pieces[i] != "") { @@ -289,7 +289,7 @@ Eigen::Vector6d toVector6d(const std::string& str) boost::token_compress_on); assert(pieces.size() == 6); - for (size_t i = 0; i < pieces.size(); ++i) + for (std::size_t i = 0; i < pieces.size(); ++i) { if (pieces[i] != "") { @@ -323,7 +323,7 @@ Eigen::VectorXd toVectorXd(const std::string& str) Eigen::VectorXd ret(pieces.size()); - for (size_t i = 0; i < pieces.size(); ++i) + for (std::size_t i = 0; i < pieces.size(); ++i) { if (pieces[i] != "") { @@ -357,7 +357,7 @@ Eigen::Isometry3d toIsometry3d(const std::string& str) boost::token_compress_on); assert(pieces.size() == 6); - for (size_t i = 0; i < pieces.size(); ++i) + for (std::size_t i = 0; i < pieces.size(); ++i) { if (pieces[i] != "") { @@ -393,7 +393,7 @@ Eigen::Isometry3d toIsometry3dWithExtrinsicRotation(const std::string& str) boost::token_compress_on); assert(pieces.size() == 6); - for (size_t i = 0; i < pieces.size(); ++i) + for (std::size_t i = 0; i < pieces.size(); ++i) { if (pieces[i] != "") { @@ -666,7 +666,7 @@ void openXMLFile(tinyxml2::XMLDocument& doc, } // C++11 guarantees that std::string has contiguous storage. - const size_t size = resource->getSize(); + const std::size_t size = resource->getSize(); std::string content; content.resize(size); if(resource->read(&content.front(), size, 1) != 1) diff --git a/dart/utils/urdf/DartLoader.cpp b/dart/utils/urdf/DartLoader.cpp index be4f56fa43327..1e81647acaa7f 100644 --- a/dart/utils/urdf/DartLoader.cpp +++ b/dart/utils/urdf/DartLoader.cpp @@ -163,7 +163,7 @@ simulation::WorldPtr DartLoader::parseWorldString( simulation::WorldPtr world(new simulation::World); - for(size_t i = 0; i < worldInterface->models.size(); ++i) + for(std::size_t i = 0; i < worldInterface->models.size(); ++i) { const urdf_parsing::Entity& entity = worldInterface->models[i]; dynamics::SkeletonPtr skeleton = modelInterfaceToSkeleton( @@ -252,7 +252,7 @@ dynamics::SkeletonPtr DartLoader::modelInterfaceToSkeleton( return nullptr; } - for(size_t i = 0; i < root->child_links.size(); i++) + for(std::size_t i = 0; i < root->child_links.size(); i++) { if (!createSkeletonRecursive( skeleton, root->child_links[i].get(), rootNode, @@ -286,7 +286,7 @@ bool DartLoader::createSkeletonRecursive( if(!result) return false; - for(size_t i = 0; i < _lk->child_links.size(); ++i) + for(std::size_t i = 0; i < _lk->child_links.size(); ++i) { if (!createSkeletonRecursive(_skel, _lk->child_links[i].get(), node, _baseUri, _resourceRetriever)) @@ -309,7 +309,7 @@ bool DartLoader::readFileToString( return false; // Safe because std::string is guaranteed to be contiguous in C++11. - const size_t size = resource->getSize(); + const std::size_t size = resource->getSize(); _output.resize(size); resource->read(&_output.front(), size, 1); diff --git a/tutorials/tutorialBiped-Finished.cpp b/tutorials/tutorialBiped-Finished.cpp index 210a0cb659bf7..41c2d40721152 100644 --- a/tutorials/tutorialBiped-Finished.cpp +++ b/tutorials/tutorialBiped-Finished.cpp @@ -67,13 +67,13 @@ class Controller mKp = Eigen::MatrixXd::Identity(nDofs, nDofs); mKd = Eigen::MatrixXd::Identity(nDofs, nDofs); - for(size_t i = 0; i < 6; ++i) + for(std::size_t i = 0; i < 6; ++i) { mKp(i, i) = 0.0; mKd(i, i) = 0.0; } - for(size_t i = 6; i < mBiped->getNumDofs(); ++i) + for(std::size_t i = 6; i < mBiped->getNumDofs(); ++i) { mKp(i, i) = 1000; mKd(i, i) = 50; @@ -172,7 +172,7 @@ class Controller { int wheelFirstIndex = mBiped->getDof("joint_front_left_1")->getIndexInSkeleton(); - for (size_t i = wheelFirstIndex; i < mBiped->getNumDofs(); ++i) + for (std::size_t i = wheelFirstIndex; i < mBiped->getNumDofs(); ++i) { mKp(i, i) = 0.0; mKd(i, i) = 0.0; @@ -308,7 +308,7 @@ SkeletonPtr loadBiped() SkeletonPtr biped = world->getSkeleton("biped"); // Set joint limits - for(size_t i = 0; i < biped->getNumJoints(); ++i) + for(std::size_t i = 0; i < biped->getNumJoints(); ++i) biped->getJoint(i)->setPositionLimitEnforced(true); // Enable self collision check but ignore adjacent bodies @@ -379,7 +379,7 @@ Eigen::VectorXd solveIK(SkeletonPtr biped) BodyNodePtr leftToe = biped->getBodyNode("h_toe_left"); double initialHeight = -0.8; - for(size_t i = 0; i < default_ik_iterations; ++i) + for(std::size_t i = 0; i < default_ik_iterations; ++i) { Eigen::Vector3d deviation = biped->getCOM() - leftHeel->getCOM(); Eigen::Vector3d localCOM = leftHeel->getCOM(leftHeel); diff --git a/tutorials/tutorialBiped.cpp b/tutorials/tutorialBiped.cpp index 72902de753eba..fe7be55e56592 100644 --- a/tutorials/tutorialBiped.cpp +++ b/tutorials/tutorialBiped.cpp @@ -68,13 +68,13 @@ class Controller mKp = Eigen::MatrixXd::Identity(nDofs, nDofs); mKd = Eigen::MatrixXd::Identity(nDofs, nDofs); - for(size_t i = 0; i < 6; ++i) + for(std::size_t i = 0; i < 6; ++i) { mKp(i, i) = 0.0; mKd(i, i) = 0.0; } - for(size_t i = 6; i < biped->getNumDofs(); ++i) + for(std::size_t i = 6; i < biped->getNumDofs(); ++i) { mKp(i, i) = 1000; mKd(i, i) = 50; diff --git a/tutorials/tutorialCollisions-Finished.cpp b/tutorials/tutorialCollisions-Finished.cpp index 05f4d83cdd399..8f7f29f0c7c71 100644 --- a/tutorials/tutorialCollisions-Finished.cpp +++ b/tutorials/tutorialCollisions-Finished.cpp @@ -78,7 +78,7 @@ using namespace dart::simulation; void setupRing(const SkeletonPtr& ring) { // Set the spring and damping coefficients for the degrees of freedom - for(size_t i=6; i < ring->getNumDofs(); ++i) + for(std::size_t i=6; i < ring->getNumDofs(); ++i) { DegreeOfFreedom* dof = ring->getDof(i); dof->setSpringStiffness(ring_spring_stiffness); @@ -86,23 +86,23 @@ void setupRing(const SkeletonPtr& ring) } // Compute the joint angle needed to form a ring - size_t numEdges = ring->getNumBodyNodes(); + std::size_t numEdges = ring->getNumBodyNodes(); double angle = 2*M_PI/numEdges; // Set the BallJoints so that they have the correct rest position angle - for(size_t i=1; i < ring->getNumJoints(); ++i) + for(std::size_t i=1; i < ring->getNumJoints(); ++i) { Joint* joint = ring->getJoint(i); Eigen::AngleAxisd rotation(angle, Eigen::Vector3d(0, 1, 0)); Eigen::Vector3d restPos = BallJoint::convertToPositions( Eigen::Matrix3d(rotation)); - for(size_t j=0; j<3; ++j) + for(std::size_t j=0; j<3; ++j) joint->setRestPosition(j, restPos[j]); } // Set the Joints to be in their rest positions - for(size_t i=6; i < ring->getNumDofs(); ++i) + for(std::size_t i=6; i < ring->getNumDofs(); ++i) { DegreeOfFreedom* dof = ring->getDof(i); dof->setPosition(dof->getRestPosition()); @@ -297,7 +297,7 @@ class MyWindow : public dart::gui::SimWindow /// it, if one existed void removeSkeleton(const SkeletonPtr& skel) { - for(size_t i=0; igetParentJoint(); - for(size_t i=0; i < joint->getNumDofs(); ++i) + for(std::size_t i=0; i < joint->getNumDofs(); ++i) joint->getDof(i)->setDampingCoefficient(default_damping_coefficient); } @@ -502,7 +502,7 @@ BodyNode* addSoftBody(const SkeletonPtr& chain, const std::string& name, void setAllColors(const SkeletonPtr& object, const Eigen::Vector3d& color) { // Set the color of all the shapes in the object - for(size_t i=0; i < object->getNumBodyNodes(); ++i) + for(std::size_t i=0; i < object->getNumBodyNodes(); ++i) { BodyNode* bn = object->getBodyNode(i); auto visualShapeNodes = bn->getShapeNodesWith(); diff --git a/tutorials/tutorialCollisions.cpp b/tutorials/tutorialCollisions.cpp index a1d2486010ff8..1124de907859f 100644 --- a/tutorials/tutorialCollisions.cpp +++ b/tutorials/tutorialCollisions.cpp @@ -224,7 +224,7 @@ class MyWindow : public SimWindow /// it, if one existed void removeSkeleton(const SkeletonPtr& skel) { - for(size_t i=0; igetNumBodyNodes(); ++i) + for(std::size_t i=0; i < object->getNumBodyNodes(); ++i) { BodyNode* bn = object->getBodyNode(i); auto visualShapeNodes = bn->getShapeNodesWith(); diff --git a/tutorials/tutorialDominoes-Finished.cpp b/tutorials/tutorialDominoes-Finished.cpp index f12e5f2747228..1f1f244b70de8 100644 --- a/tutorials/tutorialDominoes-Finished.cpp +++ b/tutorials/tutorialDominoes-Finished.cpp @@ -170,7 +170,7 @@ class Controller // Turn the control gains into matrix form Eigen::Matrix6d Kp = mKpOS * Eigen::Matrix6d::Identity(); - size_t dofs = mManipulator->getNumDofs(); + std::size_t dofs = mManipulator->getNumDofs(); Eigen::MatrixXd Kd = mKdOS * Eigen::MatrixXd::Identity(dofs, dofs); // Compute the joint forces needed to exert the desired workspace force diff --git a/tutorials/tutorialMultiPendulum-Finished.cpp b/tutorials/tutorialMultiPendulum-Finished.cpp index c01b3a0a3a14a..39a3fbf12e6e9 100644 --- a/tutorials/tutorialMultiPendulum-Finished.cpp +++ b/tutorials/tutorialMultiPendulum-Finished.cpp @@ -102,7 +102,7 @@ class MyWindow : public dart::gui::SimWindow } } - void applyForce(size_t index) + void applyForce(std::size_t index) { if(index < mForceCountDown.size()) mForceCountDown[index] = default_countdown; @@ -110,7 +110,7 @@ class MyWindow : public dart::gui::SimWindow void changeRestPosition(double delta) { - for(size_t i = 0; i < mPendulum->getNumDofs(); ++i) + for(std::size_t i = 0; i < mPendulum->getNumDofs(); ++i) { DegreeOfFreedom* dof = mPendulum->getDof(i); double q0 = dof->getRestPosition() + delta; @@ -130,7 +130,7 @@ class MyWindow : public dart::gui::SimWindow void changeStiffness(double delta) { - for(size_t i = 0; i < mPendulum->getNumDofs(); ++i) + for(std::size_t i = 0; i < mPendulum->getNumDofs(); ++i) { DegreeOfFreedom* dof = mPendulum->getDof(i); double stiffness = dof->getSpringStiffness() + delta; @@ -142,7 +142,7 @@ class MyWindow : public dart::gui::SimWindow void changeDamping(double delta) { - for(size_t i = 0; i < mPendulum->getNumDofs(); ++i) + for(std::size_t i = 0; i < mPendulum->getNumDofs(); ++i) { DegreeOfFreedom* dof = mPendulum->getDof(i); double damping = dof->getDampingCoefficient() + delta; @@ -255,11 +255,11 @@ class MyWindow : public dart::gui::SimWindow void timeStepping() override { // Reset all the shapes to be Blue - for(size_t i = 0; i < mPendulum->getNumBodyNodes(); ++i) + for(std::size_t i = 0; i < mPendulum->getNumBodyNodes(); ++i) { BodyNode* bn = mPendulum->getBodyNode(i); auto visualShapeNodes = bn->getShapeNodesWith(); - for(size_t j = 0; j < 2; ++j) + for(std::size_t j = 0; j < 2; ++j) visualShapeNodes[j]->getVisualAspect()->setColor(dart::Color::Blue()); // If we have three visualization shapes, that means the arrow is @@ -275,7 +275,7 @@ class MyWindow : public dart::gui::SimWindow if(!mBodyForce) { // Apply joint torques based on user input, and color the Joint shape red - for(size_t i = 0; i < mPendulum->getNumDofs(); ++i) + for(std::size_t i = 0; i < mPendulum->getNumDofs(); ++i) { if(mForceCountDown[i] > 0) { @@ -293,7 +293,7 @@ class MyWindow : public dart::gui::SimWindow else { // Apply body forces based on user input, and color the body shape red - for(size_t i = 0; i < mPendulum->getNumBodyNodes(); ++i) + for(std::size_t i = 0; i < mPendulum->getNumBodyNodes(); ++i) { if(mForceCountDown[i] > 0) { diff --git a/tutorials/tutorialMultiPendulum.cpp b/tutorials/tutorialMultiPendulum.cpp index df7962c710c65..bb9809f5fe339 100644 --- a/tutorials/tutorialMultiPendulum.cpp +++ b/tutorials/tutorialMultiPendulum.cpp @@ -102,7 +102,7 @@ class MyWindow : public dart::gui::SimWindow } } - void applyForce(size_t index) + void applyForce(std::size_t index) { if(index < mForceCountDown.size()) mForceCountDown[index] = default_countdown; @@ -222,7 +222,7 @@ class MyWindow : public dart::gui::SimWindow if(!mBodyForce) { // Apply joint torques based on user input, and color the Joint shape red - for(size_t i = 0; i < mPendulum->getNumDofs(); ++i) + for(std::size_t i = 0; i < mPendulum->getNumDofs(); ++i) { if(mForceCountDown[i] > 0) { @@ -235,7 +235,7 @@ class MyWindow : public dart::gui::SimWindow else { // Apply body forces based on user input, and color the body shape red - for(size_t i = 0; i < mPendulum->getNumBodyNodes(); ++i) + for(std::size_t i = 0; i < mPendulum->getNumBodyNodes(); ++i) { if(mForceCountDown[i] > 0) { diff --git a/unittests/testAspect.cpp b/unittests/testAspect.cpp index 29308d6ec1996..8a9b75aa772ba 100644 --- a/unittests/testAspect.cpp +++ b/unittests/testAspect.cpp @@ -564,7 +564,7 @@ TEST(Aspect, Releasing) template void makeStatesDifferent(AspectT* aspect, const AspectT* differentFrom) { - size_t counter = 0; + std::size_t counter = 0; while( aspect->mState.val == differentFrom->mState.val ) { aspect->randomize(); @@ -581,7 +581,7 @@ void makeStatesDifferent(AspectT* aspect, const AspectT* differentFrom) template void makePropertiesDifferent(AspectT* aspect, const AspectT* differentFrom) { - size_t counter = 0; + std::size_t counter = 0; while( aspect->mProperties.val == differentFrom->mProperties.val ) { aspect->randomize(); diff --git a/unittests/testCollision.cpp b/unittests/testCollision.cpp index 418d8980ad581..42bf4d992a3cb 100644 --- a/unittests/testCollision.cpp +++ b/unittests/testCollision.cpp @@ -123,7 +123,7 @@ void COLLISION::unrotatedTest(fcl::CollisionGeometry* _coll1, //printResult(result); - for (size_t i = 0; i < result.numContacts(); ++i) + for (std::size_t i = 0; i < result.numContacts(); ++i) { EXPECT_GE(result.getContact(i).penetration_depth, 0.0); // EXPECT_NEAR(result.getContact(i).normal[_idxAxis], -1.0); @@ -196,7 +196,7 @@ void COLLISION::dropWithRotation(fcl::CollisionGeometry* _object, fcl::Transform3f objectTransfInv = objectTransf; objectTransfInv.inverse(); - for (size_t i = 0; i < result.numContacts(); ++i) + for (std::size_t i = 0; i < result.numContacts(); ++i) { fcl::Vec3f posWorld = objectTransfInv.transform(result.getContact(i).pos); std::cout << "----- CONTACT " << i << " --------" << std::endl; @@ -216,7 +216,7 @@ void COLLISION::printResult(const fcl::CollisionResult& _result) std::cout << "====== [ RESULT ] ======" << std::endl; std::cout << "The number of contacts: " << _result.numContacts() << std::endl; - for (size_t i = 0; i < _result.numContacts(); ++i) + for (std::size_t i = 0; i < _result.numContacts(); ++i) { std::cout << "----- CONTACT " << i << " --------" << std::endl; std::cout << "contact_points: " << _result.getContact(i).pos << std::endl; @@ -456,7 +456,7 @@ TEST_F(COLLISION, FCL_BOX_BOX) << result.numContacts() << std::endl; - for (size_t i = 0; i < result.numContacts(); ++i) + for (std::size_t i = 0; i < result.numContacts(); ++i) { std::cout << "----- CONTACT " << i << " --------" << std::endl; std::cout << "contact_points: " << result.getContact(i).pos << std::endl; @@ -870,7 +870,7 @@ TEST_F(COLLISION, CollisionOfPrescribedJoints) const double tol = 1e-9; const double timeStep = 1e-3; - const size_t numFrames = 5e+0; // 5 secs + const std::size_t numFrames = 5e+0; // 5 secs // Load world and skeleton WorldPtr world = SkelParser::readWorld( @@ -911,7 +911,7 @@ TEST_F(COLLISION, CollisionOfPrescribedJoints) EXPECT_EQ(joint5->getActuatorType(), Joint::VELOCITY); EXPECT_EQ(joint6->getActuatorType(), Joint::LOCKED); - for (size_t i = 0; i < numFrames; ++i) + for (std::size_t i = 0; i < numFrames; ++i) { const double time = world->getTime(); diff --git a/unittests/testConcurrency.cpp b/unittests/testConcurrency.cpp index 84220e39ca4ae..2d0b7062b2125 100644 --- a/unittests/testConcurrency.cpp +++ b/unittests/testConcurrency.cpp @@ -49,7 +49,7 @@ using namespace dynamics; //============================================================================== void createAndDestroyFrames(int threadNum) { - for(size_t i=0; i < 100; ++i) + for(std::size_t i=0; i < 100; ++i) { EXPECT_EQ(Frame::World()->getNumChildEntities(), 0); EXPECT_EQ(Frame::World()->getNumChildFrames(), 0); @@ -67,11 +67,11 @@ TEST(Concurrency, FrameDeletion) { // Regression test for issue #576 std::vector> futures; - for(size_t i=0; i < 10; ++i) + for(std::size_t i=0; i < 10; ++i) futures.push_back(std::async(std::launch::async, &createAndDestroyFrames, i)); - for(size_t i=0; i < futures.size(); ++i) + for(std::size_t i=0; i < futures.size(); ++i) { EXPECT_EQ(Frame::World()->getNumChildEntities(), 0); EXPECT_EQ(Frame::World()->getNumChildFrames(), 0); diff --git a/unittests/testConstraint.cpp b/unittests/testConstraint.cpp index 34f60863e68b0..c1b61c86e53f7 100644 --- a/unittests/testConstraint.cpp +++ b/unittests/testConstraint.cpp @@ -116,9 +116,9 @@ void ConstraintTest::SingleContactTest(const std::string& /*_fileName*/) //---------------------------------------------------------------------------- // Number of random state tests for each skeletons #ifndef NDEBUG // Debug mode - // size_t testCount = 1; + // std::size_t testCount = 1; #else - // size_t testCount = 1; + // std::size_t testCount = 1; #endif WorldPtr world(new World); @@ -176,7 +176,7 @@ void ConstraintTest::SingleContactTest(const std::string& /*_fileName*/) continue; } - // for (size_t j = 0; j < cd->getNumContacts(); ++j) + // for (std::size_t j = 0; j < cd->getNumContacts(); ++j) // { // Contact contact = cd->getContact(j); // Vector3d pos1 = sphere->getTransform().inverse() * contact.point; diff --git a/unittests/testDynamics.cpp b/unittests/testDynamics.cpp index bd485d6a82e15..af9394718857d 100644 --- a/unittests/testDynamics.cpp +++ b/unittests/testDynamics.cpp @@ -170,7 +170,7 @@ const std::vector& DynamicsTest::getRefFrames() const //============================================================================== void DynamicsTest::randomizeRefFrames() { - for(size_t i=0; igetNumBodyNodes(); ++i) + for (std::size_t i = 0; i < _skel->getNumBodyNodes(); ++i) { dynamics::BodyNode* body = _skel->getBodyNode(i); @@ -240,7 +240,7 @@ MatrixXd DynamicsTest::getAugMassMatrix(dynamics::SkeletonPtr _skel) MatrixXd AugM; // Compute diagonal matrices of joint damping and joint stiffness - for (size_t i = 0; i < _skel->getNumBodyNodes(); ++i) + for (std::size_t i = 0; i < _skel->getNumBodyNodes(); ++i) { dynamics::BodyNode* body = _skel->getBodyNode(i); dynamics::Joint* joint = body->getParentJoint(); @@ -292,7 +292,7 @@ void compareBodyNodeFkToJacobian(const BodyNode* bn, VectorXd dq = skel->getVelocities(); VectorXd ddq = skel->getAccelerations(); - const std::vector& coords = bn->getDependentGenCoordIndices(); + const std::vector& coords = bn->getDependentGenCoordIndices(); VectorXd dqSeg = skel->getVelocities(coords); VectorXd ddqSeg = skel->getAccelerations(coords); @@ -431,7 +431,7 @@ void compareBodyNodeFkToJacobian(const BodyNode* bn, VectorXd dq = skel->getVelocities(); VectorXd ddq = skel->getAccelerations(); - const std::vector& coords = bn->getDependentGenCoordIndices(); + const std::vector& coords = bn->getDependentGenCoordIndices(); VectorXd dqSeg = skel->getVelocities(coords); VectorXd ddqSeg = skel->getAccelerations(coords); @@ -597,7 +597,7 @@ void DynamicsTest::testJacobians(const std::string& _fileName) world->setGravity(gravity); //------------------------------ Tests --------------------------------------- - for (size_t i = 0; i < world->getNumSkeletons(); ++i) + for (std::size_t i = 0; i < world->getNumSkeletons(); ++i) { SkeletonPtr skeleton = world->getSkeleton(i); assert(skeleton != nullptr); @@ -609,7 +609,7 @@ void DynamicsTest::testJacobians(const std::string& _fileName) if(j > ceil(nTestItr/2)) { SkeletonPtr copy = skeleton->clone(); - size_t maxNode = skeleton->getNumBodyNodes()-1; + std::size_t maxNode = skeleton->getNumBodyNodes()-1; BodyNode* bn1 = skeleton->getBodyNode(ceil(math::random(0, maxNode))); BodyNode* bn2 = skeleton->getBodyNode(ceil(math::random(0, maxNode))); @@ -642,7 +642,7 @@ void DynamicsTest::testJacobians(const std::string& _fileName) randomizeRefFrames(); // For each body node - for (size_t k = 0; k < skeleton->getNumBodyNodes(); ++k) + for (std::size_t k = 0; k < skeleton->getNumBodyNodes(); ++k) { const BodyNode* bn = skeleton->getBodyNode(k); @@ -652,7 +652,7 @@ void DynamicsTest::testJacobians(const std::string& _fileName) compareBodyNodeFkToJacobian(bn, bn, TOLERANCE); // Compare results using the randomized reference Frames - for(size_t r=0; rgetLocalCOM(), TOLERANCE); compareBodyNodeFkToJacobian(bn, bn, bn->getLocalCOM(), TOLERANCE); - for(size_t r=0; rgetLocalCOM(), TOLERANCE); @@ -671,7 +671,7 @@ void DynamicsTest::testJacobians(const std::string& _fileName) bn, Frame::World(), randomVector<3>(10), TOLERANCE); compareBodyNodeFkToJacobian(bn, bn, randomVector<3>(10), TOLERANCE); - for(size_t r=0; r(10), TOLERANCE); @@ -716,7 +716,7 @@ void DynamicsTest::testFiniteDifferenceGeneralizedCoordinates( world->setTimeStep(timeStep); //------------------------------ Tests --------------------------------------- - for (size_t i = 0; i < world->getNumSkeletons(); ++i) + for (std::size_t i = 0; i < world->getNumSkeletons(); ++i) { SkeletonPtr skeleton = world->getSkeleton(i); assert(skeleton != nullptr); @@ -798,10 +798,10 @@ void DynamicsTest::testFiniteDifferenceBodyNodeVelocity( //----------------------------- Settings ------------------------------------- #ifndef NDEBUG // Debug mode int nRandomItr = 2; - size_t numSteps = 1e+1; + std::size_t numSteps = 1e+1; #else int nRandomItr = 10; - size_t numSteps = 1e+3; + std::size_t numSteps = 1e+3; #endif double qLB = -0.5 * constantsd::pi(); double qUB = 0.5 * constantsd::pi(); @@ -822,13 +822,13 @@ void DynamicsTest::testFiniteDifferenceBodyNodeVelocity( //------------------------------ Tests --------------------------------------- for (int i = 0; i < nRandomItr; ++i) { - for (size_t j = 0; j < world->getNumSkeletons(); ++j) + for (std::size_t j = 0; j < world->getNumSkeletons(); ++j) { SkeletonPtr skeleton = world->getSkeleton(j); EXPECT_NE(skeleton, nullptr); - size_t dof = skeleton->getNumDofs(); - size_t numBodies = skeleton->getNumBodyNodes(); + std::size_t dof = skeleton->getNumDofs(); + std::size_t numBodies = skeleton->getNumBodyNodes(); // Generate random states VectorXd q = randomVectorXd(dof, qLB, qUB); @@ -846,12 +846,12 @@ void DynamicsTest::testFiniteDifferenceBodyNodeVelocity( Tmap[body] = body->getTransform(); } - for (size_t k = 0; k < numSteps; ++k) + for (std::size_t k = 0; k < numSteps; ++k) { skeleton->integrateVelocities(skeleton->getTimeStep()); skeleton->integratePositions(skeleton->getTimeStep()); - for (size_t l = 0; l < skeleton->getNumBodyNodes(); ++l) + for (std::size_t l = 0; l < skeleton->getNumBodyNodes(); ++l) { BodyNodePtr body = skeleton->getBodyNode(l); @@ -915,7 +915,7 @@ void DynamicsTest::testFiniteDifferenceBodyNodeAcceleration( world->setTimeStep(timeStep); //------------------------------ Tests --------------------------------------- - for (size_t i = 0; i < world->getNumSkeletons(); ++i) + for (std::size_t i = 0; i < world->getNumSkeletons(); ++i) { SkeletonPtr skeleton = world->getSkeleton(i); assert(skeleton != nullptr); @@ -935,7 +935,7 @@ void DynamicsTest::testFiniteDifferenceBodyNodeAcceleration( } // For each body node - for (size_t k = 0; k < skeleton->getNumBodyNodes(); ++k) + for (std::size_t k = 0; k < skeleton->getNumBodyNodes(); ++k) { BodyNode* bn = skeleton->getBodyNode(k); @@ -1038,11 +1038,11 @@ void DynamicsTest::testFiniteDifferenceBodyNodeAcceleration( void testForwardKinematicsSkeleton(const dynamics::SkeletonPtr& skel) { #ifndef NDEBUG // Debug mode - size_t nRandomItr = 1e+1; - size_t numSteps = 1e+1; + std::size_t nRandomItr = 1e+1; + std::size_t numSteps = 1e+1; #else - size_t nRandomItr = 1e+2; - size_t numSteps = 1e+2; + std::size_t nRandomItr = 1e+2; + std::size_t numSteps = 1e+2; #endif double qLB = -0.5 * constantsd::pi(); double qUB = 0.5 * constantsd::pi(); @@ -1188,9 +1188,9 @@ void DynamicsTest::compareEquationsOfMotion(const std::string& _fileName) //---------------------------- Settings -------------------------------------- // Number of random state tests for each skeletons #ifndef NDEBUG // Debug mode - size_t nRandomItr = 2; + std::size_t nRandomItr = 2; #else - size_t nRandomItr = 100; + std::size_t nRandomItr = 100; #endif // Lower and upper bound of configuration for system @@ -1211,11 +1211,11 @@ void DynamicsTest::compareEquationsOfMotion(const std::string& _fileName) myWorld = utils::SkelParser::readWorld(_fileName); EXPECT_TRUE(myWorld != nullptr); - for (size_t i = 0; i < myWorld->getNumSkeletons(); ++i) + for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) { dynamics::SkeletonPtr skel = myWorld->getSkeleton(i); - size_t dof = skel->getNumDofs(); + std::size_t dof = skel->getNumDofs(); // int nBodyNodes = skel->getNumBodyNodes(); if (dof == 0) @@ -1225,16 +1225,16 @@ void DynamicsTest::compareEquationsOfMotion(const std::string& _fileName) continue; } - for (size_t j = 0; j < nRandomItr; ++j) + for (std::size_t j = 0; j < nRandomItr; ++j) { // Random joint stiffness and damping coefficient - for (size_t k = 0; k < skel->getNumBodyNodes(); ++k) + for (std::size_t k = 0; k < skel->getNumBodyNodes(); ++k) { BodyNode* body = skel->getBodyNode(k); Joint* joint = body->getParentJoint(); - size_t localDof = joint->getNumDofs(); + std::size_t localDof = joint->getNumDofs(); - for (size_t l = 0; l < localDof; ++l) + for (std::size_t l = 0; l < localDof; ++l) { joint->setDampingCoefficient(l, random(lbD, ubD)); joint->setSpringStiffness (l, random(lbK, ubK)); @@ -1252,7 +1252,7 @@ void DynamicsTest::compareEquationsOfMotion(const std::string& _fileName) // Set random states Skeleton::Configuration x = skel->getConfiguration( Skeleton::CONFIG_POSITIONS | Skeleton::CONFIG_VELOCITIES); - for (size_t k = 0u; k < skel->getNumDofs(); ++k) + for (std::size_t k = 0u; k < skel->getNumDofs(); ++k) { x.mPositions[k] = random(lb, ub); x.mVelocities[k] = random(lb, ub); @@ -1465,9 +1465,9 @@ void DynamicsTest::testCenterOfMass(const std::string& _fileName) //---------------------------- Settings -------------------------------------- // Number of random state tests for each skeletons #ifndef NDEBUG // Debug mode - size_t nRandomItr = 2; + std::size_t nRandomItr = 2; #else - size_t nRandomItr = 100; + std::size_t nRandomItr = 100; #endif // Lower and upper bound of configuration for system @@ -1488,11 +1488,11 @@ void DynamicsTest::testCenterOfMass(const std::string& _fileName) myWorld = utils::SkelParser::readWorld(_fileName); EXPECT_TRUE(myWorld != nullptr); - for (size_t i = 0; i < myWorld->getNumSkeletons(); ++i) + for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) { dynamics::SkeletonPtr skeleton = myWorld->getSkeleton(i); - size_t dof = skeleton->getNumDofs(); + std::size_t dof = skeleton->getNumDofs(); if (dof == 0) { dtmsg << "Skeleton [" << skeleton->getName() << "] is skipped since it " @@ -1500,13 +1500,13 @@ void DynamicsTest::testCenterOfMass(const std::string& _fileName) continue; } - for (size_t j = 0; j < nRandomItr; ++j) + for (std::size_t j = 0; j < nRandomItr; ++j) { // For the second half of the tests, scramble up the Skeleton if(j > ceil(nRandomItr/2)) { SkeletonPtr copy = skeleton->clone(); - size_t maxNode = skeleton->getNumBodyNodes()-1; + std::size_t maxNode = skeleton->getNumBodyNodes()-1; BodyNode* bn1 = skeleton->getBodyNode(ceil(math::random(0, maxNode))); BodyNode* bn2 = skeleton->getBodyNode(ceil(math::random(0, maxNode))); @@ -1523,7 +1523,7 @@ void DynamicsTest::testCenterOfMass(const std::string& _fileName) } // Random joint stiffness and damping coefficient - for (size_t k = 0; k < skeleton->getNumBodyNodes(); ++k) + for (std::size_t k = 0; k < skeleton->getNumBodyNodes(); ++k) { BodyNode* body = skeleton->getBodyNode(k); Joint* joint = body->getParentJoint(); @@ -1548,7 +1548,7 @@ void DynamicsTest::testCenterOfMass(const std::string& _fileName) VectorXd q = VectorXd(dof); VectorXd dq = VectorXd(dof); VectorXd ddq = VectorXd(dof); - for (size_t k = 0; k < dof; ++k) + for (std::size_t k = 0; k < dof; ++k) { q[k] = math::random(lb, ub); dq[k] = math::random(lb, ub); @@ -1562,7 +1562,7 @@ void DynamicsTest::testCenterOfMass(const std::string& _fileName) compareCOMJacobianToFk(skeleton, Frame::World(), 1e-6); - for(size_t r=0; rsetGravity(gravity); - for (size_t i = 0; i < numFrames; ++i) + for (std::size_t i = 0; i < numFrames; ++i) { skel->computeForwardDynamics(); @@ -1621,9 +1621,9 @@ void DynamicsTest::testCenterOfMassFreeFall(const std::string& _fileName) //---------------------------- Settings -------------------------------------- // Number of random state tests for each skeletons #ifndef NDEBUG // Debug mode - size_t nRandomItr = 2; + std::size_t nRandomItr = 2; #else - size_t nRandomItr = 10; + std::size_t nRandomItr = 10; #endif // ------- Debug mode // Lower and upper bound of configuration for system @@ -1649,7 +1649,7 @@ void DynamicsTest::testCenterOfMassFreeFall(const std::string& _fileName) myWorld = utils::SkelParser::readWorld(_fileName); EXPECT_TRUE(myWorld != nullptr); - for (size_t i = 0; i < myWorld->getNumSkeletons(); ++i) + for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) { auto skel = myWorld->getSkeleton(i); auto rootJoint = skel->getJoint(0); @@ -1672,23 +1672,23 @@ void DynamicsTest::testCenterOfMassFreeFall(const std::string& _fileName) } // Make sure the damping and spring forces are zero for the root FreeJoint. - for (size_t l = 0; l < rootJoint->getNumDofs(); ++l) + for (std::size_t l = 0; l < rootJoint->getNumDofs(); ++l) { rootJoint->setDampingCoefficient(l, 0.0); rootJoint->setSpringStiffness(l, 0.0); rootJoint->setRestPosition(l, 0.0); } - for (size_t j = 0; j < nRandomItr; ++j) + for (std::size_t j = 0; j < nRandomItr; ++j) { // Random joint stiffness and damping coefficient - for (size_t k = 1; k < skel->getNumBodyNodes(); ++k) + for (std::size_t k = 1; k < skel->getNumBodyNodes(); ++k) { auto body = skel->getBodyNode(k); auto joint = body->getParentJoint(); auto localDof = joint->getNumDofs(); - for (size_t l = 0; l < localDof; ++l) + for (std::size_t l = 0; l < localDof; ++l) { joint->setDampingCoefficient(l, random(lbD, ubD)); joint->setSpringStiffness(l, random(lbK, ubK)); @@ -1706,7 +1706,7 @@ void DynamicsTest::testCenterOfMassFreeFall(const std::string& _fileName) // Set random states VectorXd q = VectorXd(dof); VectorXd dq = VectorXd(dof); - for (size_t k = 0; k < dof; ++k) + for (std::size_t k = 0; k < dof; ++k) { q[k] = math::random(lb, ub); dq[k] = math::random(lb, ub); @@ -1736,9 +1736,9 @@ void DynamicsTest::testConstraintImpulse(const std::string& _fileName) //---------------------------- Settings -------------------------------------- // Number of random state tests for each skeletons #ifndef NDEBUG // Debug mode - size_t nRandomItr = 1; + std::size_t nRandomItr = 1; #else - size_t nRandomItr = 1; + std::size_t nRandomItr = 1; #endif // Lower and upper bound of configuration for system @@ -1753,11 +1753,11 @@ void DynamicsTest::testConstraintImpulse(const std::string& _fileName) myWorld = utils::SkelParser::readWorld(_fileName); EXPECT_TRUE(myWorld != nullptr); - for (size_t i = 0; i < myWorld->getNumSkeletons(); ++i) + for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) { dynamics::SkeletonPtr skel = myWorld->getSkeleton(i); - size_t dof = skel->getNumDofs(); + std::size_t dof = skel->getNumDofs(); // int nBodyNodes = skel->getNumBodyNodes(); if (dof == 0 || !skel->isMobile()) @@ -1767,10 +1767,10 @@ void DynamicsTest::testConstraintImpulse(const std::string& _fileName) continue; } - for (size_t j = 0; j < nRandomItr; ++j) + for (std::size_t j = 0; j < nRandomItr; ++j) { // Set random configurations - for (size_t k = 0; k < skel->getNumBodyNodes(); ++k) + for (std::size_t k = 0; k < skel->getNumBodyNodes(); ++k) { BodyNode* body = skel->getBodyNode(k); Joint* joint = body->getParentJoint(); @@ -1801,8 +1801,8 @@ void DynamicsTest::testConstraintImpulse(const std::string& _fileName) * impulseOnBody / skel->getTimeStep(); - size_t index = 0; - for (size_t l = 0; l < dof; ++l) + std::size_t index = 0; + for (std::size_t l = 0; l < dof; ++l) { if (constraintVector1(l) == 0.0) continue; @@ -1810,7 +1810,7 @@ void DynamicsTest::testConstraintImpulse(const std::string& _fileName) EXPECT_NEAR(constraintVector1(l), constraintVector2(index), 1e-6); index++; } - assert(static_cast(bodyJacobian.cols()) == index); + assert(static_cast(bodyJacobian.cols()) == index); } } } @@ -1830,9 +1830,9 @@ void DynamicsTest::testImpulseBasedDynamics(const std::string& _fileName) //---------------------------- Settings -------------------------------------- // Number of random state tests for each skeletons #ifndef NDEBUG // Debug mode - size_t nRandomItr = 1; + std::size_t nRandomItr = 1; #else - size_t nRandomItr = 100; + std::size_t nRandomItr = 100; #endif double TOLERANCE = 1e-3; @@ -1849,7 +1849,7 @@ void DynamicsTest::testImpulseBasedDynamics(const std::string& _fileName) myWorld = utils::SkelParser::readWorld(_fileName); EXPECT_TRUE(myWorld != nullptr); - for (size_t i = 0; i < myWorld->getNumSkeletons(); ++i) + for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) { dynamics::SkeletonPtr skel = myWorld->getSkeleton(i); @@ -1863,10 +1863,10 @@ void DynamicsTest::testImpulseBasedDynamics(const std::string& _fileName) continue; } - for (size_t j = 0; j < nRandomItr; ++j) + for (std::size_t j = 0; j < nRandomItr; ++j) { // Set random configurations - for (size_t k = 0; k < skel->getNumBodyNodes(); ++k) + for (std::size_t k = 0; k < skel->getNumBodyNodes(); ++k) { BodyNode* body = skel->getBodyNode(k); Joint* joint = body->getParentJoint(); @@ -1917,7 +1917,7 @@ void DynamicsTest::testImpulseBasedDynamics(const std::string& _fileName) //============================================================================== TEST_F(DynamicsTest, testJacobians) { - for (size_t i = 0; i < getList().size(); ++i) + for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG dtdbg << getList()[i] << std::endl; @@ -1929,7 +1929,7 @@ TEST_F(DynamicsTest, testJacobians) //============================================================================== TEST_F(DynamicsTest, testFiniteDifference) { - for (size_t i = 0; i < getList().size(); ++i) + for (std::size_t i = 0; i < getList().size(); ++i) { #if BUILD_TYPE_DEBUG dtdbg << getList()[i] << std::endl; @@ -1943,7 +1943,7 @@ TEST_F(DynamicsTest, testFiniteDifference) //============================================================================== TEST_F(DynamicsTest, testForwardKinematics) { - for (size_t i = 0; i < getList().size(); ++i) + for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG dtdbg << getList()[i] << std::endl; @@ -1955,7 +1955,7 @@ TEST_F(DynamicsTest, testForwardKinematics) //============================================================================== TEST_F(DynamicsTest, compareEquationsOfMotion) { - for (size_t i = 0; i < getList().size(); ++i) + for (std::size_t i = 0; i < getList().size(); ++i) { //////////////////////////////////////////////////////////////////////////// // TODO(JS): Following skel files, which contain euler joints couldn't @@ -1982,7 +1982,7 @@ TEST_F(DynamicsTest, compareEquationsOfMotion) //============================================================================== TEST_F(DynamicsTest, testCenterOfMass) { - for (size_t i = 0; i < getList().size(); ++i) + for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG dtdbg << getList()[i] << std::endl; @@ -1994,7 +1994,7 @@ TEST_F(DynamicsTest, testCenterOfMass) //============================================================================== TEST_F(DynamicsTest, testCenterOfMassFreeFall) { - for (size_t i = 0; i < getList().size(); ++i) + for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG dtdbg << getList()[i] << std::endl; @@ -2006,7 +2006,7 @@ TEST_F(DynamicsTest, testCenterOfMassFreeFall) //============================================================================== TEST_F(DynamicsTest, testConstraintImpulse) { - for (size_t i = 0; i < getList().size(); ++i) + for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG dtdbg << getList()[i] << std::endl; @@ -2018,7 +2018,7 @@ TEST_F(DynamicsTest, testConstraintImpulse) //============================================================================== TEST_F(DynamicsTest, testImpulseBasedDynamics) { - for (size_t i = 0; i < getList().size(); ++i) + for (std::size_t i = 0; i < getList().size(); ++i) { #ifndef NDEBUG dtdbg << getList()[i] << std::endl; @@ -2033,9 +2033,9 @@ TEST_F(DynamicsTest, HybridDynamics) const double tol = 1e-9; const double timeStep = 1e-3; #ifndef NDEBUG // Debug mode - const size_t numFrames = 50; // 0.05 secs + const std::size_t numFrames = 50; // 0.05 secs #else - const size_t numFrames = 5e+3; // 5 secs + const std::size_t numFrames = 5e+3; // 5 secs #endif // ------- Debug mode // Load world and skeleton @@ -2049,7 +2049,7 @@ TEST_F(DynamicsTest, HybridDynamics) EXPECT_TRUE(skel != nullptr); EXPECT_NEAR(skel->getTimeStep(), timeStep, tol); - const size_t numDofs = skel->getNumDofs(); + const std::size_t numDofs = skel->getNumDofs(); // Zero initial states Eigen::VectorXd q0 = Eigen::VectorXd::Zero(numDofs); @@ -2071,17 +2071,17 @@ TEST_F(DynamicsTest, HybridDynamics) // Prepare command for each joint types per simulation steps Eigen::MatrixXd command = Eigen::MatrixXd::Zero(numFrames, numDofs); Eigen::VectorXd amp = Eigen::VectorXd::Zero(numDofs); - for (size_t i = 0; i < numDofs; ++i) + for (std::size_t i = 0; i < numDofs; ++i) amp[i] = math::random(-1.5, 1.5); - for (size_t i = 0; i < numFrames; ++i) + for (std::size_t i = 0; i < numFrames; ++i) { - for (size_t j = 0; j < numDofs; ++j) + for (std::size_t j = 0; j < numDofs; ++j) command(i,j) = amp[j] * std::sin(i * timeStep); } // Record joint forces for joint[1~4] Eigen::MatrixXd forces = Eigen::MatrixXd::Zero(numFrames, numDofs); - for (size_t i = 0; i < numFrames; ++i) + for (std::size_t i = 0; i < numFrames; ++i) { skel->setCommands(command.row(i)); @@ -2116,7 +2116,7 @@ TEST_F(DynamicsTest, HybridDynamics) // Test if the skeleton moves as the command with the joint forces Eigen::MatrixXd output = Eigen::MatrixXd::Zero(numFrames, numDofs); - for (size_t i = 0; i < numFrames; ++i) + for (std::size_t i = 0; i < numFrames; ++i) { skel->setCommands(forces.row(i)); diff --git a/unittests/testFileInfoWorld.cpp b/unittests/testFileInfoWorld.cpp index 85ddf23231fb8..b791741c88fdb 100644 --- a/unittests/testFileInfoWorld.cpp +++ b/unittests/testFileInfoWorld.cpp @@ -56,7 +56,7 @@ using namespace utils; //============================================================================== TEST(FileInfoWorld, Basic) { - const size_t numFrames = 100; + const std::size_t numFrames = 100; const std::string fileName = "testWorld.txt"; double tol = 1e-6; bool result = false; @@ -70,7 +70,7 @@ TEST(FileInfoWorld, Basic) Recording* recording2 = nullptr; // Do some simulation with recording - for (size_t i = 0; i < numFrames; ++i) + for (std::size_t i = 0; i < numFrames; ++i) { world->step(); world->bake(); @@ -94,22 +94,22 @@ TEST(FileInfoWorld, Basic) EXPECT_EQ(recording2->getNumFrames(), (int)numFrames); // Check number of skeletons - size_t numSkeletons = recording1->getNumSkeletons(); + std::size_t numSkeletons = recording1->getNumSkeletons(); EXPECT_EQ(recording1->getNumSkeletons(), recording2->getNumSkeletons()); // Check number of dofs of the skeletons - for (size_t i = 0; i < numSkeletons; ++i) + for (std::size_t i = 0; i < numSkeletons; ++i) EXPECT_EQ(recording1->getNumDofs(i), recording2->getNumDofs(i)); // Check generalized positions and contact info - for (size_t i = 0; i < numFrames; ++i) + for (std::size_t i = 0; i < numFrames; ++i) { // Check generalized positions - for (size_t j = 0; j < numSkeletons; ++j) + for (std::size_t j = 0; j < numSkeletons; ++j) { - size_t dofs = recording1->getNumDofs(j); + std::size_t dofs = recording1->getNumDofs(j); - for (size_t k = 0; k < dofs; ++k) + for (std::size_t k = 0; k < dofs; ++k) { EXPECT_NEAR(recording1->getGenCoord(i, j, k), recording2->getGenCoord(i, j, k), tol); @@ -118,12 +118,12 @@ TEST(FileInfoWorld, Basic) // Check contact info tol = 1e-3; - size_t numContacts = recording1->getNumContacts(i); + std::size_t numContacts = recording1->getNumContacts(i); EXPECT_EQ(recording1->getNumContacts(i), recording2->getNumContacts(i)); - for (size_t j = 0; j < numContacts; ++j) + for (std::size_t j = 0; j < numContacts; ++j) { - for (size_t k = 0; k < 3; ++k) + for (std::size_t k = 0; k < 3; ++k) { EXPECT_NEAR(recording1->getContactForce(i, j)[k], recording2->getContactForce(i, j)[k], tol); diff --git a/unittests/testForwardKinematics.cpp b/unittests/testForwardKinematics.cpp index 3ad131140e580..74c8c88169978 100644 --- a/unittests/testForwardKinematics.cpp +++ b/unittests/testForwardKinematics.cpp @@ -40,7 +40,7 @@ #include "dart/utils/urdf/DartLoader.h" -std::vector twoLinkIndices; +std::vector twoLinkIndices; //============================================================================== TEST(FORWARD_KINEMATICS, YAW_ROLL) @@ -58,7 +58,7 @@ TEST(FORWARD_KINEMATICS, YAW_ROLL) // Set the test cases with the joint values and the expected end-effector // positions - const size_t numTests = 2; + const std::size_t numTests = 2; double temp = sqrt(0.5*l2*l2); Vector2d joints [numTests] = { Vector2d( constantsd::pi()/4.0, constantsd::pi()/2.0), Vector2d(-constantsd::pi()/4.0, -constantsd::pi()/4.0) }; @@ -68,7 +68,7 @@ TEST(FORWARD_KINEMATICS, YAW_ROLL) // Check each case by setting the joint values and obtaining the end-effector // position - for (size_t i = 0; i < numTests; i++) + for (std::size_t i = 0; i < numTests; i++) { robot->setPositions(Eigen::VectorXd(joints[i])); BodyNode* bn = robot->getBodyNode("ee"); @@ -101,7 +101,7 @@ TEST(FORWARD_KINEMATICS, TWO_ROLLS) // Set the test cases with the joint values and the expected end-effector // positions - const size_t numTests = 2; + const std::size_t numTests = 2; Vector2d joints [numTests] = { Vector2d(0.0, constantsd::pi()/2.0), Vector2d(3*constantsd::pi()/4.0, -constantsd::pi()/4.0)}; @@ -110,7 +110,7 @@ TEST(FORWARD_KINEMATICS, TWO_ROLLS) // Check each case by setting the joint values and obtaining the end-effector // position - for (size_t i = 0; i < numTests; i++) + for (std::size_t i = 0; i < numTests; i++) { robot->setPositions(joints[i]); Vector3d actual @@ -130,7 +130,7 @@ TEST(FORWARD_KINEMATICS, TWO_ROLLS) Eigen::MatrixXd finiteDifferenceJacobian( const SkeletonPtr& skeleton, const Eigen::VectorXd& q, - const std::vector& active_indices) + const std::vector& active_indices) { Eigen::MatrixXd J(3, q.size()); for(int i=0; i < q.size(); ++i) @@ -162,7 +162,7 @@ Eigen::MatrixXd finiteDifferenceJacobian( Eigen::MatrixXd standardJacobian( const SkeletonPtr& skeleton, const Eigen::VectorXd& q, - const std::vector& active_indices) + const std::vector& active_indices) { skeleton->setPositions(active_indices, q); BodyNode* last_bn = skeleton->getBodyNode(skeleton->getNumBodyNodes()-1); @@ -188,8 +188,8 @@ TEST(FORWARD_KINEMATICS, JACOBIAN_PARTIAL_CHANGE) SkeletonPtr skeleton2 = skeleton1->clone(); - std::vector active_indices; - for(size_t i=0; i < 3; ++i) + std::vector active_indices; + for(std::size_t i=0; i < 3; ++i) active_indices.push_back(i); Eigen::VectorXd q = Eigen::VectorXd::Random(active_indices.size()); diff --git a/unittests/testFrames.cpp b/unittests/testFrames.cpp index 2d5397b5cc082..9377d4b8d2963 100644 --- a/unittests/testFrames.cpp +++ b/unittests/testFrames.cpp @@ -66,7 +66,7 @@ void randomize_transform(Eigen::Isometry3d& tf, void randomize_transforms(Eigen::aligned_vector& tfs) { - for(size_t i=0; isetRelativeTransform(tfs[i]); } - for(size_t i=0; isetRelativeTransform(tfs[i]); } Eigen::Isometry3d expectation(Eigen::Isometry3d::Identity()); - for(size_t j=0; jgetTransform().matrix(), @@ -196,7 +196,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) Eigen::aligned_vector v_rels(frames.size()); Eigen::aligned_vector v_total(frames.size()); - for(size_t i=0; i(); @@ -211,7 +211,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) F->getRelativeTransform(), v_total[i]); } - for(size_t i=0; i v_total(frames.size()); std::vector w_total(frames.size()); - for(size_t i=0; i(); w_rels[i] = random_vec<3>(); @@ -251,7 +251,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) offset, tf, v_total[i], w_total[i]); } - for(size_t i=0; igetLinearVelocity(); @@ -273,7 +273,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) Eigen::aligned_vector a_total(frames.size()); - for(size_t i=0; i(); a_rels[i] = random_vec<6>(); @@ -298,7 +298,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) } } - for(size_t i=0; igetParentFrame(); @@ -321,7 +321,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) } // Test offset computations - for(size_t i=0; i(); Frame* F = frames[i]; @@ -363,7 +363,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) std::vector a_total(frames.size()); std::vector alpha_total(frames.size()); - for(size_t i=0; i(); w_rels[i] = random_vec<3>(); @@ -401,7 +401,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) } } - for(size_t i=0; igetLinearVelocity(); @@ -416,7 +416,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) } // Test relative computations - for(size_t i=0; igetParentFrame(); @@ -436,7 +436,7 @@ TEST(FRAMES, FORWARD_KINEMATICS_CHAIN) void randomize_target_values(const std::vector& targets, bool spatial) { - for(size_t i=0; i& targets, const std::vector& followers, bool spatial) { - for(size_t i=0; i& targets, const std::vector& followers, double tolerance) { - for(size_t i=0; i& targets, const Frame* inCoordinatesOf, double tolerance) { - for(size_t i=0; i& targets, const Frame* inCoordinatesOf, double tolerance) { - for(size_t i=0; igetNumDofs(); +// std::size_t dof = robot->getNumDofs(); // VectorXd oldConfig = robot->getPositions(); // BodyNode* body1 = robot->getBodyNode(0); @@ -114,7 +114,7 @@ SkeletonPtr createFreeFloatingTwoLinkRobot(Vector3d dim1, // //------------------------- Free joint test ---------------------------------- // // The parent joint of body1 is free joint so body1 should be able to // // transform to arbitrary tramsformation. -// for (size_t i = 0; i < numRandomTests; ++i) +// for (std::size_t i = 0; i < numRandomTests; ++i) // { // // Get desiredT2 by transforming body1 to arbitrary transformation // Isometry3d desiredT1 = math::expMap(Vector6d::Random()); @@ -132,7 +132,7 @@ SkeletonPtr createFreeFloatingTwoLinkRobot(Vector3d dim1, // //----------------------- Revolute joint test --------------------------------- // // The parent joint of body2 is revolute joint so body2 can rotate along the // // axis of the revolute joint. -// for (size_t i = 0; i < numRandomTests; ++i) +// for (std::size_t i = 0; i < numRandomTests; ++i) // { // // Store the original transformation and joint angle // Isometry3d oldT2 = body2->getWorldTransform(); @@ -159,7 +159,7 @@ SkeletonPtr createFreeFloatingTwoLinkRobot(Vector3d dim1, // } // //---------------- Revolute joint test with joint limit ---------------------- -// for (size_t i = 0; i < numRandomTests; ++i) +// for (std::size_t i = 0; i < numRandomTests; ++i) // { // // Set joint limit // joint2->setPositionLowerLimit(0, DART_RADIAN * 0.0); @@ -205,9 +205,9 @@ SkeletonPtr createFreeFloatingTwoLinkRobot(Vector3d dim1, //{ // const double TOLERANCE = 1e-4; //#if BUILD_TYPE_RELEASE -// const size_t numRandomTests = 100; +// const std::size_t numRandomTests = 100; //#else -// const size_t numRandomTests = 10; +// const std::size_t numRandomTests = 10; //#endif // // Create two link robot @@ -226,7 +226,7 @@ SkeletonPtr createFreeFloatingTwoLinkRobot(Vector3d dim1, // //------------------------- Free joint test ---------------------------------- // // The parent joint of body1 is free joint so body1 should be able to // // transform to arbitrary tramsformation. -// for (size_t i = 0; i < numRandomTests; ++i) +// for (std::size_t i = 0; i < numRandomTests; ++i) // { // // Test for linear velocity // Vector3d desiredVel = Vector3d::Random(); diff --git a/unittests/testJoints.cpp b/unittests/testJoints.cpp index c39f19431ae76..0991d0a2df8f1 100644 --- a/unittests/testJoints.cpp +++ b/unittests/testJoints.cpp @@ -119,7 +119,7 @@ const std::vector& JOINTS::getFrames() const //============================================================================== void JOINTS::randomizeRefFrames() { - for(size_t i=0; idisableSelfCollision(); - for (size_t i = 0; i < pendulum->getNumBodyNodes(); ++i) + for (std::size_t i = 0; i < pendulum->getNumBodyNodes(); ++i) { auto bodyNode = pendulum->getBodyNode(i); bodyNode->removeAllShapeNodesWith(); @@ -662,7 +662,7 @@ void testServoMotor() { using namespace dart::math::suffixes; - size_t numPendulums = 7; + std::size_t numPendulums = 7; double timestep = 1e-3; double tol = 1e-9; double posUpperLimit = 90.0_deg; @@ -715,7 +715,7 @@ void testServoMotor() std::vector pendulums(numPendulums); std::vector joints(numPendulums); - for (size_t i = 0; i < numPendulums; ++i) + for (std::size_t i = 0; i < numPendulums; ++i) { pendulums[i] = createPendulum(Joint::SERVO); joints[i] = pendulums[i]->getJoint(0); @@ -775,7 +775,7 @@ void testServoMotor() world->step(); std::vector jointVels(numPendulums); - for (size_t j = 0; j < numPendulums; ++j) + for (std::size_t j = 0; j < numPendulums; ++j) jointVels[j] = joints[j]->getVelocity(0); EXPECT_NEAR(jointVels[0], 0.0, tol); @@ -845,8 +845,8 @@ TEST_F(JOINTS, JOINT_COULOMB_FRICTION_AND_POSITION_LIMIT) const double ll = -constantsd::pi()/12.0; // -15 degree const double ul = +constantsd::pi()/12.0; // +15 degree - size_t dof0 = joint0->getNumDofs(); - for (size_t i = 0; i < dof0; ++i) + std::size_t dof0 = joint0->getNumDofs(); + for (std::size_t i = 0; i < dof0; ++i) { joint0->setPosition(i, 0.0); joint0->setPosition(i, 0.0); @@ -854,8 +854,8 @@ TEST_F(JOINTS, JOINT_COULOMB_FRICTION_AND_POSITION_LIMIT) joint0->setPositionUpperLimit(i, ul); } - size_t dof1 = joint1->getNumDofs(); - for (size_t i = 0; i < dof1; ++i) + std::size_t dof1 = joint1->getNumDofs(); + for (std::size_t i = 0; i < dof1; ++i) { joint1->setPosition(i, 0.0); joint1->setPosition(i, 0.0); @@ -930,7 +930,7 @@ template Eigen::Matrix random_vec(double limit=100) { Eigen::Matrix v; - for(size_t i=0; isetTransformFromChildBodyNode(random_transform()); // Test a hundred times - for(size_t n=0; n<100; ++n) + for(std::size_t n=0; n<100; ++n) { // -- convert transforms to positions and then positions back to transforms Eigen::Isometry3d desired_freejoint_tf = random_transform(); @@ -1047,7 +1047,7 @@ TEST_F(JOINTS, CONVENIENCE_FUNCTIONS) desired_tfs.push_back(desired_balljoint_tf); actual_tfs.push_back(actual_balljoint_tf); - for(size_t i=0; igetNumDofs(); ++i) + for (std::size_t i = 0; i < skel->getNumDofs(); ++i) EXPECT_TRUE(skel->getDof(i)->getIndexInSkeleton() == i); // Test whether all the joint names are still unique diff --git a/unittests/testOptimizer.cpp b/unittests/testOptimizer.cpp index f9342b52f1282..a1f149441858f 100644 --- a/unittests/testOptimizer.cpp +++ b/unittests/testOptimizer.cpp @@ -172,7 +172,7 @@ TEST(Optimizer, BasicNlopt) Eigen::VectorXd optX = prob->getOptimalSolution(); EXPECT_NEAR(minF, 0.544330847, 1e-6); - EXPECT_EQ(static_cast(optX.size()), prob->getDimension()); + EXPECT_EQ(static_cast(optX.size()), prob->getDimension()); EXPECT_NEAR(optX[0], 0.333334, 1e-6); EXPECT_NEAR(optX[1], 0.296296, 1e-6); } @@ -205,7 +205,7 @@ TEST(Optimizer, BasicIpopt) Eigen::VectorXd optX = prob->getOptimalSolution(); EXPECT_NEAR(minF, 0.544330847, 1e-6); - EXPECT_EQ(static_cast(optX.size()), prob->getDimension()); + EXPECT_EQ(static_cast(optX.size()), prob->getDimension()); EXPECT_NEAR(optX[0], 0.333334, 1e-6); EXPECT_NEAR(optX[1], 0.296296, 1e-6); } diff --git a/unittests/testSkeleton.cpp b/unittests/testSkeleton.cpp index 9c06dbc9a55c4..a930e06fddbf2 100644 --- a/unittests/testSkeleton.cpp +++ b/unittests/testSkeleton.cpp @@ -82,14 +82,14 @@ std::vector getSkeletons() std::vector fileList = getFileList(); std::vector worlds; - for(size_t i=0; i skeletons; - for(size_t i=0; igetNumSkeletons(); ++j) + for(std::size_t j=0; jgetNumSkeletons(); ++j) skeletons.push_back(world->getSkeleton(j)); } @@ -99,7 +99,7 @@ std::vector getSkeletons() void constructSubtree(std::vector& _tree, BodyNode* bn) { _tree.push_back(bn); - for(size_t i=0; igetNumChildBodyNodes(); ++i) + for(std::size_t i=0; igetNumChildBodyNodes(); ++i) constructSubtree(_tree, bn->getChildBodyNode(i)); } @@ -108,25 +108,25 @@ TEST(Skeleton, Restructuring) std::vector skeletons = getSkeletons(); #ifndef NDEBUG - size_t numIterations = 10; + std::size_t numIterations = 10; #else - size_t numIterations = 2*skeletons.size(); + std::size_t numIterations = 2*skeletons.size(); #endif for(const auto& skeleton : skeletons) EXPECT_TRUE(skeleton->checkIndexingConsistency()); // Test moves within the current Skeleton - for(size_t i=0; icheckIndexingConsistency()); SkeletonPtr original = skeleton->clone(); EXPECT_TRUE(original->checkIndexingConsistency()); - size_t maxNode = skeleton->getNumBodyNodes()-1; + std::size_t maxNode = skeleton->getNumBodyNodes()-1; BodyNode* bn1 = skeleton->getBodyNode(floor(math::random(0, maxNode))); BodyNode* bn2 = skeleton->getBodyNode(ceil(math::random(0, maxNode))); @@ -144,7 +144,7 @@ TEST(Skeleton, Restructuring) EXPECT_TRUE(skeleton->getNumBodyNodes() == original->getNumBodyNodes()); if(skeleton->getNumBodyNodes() == original->getNumBodyNodes()) { - for(size_t j=0; jgetNumBodyNodes(); ++j) + for(std::size_t j=0; jgetNumBodyNodes(); ++j) { // Make sure no BodyNodes have been lost or gained in translation std::string name = original->getBodyNode(j)->getName(); @@ -176,7 +176,7 @@ TEST(Skeleton, Restructuring) } EXPECT_TRUE(skeleton->getNumDofs() == original->getNumDofs()); - for(size_t j=0; jgetNumDofs(); ++j) + for(std::size_t j=0; jgetNumDofs(); ++j) { std::string name = original->getDof(j)->getName(); DegreeOfFreedom* dof = skeleton->getDof(name); @@ -193,9 +193,9 @@ TEST(Skeleton, Restructuring) } // Test moves between Skeletons - for(size_t i=0; igetSkeleton()->checkIndexingConsistency()); // Make sure all the objects have moved - for(size_t j=0; jgetSkeleton() == toSkel); @@ -267,7 +267,7 @@ TEST(Skeleton, Restructuring) EXPECT_TRUE(childBn->getParentBodyNode() == nullptr); // The subtree should still be in the same Skeleton - for(size_t j=0; jgetSkeleton() == toSkel); @@ -746,7 +746,7 @@ TEST(Skeleton, CloneNodeOrdering) SkeletonPtr clone = skel->clone(); - for(size_t i=0; i < skel->getNumEndEffectors(); ++i) + for(std::size_t i=0; i < skel->getNumEndEffectors(); ++i) { EXPECT_EQ(skel->getEndEffector(i)->getName(), clone->getEndEffector(i)->getName()); @@ -775,15 +775,15 @@ TEST(Skeleton, Referential) std::vector skeletons = getSkeletons(); #ifndef NDEBUG // Debug mode - size_t numIterations = 1; + std::size_t numIterations = 1; #else // Release mode - size_t numIterations = 20; + std::size_t numIterations = 20; #endif - for(size_t i=0; igetNumTrees(); ++j) + for(std::size_t j=0; jgetNumTrees(); ++j) { BranchPtr tree = Branch::create(skeleton->getRootBodyNode(j)); @@ -807,7 +807,7 @@ TEST(Skeleton, Referential) Eigen::VectorXd dq = tree->getVelocities(); Eigen::VectorXd ddq = tree->getAccelerations(); - for(size_t k=0; kgetConstraintForces(); const Eigen::VectorXd& treeFc = tree->getConstraintForces(); - const size_t nDofs = tree->getNumDofs(); - for(size_t r1=0; r1getNumDofs(); + for(std::size_t r1=0; r1getDof(r1)->getIndexInSkeleton(); - for(size_t r2=0; r2getDof(r1)->getIndexInSkeleton(); + for(std::size_t r2=0; r2getDof(r2)->getIndexInSkeleton(); + const std::size_t sr2 = tree->getDof(r2)->getIndexInSkeleton(); EXPECT_TRUE( skelMassMatrix(sr1,sr2) == treeMassMatrix(r1,r2) ); EXPECT_TRUE( skelAugM(sr1,sr2) == treeAugM(r1,r2) ); @@ -873,17 +873,17 @@ TEST(Skeleton, Referential) EXPECT_TRUE( skelFc[sr1] == treeFc[r1] ); } - const size_t numBodyNodes = tree->getNumBodyNodes(); - for(size_t m=0; mgetNumBodyNodes(); + for(std::size_t m=0; mgetBodyNode(m); const Eigen::MatrixXd Jtree = tree->getJacobian(bn); const Eigen::MatrixXd Jskel = skeleton->getJacobian(bn); - for(size_t r2=0; r2getDof(r2)->getIndexInSkeleton(); - for(size_t r1=0; r1<6; ++r1) + const std::size_t sr2 = tree->getDof(r2)->getIndexInSkeleton(); + for(std::size_t r1=0; r1<6; ++r1) { EXPECT_TRUE( Jtree(r1,r2) == Jskel(r1, sr2) ); } @@ -929,7 +929,7 @@ SkeletonPtr constructLinkageTestSkeleton() } void checkForBodyNodes( - size_t& /*count*/, + std::size_t& /*count*/, const ReferentialSkeletonPtr& /*refSkel*/, const SkeletonPtr& /*skel*/) { @@ -940,7 +940,7 @@ void checkForBodyNodes( // names template void checkForBodyNodes( - size_t& count, + std::size_t& count, const ReferentialSkeletonPtr& refSkel, const SkeletonPtr& skel, const std::string& name, @@ -960,13 +960,13 @@ void checkForBodyNodes( } template -size_t checkForBodyNodes( +std::size_t checkForBodyNodes( const ReferentialSkeletonPtr& refSkel, const SkeletonPtr& skel, bool checkCount, Args ... args) { - size_t count = 0; + std::size_t count = 0; checkForBodyNodes(count, refSkel, skel, args...); if(checkCount) @@ -990,7 +990,7 @@ void checkLinkageJointConsistency(const ReferentialSkeletonPtr& refSkel) // Linkages should have the property: // getJoint(i) == getBodyNode(i)->getParentJoint() - for(size_t i=0; i < refSkel->getNumJoints(); ++i) + for(std::size_t i=0; i < refSkel->getNumJoints(); ++i) { EXPECT_EQ(refSkel->getJoint(i), refSkel->getBodyNode(i)->getParentJoint()); EXPECT_EQ(refSkel->getIndexOf(refSkel->getJoint(i)), i); @@ -1042,7 +1042,7 @@ TEST(Skeleton, Linkage) Linkage::Criteria::Target(skel2->getBodyNode("c3b1"), Linkage::Criteria::UPSTREAM)); LinkagePtr combinedSkelBases = Linkage::create(criteria, "combinedSkelBases"); - size_t count = 0; + std::size_t count = 0; count += checkForBodyNodes(combinedSkelBases, skel, false, "c3b1", "c1b3", "c2b1", "c2b2", "c2b3", "c5b1", "c5b2", "c1b2", "c1b1"); @@ -1127,13 +1127,13 @@ TEST(Skeleton, Group) EXPECT_EQ(skel1Group->getNumJoints(), skel->getNumJoints()); EXPECT_EQ(skel1Group->getNumDofs(), skel->getNumDofs()); - for(size_t i=0; i < skel1Group->getNumBodyNodes(); ++i) + for(std::size_t i=0; i < skel1Group->getNumBodyNodes(); ++i) EXPECT_EQ(skel1Group->getBodyNode(i), skel->getBodyNode(i)); - for(size_t i=0; i < skel1Group->getNumJoints(); ++i) + for(std::size_t i=0; i < skel1Group->getNumJoints(); ++i) EXPECT_EQ(skel1Group->getJoint(i), skel->getJoint(i)); - for(size_t i=0; i < skel1Group->getNumDofs(); ++i) + for(std::size_t i=0; i < skel1Group->getNumDofs(); ++i) EXPECT_EQ(skel1Group->getDof(i), skel->getDof(i)); // Test arbitrary Groups by plucking random BodyNodes, Joints, and @@ -1142,9 +1142,9 @@ TEST(Skeleton, Group) std::vector bodyNodes; std::vector joints; std::vector dofs; - for(size_t i=0; i < 2*skel->getNumBodyNodes(); ++i) + for(std::size_t i=0; i < 2*skel->getNumBodyNodes(); ++i) { - size_t randomIndex = floor(random(0, skel->getNumBodyNodes())); + std::size_t randomIndex = floor(random(0, skel->getNumBodyNodes())); BodyNode* bn = skel->getBodyNode(randomIndex); if(group->addBodyNode(bn, false)) bodyNodes.push_back(bn); @@ -1164,13 +1164,13 @@ TEST(Skeleton, Group) EXPECT_EQ(group->getNumJoints(), joints.size()); EXPECT_EQ(group->getNumDofs(), dofs.size()); - for(size_t i=0; i < group->getNumBodyNodes(); ++i) + for(std::size_t i=0; i < group->getNumBodyNodes(); ++i) EXPECT_EQ(group->getBodyNode(i), bodyNodes[i]); - for(size_t i=0; i < group->getNumJoints(); ++i) + for(std::size_t i=0; i < group->getNumJoints(); ++i) EXPECT_EQ(group->getJoint(i), joints[i]); - for(size_t i=0; i < group->getNumDofs(); ++i) + for(std::size_t i=0; i < group->getNumDofs(); ++i) EXPECT_EQ(group->getDof(i), dofs[i]); } diff --git a/unittests/testSoftDynamics.cpp b/unittests/testSoftDynamics.cpp index dc7914c8177bc..b39f344e32934 100644 --- a/unittests/testSoftDynamics.cpp +++ b/unittests/testSoftDynamics.cpp @@ -60,15 +60,15 @@ bool equals(const DenseBase& A, const DenseBase& B, double tol = 1e-5) { // Get the matrix sizes and sanity check the call - const size_t n1 = A.cols(), m1 = A.rows(); - const size_t n2 = B.cols(), m2 = B.rows(); + const std::size_t n1 = A.cols(), m1 = A.rows(); + const std::size_t n2 = B.cols(), m2 = B.rows(); if (m1 != m2 || n1 != n2) return false; // Check each index - for (size_t i = 0; i < m1; i++) + for (std::size_t i = 0; i < m1; i++) { - for (size_t j = 0; j < n1; j++) + for (std::size_t j = 0; j < n1; j++) { if (std::isnan(A(i,j)) ^ std::isnan(B(i,j))) return false; @@ -141,7 +141,7 @@ MatrixXd SoftDynamicsTest::getMassMatrix(dynamics::SkeletonPtr _skel) Eigen::Matrix6d I; // Body inertia math::Jacobian J; // Body Jacobian - for (size_t i = 0; i < _skel->getNumBodyNodes(); ++i) + for (std::size_t i = 0; i < _skel->getNumBodyNodes(); ++i) { dynamics::BodyNode* body = _skel->getBodyNode(i); @@ -184,7 +184,7 @@ MatrixXd SoftDynamicsTest::getAugMassMatrix(dynamics::SkeletonPtr _skel) MatrixXd AugM; // Compute diagonal matrices of joint damping and joint stiffness - for (size_t i = 0; i < _skel->getNumBodyNodes(); ++i) + for (std::size_t i = 0; i < _skel->getNumBodyNodes(); ++i) { dynamics::BodyNode* body = _skel->getBodyNode(i); dynamics::Joint* joint = body->getParentJoint(); @@ -248,9 +248,9 @@ void SoftDynamicsTest::compareEquationsOfMotion(const std::string& _fileName) //---------------------------- Settings -------------------------------------- // Number of random state tests for each skeletons #ifndef NDEBUG // Debug mode - size_t nRandomItr = 1; + std::size_t nRandomItr = 1; #else - size_t nRandomItr = 1; + std::size_t nRandomItr = 1; #endif // Lower and upper bound of configuration for system @@ -271,7 +271,7 @@ void SoftDynamicsTest::compareEquationsOfMotion(const std::string& _fileName) myWorld = utils::SkelParser::readWorld(_fileName); EXPECT_TRUE(myWorld != nullptr); - for (size_t i = 0; i < myWorld->getNumSkeletons(); ++i) + for (std::size_t i = 0; i < myWorld->getNumSkeletons(); ++i) { dynamics::SkeletonPtr softSkel = myWorld->getSkeleton(i); @@ -288,10 +288,10 @@ void SoftDynamicsTest::compareEquationsOfMotion(const std::string& _fileName) continue; } - for (size_t j = 0; j < nRandomItr; ++j) + for (std::size_t j = 0; j < nRandomItr; ++j) { // Random joint stiffness and damping coefficient - for (size_t k = 0; k < softSkel->getNumBodyNodes(); ++k) + for (std::size_t k = 0; k < softSkel->getNumBodyNodes(); ++k) { BodyNode* body = softSkel->getBodyNode(k); Joint* joint = body->getParentJoint(); @@ -310,7 +310,7 @@ void SoftDynamicsTest::compareEquationsOfMotion(const std::string& _fileName) // Set random states Skeleton::Configuration x = softSkel->getConfiguration(); - for (size_t k = 0u; k < softSkel->getNumDofs(); ++k) + for (std::size_t k = 0u; k < softSkel->getNumDofs(); ++k) { x.mPositions[k] = random(lb, ub); x.mVelocities[k] = random(lb, ub); diff --git a/unittests/testWorld.cpp b/unittests/testWorld.cpp index 9f2cdc5d177a5..2b279f9b40ce5 100644 --- a/unittests/testWorld.cpp +++ b/unittests/testWorld.cpp @@ -187,22 +187,22 @@ TEST(World, Cloning) fileList.push_back(DART_DATA_PATH"skel/fullbody1.skel"); std::vector worlds; - for(size_t i=0; i clones; clones.push_back(original); - for(size_t j=1; j<5; ++j) + for(std::size_t j=1; j<5; ++j) clones.push_back(clones[j-1]->clone()); // Make sure all the Skeleton states match at the start // TODO(MXG): This should be removed once state also gets copied over during a cloning - for(size_t j=1; jgetNumSkeletons(); ++k) + for(std::size_t k=0; kgetNumSkeletons(); ++k) { dart::dynamics::SkeletonPtr skel = original->getSkeleton(k); dart::dynamics::SkeletonPtr clone = clones[j]->getSkeleton(k); @@ -215,14 +215,14 @@ TEST(World, Cloning) } #ifndef NDEBUG // Debug mode - size_t numIterations = 3; + std::size_t numIterations = 3; #else - size_t numIterations = 500; + std::size_t numIterations = 500; #endif - for(size_t j=0; jgetNumSkeletons(); ++k) + for(std::size_t k=0; kgetNumSkeletons(); ++k) { dart::dynamics::SkeletonPtr skel = original->getSkeleton(k); @@ -232,7 +232,7 @@ TEST(World, Cloning) commands[q] = random(-0.1, 0.1); // Assign the command vector to each clone of the kth skeleton - for(size_t c=0; cgetSkeleton(k); skelClone->setCommands(commands); @@ -240,13 +240,13 @@ TEST(World, Cloning) } // Step each clone forward - for(size_t c=0; cstep(false); } - for(size_t c=0; cgetNumSkeletons(); ++k) + for(std::size_t k=0; kgetNumSkeletons(); ++k) { dart::dynamics::SkeletonPtr skel = original->getSkeleton(k); dart::dynamics::SkeletonPtr clone = clones[c]->getSkeleton(k); @@ -286,7 +286,7 @@ TEST(World, ValidatingClones) fileList.push_back(DART_DATA_PATH"skel/fullbody1.skel"); std::vector worlds; - for(size_t i=0; i clones; clones.push_back(original); - for(size_t j=1; j<5; ++j) + for(std::size_t j=1; j<5; ++j) { clones.push_back(clones[j-1]->clone()); From bff821f5deea0b1bee136077262b7e6f92f895b4 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 21 Apr 2016 17:48:58 -0400 Subject: [PATCH 22/34] Rollback unintended changes --- dart/math/MathTypes.h | 6 +++--- dart/utils/VskParser.cpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/dart/math/MathTypes.h b/dart/math/MathTypes.h index 40ff2b4a4e357..1d2ce95ada24b 100644 --- a/dart/math/MathTypes.h +++ b/dart/math/MathTypes.h @@ -80,7 +80,7 @@ template class aligned_allocator_cpp11 : public std::allocator { public: - typedef std::size_t std::size_type; + typedef std::size_t size_type; typedef std::ptrdiff_t difference_type; typedef T* pointer; typedef const T* const_pointer; @@ -106,13 +106,13 @@ class aligned_allocator_cpp11 : public std::allocator ~aligned_allocator_cpp11() {} - pointer allocate(std::size_type num, const void* /*hint*/ = 0) + pointer allocate(size_type num, const void* /*hint*/ = 0) { internal::check_size_for_overflow(num); return static_cast( internal::aligned_malloc(num * sizeof(T)) ); } - void deallocate(pointer p, std::size_type /*num*/) + void deallocate(pointer p, size_type /*num*/) { internal::aligned_free(p); } diff --git a/dart/utils/VskParser.cpp b/dart/utils/VskParser.cpp index dc962728cc3c8..7d95534d32cc1 100644 --- a/dart/utils/VskParser.cpp +++ b/dart/utils/VskParser.cpp @@ -1003,10 +1003,10 @@ void tokenize(const std::string& str, const std::string& delimiters) { // Skip delimiters at beginning. - std::string::std::size_type lastPos = str.find_first_not_of(delimiters, 0); + std::string::size_type lastPos = str.find_first_not_of(delimiters, 0); // Find first "non-delimiter". - std::string::std::size_type pos = str.find_first_of(delimiters, lastPos); + std::string::size_type pos = str.find_first_of(delimiters, lastPos); while (std::string::npos != pos || std::string::npos != lastPos) { From 028e214458d1b710de77360582b6239da434efa0 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 21 Apr 2016 18:08:35 -0400 Subject: [PATCH 23/34] Configure Travis to treat warnings as errors --- .travis.yml | 6 +++--- CMakeLists.txt | 10 ++++++++++ 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/.travis.yml b/.travis.yml index 66ece4e2b46a3..fe7c004b82c3c 100644 --- a/.travis.yml +++ b/.travis.yml @@ -13,8 +13,8 @@ compiler: - clang env: - - BUILD_TYPE=Debug COVERALLS=ON COVERALLS_REPO_TOKEN=FKh1HgwfV5uzNrYxIT6ZWjcFqybYZSUym - - BUILD_TYPE=Release COVERALLS=OFF + - BUILD_TYPE=Debug TREAT_WARNINGS_AS_ERRORS=ON COVERALLS=ON COVERALLS_REPO_TOKEN=FKh1HgwfV5uzNrYxIT6ZWjcFqybYZSUym + - BUILD_TYPE=Release TREAT_WARNINGS_AS_ERRORS=ON COVERALLS=OFF matrix: exclude: @@ -27,7 +27,7 @@ install: script: - mkdir build && cd build - - cmake -DCMAKE_BUILD_TYPE=$BUILD_TYPE -DDART_COVERALLS=$COVERALLS .. + - cmake -DCMAKE_BUILD_TYPE=$BUILD_TYPE -DDART_TREAT_WARNINGS_AS_ERRORS=$TREAT_WARNINGS_AS_ERRORS -DDART_COVERALLS=$COVERALLS .. - make -j4 all tutorials examples tests test - if [ $COVERALLS = ON ] && [ "$TRAVIS_OS_NAME" = "linux" ]; then make -j4 coveralls; fi diff --git a/CMakeLists.txt b/CMakeLists.txt index e51eb2db060b6..4e4ccd1a5ab6a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -72,6 +72,7 @@ endif() option(DART_BUILD_GUI_OSG "Build osgDart library" ON) option(DART_COVERALLS "Turn on coveralls support" OFF) option(DART_COVERALLS_UPLOAD "Upload the generated coveralls json" ON) +option(DART_TREAT_WARNINGS_AS_ERRORS "Treat warnings as errors" OFF) if(DART_COVERALLS) include(Coveralls) @@ -141,6 +142,9 @@ if(MSVC) if(MSVC_VERSION VERSION_LESS 1900) message(FATAL_ERROR "${PROJECT_NAME} requires VS 2015 or greater.") endif() + if(DART_TREAT_WARNINGS_AS_ERRORS) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /WX") + endif() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /MP4") set(CMAKE_EXE_LINKER_FLAGS_RELEASE "/LTCG /INCREMENTAL:NO") if(NOT DART_MSVC_DEFAULT_OPTIONS) @@ -148,6 +152,9 @@ if(MSVC) set(CMAKE_CXX_FLAGS_RELEASE "${CMAKE_CXX_FLAGS_RELEASE} ${DART_RUNTIME_LIBRARY} /Zi /GL /Gy /W1 /EHsc /arch:SSE2") endif(NOT DART_MSVC_DEFAULT_OPTIONS) elseif(CMAKE_COMPILER_IS_GNUCXX) + if(DART_TREAT_WARNINGS_AS_ERRORS) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror") + endif() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -msse2 -fPIC") execute_process( COMMAND ${CMAKE_CXX_COMPILER} -dumpversion OUTPUT_VARIABLE GCC_VERSION) @@ -162,6 +169,9 @@ elseif(CMAKE_COMPILER_IS_GNUCXX) set(CMAKE_CXX_FLAGS_RELWITHDEBINFO "${CMAKE_CXX_FLAGS_RELEASE} ${CMAKE_CXX_FLAGS_DEBUG}") set(CMAKE_CXX_FLAGS_PROFILE "${CMAKE_CXX_FLAGS_DEBUG} -pg") elseif("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") + if(DART_TREAT_WARNINGS_AS_ERRORS) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror") + endif() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -msse2 -fPIC") execute_process( COMMAND ${CMAKE_CXX_COMPILER} -dumpversion OUTPUT_VARIABLE CLANG_VERSION) From 4fb1b7fe49ae3eb8cfa3d1b40bbec27caae36064 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 21 Apr 2016 18:23:26 -0400 Subject: [PATCH 24/34] Turn deprecated warning into an warning for mac even if -Werror is specified --- CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4e4ccd1a5ab6a..05bd159e9b835 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -170,7 +170,9 @@ elseif(CMAKE_COMPILER_IS_GNUCXX) set(CMAKE_CXX_FLAGS_PROFILE "${CMAKE_CXX_FLAGS_DEBUG} -pg") elseif("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") if(DART_TREAT_WARNINGS_AS_ERRORS) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Werror -Wno-error=deprecated-declarations") + # Turn warning "deprecated-declarations" into an warning even if -Werror is + # specified until we abandon glut. endif() set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -msse2 -fPIC") execute_process( From 439de079a4c996149d431d4c790bf2c51e472d4f Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Thu, 21 Apr 2016 18:24:33 -0400 Subject: [PATCH 25/34] Fix missing override specifiers --- dart/gui/OpenGLRenderInterface.h | 2 +- dart/gui/osg/TrackballManipulator.h | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/dart/gui/OpenGLRenderInterface.h b/dart/gui/OpenGLRenderInterface.h index 51ec36ed0424f..14468a38fb01a 100644 --- a/dart/gui/OpenGLRenderInterface.h +++ b/dart/gui/OpenGLRenderInterface.h @@ -89,7 +89,7 @@ class OpenGLRenderInterface : public RenderInterface { void drawCube(const Eigen::Vector3d& _size) override; void drawCylinder(double _radius, double _height) override; void drawMesh(const Eigen::Vector3d& _scale, const aiScene* _mesh) override; - void drawSoftMesh(const aiMesh* mesh); + void drawSoftMesh(const aiMesh* mesh) override; void drawList(GLuint index) override; void drawLineSegments(const std::vector& _vertices, const Eigen::aligned_vector& _connections) override; diff --git a/dart/gui/osg/TrackballManipulator.h b/dart/gui/osg/TrackballManipulator.h index 2bc2ae197a58a..8eddbf8d8db85 100644 --- a/dart/gui/osg/TrackballManipulator.h +++ b/dart/gui/osg/TrackballManipulator.h @@ -44,11 +44,11 @@ namespace gui { namespace osg { #define DART_META_Object(library,name) \ - virtual ::osg::Object* cloneType() const { return new name (); } \ - virtual ::osg::Object* clone(const ::osg::CopyOp& copyop) const { return new name (*this,copyop); } \ - virtual bool isSameKindAs(const ::osg::Object* obj) const { return dynamic_cast(obj)!=NULL; } \ - virtual const char* libraryName() const { return #library; }\ - virtual const char* className() const { return #name; } + ::osg::Object* cloneType() const override { return new name (); } \ + ::osg::Object* clone(const ::osg::CopyOp& copyop) const override { return new name (*this,copyop); } \ + bool isSameKindAs(const ::osg::Object* obj) const override { return dynamic_cast(obj)!=NULL; } \ + const char* libraryName() const override { return #library; }\ + const char* className() const override { return #name; } // TODO(JS): Copied from osg/Object. Due to the namespace conflict between osg // and dart::gui::osg, we need to explicitly specify the root namespace osg as // ::osg From 017e148187acee54673b544e40c5e6e440c8da45 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 22 Apr 2016 00:01:51 -0400 Subject: [PATCH 26/34] Rename directory: apps --> examples --- {apps => examples}/CMakeLists.txt | 0 {apps => examples}/addDeleteSkels/CMakeLists.txt | 0 {apps => examples}/addDeleteSkels/Main.cpp | 0 {apps => examples}/addDeleteSkels/MyWindow.cpp | 0 {apps => examples}/addDeleteSkels/MyWindow.h | 0 {apps => examples}/atlasSimbicon/CMakeLists.txt | 0 {apps => examples}/atlasSimbicon/Controller.cpp | 0 {apps => examples}/atlasSimbicon/Controller.h | 0 {apps => examples}/atlasSimbicon/Humanoid.cpp | 0 {apps => examples}/atlasSimbicon/Humanoid.h | 0 {apps => examples}/atlasSimbicon/Main.cpp | 0 {apps => examples}/atlasSimbicon/MyWindow.cpp | 0 {apps => examples}/atlasSimbicon/MyWindow.h | 0 {apps => examples}/atlasSimbicon/State.cpp | 0 {apps => examples}/atlasSimbicon/State.h | 0 {apps => examples}/atlasSimbicon/StateMachine.cpp | 0 {apps => examples}/atlasSimbicon/StateMachine.h | 0 {apps => examples}/atlasSimbicon/TerminalCondition.cpp | 0 {apps => examples}/atlasSimbicon/TerminalCondition.h | 0 {apps => examples}/bipedStand/CMakeLists.txt | 0 {apps => examples}/bipedStand/Controller.cpp | 0 {apps => examples}/bipedStand/Controller.h | 0 {apps => examples}/bipedStand/Main.cpp | 0 {apps => examples}/bipedStand/MyWindow.cpp | 0 {apps => examples}/bipedStand/MyWindow.h | 0 {apps => examples}/hardcodedDesign/CMakeLists.txt | 0 {apps => examples}/hardcodedDesign/Main.cpp | 0 {apps => examples}/hardcodedDesign/MyWindow.cpp | 0 {apps => examples}/hardcodedDesign/MyWindow.h | 0 {apps => examples}/hardcodedDesign/README.txt | 0 {apps => examples}/hybridDynamics/CMakeLists.txt | 0 {apps => examples}/hybridDynamics/Main.cpp | 0 {apps => examples}/hybridDynamics/MyWindow.cpp | 0 {apps => examples}/hybridDynamics/MyWindow.h | 0 {apps => examples}/jointConstraints/CMakeLists.txt | 0 {apps => examples}/jointConstraints/Controller.cpp | 0 {apps => examples}/jointConstraints/Controller.h | 0 {apps => examples}/jointConstraints/Main.cpp | 0 {apps => examples}/jointConstraints/MyWindow.cpp | 0 {apps => examples}/jointConstraints/MyWindow.h | 0 {apps => examples}/mixedChain/CMakeLists.txt | 0 {apps => examples}/mixedChain/Main.cpp | 0 {apps => examples}/mixedChain/MyWindow.cpp | 0 {apps => examples}/mixedChain/MyWindow.h | 0 {apps => examples}/operationalSpaceControl/CMakeLists.txt | 0 {apps => examples}/operationalSpaceControl/Controller.cpp | 0 {apps => examples}/operationalSpaceControl/Controller.h | 0 {apps => examples}/operationalSpaceControl/Main.cpp | 0 {apps => examples}/operationalSpaceControl/MyWindow.cpp | 0 {apps => examples}/operationalSpaceControl/MyWindow.h | 0 {apps => examples}/rigidChain/CMakeLists.txt | 0 {apps => examples}/rigidChain/Main.cpp | 0 {apps => examples}/rigidChain/MyWindow.cpp | 0 {apps => examples}/rigidChain/MyWindow.h | 0 {apps => examples}/rigidCubes/CMakeLists.txt | 0 {apps => examples}/rigidCubes/Main.cpp | 0 {apps => examples}/rigidCubes/MyWindow.cpp | 0 {apps => examples}/rigidCubes/MyWindow.h | 0 {apps => examples}/rigidLoop/CMakeLists.txt | 0 {apps => examples}/rigidLoop/Main.cpp | 0 {apps => examples}/rigidLoop/MyWindow.cpp | 0 {apps => examples}/rigidLoop/MyWindow.h | 0 {apps => examples}/rigidShapes/CMakeLists.txt | 0 {apps => examples}/rigidShapes/Main.cpp | 0 {apps => examples}/rigidShapes/MyWindow.cpp | 0 {apps => examples}/rigidShapes/MyWindow.h | 0 {apps => examples}/simpleFrames/CMakeLists.txt | 0 {apps => examples}/simpleFrames/Main.cpp | 0 {apps => examples}/softBodies/CMakeLists.txt | 0 {apps => examples}/softBodies/Main.cpp | 0 {apps => examples}/softBodies/MyWindow.cpp | 0 {apps => examples}/softBodies/MyWindow.h | 0 {apps => examples}/speedTest/CMakeLists.txt | 0 {apps => examples}/speedTest/Main.cpp | 0 {apps => examples}/vehicle/CMakeLists.txt | 0 {apps => examples}/vehicle/Main.cpp | 0 {apps => examples}/vehicle/MyWindow.cpp | 0 {apps => examples}/vehicle/MyWindow.h | 0 78 files changed, 0 insertions(+), 0 deletions(-) rename {apps => examples}/CMakeLists.txt (100%) rename {apps => examples}/addDeleteSkels/CMakeLists.txt (100%) rename {apps => examples}/addDeleteSkels/Main.cpp (100%) rename {apps => examples}/addDeleteSkels/MyWindow.cpp (100%) rename {apps => examples}/addDeleteSkels/MyWindow.h (100%) rename {apps => examples}/atlasSimbicon/CMakeLists.txt (100%) rename {apps => examples}/atlasSimbicon/Controller.cpp (100%) rename {apps => examples}/atlasSimbicon/Controller.h (100%) rename {apps => examples}/atlasSimbicon/Humanoid.cpp (100%) rename {apps => examples}/atlasSimbicon/Humanoid.h (100%) rename {apps => examples}/atlasSimbicon/Main.cpp (100%) rename {apps => examples}/atlasSimbicon/MyWindow.cpp (100%) rename {apps => examples}/atlasSimbicon/MyWindow.h (100%) rename {apps => examples}/atlasSimbicon/State.cpp (100%) rename {apps => examples}/atlasSimbicon/State.h (100%) rename {apps => examples}/atlasSimbicon/StateMachine.cpp (100%) rename {apps => examples}/atlasSimbicon/StateMachine.h (100%) rename {apps => examples}/atlasSimbicon/TerminalCondition.cpp (100%) rename {apps => examples}/atlasSimbicon/TerminalCondition.h (100%) rename {apps => examples}/bipedStand/CMakeLists.txt (100%) rename {apps => examples}/bipedStand/Controller.cpp (100%) rename {apps => examples}/bipedStand/Controller.h (100%) rename {apps => examples}/bipedStand/Main.cpp (100%) rename {apps => examples}/bipedStand/MyWindow.cpp (100%) rename {apps => examples}/bipedStand/MyWindow.h (100%) rename {apps => examples}/hardcodedDesign/CMakeLists.txt (100%) rename {apps => examples}/hardcodedDesign/Main.cpp (100%) rename {apps => examples}/hardcodedDesign/MyWindow.cpp (100%) rename {apps => examples}/hardcodedDesign/MyWindow.h (100%) rename {apps => examples}/hardcodedDesign/README.txt (100%) rename {apps => examples}/hybridDynamics/CMakeLists.txt (100%) rename {apps => examples}/hybridDynamics/Main.cpp (100%) rename {apps => examples}/hybridDynamics/MyWindow.cpp (100%) rename {apps => examples}/hybridDynamics/MyWindow.h (100%) rename {apps => examples}/jointConstraints/CMakeLists.txt (100%) rename {apps => examples}/jointConstraints/Controller.cpp (100%) rename {apps => examples}/jointConstraints/Controller.h (100%) rename {apps => examples}/jointConstraints/Main.cpp (100%) rename {apps => examples}/jointConstraints/MyWindow.cpp (100%) rename {apps => examples}/jointConstraints/MyWindow.h (100%) rename {apps => examples}/mixedChain/CMakeLists.txt (100%) rename {apps => examples}/mixedChain/Main.cpp (100%) rename {apps => examples}/mixedChain/MyWindow.cpp (100%) rename {apps => examples}/mixedChain/MyWindow.h (100%) rename {apps => examples}/operationalSpaceControl/CMakeLists.txt (100%) rename {apps => examples}/operationalSpaceControl/Controller.cpp (100%) rename {apps => examples}/operationalSpaceControl/Controller.h (100%) rename {apps => examples}/operationalSpaceControl/Main.cpp (100%) rename {apps => examples}/operationalSpaceControl/MyWindow.cpp (100%) rename {apps => examples}/operationalSpaceControl/MyWindow.h (100%) rename {apps => examples}/rigidChain/CMakeLists.txt (100%) rename {apps => examples}/rigidChain/Main.cpp (100%) rename {apps => examples}/rigidChain/MyWindow.cpp (100%) rename {apps => examples}/rigidChain/MyWindow.h (100%) rename {apps => examples}/rigidCubes/CMakeLists.txt (100%) rename {apps => examples}/rigidCubes/Main.cpp (100%) rename {apps => examples}/rigidCubes/MyWindow.cpp (100%) rename {apps => examples}/rigidCubes/MyWindow.h (100%) rename {apps => examples}/rigidLoop/CMakeLists.txt (100%) rename {apps => examples}/rigidLoop/Main.cpp (100%) rename {apps => examples}/rigidLoop/MyWindow.cpp (100%) rename {apps => examples}/rigidLoop/MyWindow.h (100%) rename {apps => examples}/rigidShapes/CMakeLists.txt (100%) rename {apps => examples}/rigidShapes/Main.cpp (100%) rename {apps => examples}/rigidShapes/MyWindow.cpp (100%) rename {apps => examples}/rigidShapes/MyWindow.h (100%) rename {apps => examples}/simpleFrames/CMakeLists.txt (100%) rename {apps => examples}/simpleFrames/Main.cpp (100%) rename {apps => examples}/softBodies/CMakeLists.txt (100%) rename {apps => examples}/softBodies/Main.cpp (100%) rename {apps => examples}/softBodies/MyWindow.cpp (100%) rename {apps => examples}/softBodies/MyWindow.h (100%) rename {apps => examples}/speedTest/CMakeLists.txt (100%) rename {apps => examples}/speedTest/Main.cpp (100%) rename {apps => examples}/vehicle/CMakeLists.txt (100%) rename {apps => examples}/vehicle/Main.cpp (100%) rename {apps => examples}/vehicle/MyWindow.cpp (100%) rename {apps => examples}/vehicle/MyWindow.h (100%) diff --git a/apps/CMakeLists.txt b/examples/CMakeLists.txt similarity index 100% rename from apps/CMakeLists.txt rename to examples/CMakeLists.txt diff --git a/apps/addDeleteSkels/CMakeLists.txt b/examples/addDeleteSkels/CMakeLists.txt similarity index 100% rename from apps/addDeleteSkels/CMakeLists.txt rename to examples/addDeleteSkels/CMakeLists.txt diff --git a/apps/addDeleteSkels/Main.cpp b/examples/addDeleteSkels/Main.cpp similarity index 100% rename from apps/addDeleteSkels/Main.cpp rename to examples/addDeleteSkels/Main.cpp diff --git a/apps/addDeleteSkels/MyWindow.cpp b/examples/addDeleteSkels/MyWindow.cpp similarity index 100% rename from apps/addDeleteSkels/MyWindow.cpp rename to examples/addDeleteSkels/MyWindow.cpp diff --git a/apps/addDeleteSkels/MyWindow.h b/examples/addDeleteSkels/MyWindow.h similarity index 100% rename from apps/addDeleteSkels/MyWindow.h rename to examples/addDeleteSkels/MyWindow.h diff --git a/apps/atlasSimbicon/CMakeLists.txt b/examples/atlasSimbicon/CMakeLists.txt similarity index 100% rename from apps/atlasSimbicon/CMakeLists.txt rename to examples/atlasSimbicon/CMakeLists.txt diff --git a/apps/atlasSimbicon/Controller.cpp b/examples/atlasSimbicon/Controller.cpp similarity index 100% rename from apps/atlasSimbicon/Controller.cpp rename to examples/atlasSimbicon/Controller.cpp diff --git a/apps/atlasSimbicon/Controller.h b/examples/atlasSimbicon/Controller.h similarity index 100% rename from apps/atlasSimbicon/Controller.h rename to examples/atlasSimbicon/Controller.h diff --git a/apps/atlasSimbicon/Humanoid.cpp b/examples/atlasSimbicon/Humanoid.cpp similarity index 100% rename from apps/atlasSimbicon/Humanoid.cpp rename to examples/atlasSimbicon/Humanoid.cpp diff --git a/apps/atlasSimbicon/Humanoid.h b/examples/atlasSimbicon/Humanoid.h similarity index 100% rename from apps/atlasSimbicon/Humanoid.h rename to examples/atlasSimbicon/Humanoid.h diff --git a/apps/atlasSimbicon/Main.cpp b/examples/atlasSimbicon/Main.cpp similarity index 100% rename from apps/atlasSimbicon/Main.cpp rename to examples/atlasSimbicon/Main.cpp diff --git a/apps/atlasSimbicon/MyWindow.cpp b/examples/atlasSimbicon/MyWindow.cpp similarity index 100% rename from apps/atlasSimbicon/MyWindow.cpp rename to examples/atlasSimbicon/MyWindow.cpp diff --git a/apps/atlasSimbicon/MyWindow.h b/examples/atlasSimbicon/MyWindow.h similarity index 100% rename from apps/atlasSimbicon/MyWindow.h rename to examples/atlasSimbicon/MyWindow.h diff --git a/apps/atlasSimbicon/State.cpp b/examples/atlasSimbicon/State.cpp similarity index 100% rename from apps/atlasSimbicon/State.cpp rename to examples/atlasSimbicon/State.cpp diff --git a/apps/atlasSimbicon/State.h b/examples/atlasSimbicon/State.h similarity index 100% rename from apps/atlasSimbicon/State.h rename to examples/atlasSimbicon/State.h diff --git a/apps/atlasSimbicon/StateMachine.cpp b/examples/atlasSimbicon/StateMachine.cpp similarity index 100% rename from apps/atlasSimbicon/StateMachine.cpp rename to examples/atlasSimbicon/StateMachine.cpp diff --git a/apps/atlasSimbicon/StateMachine.h b/examples/atlasSimbicon/StateMachine.h similarity index 100% rename from apps/atlasSimbicon/StateMachine.h rename to examples/atlasSimbicon/StateMachine.h diff --git a/apps/atlasSimbicon/TerminalCondition.cpp b/examples/atlasSimbicon/TerminalCondition.cpp similarity index 100% rename from apps/atlasSimbicon/TerminalCondition.cpp rename to examples/atlasSimbicon/TerminalCondition.cpp diff --git a/apps/atlasSimbicon/TerminalCondition.h b/examples/atlasSimbicon/TerminalCondition.h similarity index 100% rename from apps/atlasSimbicon/TerminalCondition.h rename to examples/atlasSimbicon/TerminalCondition.h diff --git a/apps/bipedStand/CMakeLists.txt b/examples/bipedStand/CMakeLists.txt similarity index 100% rename from apps/bipedStand/CMakeLists.txt rename to examples/bipedStand/CMakeLists.txt diff --git a/apps/bipedStand/Controller.cpp b/examples/bipedStand/Controller.cpp similarity index 100% rename from apps/bipedStand/Controller.cpp rename to examples/bipedStand/Controller.cpp diff --git a/apps/bipedStand/Controller.h b/examples/bipedStand/Controller.h similarity index 100% rename from apps/bipedStand/Controller.h rename to examples/bipedStand/Controller.h diff --git a/apps/bipedStand/Main.cpp b/examples/bipedStand/Main.cpp similarity index 100% rename from apps/bipedStand/Main.cpp rename to examples/bipedStand/Main.cpp diff --git a/apps/bipedStand/MyWindow.cpp b/examples/bipedStand/MyWindow.cpp similarity index 100% rename from apps/bipedStand/MyWindow.cpp rename to examples/bipedStand/MyWindow.cpp diff --git a/apps/bipedStand/MyWindow.h b/examples/bipedStand/MyWindow.h similarity index 100% rename from apps/bipedStand/MyWindow.h rename to examples/bipedStand/MyWindow.h diff --git a/apps/hardcodedDesign/CMakeLists.txt b/examples/hardcodedDesign/CMakeLists.txt similarity index 100% rename from apps/hardcodedDesign/CMakeLists.txt rename to examples/hardcodedDesign/CMakeLists.txt diff --git a/apps/hardcodedDesign/Main.cpp b/examples/hardcodedDesign/Main.cpp similarity index 100% rename from apps/hardcodedDesign/Main.cpp rename to examples/hardcodedDesign/Main.cpp diff --git a/apps/hardcodedDesign/MyWindow.cpp b/examples/hardcodedDesign/MyWindow.cpp similarity index 100% rename from apps/hardcodedDesign/MyWindow.cpp rename to examples/hardcodedDesign/MyWindow.cpp diff --git a/apps/hardcodedDesign/MyWindow.h b/examples/hardcodedDesign/MyWindow.h similarity index 100% rename from apps/hardcodedDesign/MyWindow.h rename to examples/hardcodedDesign/MyWindow.h diff --git a/apps/hardcodedDesign/README.txt b/examples/hardcodedDesign/README.txt similarity index 100% rename from apps/hardcodedDesign/README.txt rename to examples/hardcodedDesign/README.txt diff --git a/apps/hybridDynamics/CMakeLists.txt b/examples/hybridDynamics/CMakeLists.txt similarity index 100% rename from apps/hybridDynamics/CMakeLists.txt rename to examples/hybridDynamics/CMakeLists.txt diff --git a/apps/hybridDynamics/Main.cpp b/examples/hybridDynamics/Main.cpp similarity index 100% rename from apps/hybridDynamics/Main.cpp rename to examples/hybridDynamics/Main.cpp diff --git a/apps/hybridDynamics/MyWindow.cpp b/examples/hybridDynamics/MyWindow.cpp similarity index 100% rename from apps/hybridDynamics/MyWindow.cpp rename to examples/hybridDynamics/MyWindow.cpp diff --git a/apps/hybridDynamics/MyWindow.h b/examples/hybridDynamics/MyWindow.h similarity index 100% rename from apps/hybridDynamics/MyWindow.h rename to examples/hybridDynamics/MyWindow.h diff --git a/apps/jointConstraints/CMakeLists.txt b/examples/jointConstraints/CMakeLists.txt similarity index 100% rename from apps/jointConstraints/CMakeLists.txt rename to examples/jointConstraints/CMakeLists.txt diff --git a/apps/jointConstraints/Controller.cpp b/examples/jointConstraints/Controller.cpp similarity index 100% rename from apps/jointConstraints/Controller.cpp rename to examples/jointConstraints/Controller.cpp diff --git a/apps/jointConstraints/Controller.h b/examples/jointConstraints/Controller.h similarity index 100% rename from apps/jointConstraints/Controller.h rename to examples/jointConstraints/Controller.h diff --git a/apps/jointConstraints/Main.cpp b/examples/jointConstraints/Main.cpp similarity index 100% rename from apps/jointConstraints/Main.cpp rename to examples/jointConstraints/Main.cpp diff --git a/apps/jointConstraints/MyWindow.cpp b/examples/jointConstraints/MyWindow.cpp similarity index 100% rename from apps/jointConstraints/MyWindow.cpp rename to examples/jointConstraints/MyWindow.cpp diff --git a/apps/jointConstraints/MyWindow.h b/examples/jointConstraints/MyWindow.h similarity index 100% rename from apps/jointConstraints/MyWindow.h rename to examples/jointConstraints/MyWindow.h diff --git a/apps/mixedChain/CMakeLists.txt b/examples/mixedChain/CMakeLists.txt similarity index 100% rename from apps/mixedChain/CMakeLists.txt rename to examples/mixedChain/CMakeLists.txt diff --git a/apps/mixedChain/Main.cpp b/examples/mixedChain/Main.cpp similarity index 100% rename from apps/mixedChain/Main.cpp rename to examples/mixedChain/Main.cpp diff --git a/apps/mixedChain/MyWindow.cpp b/examples/mixedChain/MyWindow.cpp similarity index 100% rename from apps/mixedChain/MyWindow.cpp rename to examples/mixedChain/MyWindow.cpp diff --git a/apps/mixedChain/MyWindow.h b/examples/mixedChain/MyWindow.h similarity index 100% rename from apps/mixedChain/MyWindow.h rename to examples/mixedChain/MyWindow.h diff --git a/apps/operationalSpaceControl/CMakeLists.txt b/examples/operationalSpaceControl/CMakeLists.txt similarity index 100% rename from apps/operationalSpaceControl/CMakeLists.txt rename to examples/operationalSpaceControl/CMakeLists.txt diff --git a/apps/operationalSpaceControl/Controller.cpp b/examples/operationalSpaceControl/Controller.cpp similarity index 100% rename from apps/operationalSpaceControl/Controller.cpp rename to examples/operationalSpaceControl/Controller.cpp diff --git a/apps/operationalSpaceControl/Controller.h b/examples/operationalSpaceControl/Controller.h similarity index 100% rename from apps/operationalSpaceControl/Controller.h rename to examples/operationalSpaceControl/Controller.h diff --git a/apps/operationalSpaceControl/Main.cpp b/examples/operationalSpaceControl/Main.cpp similarity index 100% rename from apps/operationalSpaceControl/Main.cpp rename to examples/operationalSpaceControl/Main.cpp diff --git a/apps/operationalSpaceControl/MyWindow.cpp b/examples/operationalSpaceControl/MyWindow.cpp similarity index 100% rename from apps/operationalSpaceControl/MyWindow.cpp rename to examples/operationalSpaceControl/MyWindow.cpp diff --git a/apps/operationalSpaceControl/MyWindow.h b/examples/operationalSpaceControl/MyWindow.h similarity index 100% rename from apps/operationalSpaceControl/MyWindow.h rename to examples/operationalSpaceControl/MyWindow.h diff --git a/apps/rigidChain/CMakeLists.txt b/examples/rigidChain/CMakeLists.txt similarity index 100% rename from apps/rigidChain/CMakeLists.txt rename to examples/rigidChain/CMakeLists.txt diff --git a/apps/rigidChain/Main.cpp b/examples/rigidChain/Main.cpp similarity index 100% rename from apps/rigidChain/Main.cpp rename to examples/rigidChain/Main.cpp diff --git a/apps/rigidChain/MyWindow.cpp b/examples/rigidChain/MyWindow.cpp similarity index 100% rename from apps/rigidChain/MyWindow.cpp rename to examples/rigidChain/MyWindow.cpp diff --git a/apps/rigidChain/MyWindow.h b/examples/rigidChain/MyWindow.h similarity index 100% rename from apps/rigidChain/MyWindow.h rename to examples/rigidChain/MyWindow.h diff --git a/apps/rigidCubes/CMakeLists.txt b/examples/rigidCubes/CMakeLists.txt similarity index 100% rename from apps/rigidCubes/CMakeLists.txt rename to examples/rigidCubes/CMakeLists.txt diff --git a/apps/rigidCubes/Main.cpp b/examples/rigidCubes/Main.cpp similarity index 100% rename from apps/rigidCubes/Main.cpp rename to examples/rigidCubes/Main.cpp diff --git a/apps/rigidCubes/MyWindow.cpp b/examples/rigidCubes/MyWindow.cpp similarity index 100% rename from apps/rigidCubes/MyWindow.cpp rename to examples/rigidCubes/MyWindow.cpp diff --git a/apps/rigidCubes/MyWindow.h b/examples/rigidCubes/MyWindow.h similarity index 100% rename from apps/rigidCubes/MyWindow.h rename to examples/rigidCubes/MyWindow.h diff --git a/apps/rigidLoop/CMakeLists.txt b/examples/rigidLoop/CMakeLists.txt similarity index 100% rename from apps/rigidLoop/CMakeLists.txt rename to examples/rigidLoop/CMakeLists.txt diff --git a/apps/rigidLoop/Main.cpp b/examples/rigidLoop/Main.cpp similarity index 100% rename from apps/rigidLoop/Main.cpp rename to examples/rigidLoop/Main.cpp diff --git a/apps/rigidLoop/MyWindow.cpp b/examples/rigidLoop/MyWindow.cpp similarity index 100% rename from apps/rigidLoop/MyWindow.cpp rename to examples/rigidLoop/MyWindow.cpp diff --git a/apps/rigidLoop/MyWindow.h b/examples/rigidLoop/MyWindow.h similarity index 100% rename from apps/rigidLoop/MyWindow.h rename to examples/rigidLoop/MyWindow.h diff --git a/apps/rigidShapes/CMakeLists.txt b/examples/rigidShapes/CMakeLists.txt similarity index 100% rename from apps/rigidShapes/CMakeLists.txt rename to examples/rigidShapes/CMakeLists.txt diff --git a/apps/rigidShapes/Main.cpp b/examples/rigidShapes/Main.cpp similarity index 100% rename from apps/rigidShapes/Main.cpp rename to examples/rigidShapes/Main.cpp diff --git a/apps/rigidShapes/MyWindow.cpp b/examples/rigidShapes/MyWindow.cpp similarity index 100% rename from apps/rigidShapes/MyWindow.cpp rename to examples/rigidShapes/MyWindow.cpp diff --git a/apps/rigidShapes/MyWindow.h b/examples/rigidShapes/MyWindow.h similarity index 100% rename from apps/rigidShapes/MyWindow.h rename to examples/rigidShapes/MyWindow.h diff --git a/apps/simpleFrames/CMakeLists.txt b/examples/simpleFrames/CMakeLists.txt similarity index 100% rename from apps/simpleFrames/CMakeLists.txt rename to examples/simpleFrames/CMakeLists.txt diff --git a/apps/simpleFrames/Main.cpp b/examples/simpleFrames/Main.cpp similarity index 100% rename from apps/simpleFrames/Main.cpp rename to examples/simpleFrames/Main.cpp diff --git a/apps/softBodies/CMakeLists.txt b/examples/softBodies/CMakeLists.txt similarity index 100% rename from apps/softBodies/CMakeLists.txt rename to examples/softBodies/CMakeLists.txt diff --git a/apps/softBodies/Main.cpp b/examples/softBodies/Main.cpp similarity index 100% rename from apps/softBodies/Main.cpp rename to examples/softBodies/Main.cpp diff --git a/apps/softBodies/MyWindow.cpp b/examples/softBodies/MyWindow.cpp similarity index 100% rename from apps/softBodies/MyWindow.cpp rename to examples/softBodies/MyWindow.cpp diff --git a/apps/softBodies/MyWindow.h b/examples/softBodies/MyWindow.h similarity index 100% rename from apps/softBodies/MyWindow.h rename to examples/softBodies/MyWindow.h diff --git a/apps/speedTest/CMakeLists.txt b/examples/speedTest/CMakeLists.txt similarity index 100% rename from apps/speedTest/CMakeLists.txt rename to examples/speedTest/CMakeLists.txt diff --git a/apps/speedTest/Main.cpp b/examples/speedTest/Main.cpp similarity index 100% rename from apps/speedTest/Main.cpp rename to examples/speedTest/Main.cpp diff --git a/apps/vehicle/CMakeLists.txt b/examples/vehicle/CMakeLists.txt similarity index 100% rename from apps/vehicle/CMakeLists.txt rename to examples/vehicle/CMakeLists.txt diff --git a/apps/vehicle/Main.cpp b/examples/vehicle/Main.cpp similarity index 100% rename from apps/vehicle/Main.cpp rename to examples/vehicle/Main.cpp diff --git a/apps/vehicle/MyWindow.cpp b/examples/vehicle/MyWindow.cpp similarity index 100% rename from apps/vehicle/MyWindow.cpp rename to examples/vehicle/MyWindow.cpp diff --git a/apps/vehicle/MyWindow.h b/examples/vehicle/MyWindow.h similarity index 100% rename from apps/vehicle/MyWindow.h rename to examples/vehicle/MyWindow.h From 95ad8b598d742f4f7f1a5a593e284e205f430c05 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 22 Apr 2016 01:52:42 -0400 Subject: [PATCH 27/34] More rename: app --> example --- CMakeLists.txt | 2 +- dart/CMakeLists.txt | 4 ++-- examples/CMakeLists.txt | 14 +++++++------- examples/addDeleteSkels/CMakeLists.txt | 17 ++++++++++------- examples/addDeleteSkels/MyWindow.h | 6 +++--- examples/atlasSimbicon/CMakeLists.txt | 18 +++++++++++------- examples/atlasSimbicon/Controller.cpp | 8 ++++---- examples/atlasSimbicon/Controller.h | 6 +++--- examples/atlasSimbicon/Humanoid.cpp | 4 ++-- examples/atlasSimbicon/Humanoid.h | 6 +++--- examples/atlasSimbicon/Main.cpp | 4 ++-- examples/atlasSimbicon/MyWindow.cpp | 2 +- examples/atlasSimbicon/MyWindow.h | 8 ++++---- examples/atlasSimbicon/State.cpp | 4 ++-- examples/atlasSimbicon/State.h | 6 +++--- examples/atlasSimbicon/StateMachine.cpp | 4 ++-- examples/atlasSimbicon/StateMachine.h | 6 +++--- examples/atlasSimbicon/TerminalCondition.cpp | 4 ++-- examples/atlasSimbicon/TerminalCondition.h | 6 +++--- examples/bipedStand/CMakeLists.txt | 17 ++++++++++------- examples/bipedStand/Controller.cpp | 2 +- examples/bipedStand/Controller.h | 6 +++--- examples/bipedStand/Main.cpp | 2 +- examples/bipedStand/MyWindow.cpp | 2 +- examples/bipedStand/MyWindow.h | 8 ++++---- examples/hardcodedDesign/CMakeLists.txt | 18 ++++++++++-------- examples/hardcodedDesign/Main.cpp | 2 +- examples/hardcodedDesign/MyWindow.cpp | 2 +- examples/hardcodedDesign/MyWindow.h | 6 +++--- examples/hybridDynamics/CMakeLists.txt | 18 +++++++++++------- examples/hybridDynamics/MyWindow.h | 6 +++--- examples/jointConstraints/CMakeLists.txt | 18 +++++++++++------- examples/jointConstraints/Controller.cpp | 2 +- examples/jointConstraints/Controller.h | 6 +++--- examples/jointConstraints/Main.cpp | 2 +- examples/jointConstraints/MyWindow.cpp | 2 +- examples/jointConstraints/MyWindow.h | 8 ++++---- examples/mixedChain/CMakeLists.txt | 19 +++++++++++-------- examples/mixedChain/Main.cpp | 2 +- examples/mixedChain/MyWindow.cpp | 2 +- examples/mixedChain/MyWindow.h | 6 +++--- .../operationalSpaceControl/CMakeLists.txt | 17 ++++++++++------- .../operationalSpaceControl/Controller.cpp | 2 +- examples/operationalSpaceControl/Controller.h | 6 +++--- examples/operationalSpaceControl/Main.cpp | 2 +- examples/operationalSpaceControl/MyWindow.cpp | 2 +- examples/operationalSpaceControl/MyWindow.h | 6 +++--- examples/rigidChain/CMakeLists.txt | 17 ++++++++++------- examples/rigidChain/Main.cpp | 2 +- examples/rigidChain/MyWindow.cpp | 2 +- examples/rigidChain/MyWindow.h | 6 +++--- examples/rigidCubes/CMakeLists.txt | 17 ++++++++++------- examples/rigidCubes/Main.cpp | 2 +- examples/rigidCubes/MyWindow.cpp | 2 +- examples/rigidCubes/MyWindow.h | 6 +++--- examples/rigidLoop/CMakeLists.txt | 17 ++++++++++------- examples/rigidLoop/Main.cpp | 2 +- examples/rigidLoop/MyWindow.cpp | 2 +- examples/rigidLoop/MyWindow.h | 6 +++--- examples/rigidShapes/CMakeLists.txt | 18 ++++++++++-------- examples/rigidShapes/MyWindow.h | 6 +++--- examples/simpleFrames/CMakeLists.txt | 18 ++++++++++-------- examples/softBodies/CMakeLists.txt | 18 ++++++++++-------- examples/softBodies/Main.cpp | 2 +- examples/softBodies/MyWindow.cpp | 2 +- examples/softBodies/MyWindow.h | 6 +++--- examples/speedTest/CMakeLists.txt | 12 ++++++------ examples/vehicle/CMakeLists.txt | 17 ++++++++++------- examples/vehicle/Main.cpp | 2 +- examples/vehicle/MyWindow.cpp | 2 +- examples/vehicle/MyWindow.h | 6 +++--- 71 files changed, 277 insertions(+), 233 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 05bd159e9b835..48dfd3874e415 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -279,7 +279,7 @@ endfunction(dart_add_unittest) #=============================================================================== add_subdirectory(dart) -add_subdirectory(apps EXCLUDE_FROM_ALL) +add_subdirectory(examples EXCLUDE_FROM_ALL) add_subdirectory(tutorials EXCLUDE_FROM_ALL) # Add a "tutorials" target to build tutorials. diff --git a/dart/CMakeLists.txt b/dart/CMakeLists.txt index b5857112505f9..0dd56179d5077 100644 --- a/dart/CMakeLists.txt +++ b/dart/CMakeLists.txt @@ -1,6 +1,6 @@ # Enable multi-threaded compilation. -# We do this here and not in the root folder since the example apps -# do not have enough source files to benefit from this. +# We do this here and not in the root folder since the examples and the +# tutorialsdo not have enough source files to benefit from this. if(MSVC) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /MP") endif() diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 6a2e9539a6963..79161a571dcf8 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -1,7 +1,7 @@ -# A list of applications -set_property(DIRECTORY PROPERTY FOLDER Apps) +# A list of examples +set_property(DIRECTORY PROPERTY FOLDER Examples) -# Automatically identify all directories in the apps folder +# Automatically identify all directories in the examples folder file(GLOB children RELATIVE ${CMAKE_CURRENT_LIST_DIR} "*") set(directories "") foreach(child ${children}) @@ -13,7 +13,7 @@ foreach(child ${children}) endforeach(child) # List of all the subdirectories to include -foreach(APPDIR ${directories}) - add_subdirectory(${APPDIR}) - dart_add_example(${APPDIR}) -endforeach(APPDIR) +foreach(EXAMPLE_DIR ${directories}) + add_subdirectory(${EXAMPLE_DIR}) + dart_add_example(${EXAMPLE_DIR}) +endforeach(EXAMPLE_DIR) diff --git a/examples/addDeleteSkels/CMakeLists.txt b/examples/addDeleteSkels/CMakeLists.txt index 283f4ed6064dc..4c79c3b22d1f5 100644 --- a/examples/addDeleteSkels/CMakeLists.txt +++ b/examples/addDeleteSkels/CMakeLists.txt @@ -1,7 +1,10 @@ -############################################### -# apps/addDeleteSkels -file(GLOB addDeleteSkels_srcs "*.cpp") -file(GLOB addDeleteSkels_hdrs "*.h") -add_executable(addDeleteSkels ${addDeleteSkels_srcs} ${addDeleteSkels_hdrs}) -target_link_libraries(addDeleteSkels dart dart-gui) -set_target_properties(addDeleteSkels PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/addDeleteSkels/MyWindow.h b/examples/addDeleteSkels/MyWindow.h index d440b2c656235..be0c7bf1b9289 100644 --- a/examples/addDeleteSkels/MyWindow.h +++ b/examples/addDeleteSkels/MyWindow.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_ADDDELETESKELS_MYWINDOW_H_ -#define APPS_ADDDELETESKELS_MYWINDOW_H_ +#ifndef EXAMPLES_ADDDELETESKELS_MYWINDOW_H_ +#define EXAMPLES_ADDDELETESKELS_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -63,4 +63,4 @@ class MyWindow : public dart::gui::SimWindow { double _mass = 0.1); }; -#endif // APPS_ADDDELETESKELS_MYWINDOW_H_ +#endif // EXAMPLES_ADDDELETESKELS_MYWINDOW_H_ diff --git a/examples/atlasSimbicon/CMakeLists.txt b/examples/atlasSimbicon/CMakeLists.txt index 129ea9a0316f0..8e3d7081cab4f 100644 --- a/examples/atlasSimbicon/CMakeLists.txt +++ b/examples/atlasSimbicon/CMakeLists.txt @@ -1,7 +1,11 @@ -############################################### -# apps/atlasSimbicon -file(GLOB atlasSimbicon_srcs "*.cpp") -file(GLOB atlasSimbicon_hdrs "*.h") -add_executable(atlasSimbicon ${atlasSimbicon_srcs} ${atlasSimbicon_hdrs}) -target_link_libraries(atlasSimbicon dart dart-gui dart-utils-urdf) -set_target_properties(atlasSimbicon PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui dart-utils-urdf) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") + diff --git a/examples/atlasSimbicon/Controller.cpp b/examples/atlasSimbicon/Controller.cpp index e49abbce0bad7..386b2008ca213 100644 --- a/examples/atlasSimbicon/Controller.cpp +++ b/examples/atlasSimbicon/Controller.cpp @@ -34,11 +34,11 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/atlasSimbicon/Controller.h" +#include "examples/atlasSimbicon/Controller.h" -#include "apps/atlasSimbicon/State.h" -#include "apps/atlasSimbicon/StateMachine.h" -#include "apps/atlasSimbicon/TerminalCondition.h" +#include "examples/atlasSimbicon/State.h" +#include "examples/atlasSimbicon/StateMachine.h" +#include "examples/atlasSimbicon/TerminalCondition.h" using namespace std; diff --git a/examples/atlasSimbicon/Controller.h b/examples/atlasSimbicon/Controller.h index 4c5f6c50d700b..af62815842969 100644 --- a/examples/atlasSimbicon/Controller.h +++ b/examples/atlasSimbicon/Controller.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_ATLASROBOT_CONTROLLER_H_ -#define APPS_ATLASROBOT_CONTROLLER_H_ +#ifndef EXAMPLES_ATLASSIMBICON_CONTROLLER_H_ +#define EXAMPLES_ATLASSIMBICON_CONTROLLER_H_ #include @@ -184,4 +184,4 @@ class Controller dart::dynamics::Skeleton::Configuration mInitialState; }; -#endif // APPS_ATLASROBOT_CONTROLLER_H_ +#endif // EXAMPLES_ATLASSIMBICON_CONTROLLER_H_ diff --git a/examples/atlasSimbicon/Humanoid.cpp b/examples/atlasSimbicon/Humanoid.cpp index b09c6bc0f80df..4b45323619477 100644 --- a/examples/atlasSimbicon/Humanoid.cpp +++ b/examples/atlasSimbicon/Humanoid.cpp @@ -34,9 +34,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/atlasSimbicon/Humanoid.h" +#include "examples/atlasSimbicon/Humanoid.h" -#include "apps/atlasSimbicon/State.h" +#include "examples/atlasSimbicon/State.h" // Macro for functions not implemented yet #define NOT_YET(FUNCTION) std::cout << #FUNCTION\ diff --git a/examples/atlasSimbicon/Humanoid.h b/examples/atlasSimbicon/Humanoid.h index 83d74d1cae1f7..9f7fbedd03334 100644 --- a/examples/atlasSimbicon/Humanoid.h +++ b/examples/atlasSimbicon/Humanoid.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_ATLASROBOT_HUMANOID_H_ -#define APPS_ATLASROBOT_HUMANOID_H_ +#ifndef EXAMPLES_ATLASSIMBICON_HUMANOID_H_ +#define EXAMPLES_ATLASSIMBICON_HUMANOID_H_ #include #include @@ -123,4 +123,4 @@ class AtlasRobot : public Humanoid protected: }; -#endif // APPS_ATLASROBOT_HUMANOID_H_ +#endif // EXAMPLES_ATLASSIMBICON_HUMANOID_H_ diff --git a/examples/atlasSimbicon/Main.cpp b/examples/atlasSimbicon/Main.cpp index 69856deffb58e..54098d2ca22f2 100644 --- a/examples/atlasSimbicon/Main.cpp +++ b/examples/atlasSimbicon/Main.cpp @@ -39,8 +39,8 @@ #include "dart/dart.h" -#include "apps/atlasSimbicon/MyWindow.h" -#include "apps/atlasSimbicon/Controller.h" +#include "examples/atlasSimbicon/MyWindow.h" +#include "examples/atlasSimbicon/Controller.h" using namespace std; using namespace Eigen; diff --git a/examples/atlasSimbicon/MyWindow.cpp b/examples/atlasSimbicon/MyWindow.cpp index d06c654b3ddd6..48b29ccd01d15 100644 --- a/examples/atlasSimbicon/MyWindow.cpp +++ b/examples/atlasSimbicon/MyWindow.cpp @@ -35,7 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/atlasSimbicon/MyWindow.h" +#include "examples/atlasSimbicon/MyWindow.h" //============================================================================== MyWindow::MyWindow(Controller* _controller) diff --git a/examples/atlasSimbicon/MyWindow.h b/examples/atlasSimbicon/MyWindow.h index bbf19a732b0fc..453851fae588c 100644 --- a/examples/atlasSimbicon/MyWindow.h +++ b/examples/atlasSimbicon/MyWindow.h @@ -35,13 +35,13 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_ATLASROBOT_MYWINDOW_H_ -#define APPS_ATLASROBOT_MYWINDOW_H_ +#ifndef EXAMPLES_ATLASSIMBICON_MYWINDOW_H_ +#define EXAMPLES_ATLASSIMBICON_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" -#include "apps/atlasSimbicon/Controller.h" +#include "examples/atlasSimbicon/Controller.h" /// \brief class MyWindow class MyWindow : public dart::gui::SimWindow @@ -73,4 +73,4 @@ class MyWindow : public dart::gui::SimWindow Controller* mController; }; -#endif // APPS_ATLASROBOT_MYWINDOW_H_ +#endif // EXAMPLES_ATLASSIMBICON_MYWINDOW_H_ diff --git a/examples/atlasSimbicon/State.cpp b/examples/atlasSimbicon/State.cpp index 43a2e0083e599..b8e82f9c040b1 100644 --- a/examples/atlasSimbicon/State.cpp +++ b/examples/atlasSimbicon/State.cpp @@ -34,9 +34,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/atlasSimbicon/State.h" +#include "examples/atlasSimbicon/State.h" -#include "apps/atlasSimbicon/TerminalCondition.h" +#include "examples/atlasSimbicon/TerminalCondition.h" // Macro for functions not implemented yet #define NOT_YET(FUNCTION) std::cout << #FUNCTION\ diff --git a/examples/atlasSimbicon/State.h b/examples/atlasSimbicon/State.h index abdda3a92f817..b1a3e5bc2ffd1 100644 --- a/examples/atlasSimbicon/State.h +++ b/examples/atlasSimbicon/State.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_ATLASROBOT_STATE_H_ -#define APPS_ATLASROBOT_STATE_H_ +#ifndef EXAMPLES_ATLASSIMBICON_STATE_H_ +#define EXAMPLES_ATLASSIMBICON_STATE_H_ #include #include @@ -336,4 +336,4 @@ class State Eigen::VectorXd mDesiredJointPositionsBalance; }; -#endif // APPS_ATLASROBOT_STATE_H_ +#endif // EXAMPLES_ATLASSIMBICON_STATE_H_ diff --git a/examples/atlasSimbicon/StateMachine.cpp b/examples/atlasSimbicon/StateMachine.cpp index dad6348b6f5ad..7d2130c32edc3 100644 --- a/examples/atlasSimbicon/StateMachine.cpp +++ b/examples/atlasSimbicon/StateMachine.cpp @@ -34,9 +34,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/atlasSimbicon/StateMachine.h" +#include "examples/atlasSimbicon/StateMachine.h" -#include "apps/atlasSimbicon/State.h" +#include "examples/atlasSimbicon/State.h" // Macro for functions not implemented yet #define NOT_YET(FUNCTION) std::cout << #FUNCTION\ diff --git a/examples/atlasSimbicon/StateMachine.h b/examples/atlasSimbicon/StateMachine.h index b0a574255c826..f5b1608151bd1 100644 --- a/examples/atlasSimbicon/StateMachine.h +++ b/examples/atlasSimbicon/StateMachine.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_ATLASROBOT_STATEMACHINE_H_ -#define APPS_ATLASROBOT_STATEMACHINE_H_ +#ifndef EXAMPLES_ATLASSIMBICON_STATEMACHINE_H_ +#define EXAMPLES_ATLASSIMBICON_STATEMACHINE_H_ #include #include @@ -129,4 +129,4 @@ class StateMachine State* _findState(const std::string& _name) const; }; -#endif // APPS_ATLASROBOT_STATEMACHINE_H_ +#endif // EXAMPLES_ATLASSIMBICON_STATEMACHINE_H_ diff --git a/examples/atlasSimbicon/TerminalCondition.cpp b/examples/atlasSimbicon/TerminalCondition.cpp index 84df24074a7dd..41bf99b303264 100644 --- a/examples/atlasSimbicon/TerminalCondition.cpp +++ b/examples/atlasSimbicon/TerminalCondition.cpp @@ -34,9 +34,9 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/atlasSimbicon/TerminalCondition.h" +#include "examples/atlasSimbicon/TerminalCondition.h" -#include "apps/atlasSimbicon/State.h" +#include "examples/atlasSimbicon/State.h" // Macro for functions not implemented yet #define NOT_YET(FUNCTION) std::cout << #FUNCTION\ diff --git a/examples/atlasSimbicon/TerminalCondition.h b/examples/atlasSimbicon/TerminalCondition.h index 0f52cf358f37d..daea7ef30bc5f 100644 --- a/examples/atlasSimbicon/TerminalCondition.h +++ b/examples/atlasSimbicon/TerminalCondition.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_ATLASROBOT_TERMINALCONDITION_H_ -#define APPS_ATLASROBOT_TERMINALCONDITION_H_ +#ifndef EXAMPLES_ATLASSIMBICON_TERMINALCONDITION_H_ +#define EXAMPLES_ATLASSIMBICON_TERMINALCONDITION_H_ #include #include @@ -103,4 +103,4 @@ class BodyContactCondition : public TerminalCondition dart::dynamics::BodyNode* mBodyNode; }; -#endif // APPS_ATLASROBOT_TERMINALCONDITION_H_ +#endif // EXAMPLES_ATLASSIMBICON_TERMINALCONDITION_H_ diff --git a/examples/bipedStand/CMakeLists.txt b/examples/bipedStand/CMakeLists.txt index d19b01cb72e8e..4c79c3b22d1f5 100644 --- a/examples/bipedStand/CMakeLists.txt +++ b/examples/bipedStand/CMakeLists.txt @@ -1,7 +1,10 @@ -############################################### -# apps/bipedStand -file(GLOB bipedStand_srcs "*.cpp") -file(GLOB bipedStand_hdrs "*.h") -add_executable(bipedStand ${bipedStand_srcs} ${bipedStand_hdrs}) -target_link_libraries(bipedStand dart dart-gui) -set_target_properties(bipedStand PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/bipedStand/Controller.cpp b/examples/bipedStand/Controller.cpp index 301a735f0e3e5..0ffc21c288eb8 100644 --- a/examples/bipedStand/Controller.cpp +++ b/examples/bipedStand/Controller.cpp @@ -35,7 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/bipedStand/Controller.h" +#include "examples/bipedStand/Controller.h" Controller::Controller(dart::dynamics::SkeletonPtr _skel, double _t) { diff --git a/examples/bipedStand/Controller.h b/examples/bipedStand/Controller.h index e17625835106b..733fcbdbe4eb4 100644 --- a/examples/bipedStand/Controller.h +++ b/examples/bipedStand/Controller.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_BALANCE_CONTROLLER_H_ -#define APPS_BALANCE_CONTROLLER_H_ +#ifndef EXAMPLES_BIPEDSTAND_CONTROLLER_H_ +#define EXAMPLES_BIPEDSTAND_CONTROLLER_H_ #include @@ -75,4 +75,4 @@ class Controller { /// \brief SPD utilizes the current info about contact forces }; -#endif // APPS_BALANCE_CONTROLLER_H_ +#endif // EXAMPLES_BIPEDSTAND_CONTROLLER_H_ diff --git a/examples/bipedStand/Main.cpp b/examples/bipedStand/Main.cpp index 79ab04fc6cb66..a64b4a2830137 100644 --- a/examples/bipedStand/Main.cpp +++ b/examples/bipedStand/Main.cpp @@ -40,7 +40,7 @@ #include "dart/dart.h" -#include "apps/bipedStand/MyWindow.h" +#include "examples/bipedStand/MyWindow.h" int main(int argc, char* argv[]) { // create and initialize the world diff --git a/examples/bipedStand/MyWindow.cpp b/examples/bipedStand/MyWindow.cpp index 8b222b95fdb7a..9deeeea982ad7 100644 --- a/examples/bipedStand/MyWindow.cpp +++ b/examples/bipedStand/MyWindow.cpp @@ -35,7 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/bipedStand/MyWindow.h" +#include "examples/bipedStand/MyWindow.h" MyWindow::MyWindow(): SimWindow() { mForce = Eigen::Vector3d::Zero(); diff --git a/examples/bipedStand/MyWindow.h b/examples/bipedStand/MyWindow.h index a81d71ecbea30..896f3f1c00e18 100644 --- a/examples/bipedStand/MyWindow.h +++ b/examples/bipedStand/MyWindow.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_BALANCE_MYWINDOW_H_ -#define APPS_BALANCE_MYWINDOW_H_ +#ifndef EXAMPLES_BIPEDSTAND_MYWINDOW_H_ +#define EXAMPLES_BIPEDSTAND_MYWINDOW_H_ #include @@ -45,7 +45,7 @@ #include "dart/dart.h" #include "dart/gui/gui.h" -#include "apps/bipedStand/Controller.h" +#include "examples/bipedStand/Controller.h" class MyWindow : public dart::gui::SimWindow { public: @@ -65,4 +65,4 @@ class MyWindow : public dart::gui::SimWindow { int mImpulseDuration; }; -#endif // APPS_BALANCE_MYWINDOW_H_ +#endif // EXAMPLES_BIPEDSTAND_MYWINDOW_H_ diff --git a/examples/hardcodedDesign/CMakeLists.txt b/examples/hardcodedDesign/CMakeLists.txt index 1a76038462d1c..4c79c3b22d1f5 100644 --- a/examples/hardcodedDesign/CMakeLists.txt +++ b/examples/hardcodedDesign/CMakeLists.txt @@ -1,8 +1,10 @@ -############################################### -# apps/hardcodedDesign - -file(GLOB hardcodedDesign_srcs "*.cpp") -file(GLOB hardcodedDesign_hdrs "*.h") -add_executable(hardcodedDesign ${hardcodedDesign_srcs} ${hardcodedDesign_hdrs}) -target_link_libraries(hardcodedDesign dart dart-gui) -set_target_properties(hardcodedDesign PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/hardcodedDesign/Main.cpp b/examples/hardcodedDesign/Main.cpp index aaf8b63fa2d81..54a9d5f1fe7b9 100644 --- a/examples/hardcodedDesign/Main.cpp +++ b/examples/hardcodedDesign/Main.cpp @@ -47,7 +47,7 @@ #include "dart/dart.h" -#include "apps/hardcodedDesign/MyWindow.h" +#include "examples/hardcodedDesign/MyWindow.h" int main(int argc, char* argv[]) { // Create Left Leg skeleton diff --git a/examples/hardcodedDesign/MyWindow.cpp b/examples/hardcodedDesign/MyWindow.cpp index 4ae321d31df63..c2322793c0c27 100644 --- a/examples/hardcodedDesign/MyWindow.cpp +++ b/examples/hardcodedDesign/MyWindow.cpp @@ -41,7 +41,7 @@ * @brief Simple example of a skeleton created from scratch. */ -#include "apps/hardcodedDesign/MyWindow.h" +#include "examples/hardcodedDesign/MyWindow.h" void MyWindow::draw() { glDisable(GL_LIGHTING); diff --git a/examples/hardcodedDesign/MyWindow.h b/examples/hardcodedDesign/MyWindow.h index 6560476d46ecb..6ae82003a129f 100644 --- a/examples/hardcodedDesign/MyWindow.h +++ b/examples/hardcodedDesign/MyWindow.h @@ -41,8 +41,8 @@ * @brief Simple example of a skeleton created from scratch. */ -#ifndef APPS_HARDCODEDDESIGN_MYWINDOW_H_ -#define APPS_HARDCODEDDESIGN_MYWINDOW_H_ +#ifndef EXAMPLES_HARDCODEDDESIGN_MYWINDOW_H_ +#define EXAMPLES_HARDCODEDDESIGN_MYWINDOW_H_ #include #include @@ -68,4 +68,4 @@ class MyWindow : public dart::gui::SimWindow { dart::dynamics::SkeletonPtr skel; }; -#endif // APPS_HARDCODEDDESIGN_MYWINDOW_H_ +#endif // EXAMPLES_HARDCODEDDESIGN_MYWINDOW_H_ diff --git a/examples/hybridDynamics/CMakeLists.txt b/examples/hybridDynamics/CMakeLists.txt index cb0b72e655732..d309d200fcf6f 100644 --- a/examples/hybridDynamics/CMakeLists.txt +++ b/examples/hybridDynamics/CMakeLists.txt @@ -1,7 +1,11 @@ -############################################### -# apps/hybridDynamics -file(GLOB hybridDynamics_srcs "*.cpp") -file(GLOB hybridDynamics_hdrs "*.h") -add_executable(hybridDynamics ${hybridDynamics_srcs} ${hybridDynamics_hdrs}) -target_link_libraries(hybridDynamics dart dart-gui) -set_target_properties(hybridDynamics PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") + diff --git a/examples/hybridDynamics/MyWindow.h b/examples/hybridDynamics/MyWindow.h index f45c820142c78..c71c3603772d9 100644 --- a/examples/hybridDynamics/MyWindow.h +++ b/examples/hybridDynamics/MyWindow.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_HYBRIDDYNAMICS_MYWINDOW_H_ -#define APPS_HYBRIDDYNAMICS_MYWINDOW_H_ +#ifndef EXAMPLES_HYBRIDDYNAMICS_MYWINDOW_H_ +#define EXAMPLES_HYBRIDDYNAMICS_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -63,4 +63,4 @@ class MyWindow : public dart::gui::SimWindow bool mHarnessOn; }; -#endif // APPS_HYBRIDDYNAMICS_MYWINDOW_H_ +#endif // EXAMPLES_HYBRIDDYNAMICS_MYWINDOW_H_ diff --git a/examples/jointConstraints/CMakeLists.txt b/examples/jointConstraints/CMakeLists.txt index 76a2f2d6c2cfa..d309d200fcf6f 100644 --- a/examples/jointConstraints/CMakeLists.txt +++ b/examples/jointConstraints/CMakeLists.txt @@ -1,7 +1,11 @@ -############################################### -# apps/jointConstraints -file(GLOB jointConstraints_srcs "*.cpp") -file(GLOB jointConstraints_hdrs "*.h") -add_executable(jointConstraints ${jointConstraints_srcs} ${jointConstraints_hdrs}) -target_link_libraries(jointConstraints dart dart-gui) -set_target_properties(jointConstraints PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") + diff --git a/examples/jointConstraints/Controller.cpp b/examples/jointConstraints/Controller.cpp index 44dd9f8892f5a..4a444ff95dd71 100644 --- a/examples/jointConstraints/Controller.cpp +++ b/examples/jointConstraints/Controller.cpp @@ -34,7 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/jointConstraints/Controller.h" +#include "examples/jointConstraints/Controller.h" using namespace dart; using namespace dynamics; diff --git a/examples/jointConstraints/Controller.h b/examples/jointConstraints/Controller.h index 05fa693644b13..d90f99584eddb 100644 --- a/examples/jointConstraints/Controller.h +++ b/examples/jointConstraints/Controller.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_HARNESSTEST_CONTROLLER_H_ -#define APPS_HARNESSTEST_CONTROLLER_H_ +#ifndef EXAMPLES_JOINTCONSTRAINTS_CONTROLLER_H_ +#define EXAMPLES_JOINTCONSTRAINTS_CONTROLLER_H_ #include @@ -80,4 +80,4 @@ class Controller Eigen::VectorXd mConstrForces; // SPD utilizes the current info about contact forces }; -#endif // APPS_HARNESSTEST_CONTROLLER_H_ +#endif // EXAMPLES_JOINTCONSTRAINTS_CONTROLLER_H_ diff --git a/examples/jointConstraints/Main.cpp b/examples/jointConstraints/Main.cpp index 45b316879d160..f04b922772277 100644 --- a/examples/jointConstraints/Main.cpp +++ b/examples/jointConstraints/Main.cpp @@ -34,7 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/jointConstraints/MyWindow.h" +#include "examples/jointConstraints/MyWindow.h" #include diff --git a/examples/jointConstraints/MyWindow.cpp b/examples/jointConstraints/MyWindow.cpp index 55846bc39c0b5..1fdae824f74c4 100644 --- a/examples/jointConstraints/MyWindow.cpp +++ b/examples/jointConstraints/MyWindow.cpp @@ -34,7 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/jointConstraints/MyWindow.h" +#include "examples/jointConstraints/MyWindow.h" using namespace dart; using namespace math; diff --git a/examples/jointConstraints/MyWindow.h b/examples/jointConstraints/MyWindow.h index efc397bddd7fe..f3fe730013866 100644 --- a/examples/jointConstraints/MyWindow.h +++ b/examples/jointConstraints/MyWindow.h @@ -34,13 +34,13 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_HARNESSTEST_MYWINDOW_H_ -#define APPS_HARNESSTEST_MYWINDOW_H_ +#ifndef EXAMPLES_JOINTCONSTRAINTS_MYWINDOW_H_ +#define EXAMPLES_JOINTCONSTRAINTS_MYWINDOW_H_ #include #include -#include "apps/jointConstraints/Controller.h" +#include "examples/jointConstraints/Controller.h" #include "dart/dart.h" #include "dart/gui/gui.h" @@ -79,7 +79,7 @@ class MyWindow : public dart::gui::SimWindow }; -#endif // APPS_HARNESSTEST_MYWINDOW_H_ +#endif // EXAMPLES_JOINTCONSTRAINTS_MYWINDOW_H_ /* #include diff --git a/examples/mixedChain/CMakeLists.txt b/examples/mixedChain/CMakeLists.txt index 97c2d83bf88db..d309d200fcf6f 100644 --- a/examples/mixedChain/CMakeLists.txt +++ b/examples/mixedChain/CMakeLists.txt @@ -1,8 +1,11 @@ -############################################### -# apps/mixedChain -set(APP_NAME mixedChain) -file(GLOB ${APP_NAME}_srcs "*.cpp") -file(GLOB ${APP_NAME}_hdrs "*.h") -add_executable(${APP_NAME} ${${APP_NAME}_srcs} ${${APP_NAME}_hdrs}) -target_link_libraries(${APP_NAME} dart dart-gui) -set_target_properties(${APP_NAME} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") + diff --git a/examples/mixedChain/Main.cpp b/examples/mixedChain/Main.cpp index 8bc2810be083d..f319f2be45477 100644 --- a/examples/mixedChain/Main.cpp +++ b/examples/mixedChain/Main.cpp @@ -44,7 +44,7 @@ #include "dart/dart.h" -#include "apps/mixedChain/MyWindow.h" +#include "examples/mixedChain/MyWindow.h" int main(int argc, char* argv[]) { diff --git a/examples/mixedChain/MyWindow.cpp b/examples/mixedChain/MyWindow.cpp index eb99784511ffe..f160d0913e2c2 100644 --- a/examples/mixedChain/MyWindow.cpp +++ b/examples/mixedChain/MyWindow.cpp @@ -40,7 +40,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/mixedChain/MyWindow.h" +#include "examples/mixedChain/MyWindow.h" #define FORCE_ON_RIGIDBODY 500.0; #define FORCE_ON_VERTEX 1.00; diff --git a/examples/mixedChain/MyWindow.h b/examples/mixedChain/MyWindow.h index a428a22999cf7..e35f620d7a97a 100644 --- a/examples/mixedChain/MyWindow.h +++ b/examples/mixedChain/MyWindow.h @@ -40,8 +40,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_TESTDROP_MYWINDOW_H_ -#define APPS_TESTDROP_MYWINDOW_H_ +#ifndef EXAMPLES_TESTDROP_MYWINDOW_H_ +#define EXAMPLES_TESTDROP_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -76,4 +76,4 @@ class MyWindow : public dart::gui::SoftSimWindow Eigen::Vector3d mForceOnVertex; }; -#endif // APPS_TESTDROP_MYWINDOW_H_ +#endif // EXAMPLES_TESTDROP_MYWINDOW_H_ diff --git a/examples/operationalSpaceControl/CMakeLists.txt b/examples/operationalSpaceControl/CMakeLists.txt index d7faed39593f2..970de2e36569e 100644 --- a/examples/operationalSpaceControl/CMakeLists.txt +++ b/examples/operationalSpaceControl/CMakeLists.txt @@ -1,7 +1,10 @@ -############################################### -# apps/operationalSpaceControl -file(GLOB operationalSpaceControl_srcs "*.cpp") -file(GLOB operationalSpaceControl_hdrs "*.h") -add_executable(operationalSpaceControl ${operationalSpaceControl_srcs} ${operationalSpaceControl_hdrs}) -target_link_libraries(operationalSpaceControl dart dart-gui dart-utils-urdf) -set_target_properties(operationalSpaceControl PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui dart-utils-urdf) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/operationalSpaceControl/Controller.cpp b/examples/operationalSpaceControl/Controller.cpp index df4ebe105f3ad..567d090436c0c 100644 --- a/examples/operationalSpaceControl/Controller.cpp +++ b/examples/operationalSpaceControl/Controller.cpp @@ -34,7 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/operationalSpaceControl/Controller.h" +#include "examples/operationalSpaceControl/Controller.h" //============================================================================== Controller::Controller(dart::dynamics::SkeletonPtr _robot, diff --git a/examples/operationalSpaceControl/Controller.h b/examples/operationalSpaceControl/Controller.h index 58b07f29143d5..b6c704f769976 100644 --- a/examples/operationalSpaceControl/Controller.h +++ b/examples/operationalSpaceControl/Controller.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_OPERATIONALSPACECONTROL_CONTROLLER_H_ -#define APPS_OPERATIONALSPACECONTROL_CONTROLLER_H_ +#ifndef EXAMPLES_OPERATIONALSPACECONTROL_CONTROLLER_H_ +#define EXAMPLES_OPERATIONALSPACECONTROL_CONTROLLER_H_ #include @@ -81,4 +81,4 @@ class Controller Eigen::Matrix3d mKv; }; -#endif // APPS_OPERATIONALSPACECONTROL_CONTROLLER_H_ +#endif // EXAMPLES_OPERATIONALSPACECONTROL_CONTROLLER_H_ diff --git a/examples/operationalSpaceControl/Main.cpp b/examples/operationalSpaceControl/Main.cpp index 3e4946eaa719e..8e72a9bf90c6b 100644 --- a/examples/operationalSpaceControl/Main.cpp +++ b/examples/operationalSpaceControl/Main.cpp @@ -36,7 +36,7 @@ #include "dart/dart.h" -#include "apps/operationalSpaceControl/MyWindow.h" +#include "examples/operationalSpaceControl/MyWindow.h" int main(int argc, char* argv[]) { diff --git a/examples/operationalSpaceControl/MyWindow.cpp b/examples/operationalSpaceControl/MyWindow.cpp index 9f5388a3ece58..af73af7f41c11 100644 --- a/examples/operationalSpaceControl/MyWindow.cpp +++ b/examples/operationalSpaceControl/MyWindow.cpp @@ -34,7 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/operationalSpaceControl/MyWindow.h" +#include "examples/operationalSpaceControl/MyWindow.h" #include diff --git a/examples/operationalSpaceControl/MyWindow.h b/examples/operationalSpaceControl/MyWindow.h index 56a4433d7a991..0686e3f44a67a 100644 --- a/examples/operationalSpaceControl/MyWindow.h +++ b/examples/operationalSpaceControl/MyWindow.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_OPERATIONALSPACECONTROL_MYWINDOW_H_ -#define APPS_OPERATIONALSPACECONTROL_MYWINDOW_H_ +#ifndef EXAMPLES_OPERATIONALSPACECONTROL_MYWINDOW_H_ +#define EXAMPLES_OPERATIONALSPACECONTROL_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -72,4 +72,4 @@ class MyWindow : public dart::gui::SimWindow bool mCircleTask; }; -#endif // APPS_OPERATIONALSPACECONTROL_MYWINDOW_H_ +#endif // EXAMPLES_OPERATIONALSPACECONTROL_MYWINDOW_H_ diff --git a/examples/rigidChain/CMakeLists.txt b/examples/rigidChain/CMakeLists.txt index 94393a6d58c55..4c79c3b22d1f5 100644 --- a/examples/rigidChain/CMakeLists.txt +++ b/examples/rigidChain/CMakeLists.txt @@ -1,7 +1,10 @@ -############################################### -# apps/rigidChain -file(GLOB rigidChain_srcs "*.cpp") -file(GLOB rigidChain_hdrs "*.h") -add_executable(rigidChain ${rigidChain_srcs} ${rigidChain_hdrs}) -target_link_libraries(rigidChain dart dart-gui) -set_target_properties(rigidChain PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/rigidChain/Main.cpp b/examples/rigidChain/Main.cpp index b9d5b88bd312d..574cf7da6ab08 100644 --- a/examples/rigidChain/Main.cpp +++ b/examples/rigidChain/Main.cpp @@ -37,7 +37,7 @@ #include "dart/dart.h" -#include "apps/rigidChain/MyWindow.h" +#include "examples/rigidChain/MyWindow.h" int main(int argc, char* argv[]) { // create and initialize the world diff --git a/examples/rigidChain/MyWindow.cpp b/examples/rigidChain/MyWindow.cpp index fa5596ab30e44..9cbb0aeba19fb 100644 --- a/examples/rigidChain/MyWindow.cpp +++ b/examples/rigidChain/MyWindow.cpp @@ -35,7 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/rigidChain/MyWindow.h" +#include "examples/rigidChain/MyWindow.h" MyWindow::MyWindow() : SimWindow() { } diff --git a/examples/rigidChain/MyWindow.h b/examples/rigidChain/MyWindow.h index a9d5b5409c6c1..58517e32bf4c1 100644 --- a/examples/rigidChain/MyWindow.h +++ b/examples/rigidChain/MyWindow.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_FORWARDSIM_MYWINDOW_H_ -#define APPS_FORWARDSIM_MYWINDOW_H_ +#ifndef EXAMPLES_FORWARDSIM_MYWINDOW_H_ +#define EXAMPLES_FORWARDSIM_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -53,4 +53,4 @@ class MyWindow : public dart::gui::SimWindow { Eigen::VectorXd computeDamping(); }; -#endif // APPS_FORWARDSIM_MYWINDOW_H_ +#endif // EXAMPLES_FORWARDSIM_MYWINDOW_H_ diff --git a/examples/rigidCubes/CMakeLists.txt b/examples/rigidCubes/CMakeLists.txt index fe231e4b0edfa..4c79c3b22d1f5 100644 --- a/examples/rigidCubes/CMakeLists.txt +++ b/examples/rigidCubes/CMakeLists.txt @@ -1,7 +1,10 @@ -############################################### -# apps/rigidCubes -file(GLOB rigidCubes_srcs "*.cpp") -file(GLOB rigidCubes_hdrs "*.h") -add_executable(rigidCubes ${rigidCubes_srcs} ${rigidCubes_hdrs}) -target_link_libraries(rigidCubes dart dart-gui) -set_target_properties(rigidCubes PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/rigidCubes/Main.cpp b/examples/rigidCubes/Main.cpp index 7e22ae6d212e5..b147a086cf8e4 100644 --- a/examples/rigidCubes/Main.cpp +++ b/examples/rigidCubes/Main.cpp @@ -39,7 +39,7 @@ #include "dart/dart.h" -#include "apps/rigidCubes/MyWindow.h" +#include "examples/rigidCubes/MyWindow.h" int main(int argc, char* argv[]) { // create and initialize the world diff --git a/examples/rigidCubes/MyWindow.cpp b/examples/rigidCubes/MyWindow.cpp index e6d34dc9a5713..c8d6b22e9205b 100644 --- a/examples/rigidCubes/MyWindow.cpp +++ b/examples/rigidCubes/MyWindow.cpp @@ -35,7 +35,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/rigidCubes/MyWindow.h" +#include "examples/rigidCubes/MyWindow.h" MyWindow::MyWindow() : SimWindow() { diff --git a/examples/rigidCubes/MyWindow.h b/examples/rigidCubes/MyWindow.h index f91e502145437..fbc84933b7ef1 100644 --- a/examples/rigidCubes/MyWindow.h +++ b/examples/rigidCubes/MyWindow.h @@ -35,8 +35,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_CUBES_MYWINDOW_H_ -#define APPS_CUBES_MYWINDOW_H_ +#ifndef EXAMPLES_CUBES_MYWINDOW_H_ +#define EXAMPLES_CUBES_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -64,4 +64,4 @@ class MyWindow : public dart::gui::SimWindow { Eigen::Vector3d mForce; }; -#endif // APPS_CUBES_MYWINDOW_H_ +#endif // EXAMPLES_CUBES_MYWINDOW_H_ diff --git a/examples/rigidLoop/CMakeLists.txt b/examples/rigidLoop/CMakeLists.txt index c1b0b31faac87..4c79c3b22d1f5 100644 --- a/examples/rigidLoop/CMakeLists.txt +++ b/examples/rigidLoop/CMakeLists.txt @@ -1,7 +1,10 @@ -############################################### -# apps/rigidLoop -file(GLOB rigidLoop_srcs "*.cpp") -file(GLOB rigidLoop_hdrs "*.h") -add_executable(rigidLoop ${rigidLoop_srcs} ${rigidLoop_hdrs}) -target_link_libraries(rigidLoop dart dart-gui) -set_target_properties(rigidLoop PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/rigidLoop/Main.cpp b/examples/rigidLoop/Main.cpp index e2c8fccfdfb66..b6fd9691b2270 100644 --- a/examples/rigidLoop/Main.cpp +++ b/examples/rigidLoop/Main.cpp @@ -36,7 +36,7 @@ #include "dart/dart.h" -#include "apps/rigidLoop/MyWindow.h" +#include "examples/rigidLoop/MyWindow.h" using namespace dart; using namespace math; diff --git a/examples/rigidLoop/MyWindow.cpp b/examples/rigidLoop/MyWindow.cpp index 1430c080b6dc0..e6a358b2d195a 100644 --- a/examples/rigidLoop/MyWindow.cpp +++ b/examples/rigidLoop/MyWindow.cpp @@ -34,7 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/rigidLoop/MyWindow.h" +#include "examples/rigidLoop/MyWindow.h" void MyWindow::timeStepping() { diff --git a/examples/rigidLoop/MyWindow.h b/examples/rigidLoop/MyWindow.h index 18b1e24b12f5d..f8799c2093500 100644 --- a/examples/rigidLoop/MyWindow.h +++ b/examples/rigidLoop/MyWindow.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_CLOSEDLOOP_MYWINDOW_H_ -#define APPS_CLOSEDLOOP_MYWINDOW_H_ +#ifndef EXAMPLES_CLOSEDLOOP_MYWINDOW_H_ +#define EXAMPLES_CLOSEDLOOP_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -56,4 +56,4 @@ class MyWindow : public dart::gui::SimWindow Eigen::VectorXd computeDamping(); }; -#endif // APPS_CLOSEDLOOP_MYWINDOW_H_ +#endif // EXAMPLES_CLOSEDLOOP_MYWINDOW_H_ diff --git a/examples/rigidShapes/CMakeLists.txt b/examples/rigidShapes/CMakeLists.txt index 3ecb6b7f372f9..4c79c3b22d1f5 100644 --- a/examples/rigidShapes/CMakeLists.txt +++ b/examples/rigidShapes/CMakeLists.txt @@ -1,8 +1,10 @@ -############################################### -# apps/rigidShapes -set(APP_NAME rigidShapes) -file(GLOB ${APP_NAME}_srcs "*.cpp") -file(GLOB ${APP_NAME}_hdrs "*.h") -add_executable(${APP_NAME} ${${APP_NAME}_srcs} ${${APP_NAME}_hdrs}) -target_link_libraries(${APP_NAME} dart dart-gui) -set_target_properties(${APP_NAME} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/rigidShapes/MyWindow.h b/examples/rigidShapes/MyWindow.h index 9e314b1846c80..b699d7c87e3bb 100644 --- a/examples/rigidShapes/MyWindow.h +++ b/examples/rigidShapes/MyWindow.h @@ -40,8 +40,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_RIGIDSHAPES_MYWINDOW_H_ -#define APPS_RIGIDSHAPES_MYWINDOW_H_ +#ifndef EXAMPLES_RIGIDSHAPES_MYWINDOW_H_ +#define EXAMPLES_RIGIDSHAPES_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -85,4 +85,4 @@ class MyWindow : public dart::gui::SimWindow double _mass = 10); }; -#endif // APPS_RIGIDSHAPES_MYWINDOW_H_ +#endif // EXAMPLES_RIGIDSHAPES_MYWINDOW_H_ diff --git a/examples/simpleFrames/CMakeLists.txt b/examples/simpleFrames/CMakeLists.txt index 232b4c4c59ab1..4c79c3b22d1f5 100644 --- a/examples/simpleFrames/CMakeLists.txt +++ b/examples/simpleFrames/CMakeLists.txt @@ -1,8 +1,10 @@ -############################################### -# apps/simpleFrames -set(APP_NAME simpleFrames) -file(GLOB ${APP_NAME}_srcs "*.cpp") -file(GLOB ${APP_NAME}_hdrs "*.h") -add_executable(${APP_NAME} ${${APP_NAME}_srcs} ${${APP_NAME}_hdrs}) -target_link_libraries(${APP_NAME} dart dart-gui) -set_target_properties(${APP_NAME} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/softBodies/CMakeLists.txt b/examples/softBodies/CMakeLists.txt index f1f3d40f30463..4c79c3b22d1f5 100644 --- a/examples/softBodies/CMakeLists.txt +++ b/examples/softBodies/CMakeLists.txt @@ -1,8 +1,10 @@ -############################################### -# apps/softDropBoxTest -set(APP_NAME softBodies) -file(GLOB ${APP_NAME}_srcs "*.cpp") -file(GLOB ${APP_NAME}_hdrs "*.h") -add_executable(${APP_NAME} ${${APP_NAME}_srcs} ${${APP_NAME}_hdrs}) -target_link_libraries(${APP_NAME} dart dart-gui) -set_target_properties(${APP_NAME} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/softBodies/Main.cpp b/examples/softBodies/Main.cpp index 9689782178f7e..1c16859a3b63d 100644 --- a/examples/softBodies/Main.cpp +++ b/examples/softBodies/Main.cpp @@ -44,7 +44,7 @@ #include "dart/dart.h" -#include "apps/softBodies/MyWindow.h" +#include "examples/softBodies/MyWindow.h" int main(int argc, char* argv[]) { diff --git a/examples/softBodies/MyWindow.cpp b/examples/softBodies/MyWindow.cpp index 1f541e5d57caf..fc92f1eb2518b 100644 --- a/examples/softBodies/MyWindow.cpp +++ b/examples/softBodies/MyWindow.cpp @@ -40,7 +40,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/softBodies/MyWindow.h" +#include "examples/softBodies/MyWindow.h" #define FORCE_ON_RIGIDBODY 25.0; #define FORCE_ON_VERTEX 1.00; diff --git a/examples/softBodies/MyWindow.h b/examples/softBodies/MyWindow.h index f83c2621678b6..18668cbd09639 100644 --- a/examples/softBodies/MyWindow.h +++ b/examples/softBodies/MyWindow.h @@ -40,8 +40,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef APPS_SOFTBODIES_MYWINDOW_H_ -#define APPS_SOFTBODIES_MYWINDOW_H_ +#ifndef EXAMPLES_SOFTBODIES_MYWINDOW_H_ +#define EXAMPLES_SOFTBODIES_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -76,4 +76,4 @@ class MyWindow : public dart::gui::SoftSimWindow Eigen::Vector3d mForceOnVertex; }; -#endif // APPS_SOFTBODIES_MYWINDOW_H_ +#endif // EXAMPLES_SOFTBODIES_MYWINDOW_H_ diff --git a/examples/speedTest/CMakeLists.txt b/examples/speedTest/CMakeLists.txt index 4f73e2967ae18..4c79c3b22d1f5 100644 --- a/examples/speedTest/CMakeLists.txt +++ b/examples/speedTest/CMakeLists.txt @@ -1,10 +1,10 @@ ############################################################### -# This file can be used as-is in the directory of any app, # +# This file can be used as-is in the directory of any example,# # however you might need to specify your own dependencies in # # target_link_libraries if your app depends on more than dart # ############################################################### -get_filename_component(app_name ${CMAKE_CURRENT_LIST_DIR} NAME) -file(GLOB ${app_name}_srcs "*.cpp" "*.h" "*.hpp") -add_executable(${app_name} ${${app_name}_srcs}) -target_link_libraries(${app_name} dart dart-gui) -set_target_properties(${app_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/vehicle/CMakeLists.txt b/examples/vehicle/CMakeLists.txt index 2fc5753715964..4c79c3b22d1f5 100644 --- a/examples/vehicle/CMakeLists.txt +++ b/examples/vehicle/CMakeLists.txt @@ -1,7 +1,10 @@ -############################################### -# apps/vehicle -file(GLOB vehicle_srcs "*.cpp") -file(GLOB vehicle_hdrs "*.h") -add_executable(vehicle ${vehicle_srcs} ${vehicle_hdrs}) -target_link_libraries(vehicle dart dart-gui) -set_target_properties(vehicle PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") +############################################################### +# This file can be used as-is in the directory of any example,# +# however you might need to specify your own dependencies in # +# target_link_libraries if your app depends on more than dart # +############################################################### +get_filename_component(example_name ${CMAKE_CURRENT_LIST_DIR} NAME) +file(GLOB ${example_name}_srcs "*.cpp" "*.h" "*.hpp") +add_executable(${example_name} ${${example_name}_srcs}) +target_link_libraries(${example_name} dart dart-gui) +set_target_properties(${example_name} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin") diff --git a/examples/vehicle/Main.cpp b/examples/vehicle/Main.cpp index ed006321055a6..b6367d3fbd73d 100644 --- a/examples/vehicle/Main.cpp +++ b/examples/vehicle/Main.cpp @@ -38,7 +38,7 @@ #include "dart/dart.h" -#include "apps/vehicle/MyWindow.h" +#include "examples/vehicle/MyWindow.h" int main(int argc, char* argv[]) { diff --git a/examples/vehicle/MyWindow.cpp b/examples/vehicle/MyWindow.cpp index 7fa753c886c47..8900c763b9de6 100644 --- a/examples/vehicle/MyWindow.cpp +++ b/examples/vehicle/MyWindow.cpp @@ -34,7 +34,7 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#include "apps/vehicle/MyWindow.h" +#include "examples/vehicle/MyWindow.h" MyWindow::MyWindow() : SimWindow() { diff --git a/examples/vehicle/MyWindow.h b/examples/vehicle/MyWindow.h index 4d8d9f41bef4e..aa9b1b6eb24fb 100644 --- a/examples/vehicle/MyWindow.h +++ b/examples/vehicle/MyWindow.h @@ -35,8 +35,8 @@ */ -#ifndef APPS_VEHICLE_MYWINDOW_H_ -#define APPS_VEHICLE_MYWINDOW_H_ +#ifndef EXAMPLES_VEHICLE_MYWINDOW_H_ +#define EXAMPLES_VEHICLE_MYWINDOW_H_ #include "dart/dart.h" #include "dart/gui/gui.h" @@ -73,4 +73,4 @@ class MyWindow : public dart::gui::SimWindow { double mD; }; -#endif // APPS_VEHICLE_MYWINDOW_H_ +#endif // EXAMPLES_VEHICLE_MYWINDOW_H_ From 29df2fa84f144ff2762bc139d13cc703054edd5f Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 22 Apr 2016 11:58:07 -0400 Subject: [PATCH 28/34] Remove coveralls token from .travis.yml --- .travis.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 66ece4e2b46a3..d440860711d9b 100644 --- a/.travis.yml +++ b/.travis.yml @@ -13,7 +13,7 @@ compiler: - clang env: - - BUILD_TYPE=Debug COVERALLS=ON COVERALLS_REPO_TOKEN=FKh1HgwfV5uzNrYxIT6ZWjcFqybYZSUym + - BUILD_TYPE=Debug COVERALLS=ON - BUILD_TYPE=Release COVERALLS=OFF matrix: From bc9a0007d5ad556bdd3af410067c8d303c9f0bca Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 22 Apr 2016 18:27:23 -0400 Subject: [PATCH 29/34] Update more copyright year --- unittests/TestHelpers.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/unittests/TestHelpers.h b/unittests/TestHelpers.h index 99a052c5d6170..31c07c7c05c03 100644 --- a/unittests/TestHelpers.h +++ b/unittests/TestHelpers.h @@ -1,5 +1,5 @@ /* - * Copyright (c) 2013-2014, Georgia Tech Research Corporation + * Copyright (c) 2013-2016, Georgia Tech Research Corporation * All rights reserved. * * Author(s): Can Erdogan , From fac99e5aecf20b3550e0276d9363c79d7beca360 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 22 Apr 2016 19:45:27 -0400 Subject: [PATCH 30/34] Generate doxygen tag file (https://www.stack.nl/~dimitri/doxygen/manual/config.html#cfg_generate_tagfile) --- doxygen/Doxyfile.in | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doxygen/Doxyfile.in b/doxygen/Doxyfile.in index f226c2d6a6db9..b4e8d2c23165a 100644 --- a/doxygen/Doxyfile.in +++ b/doxygen/Doxyfile.in @@ -1968,7 +1968,7 @@ TAGFILES = # tag file that is based on the input files it reads. See section "Linking to # external documentation" for more information about the usage of tag files. -GENERATE_TAGFILE = +GENERATE_TAGFILE = html/dart.tag # If the ALLEXTERNALS tag is set to YES all external class will be listed in the # class index. If set to NO only the inherited external classes will be listed. From 8ed2785ed32d0bf08fb4a7ea90654ae25052aca6 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Fri, 22 Apr 2016 19:56:45 -0400 Subject: [PATCH 31/34] Use cmake variable to configure Doxygen tagfile name --- CMakeLists.txt | 1 + doxygen/Doxyfile.in | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e51eb2db060b6..29170eac44a20 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -326,6 +326,7 @@ if(DOXYGEN_FOUND) set(DOXYGEN_DOXYFILE ${PROJECT_BINARY_DIR}/doxygen/Doxyfile ) set(DOXYGEN_HTML_INDEX ${PROJECT_SOURCE_DIR}/doxygen/html/index.html) set(DOXYGEN_OUTPUT_ROOT ${PROJECT_SOURCE_DIR}/doxygen/html ) # Pasted into Doxyfile.in + set(DOXYGEN_GENERATE_TAGFILE ${DOXYGEN_OUTPUT_ROOT}/${PROJECT_NAME}.tag) set(DOXYGEN_INPUT_ROOT ${PROJECT_SOURCE_DIR}/dart ) # Pasted into Doxyfile.in set(DOXYGEN_EXTRA_INPUTS ${PROJECT_SOURCE_DIR}/doxygen/mainpage.dox ) # Pasted into Doxyfile.in diff --git a/doxygen/Doxyfile.in b/doxygen/Doxyfile.in index b4e8d2c23165a..7e2a37384552e 100644 --- a/doxygen/Doxyfile.in +++ b/doxygen/Doxyfile.in @@ -1968,7 +1968,7 @@ TAGFILES = # tag file that is based on the input files it reads. See section "Linking to # external documentation" for more information about the usage of tag files. -GENERATE_TAGFILE = html/dart.tag +GENERATE_TAGFILE = @DOXYGEN_GENERATE_TAGFILE@ # If the ALLEXTERNALS tag is set to YES all external class will be listed in the # class index. If set to NO only the inherited external classes will be listed. From 316a583e5e5a5c23360678c44fdf3834bd3573da Mon Sep 17 00:00:00 2001 From: "M.X. Grey" Date: Fri, 22 Apr 2016 20:52:29 -0400 Subject: [PATCH 32/34] Using Marker Properties to construct Markers in SkelParser --- dart/utils/SkelParser.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/dart/utils/SkelParser.cpp b/dart/utils/SkelParser.cpp index c9473c7abc1e4..5a382cf2d7fe2 100644 --- a/dart/utils/SkelParser.cpp +++ b/dart/utils/SkelParser.cpp @@ -916,6 +916,10 @@ bool createJointAndNodePair(dynamics::SkeletonPtr skeleton, newJoint->setAccelerations(joint.acceleration); newJoint->setForces(joint.force); + dynamics::BodyNode* bn = pair.second; + for(std::size_t i=0; i < body.markers.size(); ++i) + bn->createNode(body.markers[i]); + return true; } From bc7fe49e4dc1a1a1cb6be101cdf4b1e40b285514 Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sat, 23 Apr 2016 21:30:07 -0400 Subject: [PATCH 33/34] Minor updates for code quality --- dart/dynamics/Marker.cpp | 2 -- dart/dynamics/Marker.h | 4 ---- dart/dynamics/detail/MarkerAspect.h | 7 +++---- dart/utils/VskParser.h | 2 +- 4 files changed, 4 insertions(+), 11 deletions(-) diff --git a/dart/dynamics/Marker.cpp b/dart/dynamics/Marker.cpp index ef9b5ac17a5b6..d59345d6e0233 100644 --- a/dart/dynamics/Marker.cpp +++ b/dart/dynamics/Marker.cpp @@ -36,8 +36,6 @@ #include "dart/dynamics/Marker.h" -#include - #include "dart/dynamics/BodyNode.h" namespace dart { diff --git a/dart/dynamics/Marker.h b/dart/dynamics/Marker.h index 97ebc6950cefe..752565741453a 100644 --- a/dart/dynamics/Marker.h +++ b/dart/dynamics/Marker.h @@ -37,7 +37,6 @@ #ifndef DART_DYNAMICS_MARKER_H_ #define DART_DYNAMICS_MARKER_H_ -#include #include #include "dart/common/Deprecated.h" #include "dart/dynamics/detail/MarkerAspect.h" @@ -131,11 +130,8 @@ class Marker final : EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; -// TODO: Marker class should be refactored into a Node once pull request #531 is -// finished. } // namespace dynamics } // namespace dart #endif // DART_DYNAMICS_MARKER_H_ - diff --git a/dart/dynamics/detail/MarkerAspect.h b/dart/dynamics/detail/MarkerAspect.h index afd8a99f99737..f7d7e40f69e6d 100644 --- a/dart/dynamics/detail/MarkerAspect.h +++ b/dart/dynamics/detail/MarkerAspect.h @@ -34,8 +34,8 @@ * POSSIBILITY OF SUCH DAMAGE. */ -#ifndef DART_DYNAMICS_DETAIL_MARKER_H_ -#define DART_DYNAMICS_DETAIL_MARKER_H_ +#ifndef DART_DYNAMICS_DETAIL_MARKERASPECT_H_ +#define DART_DYNAMICS_DETAIL_MARKERASPECT_H_ #include #include "dart/math/Helpers.h" @@ -64,9 +64,8 @@ struct MarkerProperties EIGEN_MAKE_ALIGNED_OPERATOR_NEW }; - } // namespace detail } // namespace dynamics } // namespace dart -#endif // DART_DYNAMICS_DETAIL_MARKER_H_ +#endif // DART_DYNAMICS_DETAIL_MARKERASPECT_H_ diff --git a/dart/utils/VskParser.h b/dart/utils/VskParser.h index 0d89b8d7d3d31..cbd04152838c1 100644 --- a/dart/utils/VskParser.h +++ b/dart/utils/VskParser.h @@ -40,8 +40,8 @@ #include "dart/common/ResourceRetriever.h" #include "dart/common/Uri.h" +#include "dart/math/Constants.h" #include "dart/dynamics/Skeleton.h" -#include "dart/math/Helpers.h" namespace dart { namespace utils { From 426f393ef568ca523ecdbe346ae550edc59675ec Mon Sep 17 00:00:00 2001 From: Jeongseok Lee Date: Sun, 24 Apr 2016 11:18:52 -0400 Subject: [PATCH 34/34] Fix typo in dart/CMakeLists.txt: tutorialsdo --> tutorials do --- dart/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dart/CMakeLists.txt b/dart/CMakeLists.txt index 0dd56179d5077..37614ccb9fe58 100644 --- a/dart/CMakeLists.txt +++ b/dart/CMakeLists.txt @@ -1,6 +1,6 @@ # Enable multi-threaded compilation. # We do this here and not in the root folder since the examples and the -# tutorialsdo not have enough source files to benefit from this. +# tutorials do not have enough source files to benefit from this. if(MSVC) set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /MP") endif()