From 58d12d1efdfb384dee504f31087f4b47ab7bbc93 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 21:31:45 +0200 Subject: [PATCH 001/546] Fix return type of Transform::getDelta() --- src/rl/math/TransformAddons.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index a8d51d86..90f7301f 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -111,9 +111,8 @@ fromDenavitHartenbergPaul(const Scalar& d, const Scalar& theta, const Scalar& a, (*this)(3, 3) = Scalar(1); } -template inline -void +Matrix getDelta() const { Matrix res; From d97b3af0fe1ccd72095ed119c77b62dcd425833b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 21:49:13 +0200 Subject: [PATCH 002/546] Fix distance in rl::mdl::Metric --- src/rl/mdl/Metric.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/mdl/Metric.cpp b/src/rl/mdl/Metric.cpp index 5463344a..6284301c 100644 --- a/src/rl/mdl/Metric.cpp +++ b/src/rl/mdl/Metric.cpp @@ -69,13 +69,13 @@ namespace rl for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { - d += this->joints[i]->distance( + d += this->joints[i]->transformedDistance( q1.segment(j, this->joints[i]->getDofPosition()), q2.segment(j, this->joints[i]->getDofPosition()) ); } - return d; + return this->inverseOfTransformedDistance(d); } void From 2398cea996dce6c54330d6562fa1079daa1a9d4a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 22:22:04 +0200 Subject: [PATCH 003/546] Link libccd if FCL or ODE depend on it --- src/rl/sg/CMakeLists.txt | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 79a4148f..f0fb0ad5 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -181,6 +181,11 @@ if(BULLET_FOUND) install(FILES ${BULLET_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/bullet COMPONENT development) endif() +if(CCD_FOUND AND (FCL_FOUND OR ODE_FOUND)) + target_include_directories(sg PUBLIC ${CCD_INCLUDE_DIRS}) + target_link_libraries(sg ${CCD_LIBRARIES}) +endif() + if(Coin_FOUND) target_compile_definitions(sg PUBLIC ${Coin_DEFINITIONS}) target_include_directories(sg PUBLIC ${Coin_INCLUDE_DIRS}) @@ -188,11 +193,11 @@ if(Coin_FOUND) install(FILES ${COIN_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/so COMPONENT development) endif() -if(CCD_FOUND AND FCL_FOUND) +if(FCL_FOUND AND CCD_FOUND) target_compile_definitions(sg INTERFACE -DRL_SG_FCL) target_compile_definitions(sg PUBLIC ${FCL_DEFINITIONS}) - target_include_directories(sg PUBLIC ${CCD_INCLUDE_DIRS} ${FCL_INCLUDE_DIRS}) - target_link_libraries(sg ${FCL_LIBRARIES} ${CCD_LIBRARIES}) + target_include_directories(sg PUBLIC ${FCL_INCLUDE_DIRS}) + target_link_libraries(sg ${FCL_LIBRARIES}) install(FILES ${FCL_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/fcl COMPONENT development) endif() From 09f2abfbe11b18522e3fe22f898e00f8df54ab8c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 23:07:35 +0200 Subject: [PATCH 004/546] Use Eigen::Map for quaternions in rl::mdl::Spherical --- src/rl/mdl/Spherical.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 534814fa..0d52be9a 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -63,14 +63,14 @@ namespace rl void Spherical::clip(::rl::math::Vector& q) const { - q = ::rl::math::Quaternion(q(0), q(1), q(2), q(3)).normalized().coeffs(); + ::Eigen::Map< ::rl::math::Quaternion>(q.data()).normalize(); } ::rl::math::Real Spherical::distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const { - ::rl::math::Quaternion quaternion1(q1(0), q1(1), q1(2), q1(3)); - ::rl::math::Quaternion quaternion2(q2(0), q2(1), q2(2), q2(3)); + ::Eigen::Map quaternion1(q1.data()); + ::Eigen::Map quaternion2(q2.data()); return quaternion1.angularDistance(quaternion2); } @@ -78,7 +78,7 @@ namespace rl Spherical::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma) const { ::rl::math::Quaternion quaternion; - quaternion.setFromGaussian(rand, ::rl::math::Quaternion(mean(0), mean(1), mean(2), mean(3)), sigma); + quaternion.setFromGaussian(rand, ::Eigen::Map< const ::rl::math::Quaternion>(mean.data()), sigma); return quaternion.coeffs(); } @@ -93,29 +93,29 @@ namespace rl void Spherical::interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q) const { - ::rl::math::Quaternion quaternion1(q1(0), q1(1), q1(2), q1(3)); - ::rl::math::Quaternion quaternion2(q2(0), q2(1), q2(2), q2(3)); + ::Eigen::Map quaternion1(q1.data()); + ::Eigen::Map quaternion2(q2.data()); q = quaternion1.slerp(alpha, quaternion2).coeffs(); } void Spherical::normalize(::rl::math::Vector& q) const { - q = ::rl::math::Quaternion(q(0), q(1), q(2), q(3)).normalized().coeffs(); + ::Eigen::Map< ::rl::math::Quaternion>(q.data()).normalize(); } void Spherical::setPosition(const ::rl::math::Vector& q) { this->q = q; - this->t = ::rl::math::Quaternion(this->q(0), this->q(1), this->q(2), this->q(3)); + this->t = ::Eigen::Map(this->q.data()); this->x.rotation() = this->t.linear().transpose(); } void Spherical::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const { - ::rl::math::Quaternion quaternion1(q1(0), q1(1), q1(2), q1(3)); + ::Eigen::Map quaternion1(q1.data()); ::rl::math::Quaternion quaterniondot = quaternion1.firstDerivative(qdot); q2 = (quaternion1 * quaterniondot).coeffs(); } From d4cc20d13bb839f4305c70e1db971a8f5a6f1f68 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 23:08:44 +0200 Subject: [PATCH 005/546] Check for zero quaternion in Joint::normalize() --- src/rl/mdl/Spherical.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 0d52be9a..e0651fed 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -101,7 +101,16 @@ namespace rl void Spherical::normalize(::rl::math::Vector& q) const { - ::Eigen::Map< ::rl::math::Quaternion>(q.data()).normalize(); + ::Eigen::Map< ::rl::math::Quaternion> quaternion(q.data()); + + if (quaternion.squaredNorm() > 0) + { + quaternion.normalize(); + } + else + { + quaternion.setIdentity(); + } } void From c05f66bef97b511928961e527eed7d8ae4bb5e25 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 23:10:33 +0200 Subject: [PATCH 006/546] Fix step function for Spherical joints --- src/rl/mdl/Spherical.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index e0651fed..7df08d68 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -125,8 +125,7 @@ namespace rl Spherical::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const { ::Eigen::Map quaternion1(q1.data()); - ::rl::math::Quaternion quaterniondot = quaternion1.firstDerivative(qdot); - q2 = (quaternion1 * quaterniondot).coeffs(); + q2 = (quaternion1 * ::rl::math::AngleAxis(qdot.norm(), qdot.normalized())).coeffs(); } ::rl::math::Real From c477ec8119d69b37965e3af14e586f7ec6e3423a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 23:16:07 +0200 Subject: [PATCH 007/546] Check for other rotation in Quaternion::slerpFirstDerivative() --- src/rl/math/QuaternionBaseAddons.h | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 34fa3d2a..808e8b43 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -105,6 +105,12 @@ operator+(const QuaternionBase& other) const return Quaternion(this->derived().coeffs() + other.coeffs()); } +Quaternion +operator-() const +{ + return Quaternion(-this->derived().coeffs()); +} + template Quaternion operator-(const QuaternionBase& other) const @@ -198,7 +204,7 @@ template Quaternion slerpFirstDerivative(const Scalar& t, const QuaternionBase& other) const { - Quaternion tmp = this->derived().conjugate() * other; + Quaternion tmp = this->derived().dot(other) < Scalar(0) ? this->derived().conjugate() * -other : this->derived().conjugate() * other; return this->derived() * tmp.pow(t) * tmp.log(); } From 7c64c74a1e4c49be2d0e78c59bbd0ad83917b1e7 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 23:26:58 +0200 Subject: [PATCH 008/546] Update rl::hal::UniversalRobotsRealtime for firmware 3.5 --- src/rl/hal/UniversalRobotsRealtime.cpp | 23 +++++++++++++++-------- src/rl/hal/UniversalRobotsRealtime.h | 6 +++++- 2 files changed, 20 insertions(+), 9 deletions(-) diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index 6db08c2e..6f555c1e 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -28,6 +28,7 @@ #include #include +#include "DeviceException.h" #include "UniversalRobotsRealtime.h" namespace rl @@ -222,7 +223,7 @@ namespace rl void UniversalRobotsRealtime::step() { - ::std::array< ::std::uint8_t, 1060> buffer; + ::std::array< ::std::uint8_t, 1108> buffer; this->socket.recv(buffer.data(), buffer.size()); #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) this->socket.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); @@ -288,9 +289,9 @@ namespace rl { this->unserialize(ptr, this->messageSize); - if (756 != this->messageSize && 764 != this->messageSize && 812 != this->messageSize && 1044 != this->messageSize && 1060 != this->messageSize) + if (756 != this->messageSize && 764 != this->messageSize && 812 != this->messageSize && 1044 != this->messageSize && 1060 != this->messageSize && 1108 != this->messageSize) { - return; + throw DeviceException("UniversalRobotsRealtime::Message::unserialize() - Incorrect message size"); } this->unserialize(ptr, this->time); @@ -319,7 +320,7 @@ namespace rl this->unserialize(ptr, this->toolVectorActual); this->unserialize(ptr, this->tcpSpeedActual); } - else if (1044 == this->messageSize || 1060 == this->messageSize) + else if (1044 == this->messageSize || 1060 == this->messageSize || 1108 == this->messageSize) { this->unserialize(ptr, this->iControl); this->unserialize(ptr, this->toolVectorActual); @@ -334,17 +335,17 @@ namespace rl this->unserialize(ptr, this->controllerTimer); this->unserialize(ptr, this->testValue); - if (764 == this->messageSize || 812 == this->messageSize || 1044 == this->messageSize || 1060 == this->messageSize) + if (764 == this->messageSize || 812 == this->messageSize || 1044 == this->messageSize || 1060 == this->messageSize || 1108 == this->messageSize) { this->unserialize(ptr, this->robotMode); } - if (812 == this->messageSize || 1044 == this->messageSize || 1060 == this->messageSize) + if (812 == this->messageSize || 1044 == this->messageSize || 1060 == this->messageSize || 1108 == this->messageSize) { this->unserialize(ptr, this->jointModes); } - if (1044 == this->messageSize || 1060 == this->messageSize) + if (1044 == this->messageSize || 1060 == this->messageSize || 1108 == this->messageSize) { this->unserialize(ptr, this->safetyMode); ptr += 6 * sizeof(double); @@ -360,11 +361,17 @@ namespace rl this->unserialize(ptr, this->vActual); } - if (1060 == this->messageSize) + if (1060 == this->messageSize || 1108 == this->messageSize) { this->unserialize(ptr, this->digitalOutputs); this->unserialize(ptr, this->programState); } + + if (1108 == this->messageSize) + { + this->unserialize(ptr, this->elbowPosition); + this->unserialize(ptr, this->elbowVelocity); + } } template<> diff --git a/src/rl/hal/UniversalRobotsRealtime.h b/src/rl/hal/UniversalRobotsRealtime.h index e3d445e4..5864c50b 100644 --- a/src/rl/hal/UniversalRobotsRealtime.h +++ b/src/rl/hal/UniversalRobotsRealtime.h @@ -46,7 +46,7 @@ namespace rl namespace hal { /** - * Universal Robots realtime interface (pre-3.0, 3.0, 3.1, 3.2). + * Universal Robots realtime interface (pre-3.0, 3.0, 3.1, 3.2, 3.3, 3.4, 3.5). */ class UniversalRobotsRealtime : public CartesianForceSensor, @@ -187,6 +187,10 @@ namespace rl ::std::int64_t digitalOutputs; double programState; + + double elbowPosition[3]; + + double elbowVelocity[3]; }; Message in; From 9e667c55a6f14aa6a1e162c1e44a51abfee22d20 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 23:30:18 +0200 Subject: [PATCH 009/546] Optimize rl::sg::solid::Shape::areColliding --- src/rl/sg/solid/Scene.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/sg/solid/Scene.cpp b/src/rl/sg/solid/Scene.cpp index 9055e546..c1f0c84f 100644 --- a/src/rl/sg/solid/Scene.cpp +++ b/src/rl/sg/solid/Scene.cpp @@ -72,7 +72,7 @@ namespace rl Shape* shape1 = static_cast(first); Shape* shape2 = static_cast(second); - if (shape1->encounters.count(shape2) > 0 || shape2->encounters.count(shape1) > 0) + if (shape1->encounters.find(shape2) != shape1->encounters.end() || shape2->encounters.find(shape1) != shape2->encounters.end()) { DT_Vector3 point; From c5c458ba96989719962094d5d2cbf7522ad8992f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 23:34:38 +0200 Subject: [PATCH 010/546] Use Coin default branch after CMake merge --- 3rdparty/coin/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/coin/CMakeLists.txt b/3rdparty/coin/CMakeLists.txt index 8b811953..075179fb 100644 --- a/3rdparty/coin/CMakeLists.txt +++ b/3rdparty/coin/CMakeLists.txt @@ -17,9 +17,9 @@ ExternalProject_Add( coin DEPENDS boost-header-libs-full simage #HG_REPOSITORY https://bitbucket.org/Coin3D/coin - #HG_TAG CMake - URL https://bitbucket.org/Coin3D/coin/get/CMake.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/CMake.tar.bz2 + #HG_TAG default + URL https://bitbucket.org/Coin3D/coin/get/default.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 PATCH_COMMAND ${CMAKE_COMMAND} -E rename ${CMAKE_CURRENT_BINARY_DIR}/boost-header-libs-full-prefix/src/boost-header-libs-full /include/boost CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DCOIN_BUILD_DOCUMENTATION=OFF From 2b7efebc896d9e995930715334943c0f5d8a69ea Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 23:35:42 +0200 Subject: [PATCH 011/546] Skip building SoQt documentation in dependencies --- 3rdparty/soqt/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/3rdparty/soqt/CMakeLists.txt b/3rdparty/soqt/CMakeLists.txt index 6c266cbe..2f689c7b 100644 --- a/3rdparty/soqt/CMakeLists.txt +++ b/3rdparty/soqt/CMakeLists.txt @@ -22,6 +22,6 @@ ExternalProject_Add( #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 PATCH_COMMAND ${CMAKE_COMMAND} -E rename ${CMAKE_CURRENT_BINARY_DIR}/sogui-prefix/src/sogui /src/Inventor/Qt/common - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DSOQT_BUILD_DOCUMENTATION=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From a696657d30cb08b73e3ba83c0a59256e3cc514a0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 13:24:33 +0100 Subject: [PATCH 012/546] Fix Transform::toDenavitHartenbergPaul() calculation of variable a --- src/rl/math/TransformAddons.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index 90f7301f..fb1e47f8 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -205,7 +205,7 @@ toDenavitHartenbergPaul(Scalar& d, Scalar& theta, Scalar& a, Scalar& alpha) cons } else { - a = (*this)(1, 3) / (*this)(1, 0) + (*this)(0, 3) / (*this)(0, 0); + a = ((*this)(1, 3) / (*this)(1, 0) + (*this)(0, 3) / (*this)(0, 0)) * Scalar(0.5); } alpha = ::std::atan2((*this)(2, 1), (*this)(2, 2)); From b76dc5e13a024573718369e7654009c405b77f0f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 13:27:45 +0100 Subject: [PATCH 013/546] Clear outgoing buffer in rl::hal::Coach in stop() --- src/rl/hal/Coach.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/rl/hal/Coach.cpp b/src/rl/hal/Coach.cpp index 204fd2a9..76c5ddab 100644 --- a/src/rl/hal/Coach.cpp +++ b/src/rl/hal/Coach.cpp @@ -166,6 +166,8 @@ namespace rl void Coach::stop() { + this->out.clear(); + this->out.str(""); this->setRunning(false); } } From ba34e3f59ef48f993b8f78ff084b6cbc739638de Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 13:28:51 +0100 Subject: [PATCH 014/546] Fix FormatMessage parameter --- src/rl/hal/Exception.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/hal/Exception.cpp b/src/rl/hal/Exception.cpp index 9d0d00cc..3cd65d28 100644 --- a/src/rl/hal/Exception.cpp +++ b/src/rl/hal/Exception.cpp @@ -57,7 +57,7 @@ namespace rl { #ifdef WIN32 ::LPTSTR buffer = nullptr; - ::FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM, nullptr, errnum, 0, buffer, 0, nullptr); + ::FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM, nullptr, errnum, 0, reinterpret_cast(&buffer), 0, nullptr); ::std::string message = nullptr != buffer ? buffer : ::boost::lexical_cast< ::std::string>(errnum); ::LocalFree(buffer); return message; From bba274c63d8f733cdcc2cb7c289f2096293049ac Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 13:30:33 +0100 Subject: [PATCH 015/546] Remove O_NONBLOCK default flag from rl::hal::Serial --- src/rl/hal/Serial.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/hal/Serial.h b/src/rl/hal/Serial.h index a928e9f0..43dd7dbe 100644 --- a/src/rl/hal/Serial.h +++ b/src/rl/hal/Serial.h @@ -166,7 +166,7 @@ namespace rl #ifdef WIN32 const int& flags = GENERIC_READ | GENERIC_WRITE #else // WIN32 - const int& flags = O_RDWR | O_NONBLOCK | O_NOCTTY + const int& flags = O_RDWR | O_NOCTTY #endif // WIN32 ); From cdaf551c19cc523dd168c45cd965bbe0dfe99032 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 14:09:27 +0100 Subject: [PATCH 016/546] Use boost::same_component --- src/rl/plan/Prm.cpp | 7 ++++--- src/rl/plan/PrmUtilityGuided.cpp | 3 ++- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/src/rl/plan/Prm.cpp b/src/rl/plan/Prm.cpp index 12cb01b4..d317f2a4 100644 --- a/src/rl/plan/Prm.cpp +++ b/src/rl/plan/Prm.cpp @@ -25,6 +25,7 @@ // #include +#include #include "BridgeSampler.h" #include "GaussianSampler.h" @@ -173,7 +174,7 @@ namespace rl if (d < this->radius) { - if (this->ds.find_set(u) != this->ds.find_set(v)) + if (!::boost::same_component(u, v, this->ds)) { if (!this->verifier->isColliding(*this->graph[u].q, *this->graph[v].q, d)) { @@ -213,12 +214,12 @@ namespace rl this->end = this->addVertex(::std::make_shared< ::rl::math::Vector>(*this->goal)); this->insert(this->end); - while ((::std::chrono::steady_clock::now() - this->time) < this->duration && this->ds.find_set(this->begin) != this->ds.find_set(this->end)) + while ((::std::chrono::steady_clock::now() - this->time) < this->duration && !::boost::same_component(this->begin, this->end, this->ds)) { this->construct(1); } - if (this->ds.find_set(this->begin) != this->ds.find_set(this->end)) + if (!::boost::same_component(this->begin, this->end, this->ds)) { return false; } diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index 499e52e7..96e90fa0 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -26,6 +26,7 @@ #include #include +#include #include "PrmUtilityGuided.h" #include "Sampler.h" @@ -135,7 +136,7 @@ namespace rl sample2 = ::boost::vertex(randIndex2, this->graph); // The two vertices have to be from two unconnected components. } - while (this->ds.find_set(sample1) == this->ds.find_set(sample2)); + while (boost::same_component(sample1, sample2, this->ds)); // The point in the middle of the two samples. ::rl::math::Vector midPoint = 0.5f * (*this->graph[sample1].q + *this->graph[sample2].q); From 918d8b8c05eed6e0bfde2ae3bb4b75179a0e3eb6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 14:16:33 +0100 Subject: [PATCH 017/546] Add missing include for AngleAxis --- src/rl/math/Rotation.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/rl/math/Rotation.h b/src/rl/math/Rotation.h index 6425aecc..0bc221d2 100644 --- a/src/rl/math/Rotation.h +++ b/src/rl/math/Rotation.h @@ -27,6 +27,8 @@ #ifndef RL_MATH_ROTATION_H #define RL_MATH_ROTATION_H +#include + #include "Matrix.h" namespace rl From cbf55a7fb93135836fede914b4551efeb0c7a5af Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 14:16:59 +0100 Subject: [PATCH 018/546] Add missing Eigen plugins --- src/rl/math/Rotation.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/rl/math/Rotation.h b/src/rl/math/Rotation.h index 0bc221d2..206debff 100644 --- a/src/rl/math/Rotation.h +++ b/src/rl/math/Rotation.h @@ -27,6 +27,10 @@ #ifndef RL_MATH_ROTATION_H #define RL_MATH_ROTATION_H +#define EIGEN_MATRIXBASE_PLUGIN +#define EIGEN_QUATERNIONBASE_PLUGIN +#define EIGEN_TRANSFORM_PLUGIN + #include #include "Matrix.h" From e48c45d3a4698d892a104ef1d6d22fa1f04cec3e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 4 Apr 2018 16:42:45 +0200 Subject: [PATCH 019/546] Fix includes --- src/rl/plan/Eet.h | 1 + src/rl/plan/Rrt.cpp | 1 - src/rl/plan/Rrt.h | 3 --- 3 files changed, 1 insertion(+), 4 deletions(-) diff --git a/src/rl/plan/Eet.h b/src/rl/plan/Eet.h index 69f0cbcc..b0d7771b 100644 --- a/src/rl/plan/Eet.h +++ b/src/rl/plan/Eet.h @@ -31,6 +31,7 @@ #include #include "RrtCon.h" +#include "TransformPtr.h" #include "WorkspaceMetric.h" namespace rl diff --git a/src/rl/plan/Rrt.cpp b/src/rl/plan/Rrt.cpp index 44192941..97a6de61 100644 --- a/src/rl/plan/Rrt.cpp +++ b/src/rl/plan/Rrt.cpp @@ -27,7 +27,6 @@ #include "Rrt.h" #include "Sampler.h" #include "SimpleModel.h" -#include "Verifier.h" #include "Viewer.h" #include "NearestNeighbors.h" diff --git a/src/rl/plan/Rrt.h b/src/rl/plan/Rrt.h index 5928477e..b6a15024 100644 --- a/src/rl/plan/Rrt.h +++ b/src/rl/plan/Rrt.h @@ -30,11 +30,9 @@ #include #include -#include "MatrixPtr.h" #include "Metric.h" #include "NearestNeighbors.h" #include "Planner.h" -#include "TransformPtr.h" #include "VectorPtr.h" namespace rl @@ -43,7 +41,6 @@ namespace rl { class Model; class Sampler; - class Verifier; /** * Rapidly-Exploring Random Trees. From f5dbc15b53a2aec2b63256074808ce7d1e9c1093 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 20 Mar 2018 11:08:43 +0100 Subject: [PATCH 020/546] Fix formatting --- demos/rlCoachKin/Server.h | 2 +- demos/rlCoachMdl/Server.h | 2 +- demos/rlSimulator/Server.h | 2 +- src/rl/plan/AddRrtConCon.h | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/demos/rlCoachKin/Server.h b/demos/rlCoachKin/Server.h index d2bc1ffd..a4ea64d4 100644 --- a/demos/rlCoachKin/Server.h +++ b/demos/rlCoachKin/Server.h @@ -49,4 +49,4 @@ class Server : public QTcpServer }; -#endif //_SERVER_H +#endif // SERVER_H diff --git a/demos/rlCoachMdl/Server.h b/demos/rlCoachMdl/Server.h index d2bc1ffd..a4ea64d4 100644 --- a/demos/rlCoachMdl/Server.h +++ b/demos/rlCoachMdl/Server.h @@ -49,4 +49,4 @@ class Server : public QTcpServer }; -#endif //_SERVER_H +#endif // SERVER_H diff --git a/demos/rlSimulator/Server.h b/demos/rlSimulator/Server.h index d2bc1ffd..a4ea64d4 100644 --- a/demos/rlSimulator/Server.h +++ b/demos/rlSimulator/Server.h @@ -49,4 +49,4 @@ class Server : public QTcpServer }; -#endif //_SERVER_H +#endif // SERVER_H diff --git a/src/rl/plan/AddRrtConCon.h b/src/rl/plan/AddRrtConCon.h index 5df9bb8c..56409040 100644 --- a/src/rl/plan/AddRrtConCon.h +++ b/src/rl/plan/AddRrtConCon.h @@ -79,4 +79,4 @@ namespace rl } } -#endif //_RL_PLAN_ADDRRTCONCON_H +#endif // RL_PLAN_ADDRRTCONCON_H From fea64026493026c50496b618752c550c089b0d70 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 20 Mar 2018 13:59:29 +0100 Subject: [PATCH 021/546] Update to Boost 1.66.0 --- 3rdparty/boost/CMakeLists.txt | 6 +++--- CMakeLists.txt | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/3rdparty/boost/CMakeLists.txt b/3rdparty/boost/CMakeLists.txt index 9d31d140..e72f12cf 100644 --- a/3rdparty/boost/CMakeLists.txt +++ b/3rdparty/boost/CMakeLists.txt @@ -7,9 +7,9 @@ include(GNUInstallDirs) ExternalProject_Add( boost - URL https://dl.bintray.com/boostorg/release/1.65.1/source/boost_1_65_1.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_65_1.tar.bz2 - URL_MD5 41d7542ce40e171f3f7982aff008ff0d + URL https://dl.bintray.com/boostorg/release/1.66.0/source/boost_1_66_0.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_66_0.tar.bz2 + URL_MD5 b2dfbd6c717be4a7bb2d88018eaccf75 CONFIGURE_COMMAND "" BUILD_COMMAND "" BUILD_IN_SOURCE 1 diff --git a/CMakeLists.txt b/CMakeLists.txt index 56f1e345..e94761d7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -39,7 +39,7 @@ if(WIN32) ) endif() -set(Boost_ADDITIONAL_VERSIONS "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") +set(Boost_ADDITIONAL_VERSIONS "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") include(Qt4AutomocMocOptionsBoost) From 9caf83c2005d64d9c8a3e8d8f21dfdfeaed384e4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 4 Apr 2018 17:08:21 +0200 Subject: [PATCH 022/546] Minor fix --- demos/rlPlanDemo/MainWindow.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 71057251..4522df26 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -1812,7 +1812,7 @@ MainWindow::load(const QString& filename) { prm->setNearestNeighbors(nearestNeighbors.get()); } - if (rl::plan::Rrt* rrt = dynamic_cast(this->planner.get())) + else if (rl::plan::Rrt* rrt = dynamic_cast(this->planner.get())) { rrt->setNearestNeighbors(nearestNeighbors.get(), i); } From 1da8dfdc605cb7a1ab544b00e5a3222eb042ee82 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 10 Apr 2018 15:21:26 +0200 Subject: [PATCH 023/546] Update recursive edge verifier to use fewer collision checks --- src/rl/plan/RecursiveVerifier.cpp | 67 ++++++++++++++++-------------- src/rl/plan/RecursiveVerifier.h | 5 --- src/rl/plan/SequentialVerifier.cpp | 6 +-- src/rl/plan/Verifier.cpp | 6 +++ src/rl/plan/Verifier.h | 2 + 5 files changed, 47 insertions(+), 39 deletions(-) diff --git a/src/rl/plan/RecursiveVerifier.cpp b/src/rl/plan/RecursiveVerifier.cpp index 60952189..49f4b59f 100644 --- a/src/rl/plan/RecursiveVerifier.cpp +++ b/src/rl/plan/RecursiveVerifier.cpp @@ -24,6 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include + #include "RecursiveVerifier.h" #include "SimpleModel.h" @@ -46,42 +48,45 @@ namespace rl assert(u.size() == this->model->getDofPosition()); assert(v.size() == this->model->getDofPosition()); - ::rl::math::Real exponent = ::std::ceil( - ::std::log(d / this->delta) / - ::std::log(static_cast< ::rl::math::Real>(2)) - ); - - ::rl::math::Real steps = ::std::pow(2, exponent); - - ::rl::math::Vector inter(u.size()); + ::std::size_t steps = this->getSteps(d); - for (int i = 0; i < steps - 1; ++i) + if (steps > 1) { - // reverse bits - - ::std::size_t tmp = i + 1; - ::std::size_t tmp2 = tmp & 1; - - for (int j = 0; j < exponent - 1; ++j) - { - tmp >>= 1; - tmp2 <<= 1; - tmp2 |= tmp & 1; - } - - this->model->interpolate(u, v, tmp2 / steps, inter); - - if (!this->model->isValid(inter)) - { - return true; - } + ::std::queue< ::std::pair< ::std::size_t, ::std::size_t>> queue; + queue.push(::std::make_pair(1, steps - 1)); - this->model->setPosition(inter); - this->model->updateFrames(); + ::rl::math::Vector inter(u.size()); - if (this->model->isColliding()) + while (!queue.empty()) { - return true; + ::std::size_t midpoint = (queue.front().first + queue.front().second) / 2; + + this->model->interpolate(u, v, static_cast< ::rl::math::Real>(midpoint) / static_cast< ::rl::math::Real>(steps), inter); + + if (!this->model->isValid(inter)) + { + return true; + } + + this->model->setPosition(inter); + this->model->updateFrames(); + + if (this->model->isColliding()) + { + return true; + } + + if (queue.front().first < midpoint) + { + queue.push(::std::make_pair(queue.front().first, midpoint - 1)); + } + + if (queue.front().second > midpoint) + { + queue.push(::std::make_pair(midpoint + 1, queue.front().second)); + } + + queue.pop(); } } diff --git a/src/rl/plan/RecursiveVerifier.h b/src/rl/plan/RecursiveVerifier.h index e017a17a..c558ad65 100644 --- a/src/rl/plan/RecursiveVerifier.h +++ b/src/rl/plan/RecursiveVerifier.h @@ -33,11 +33,6 @@ namespace rl { namespace plan { - /** - * Recursive binary strategy using the van der Corput sequence. - * - * \f[ \frac{1}{2}, \frac{1}{4}, \frac{3}{4}, \frac{1}{8}, \frac{5}{8}, \frac{3}{8}, \frac{7}{8}, \ldots \f]. - */ class RecursiveVerifier : public Verifier { public: diff --git a/src/rl/plan/SequentialVerifier.cpp b/src/rl/plan/SequentialVerifier.cpp index 217d831c..c2ec5921 100644 --- a/src/rl/plan/SequentialVerifier.cpp +++ b/src/rl/plan/SequentialVerifier.cpp @@ -46,13 +46,13 @@ namespace rl assert(u.size() == this->model->getDofPosition()); assert(v.size() == this->model->getDofPosition()); - ::std::size_t steps = static_cast< ::std::size_t>(::std::ceil(d / this->delta)) - 1; + ::std::size_t steps = this->getSteps(d);; ::rl::math::Vector inter(u.size()); - for (::std::size_t i = 0; i < steps; ++i) + for (::std::size_t i = 0; i < steps - 1; ++i) { - this->model->interpolate(u, v, (i + 1.0f) / (steps + 1.0f), inter); + this->model->interpolate(u, v, static_cast< ::rl::math::Real>(i + 1) / static_cast< ::rl::math::Real>(steps), inter); if (!this->model->isValid(inter)) { diff --git a/src/rl/plan/Verifier.cpp b/src/rl/plan/Verifier.cpp index c7a8b42b..9cf47481 100644 --- a/src/rl/plan/Verifier.cpp +++ b/src/rl/plan/Verifier.cpp @@ -39,5 +39,11 @@ namespace rl Verifier::~Verifier() { } + + ::std::size_t + Verifier::getSteps(const ::rl::math::Real& d) + { + return static_cast< ::std::size_t>(::std::ceil(d / this->delta)); + } } } diff --git a/src/rl/plan/Verifier.h b/src/rl/plan/Verifier.h index 781c4cc0..191c4bef 100644 --- a/src/rl/plan/Verifier.h +++ b/src/rl/plan/Verifier.h @@ -42,6 +42,8 @@ namespace rl virtual ~Verifier(); + virtual ::std::size_t getSteps(const ::rl::math::Real& d); + virtual bool isColliding(const ::rl::math::Vector& u, const ::rl::math::Vector& v, const ::rl::math::Real& d) = 0; ::rl::math::Real delta; From 448bf0247def28117102a97500bb304d78f8fe1a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 10 Apr 2018 22:04:50 +0200 Subject: [PATCH 024/546] Improve error checking in rl::mdl::XmlFactory --- src/rl/mdl/XmlFactory.cpp | 111 +++++++++++++++++++++++++++++++------- 1 file changed, 91 insertions(+), 20 deletions(-) diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index 60ab0e1f..6f7eeba0 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -24,7 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include +#include #include #include #include @@ -104,12 +104,14 @@ namespace rl ::rl::xml::NodeSet frames = path.eval("body|frame|world").getValue< ::rl::xml::NodeSet>(); - ::std::map< ::std::string, Frame*> id2frame; + ::std::unordered_map< ::std::string, Frame*> id2frame; for (int j = 0; j < frames.size(); ++j) { ::rl::xml::Path path(document, frames[j]); + Frame* frame = nullptr; + if ("body" == frames[j].getName()) { Body* b = new Body(); @@ -135,9 +137,7 @@ namespace rl path.eval("number(m)").getValue< ::rl::math::Real>(1) ); - b->setName(path.eval("string(@id)").getValue< ::std::string>()); - - id2frame[path.eval("string(@id)").getValue< ::std::string>()] = b; + frame = b; } else if ("frame" == frames[j].getName()) { @@ -145,9 +145,7 @@ namespace rl model->add(f); - f->setName(path.eval("string(@id)").getValue< ::std::string>()); - - id2frame[path.eval("string(@id)").getValue< ::std::string>()] = f; + frame = f; } else if ("world" == frames[j].getName()) { @@ -176,9 +174,19 @@ namespace rl path.eval("number(g/z)").getValue< ::rl::math::Real>(0) ); - w->setName(path.eval("string(@id)").getValue< ::std::string>()); + frame = w; + } + + if (nullptr != frame) + { + frame->setName(path.eval("string(@id)").getValue< ::std::string>()); - id2frame[path.eval("string(@id)").getValue< ::std::string>()] = w; + if (id2frame.find(frame->getName()) != id2frame.end()) + { + throw Exception("Frame with ID " + frame->getName() + " not unique in file " + filename); + } + + id2frame[frame->getName()] = frame; } } @@ -190,7 +198,14 @@ namespace rl if ("body" == frames[j].getName()) { - Body* b1 = dynamic_cast(id2frame[path.eval("string(@id)").getValue< ::std::string>()]); + ::std::string b1IdRef = path.eval("string(@id)").getValue< ::std::string>(); + + if (id2frame.find(b1IdRef) == id2frame.end()) + { + throw Exception("Body with IDREF " + b1IdRef + " not found in file " + filename); + } + + Body* b1 = dynamic_cast(id2frame[b1IdRef]); ::rl::xml::NodeSet ignores = path.eval("ignore").getValue< ::rl::xml::NodeSet>(); @@ -198,7 +213,14 @@ namespace rl { if (!ignores[k].getProperty("idref").empty()) { - Body* b2 = dynamic_cast(id2frame[ignores[k].getProperty("idref")]); + ::std::string b2IdRef = ignores[k].getProperty("idref"); + + if (id2frame.find(b2IdRef) == id2frame.end()) + { + throw Exception("Body with IDREF " + b2IdRef + " in Body with ID " + b1IdRef + " not found in file " + filename); + } + + Body* b2 = dynamic_cast(id2frame[b2IdRef]); b1->selfcollision.insert(b2); b2->selfcollision.insert(b1); @@ -219,8 +241,27 @@ namespace rl { ::rl::xml::Path path(document, transforms[j]); - Frame* a = id2frame[path.eval("string(frame/a/@idref)").getValue< ::std::string>()]; - Frame* b = id2frame[path.eval("string(frame/b/@idref)").getValue< ::std::string>()]; + ::std::string name = path.eval("string(@id)").getValue< ::std::string>(); + + ::std::string aIdRef = path.eval("string(frame/a/@idref)").getValue< ::std::string>(); + + if (id2frame.find(aIdRef) == id2frame.end()) + { + throw Exception("Frame A with IDREF " + aIdRef + " in Transform with ID " + name + " not found in file " + filename); + } + + Frame* a = id2frame[aIdRef]; + + ::std::string bIdRef = path.eval("string(frame/b/@idref)").getValue< ::std::string>(); + + if (id2frame.find(bIdRef) == id2frame.end()) + { + throw Exception("Frame B with IDREF " + bIdRef + " in Transform with ID " + name + " not found in file " + filename); + } + + Frame* b = id2frame[bIdRef]; + + Transform* transform = nullptr; if ("cylindrical" == transforms[j].getName()) { @@ -248,7 +289,7 @@ namespace rl c->S(4, 1) = path.eval("number(axis[2]/y)").getValue< ::rl::math::Real>(0); c->S(5, 1) = path.eval("number(axis[2]/z)").getValue< ::rl::math::Real>(1); - c->setName(path.eval("string(@id)").getValue< ::std::string>()); + transform = c; } else if ("fixed" == transforms[j].getName()) { @@ -274,7 +315,7 @@ namespace rl f->x.rotation() = f->t.linear().transpose(); f->x.translation() = f->t.translation(); - f->setName(path.eval("string(@id)").getValue< ::std::string>()); + transform = f; } else if ("helical" == transforms[j].getName()) { @@ -298,7 +339,7 @@ namespace rl h->setPitch(path.eval("number(pitch)").getValue< ::rl::math::Real>(1)); - h->setName(path.eval("string(@id)").getValue< ::std::string>()); + transform = h; } else if ("prismatic" == transforms[j].getName()) { @@ -316,7 +357,7 @@ namespace rl p->S(4, 0) = path.eval("number(axis/y)").getValue< ::rl::math::Real>(0); p->S(5, 0) = path.eval("number(axis/z)").getValue< ::rl::math::Real>(1); - p->setName(path.eval("string(@id)").getValue< ::std::string>()); + transform = p; } else if ("revolute" == transforms[j].getName()) { @@ -339,7 +380,7 @@ namespace rl r->offset *= ::rl::math::DEG2RAD; r->speed *= ::rl::math::DEG2RAD; - r->setName(path.eval("string(@id)").getValue< ::std::string>()); + transform = r; } else if ("spherical" == transforms[j].getName()) { @@ -347,7 +388,12 @@ namespace rl model->add(s, a, b); - s->setName(path.eval("string(@id)").getValue< ::std::string>()); + transform = s; + } + + if (nullptr != transform) + { + transform->setName(name); } } @@ -357,6 +403,11 @@ namespace rl if (home.size() > 0) { + if (home.size() != model->getDofPosition()) + { + throw Exception("Incorrect size of home position vector in file " + filename); + } + ::rl::math::Vector q(home.size()); for (int j = 0; j < home.size(); ++j) @@ -381,6 +432,11 @@ namespace rl ::std::size_t m = path.eval("count(row)").getValue< ::std::size_t>(0); ::std::size_t n = path.eval("count(row[1]/col)").getValue< ::std::size_t>(0); + if (m != model->getDofPosition()) + { + throw Exception("Incorrect number of rows in gamma position matrix in file " + filename); + } + ::rl::math::Matrix G(m, n); ::rl::xml::NodeSet rows = path.eval("row").getValue< ::rl::xml::NodeSet>(); @@ -389,6 +445,11 @@ namespace rl { ::rl::xml::Path path(document, rows[k]); + if (path.eval("count(col)").getValue< ::std::size_t>(0) != model->getDofPosition()) + { + throw Exception("Incorrect number of columns in gamma position matrix in file " + filename); + } + ::rl::xml::NodeSet cols = path.eval("col").getValue< ::rl::xml::NodeSet>(); for (int l = 0; l < cols.size(); ++l) @@ -409,6 +470,11 @@ namespace rl ::std::size_t m = path.eval("count(row)").getValue< ::std::size_t>(0); ::std::size_t n = path.eval("count(row[1]/col)").getValue< ::std::size_t>(0); + if (m != model->getDof()) + { + throw Exception("Incorrect number of rows in gamma velocity matrix in file " + filename); + } + ::rl::math::Matrix G(m, n); ::rl::xml::NodeSet rows = path.eval("row").getValue< ::rl::xml::NodeSet>(); @@ -417,6 +483,11 @@ namespace rl { ::rl::xml::Path path(document, rows[k]); + if (path.eval("count(col)").getValue< ::std::size_t>(0) != model->getDof()) + { + throw Exception("Incorrect number of columns in gamma velocity matrix in file " + filename); + } + ::rl::xml::NodeSet cols = path.eval("col").getValue< ::rl::xml::NodeSet>(); for (int l = 0; l < cols.size(); ++l) From f8342a4622ff2661fb49fb3b581640269c8e07b6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 11 Apr 2018 17:52:22 +0200 Subject: [PATCH 025/546] Use std::queue::emplace if supported by compiler --- src/rl/plan/RecursiveVerifier.cpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/src/rl/plan/RecursiveVerifier.cpp b/src/rl/plan/RecursiveVerifier.cpp index 49f4b59f..65f0f992 100644 --- a/src/rl/plan/RecursiveVerifier.cpp +++ b/src/rl/plan/RecursiveVerifier.cpp @@ -53,7 +53,12 @@ namespace rl if (steps > 1) { ::std::queue< ::std::pair< ::std::size_t, ::std::size_t>> queue; + +#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) queue.push(::std::make_pair(1, steps - 1)); +#else + queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(1), ::std::forward_as_tuple(steps - 1)); +#endif ::rl::math::Vector inter(u.size()); @@ -78,12 +83,20 @@ namespace rl if (queue.front().first < midpoint) { +#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) queue.push(::std::make_pair(queue.front().first, midpoint - 1)); +#else + queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(queue.front().first), ::std::forward_as_tuple(midpoint - 1)); +#endif } if (queue.front().second > midpoint) { +#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) queue.push(::std::make_pair(midpoint + 1, queue.front().second)); +#else + queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(midpoint + 1), ::std::forward_as_tuple(queue.front().second)); +#endif } queue.pop(); From 0bf09826a63596eaac18e081f0822b6a9506e68d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 12 Apr 2018 22:48:35 +0200 Subject: [PATCH 026/546] Use A* search in PRM --- demos/rlPlanDemo/MainWindow.cpp | 12 +++++++ examples/rlplan/rlplan.xsd | 1 + src/rl/plan/Prm.cpp | 62 ++++++++++++++++++++++++++------- src/rl/plan/Prm.h | 26 +++++++++++++- 4 files changed, 87 insertions(+), 14 deletions(-) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 4522df26..54d1cb84 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -1493,6 +1493,12 @@ MainWindow::load(const QString& filename) this->planner = std::make_shared(); rl::plan::Prm* prm = static_cast(this->planner.get()); prm->degree = path.eval("number(degree)").getValue(std::numeric_limits::max()); + + if (path.eval("count(dijkstra) > 0").getValue()) + { + prm->astar = false; + } + prm->k = path.eval("number(k)").getValue(30); prm->radius = path.eval("number(radius)").getValue(std::numeric_limits::max()); @@ -1509,6 +1515,12 @@ MainWindow::load(const QString& filename) this->planner = std::make_shared(); rl::plan::PrmUtilityGuided* prmUtilityGuided = static_cast(this->planner.get()); prmUtilityGuided->degree = path.eval("number(degree)").getValue(std::numeric_limits::max()); + + if (path.eval("count(dijkstra) > 0").getValue()) + { + prmUtilityGuided->astar = false; + } + prmUtilityGuided->k = path.eval("number(k)").getValue(30); prmUtilityGuided->radius = path.eval("number(radius)").getValue(std::numeric_limits::max()); diff --git a/examples/rlplan/rlplan.xsd b/examples/rlplan/rlplan.xsd index 5ff9819a..9dcb1ecc 100644 --- a/examples/rlplan/rlplan.xsd +++ b/examples/rlplan/rlplan.xsd @@ -336,6 +336,7 @@ + diff --git a/src/rl/plan/Prm.cpp b/src/rl/plan/Prm.cpp index d317f2a4..697f40d6 100644 --- a/src/rl/plan/Prm.cpp +++ b/src/rl/plan/Prm.cpp @@ -42,6 +42,7 @@ namespace rl { Prm::Prm() : Planner(), + astar(true), degree(::std::numeric_limits< ::std::size_t>::max()), k(30), radius(::std::numeric_limits< ::rl::math::Real>::max()), @@ -224,21 +225,56 @@ namespace rl return false; } - ::boost::dijkstra_shortest_paths( - this->graph, - this->begin, - ::boost::get(&VertexBundle::predecessor, this->graph), - ::boost::get(&VertexBundle::distance, this->graph), - ::boost::get(&EdgeBundle::weight, this->graph), - ::boost::get(&VertexBundle::index, this->graph), - ::std::less< ::rl::math::Real>(), - ::boost::closed_plus< ::rl::math::Real>(), - ::std::numeric_limits< ::rl::math::Real>::max(), - 0, - ::boost::default_dijkstra_visitor() - ); + if (this->astar) + { + ::boost::astar_search( + this->graph, + this->begin, + AStarHeuristic(this->model, this->graph, this->end), + ::boost::default_astar_visitor(), + ::boost::get(&VertexBundle::predecessor, this->graph), + ::boost::get(&VertexBundle::cost, this->graph), + ::boost::get(&VertexBundle::distance, this->graph), + ::boost::get(&EdgeBundle::weight, this->graph), + ::boost::get(&VertexBundle::index, this->graph), + ::boost::get(&VertexBundle::color, this->graph), + ::std::less< ::rl::math::Real>(), + ::std::plus< ::rl::math::Real>(), + ::std::numeric_limits< ::rl::math::Real>::max(), + 0 + ); + } + else + { + ::boost::dijkstra_shortest_paths( + this->graph, + this->begin, + ::boost::get(&VertexBundle::predecessor, this->graph), + ::boost::get(&VertexBundle::distance, this->graph), + ::boost::get(&EdgeBundle::weight, this->graph), + ::boost::get(&VertexBundle::index, this->graph), + ::std::less< ::rl::math::Real>(), + ::boost::closed_plus< ::rl::math::Real>(), + ::std::numeric_limits< ::rl::math::Real>::max(), + 0, + ::boost::default_dijkstra_visitor() + ); + } return true; } + + Prm::AStarHeuristic::AStarHeuristic(Model* model, Graph& graph, Vertex& goal) : + goal(goal), + graph(graph), + model(model) + { + } + + ::rl::math::Real + Prm::AStarHeuristic::operator()(Vertex u) + { + return this->model->transformedDistance(*this->graph[u].q, *this->graph[this->goal].q); + } } } diff --git a/src/rl/plan/Prm.h b/src/rl/plan/Prm.h index 97a3a821..7cf77450 100644 --- a/src/rl/plan/Prm.h +++ b/src/rl/plan/Prm.h @@ -29,6 +29,7 @@ #include #include +#include #include #include "Metric.h" @@ -86,6 +87,8 @@ namespace rl bool solve(); + bool astar; + /** Maximum degree per vertex. */ ::std::size_t degree; @@ -116,6 +119,10 @@ namespace rl struct VertexBundle { + ::boost::default_color_type color; + + ::rl::math::Real cost; + ::rl::math::Real distance; ::std::size_t index; @@ -143,6 +150,23 @@ namespace rl NearestNeighbors* nn; }; + class AStarHeuristic : public ::boost::astar_heuristic + { + public: + AStarHeuristic(Model* model, Graph& graph, Vertex& goal); + + ::rl::math::Real operator()(Vertex u); + + protected: + + private: + Vertex& goal; + + Graph& graph; + + Model* model; + }; + typedef ::boost::graph_traits::edge_descriptor Edge; typedef ::boost::graph_traits::edge_iterator EdgeIterator; @@ -155,7 +179,7 @@ namespace rl typedef ::std::pair VertexIteratorPair; - typedef ::boost::property_map::type VertexParentMap; + typedef ::boost::property_map::type VertexParentMap; typedef ::boost::property_map::type VertexRankMap; From 46231ffe2462f077b1cc65e9126307e09d30f7d1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 12 Apr 2018 22:49:08 +0200 Subject: [PATCH 027/546] Remove extra header --- src/rl/plan/Prm.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/rl/plan/Prm.h b/src/rl/plan/Prm.h index 7cf77450..e1dd4484 100644 --- a/src/rl/plan/Prm.h +++ b/src/rl/plan/Prm.h @@ -27,7 +27,6 @@ #ifndef RL_PLAN_PRM_H #define RL_PLAN_PRM_H -#include #include #include #include From 40a0d6fcba44ae63ae848694a44b6c130f69899b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 12 Apr 2018 23:46:04 +0200 Subject: [PATCH 028/546] Add missing header --- src/rl/plan/PrmUtilityGuided.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index 96e90fa0..ad32f1fc 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -25,6 +25,7 @@ // #include +#include #include #include From 4936cd2a4fd85a925dbe658355baf1eb9333078f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 15 Apr 2018 17:20:15 +0200 Subject: [PATCH 029/546] Remove extra header --- src/rl/plan/Rrt.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/rl/plan/Rrt.cpp b/src/rl/plan/Rrt.cpp index 97a6de61..bc7ac5e8 100644 --- a/src/rl/plan/Rrt.cpp +++ b/src/rl/plan/Rrt.cpp @@ -29,8 +29,6 @@ #include "SimpleModel.h" #include "Viewer.h" -#include "NearestNeighbors.h" - namespace rl { namespace plan From ea39c5aedf787c0afa85d96b489fe65afadbee84 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 15 Apr 2018 17:21:52 +0200 Subject: [PATCH 030/546] Remove extra distance call in RRT connect --- src/rl/plan/Rrt.cpp | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/src/rl/plan/Rrt.cpp b/src/rl/plan/Rrt.cpp index bc7ac5e8..bc25f780 100644 --- a/src/rl/plan/Rrt.cpp +++ b/src/rl/plan/Rrt.cpp @@ -138,19 +138,15 @@ namespace rl while (!reached) { - distance = this->model->distance(*last, chosen); - step = distance; + step += this->delta; - if (step <= this->delta) + if (step >= distance) { reached = true; - } - else - { - step = this->delta; + step = distance; } - this->model->interpolate(*last, chosen, step / distance, next); + this->model->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, next); if (nullptr != this->viewer) { From d6ccdef46b98b82f7271004aacedf0725581a503 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 27 Apr 2018 11:23:24 +0200 Subject: [PATCH 031/546] Update to Boost 1.67.0 --- 3rdparty/boost/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/boost/CMakeLists.txt b/3rdparty/boost/CMakeLists.txt index e72f12cf..44fc315f 100644 --- a/3rdparty/boost/CMakeLists.txt +++ b/3rdparty/boost/CMakeLists.txt @@ -7,9 +7,9 @@ include(GNUInstallDirs) ExternalProject_Add( boost - URL https://dl.bintray.com/boostorg/release/1.66.0/source/boost_1_66_0.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_66_0.tar.bz2 - URL_MD5 b2dfbd6c717be4a7bb2d88018eaccf75 + URL https://dl.bintray.com/boostorg/release/1.67.0/source/boost_1_67_0.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_67_0.tar.bz2 + URL_MD5 ced776cb19428ab8488774e1415535ab CONFIGURE_COMMAND "" BUILD_COMMAND "" BUILD_IN_SOURCE 1 From 841ac31747dabcc2dcf5fdd3dd41146b1b722b58 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 27 Apr 2018 22:04:50 +0200 Subject: [PATCH 032/546] Update Boost_ADDITIONAL_VERSIONS to support 1.67 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e94761d7..476f9a29 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -39,7 +39,7 @@ if(WIN32) ) endif() -set(Boost_ADDITIONAL_VERSIONS "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") +set(Boost_ADDITIONAL_VERSIONS "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") include(Qt4AutomocMocOptionsBoost) From eed49b43635ba07e64d5e7526bc6a582a87ff234 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 17:35:35 +0200 Subject: [PATCH 033/546] Use Eigen::Map in WorkspaceSphereExplorer --- src/rl/plan/WorkspaceSphereExplorer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index 5136e6ea..0bcac165 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -171,7 +171,7 @@ namespace rl ::boost::uniform_on_sphere< ::rl::math::Real>::result_type sample = this->rand(); sphere.center = ::std::make_shared< ::rl::math::Vector3>( - top.radius * ::rl::math::Vector3(sample[0], sample[1], sample[2]) + *top.center // TODO + top.radius * ::Eigen::Map< ::rl::math::Vector3>(sample.data()) + *top.center ); if ((*this->start - *sphere.center).norm() <= this->range) From ef271f231293d8ad94883bc53c1bf116ff4eff9a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 14:46:27 +0100 Subject: [PATCH 034/546] Enable Doxygen for static members and Eigen plugins --- doc/Doxyfile.in | 4 ++-- src/rl/math/MatrixBaseAddons.h | 8 ++++++++ src/rl/math/QuaternionBaseAddons.h | 8 ++++++++ src/rl/math/TransformAddons.h | 8 ++++++++ 4 files changed, 26 insertions(+), 2 deletions(-) diff --git a/doc/Doxyfile.in b/doc/Doxyfile.in index cf406092..bf6871f9 100644 --- a/doc/Doxyfile.in +++ b/doc/Doxyfile.in @@ -437,7 +437,7 @@ EXTRACT_PACKAGE = NO # included in the documentation. # The default value is: NO. -EXTRACT_STATIC = NO +EXTRACT_STATIC = YES # If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) defined # locally in source files will be included in the documentation. If set to NO @@ -2012,7 +2012,7 @@ INCLUDE_FILE_PATTERNS = # recursively expanded use the := operator instead of the = operator. # This tag requires that the tag ENABLE_PREPROCESSING is set to YES. -PREDEFINED = +PREDEFINED = DOXYGEN_SHOULD_PARSE_THIS # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then this # tag can be used to specify a list of macro names that should be expanded. The diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index 339dc21e..abfb4543 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -27,6 +27,10 @@ #ifndef RL_MATH_MATRIXBASEADDONS_H #define RL_MATH_MATRIXBASEADDONS_H +#ifdef DOXYGEN_SHOULD_PARSE_THIS +namespace Eigen { template class MatrixBase { +#endif + Matrix cross3() const { @@ -86,4 +90,8 @@ voigt33() const return res; } +#ifdef DOXYGEN_SHOULD_PARSE_THIS +} } +#endif + #endif // RL_MATH_MATRIXBASEADDONS_H diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 808e8b43..1ea6ba79 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -27,6 +27,10 @@ #ifndef RL_MATH_QUATERNIONBASEADDONS_H #define RL_MATH_QUATERNIONBASEADDONS_H +#ifdef DOXYGEN_SHOULD_PARSE_THIS +namespace Eigen { template class QuaternionBase { +#endif + template Vector3 angularVelocity(const QuaternionBase& qd) const @@ -236,4 +240,8 @@ squadFirstDerivative(const Scalar& t, const QuaternionBase& a, co return u * (w.pow(tmp) * (Scalar(2) - Scalar(4) * t) * w.log() + w.pow(tmp - Scalar(1)) * tmp * wd) + ud * w.pow(tmp); } +#ifdef DOXYGEN_SHOULD_PARSE_THIS +} } +#endif + #endif // RL_MATH_QUATERNIONBASEADDONS_H diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index fb1e47f8..5cb38943 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -27,6 +27,10 @@ #ifndef RL_MATH_TRANSFORMADDONS_H #define RL_MATH_TRANSFORMADDONS_H +#ifdef DOXYGEN_SHOULD_PARSE_THIS +namespace Eigen { template class Transform { +#endif + template inline Scalar @@ -211,4 +215,8 @@ toDenavitHartenbergPaul(Scalar& d, Scalar& theta, Scalar& a, Scalar& alpha) cons alpha = ::std::atan2((*this)(2, 1), (*this)(2, 2)); } +#ifdef DOXYGEN_SHOULD_PARSE_THIS +} } +#endif + #endif // RL_MATH_TRANSFORMADDONS_H From c3a867856e0199a99500c894d26003993c25875c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 1 May 2018 16:05:59 +0200 Subject: [PATCH 035/546] Replace \dag with \dagger for MathJax --- src/rl/kin/Kinematics.h | 6 +++--- src/rl/mdl/Kinematic.h | 14 +++++++------- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 843ca5fd..db93f988 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -220,7 +220,7 @@ namespace rl /** * Calculate inverse velocity kinematics. * - * \f[ \dot{\vec{q}} = \matr{J}^{\dag} \dot{\vec{x}} \f] + * \f[ \dot{\vec{q}} = \matr{J}^{\dagger} \dot{\vec{x}} \f] * * @param[in] xdot \f$\dot{\vec{x}}\f$ * @param[out] qdot \f$\dot{\vec{q}}\f$ @@ -304,8 +304,8 @@ namespace rl /** * Update Jacobian-Inverse. * - * \f[ \matr{J}^{\dag}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \f] - * \f[ \matr{J}^{\dag}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \f] + * \f[ \matr{J}^{\dagger}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \f] + * \f[ \matr{J}^{\dagger}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \f] * * @param[in] lambda Damping factor \f$\lambda\f$ * @param[in] doSvd Use singular value decomposition or damped least squares diff --git a/src/rl/mdl/Kinematic.h b/src/rl/mdl/Kinematic.h index cfc0a158..1e851327 100644 --- a/src/rl/mdl/Kinematic.h +++ b/src/rl/mdl/Kinematic.h @@ -118,8 +118,8 @@ namespace rl /** * Calculate Jacobian matrix inverse. * - * \f[ \matr{J}^{\dag}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \f] - * \f[ \matr{J}^{\dag}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \f] + * \f[ \matr{J}^{\dagger}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \f] + * \f[ \matr{J}^{\dagger}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \f] * * @param[in] lambda Damping factor \f$\lambda\f$ * @param[in] doSvd Use singular value decomposition or damped least squares @@ -133,11 +133,11 @@ namespace rl /** * Calculate Jacobian matrix inverse. * - * \f[ \matr{J}^{\dag}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \f] - * \f[ \matr{J}^{\dag}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \f] + * \f[ \matr{J}^{\dagger}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \f] + * \f[ \matr{J}^{\dagger}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \f] * * @param[in] J Jacobian matrix \f$\matr{J}\f$ - * @param[in] invJ Jacobian matrix inverse \f$\matr{J}^{\dag}\f$ + * @param[in] invJ Jacobian matrix inverse \f$\matr{J}^{\dagger}\f$ * @param[in] lambda Damping factor \f$\lambda\f$ * @param[in] doSvd Use singular value decomposition or damped least squares * @@ -214,7 +214,7 @@ namespace rl /** * Access calculated Jacobian matrix inverse. * - * @return Jacobian matrix inverse \f$\matr{J}^{\dag}(\vec{q})\f$ + * @return Jacobian matrix inverse \f$\matr{J}^{\dagger}(\vec{q})\f$ * * @pre setPosition() * @pre calculateJacobian() @@ -242,7 +242,7 @@ namespace rl /** * Jacobian matrix inverse. * - * \f[ \matr{J}^{\dag}(\vec{q}) \f] + * \f[ \matr{J}^{\dagger}(\vec{q}) \f] * * @pre calculateJacobianInverse() * From ec7d5338cce62718d8b6666e68b9c5b51a32a495 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 24 May 2018 15:18:31 +0200 Subject: [PATCH 036/546] Fix DoF calls in dynamics demos --- demos/rlDynamics1Demo/rlDynamics1Demo.cpp | 16 ++++++++++------ demos/rlDynamics2Demo/rlDynamics2Demo.cpp | 12 ++++++++---- 2 files changed, 18 insertions(+), 10 deletions(-) diff --git a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp index 8deb7291..ef19a649 100644 --- a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp +++ b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp @@ -48,15 +48,19 @@ main(int argc, char** argv) rl::mdl::Dynamic* dynamic = dynamic_cast(model.get()); - rl::math::Vector q(model->getDof()); - rl::math::Vector qd(model->getDof()); - rl::math::Vector qdd(model->getDof()); + rl::math::Vector q(dynamic->getDofPosition()); + rl::math::Vector qd(dynamic->getDof()); + rl::math::Vector qdd(dynamic->getDof()); - for (std::size_t i = 0; i < model->getDof(); ++i) + for (std::size_t i = 0; i < dynamic->getDofPosition(); ++i) { q(i) = boost::lexical_cast(argv[i + 2]); - qd(i) = boost::lexical_cast(argv[i + 2 + model->getDof()]); - qdd(i) = boost::lexical_cast(argv[i + 2 + 2 * model->getDof()]); + } + + for (std::size_t i = 0; i < dynamic->getDof(); ++i) + { + qd(i) = boost::lexical_cast(argv[i + 2 + dynamic->getDofPosition()]); + qdd(i) = boost::lexical_cast(argv[i + 2 + dynamic->getDofPosition() + dynamic->getDof()]); } dynamic->setPosition(q); diff --git a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp index b1192c02..29e47bc3 100644 --- a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp +++ b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp @@ -49,15 +49,19 @@ main(int argc, char** argv) rl::mdl::Dynamic* dynamic = dynamic_cast(model.get()); - rl::math::Vector q(dynamic->getDof()); + rl::math::Vector q(dynamic->getDofPosition()); rl::math::Vector qd(dynamic->getDof()); rl::math::Vector qdd(dynamic->getDof()); - for (std::size_t i = 0; i < dynamic->getDof(); ++i) + for (std::size_t i = 0; i < dynamic->getDofPosition(); ++i) { q(i) = boost::lexical_cast(argv[i + 2]); - qd(i) = boost::lexical_cast(argv[i + 2 + dynamic->getDof()]); - qdd(i) = boost::lexical_cast(argv[i + 2 + 2 * dynamic->getDof()]); + } + + for (std::size_t i = 0; i < dynamic->getDof(); ++i) + { + qd(i) = boost::lexical_cast(argv[i + 2 + dynamic->getDofPosition()]); + qdd(i) = boost::lexical_cast(argv[i + 2 + dynamic->getDofPosition() + dynamic->getDof()]); } rl::math::Vector g(3); From a35dee1109c6e9857497506452d453aa5456cb72 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 29 May 2018 11:27:00 +0200 Subject: [PATCH 037/546] Update rlmdl.xsd gamma to gammaPosition and gammaVelocity --- examples/rlmdl/rlmdl.xsd | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/examples/rlmdl/rlmdl.xsd b/examples/rlmdl/rlmdl.xsd index 672cc437..325e01ad 100644 --- a/examples/rlmdl/rlmdl.xsd +++ b/examples/rlmdl/rlmdl.xsd @@ -145,7 +145,8 @@ - + + From 307dacfe4611ff3c3b9a78f5c48b8e3f60285d73 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 31 May 2018 18:59:21 +0200 Subject: [PATCH 038/546] Normalize zero home position vector --- src/rl/mdl/Kinematic.cpp | 2 +- src/rl/mdl/Metric.cpp | 8 ++++++++ src/rl/mdl/Metric.h | 2 ++ 3 files changed, 11 insertions(+), 1 deletion(-) diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 9e4499e5..89e228f7 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -283,7 +283,7 @@ namespace rl void Kinematic::update() { - Model::update(); + Metric::update(); this->invJ.resize(this->getDof(), 6 * this->getOperationalDof()); this->J.resize(6 * this->getOperationalDof(), this->getDof()); diff --git a/src/rl/mdl/Metric.cpp b/src/rl/mdl/Metric.cpp index 6284301c..a45b13f4 100644 --- a/src/rl/mdl/Metric.cpp +++ b/src/rl/mdl/Metric.cpp @@ -273,5 +273,13 @@ namespace rl return this->transformedDistance(delta); } } + + void + Metric::update() + { + Model::update(); + + this->normalize(this->home); + } } } diff --git a/src/rl/mdl/Metric.h b/src/rl/mdl/Metric.h index 00458a55..e887996a 100644 --- a/src/rl/mdl/Metric.h +++ b/src/rl/mdl/Metric.h @@ -70,6 +70,8 @@ namespace rl ::rl::math::Real transformedDistance(const ::rl::math::Real& q1, const ::rl::math::Real& q2, const ::std::size_t& i) const; + virtual void update(); + protected: private: From cebe8773df0cffecd746f6d8e3a43854eb665709 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 2 Jul 2018 18:14:15 +0200 Subject: [PATCH 039/546] Add support for 2 ms update rate of UR e-series --- src/rl/hal/UniversalRobotsRtde.cpp | 8 ++++---- src/rl/hal/UniversalRobotsRtde.h | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index ec9d53f8..63f65d3d 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -35,9 +35,9 @@ namespace rl { namespace hal { - UniversalRobotsRtde::UniversalRobotsRtde(const ::std::string& address) : + UniversalRobotsRtde::UniversalRobotsRtde(const ::std::string& address, const ::std::chrono::nanoseconds& updateRate) : AxisController(6), - CyclicDevice(::std::chrono::milliseconds(8)), + CyclicDevice(updateRate), AnalogInputReader(), AnalogOutputReader(), AnalogOutputWriter(), @@ -1182,9 +1182,9 @@ namespace rl program << '\t' << '\t' << "qd[5] = read_input_float_register(11)" << '\n'; program << '\t' << '\t' << "qdd = read_input_float_register(12)" << '\n'; #if 1 - program << '\t' << '\t' << "servoj(q, 0, 0, 0.008, 0.03, 2000)" << '\n'; + program << '\t' << '\t' << "servoj(q, 0, 0, " << ::std::chrono::duration_cast< ::std::chrono::duration>(this->getUpdateRate()).count() << ", 0.03, 2000)" << '\n'; #else - program << '\t' << '\t' << "speedj(qd, qdd, 0.008)" << '\n'; + program << '\t' << '\t' << "speedj(qd, qdd, " << ::std::chrono::duration_cast< ::std::chrono::duration>(this->getUpdateRate()).count() << ")" << '\n'; #endif program << '\t' << "end" << '\n'; program << "end" << '\n'; diff --git a/src/rl/hal/UniversalRobotsRtde.h b/src/rl/hal/UniversalRobotsRtde.h index 91f121c7..9ffd8ee4 100644 --- a/src/rl/hal/UniversalRobotsRtde.h +++ b/src/rl/hal/UniversalRobotsRtde.h @@ -151,7 +151,7 @@ namespace rl SAFETY_STATUS_STOPPED_DUE_TO_SAFETY = 1024 }; - UniversalRobotsRtde(const ::std::string& address); + UniversalRobotsRtde(const ::std::string& address, const ::std::chrono::nanoseconds& updateRate = ::std::chrono::milliseconds(8)); virtual ~UniversalRobotsRtde(); From d70d001db5978f51f80c7bc8a19859c0c11828d6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 4 Jul 2018 16:15:19 +0200 Subject: [PATCH 040/546] Minor fix --- src/rl/mdl/XmlFactory.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index 6f7eeba0..eb9be204 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -198,14 +198,14 @@ namespace rl if ("body" == frames[j].getName()) { - ::std::string b1IdRef = path.eval("string(@id)").getValue< ::std::string>(); + ::std::string b1Id = path.eval("string(@id)").getValue< ::std::string>(); - if (id2frame.find(b1IdRef) == id2frame.end()) + if (id2frame.find(b1Id) == id2frame.end()) { - throw Exception("Body with IDREF " + b1IdRef + " not found in file " + filename); + throw Exception("Body with ID " + b1Id + " not found in file " + filename); } - Body* b1 = dynamic_cast(id2frame[b1IdRef]); + Body* b1 = dynamic_cast(id2frame[b1Id]); ::rl::xml::NodeSet ignores = path.eval("ignore").getValue< ::rl::xml::NodeSet>(); @@ -217,7 +217,7 @@ namespace rl if (id2frame.find(b2IdRef) == id2frame.end()) { - throw Exception("Body with IDREF " + b2IdRef + " in Body with ID " + b1IdRef + " not found in file " + filename); + throw Exception("Body with IDREF " + b2IdRef + " in Body with ID " + b1Id + " not found in file " + filename); } Body* b2 = dynamic_cast(id2frame[b2IdRef]); From c458cb8bf5e05d530124e3462e757bf24ab9b8ba Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 4 Jul 2018 16:16:21 +0200 Subject: [PATCH 041/546] Add exception handling to rl::kin::Kinematics::create --- src/rl/kin/Kinematics.cpp | 94 +++++++++++++++++++++++++++++++++++---- 1 file changed, 86 insertions(+), 8 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 26ba47b0..c631b7c1 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -252,7 +252,14 @@ namespace rl kinematics->tree[v].reset(f); } - id2vertex[path.eval("string(@id)").getValue< ::std::string>()] = v; + ::std::string id = path.eval("string(@id)").getValue< ::std::string>(); + + if (id2vertex.find(id) != id2vertex.end()) + { + throw Exception("Frame with ID " + id + " not unique in file " + filename); + } + + id2vertex[id] = v; } for (int j = 0; j < frames.size(); ++j) @@ -261,7 +268,14 @@ namespace rl if ("link" == frames[j].getName()) { - Vertex v1 = id2vertex[path.eval("string(@id)").getValue< ::std::string>()]; + ::std::string v1Id = path.eval("string(@id)").getValue< ::std::string>(); + + if (id2vertex.find(v1Id) == id2vertex.end()) + { + throw Exception("Link with ID " + v1Id + " not found in file " + filename); + } + + Vertex v1 = id2vertex[v1Id]; Link* l1 = dynamic_cast(kinematics->tree[v1].get()); ::rl::xml::NodeSet ignores = path.eval("ignore").getValue< ::rl::xml::NodeSet>(); @@ -270,7 +284,14 @@ namespace rl { if (!ignores[k].getProperty("idref").empty()) { - Vertex v2 = id2vertex[ignores[k].getProperty("idref")]; + ::std::string v2IdRef = ignores[k].getProperty("idref"); + + if (id2vertex.find(v2IdRef) == id2vertex.end()) + { + throw Exception("Link with IDREF " + v2IdRef + " in Link with ID " + v1Id + " not found in file " + filename); + } + + Vertex v2 = id2vertex[v2IdRef]; Link* l2 = dynamic_cast(kinematics->tree[v2].get()); l1->selfcollision.insert(l2); @@ -292,8 +313,25 @@ namespace rl { ::rl::xml::Path path(document, transforms[j]); - Vertex a = id2vertex[path.eval("string(frame/a/@idref)").getValue< ::std::string>()]; - Vertex b = id2vertex[path.eval("string(frame/b/@idref)").getValue< ::std::string>()]; + ::std::string name = path.eval("string(@id)").getValue< ::std::string>(); + + ::std::string aIdRef = path.eval("string(frame/a/@idref)").getValue< ::std::string>(); + + if (id2vertex.find(aIdRef) == id2vertex.end()) + { + throw Exception("Frame A with IDREF " + aIdRef + " in Transform with ID " + name + " not found in file " + filename); + } + + Vertex a = id2vertex[aIdRef]; + + ::std::string bIdRef = path.eval("string(frame/b/@idref)").getValue< ::std::string>(); + + if (id2vertex.find(bIdRef) == id2vertex.end()) + { + throw Exception("Frame B with IDREF " + bIdRef + " in Transform with ID " + name + " not found in file " + filename); + } + + Vertex b = id2vertex[bIdRef]; Edge e = ::boost::add_edge(a, b, kinematics->tree).first; @@ -301,7 +339,7 @@ namespace rl { Prismatic* p = new Prismatic(); - p->name = path.eval("string(@id)").getValue< ::std::string>(); + p->name = name; p->a = path.eval("number(dh/a)").getValue< ::rl::math::Real>(0); p->alpha = path.eval("number(dh/alpha)").getValue< ::rl::math::Real>(0); @@ -322,7 +360,7 @@ namespace rl { Revolute* r = new Revolute(); - r->name = path.eval("string(@id)").getValue< ::std::string>(); + r->name = name; r->a = path.eval("number(dh/a)").getValue< ::rl::math::Real>(0); r->alpha = path.eval("number(dh/alpha)").getValue< ::rl::math::Real>(0); @@ -347,7 +385,7 @@ namespace rl { Transform* t = new Transform(); - t->name = path.eval("string(@id)").getValue< ::std::string>(); + t->name = name; t->transform.setIdentity(); @@ -379,6 +417,26 @@ namespace rl { delete kinematics; kinematics = nullptr; + + if (kinematics->joints.size() != 6) + { + throw Exception("Puma kinematics with incorrect number of joints"); + } + + if (kinematics->links.size() != 7) + { + throw Exception("Puma kinematics with incorrect number of links"); + } + + if (kinematics->transforms.size() != 8) + { + throw Exception("Puma kinematics with incorrect number of transforms"); + } + + if (kinematics->frames.size() != 9) + { + throw Exception("Puma kinematics with incorrect number of frames"); + } } } else if (dynamic_cast(kinematics)) @@ -387,6 +445,26 @@ namespace rl { delete kinematics; kinematics = nullptr; + + if (kinematics->joints.size() != 5) + { + throw Exception("Rhino kinematics with incorrect number of joints"); + } + + if (kinematics->links.size() != 6) + { + throw Exception("Rhino kinematics with incorrect number of links"); + } + + if (kinematics->transforms.size() != 7) + { + throw Exception("Rhino kinematics with incorrect number of transforms"); + } + + if (kinematics->frames.size() != 8) + { + throw Exception("Rhino kinematics with incorrect number of frames"); + } } } From e941fb5fd744d883cfe371470710fa36f993ee1d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Jul 2018 18:53:17 +0200 Subject: [PATCH 042/546] Add default constructor for rl::xml::Node --- src/rl/xml/Node.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/rl/xml/Node.h b/src/rl/xml/Node.h index ef25d97e..f81dc523 100644 --- a/src/rl/xml/Node.h +++ b/src/rl/xml/Node.h @@ -45,6 +45,11 @@ namespace rl class Node { public: + explicit Node() : + node(nullptr) + { + } + explicit Node(::xmlNodePtr node) : node(node) { From 5c90fbc088904246c7a0a96d770a14be3d8b63aa Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 15 Aug 2018 14:48:06 +0200 Subject: [PATCH 043/546] Add _ENABLE_EXTENDED_ALIGNED_STORAGE for Visual Studio 15.8 --- CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 476f9a29..75ab204e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -31,6 +31,7 @@ endif() if(WIN32) add_definitions( -D_CRT_SECURE_NO_WARNINGS + -D_ENABLE_EXTENDED_ALIGNED_STORAGE -D_SCL_SECURE_NO_WARNINGS -D_USE_MATH_DEFINES -D_WIN32_WINNT=0x501 From 51b440d1ae56b13aa1493f49bb60348298024218 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 23 Aug 2018 20:33:35 +0200 Subject: [PATCH 044/546] Fix rlViewDemo CMake target_include_directories() --- demos/rlViewDemo/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/rlViewDemo/CMakeLists.txt b/demos/rlViewDemo/CMakeLists.txt index ca854343..a4754da5 100644 --- a/demos/rlViewDemo/CMakeLists.txt +++ b/demos/rlViewDemo/CMakeLists.txt @@ -31,7 +31,7 @@ if(QT_FOUND AND SoQt_FOUND) ${SoQt_DEFINITIONS} ) - include_directories( + target_include_directories( rlViewDemo PUBLIC ${SoQt_INCLUDE_DIRS} From 9156fb437b9783e4a2da431e2d5d6f60ddf0fcdc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 26 Sep 2018 00:49:40 +0200 Subject: [PATCH 045/546] Resize bottom dock widget in rlCoachKin and rlCoachMdl for Qt >= 5.6 --- demos/rlCoachKin/MainWindow.cpp | 8 ++++++++ demos/rlCoachMdl/MainWindow.cpp | 8 ++++++++ 2 files changed, 16 insertions(+) diff --git a/demos/rlCoachKin/MainWindow.cpp b/demos/rlCoachKin/MainWindow.cpp index 8d121d89..ae634b1d 100644 --- a/demos/rlCoachKin/MainWindow.cpp +++ b/demos/rlCoachKin/MainWindow.cpp @@ -154,6 +154,14 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->addDockWidget(Qt::LeftDockWidgetArea, this->configurationDockWidget); this->addDockWidget(Qt::BottomDockWidgetArea, this->operationalDockWidget); +#if QT_VERSION >= 0x050600 + QList resizeDocksWidgets; + resizeDocksWidgets.append(this->operationalDockWidget); + QList resizeDocksSizes; + resizeDocksSizes.append(0); + this->resizeDocks(resizeDocksWidgets, resizeDocksSizes, Qt::Vertical); +#endif // QT_VERSION + this->gradientBackground = new SoGradientBackground(); this->gradientBackground->ref(); this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index c9bae168..97b2a848 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -158,6 +158,14 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->addDockWidget(Qt::LeftDockWidgetArea, this->configurationDockWidget); this->addDockWidget(Qt::BottomDockWidgetArea, this->operationalDockWidget); +#if QT_VERSION >= 0x050600 + QList resizeDocksWidgets; + resizeDocksWidgets.append(this->operationalDockWidget); + QList resizeDocksSizes; + resizeDocksSizes.append(0); + this->resizeDocks(resizeDocksWidgets, resizeDocksSizes, Qt::Vertical); +#endif // QT_VERSION + this->ikAlgorithmComboBox->addItem("JacobianInverseKinematics"); #ifdef RL_MDL_NLOPT this->ikAlgorithmComboBox->addItem("NloptInverseKinematics"); From d2a93409906d4f8314d397eda92d309ebca90e4e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 24 May 2018 15:59:32 +0200 Subject: [PATCH 046/546] Use generatePositionUniform() in IK implementations --- src/rl/mdl/JacobianInverseKinematics.cpp | 8 ++++---- src/rl/mdl/NloptInverseKinematics.cpp | 12 +++++------- 2 files changed, 9 insertions(+), 11 deletions(-) diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index bd01d8f1..30cf5e20 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -32,8 +32,7 @@ namespace rl ::rl::math::Vector dq(this->kinematic->getDofPosition()); ::rl::math::Vector dx(6 * this->kinematic->getOperationalDof()); - ::rl::math::Vector lb = this->kinematic->getMinimum(); - ::rl::math::Vector ub = this->kinematic->getMaximum(); + ::rl::math::Vector rand(this->kinematic->getDof()); do { @@ -87,11 +86,12 @@ namespace rl } } - for (::std::size_t i = 0; i < this->kinematic->getDofPosition(); ++i) + for (::std::size_t i = 0; i < this->kinematic->getDof(); ++i) { - q(i) = lb(i) + this->randDistribution(this->randEngine) * (ub(i) - lb(i)); + rand(i) = this->randDistribution(this->randEngine); } + q = this->kinematic->generatePositionUniform(rand); this->kinematic->setPosition(q); remaining = ::std::chrono::duration(this->duration - (::std::chrono::steady_clock::now() - start)).count(); diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 83e52168..1ed5998a 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -114,16 +114,12 @@ namespace rl ::nlopt_destroy ); - ::rl::math::Vector lb = this->kinematic->getMinimum(); - ::rl::math::Vector ub = this->kinematic->getMaximum(); - ::std::vector tolerance(this->kinematic->getDofPosition(), this->tolerance); check(::nlopt_set_xtol_abs(opt.get(), tolerance.data())); check(::nlopt_set_min_objective(opt.get(), &NloptInverseKinematics::f, this)); - check(::nlopt_set_lower_bounds(opt.get(), lb.data())); - check(::nlopt_set_upper_bounds(opt.get(), ub.data())); + ::rl::math::Vector rand(this->kinematic->getDof()); ::rl::math::Vector q = this->kinematic->getPosition(); double optF; @@ -137,11 +133,13 @@ namespace rl return true; } - for (::std::size_t i = 0; i < this->kinematic->getDofPosition(); ++i) + for (::std::size_t i = 0; i < this->kinematic->getDof(); ++i) { - q(i) = lb(i) + this->randDistribution(this->randEngine) * (ub(i) - lb(i)); + rand(i) = this->randDistribution(this->randEngine); } + q = this->kinematic->generatePositionUniform(rand); + remaining = ::std::chrono::duration(this->duration - (::std::chrono::steady_clock::now() - start)).count(); } while (remaining > 0); From 71a2fc35f1514072e1607dc3186bb37d7f5028e4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 25 May 2018 13:10:29 +0200 Subject: [PATCH 047/546] Undo removal of upper and lower bounds for NLopt --- src/rl/mdl/NloptInverseKinematics.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 1ed5998a..42fa874c 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -114,10 +114,15 @@ namespace rl ::nlopt_destroy ); + ::rl::math::Vector lb = this->kinematic->getMinimum(); + ::rl::math::Vector ub = this->kinematic->getMaximum(); + ::std::vector tolerance(this->kinematic->getDofPosition(), this->tolerance); check(::nlopt_set_xtol_abs(opt.get(), tolerance.data())); check(::nlopt_set_min_objective(opt.get(), &NloptInverseKinematics::f, this)); + check(::nlopt_set_lower_bounds(opt.get(), lb.data())); + check(::nlopt_set_upper_bounds(opt.get(), ub.data())); ::rl::math::Vector rand(this->kinematic->getDof()); ::rl::math::Vector q = this->kinematic->getPosition(); From 128a0663f5de29854836b8335862b1bb2ad47018 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 5 Oct 2018 22:33:00 +0200 Subject: [PATCH 048/546] Avoid exceptions in rl::mdl::NloptInverseKinematics --- src/rl/mdl/NloptInverseKinematics.cpp | 53 ++++++++++++++------------- src/rl/mdl/NloptInverseKinematics.h | 2 - 2 files changed, 28 insertions(+), 27 deletions(-) diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 42fa874c..eb6c90ba 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -23,25 +23,6 @@ namespace rl { } - void - NloptInverseKinematics::check(const nlopt_result& ret) - { - switch (ret) - { - case ::NLOPT_FAILURE: - throw ::std::runtime_error("nlopt failure"); - break; - case ::NLOPT_INVALID_ARGS: - throw ::std::invalid_argument("nlopt invalid argument"); - break; - case ::NLOPT_OUT_OF_MEMORY: - throw ::std::bad_alloc(); - break; - default: - break; - } - } - ::rl::math::Real NloptInverseKinematics::error(const ::rl::math::Vector& q) { @@ -119,10 +100,25 @@ namespace rl ::std::vector tolerance(this->kinematic->getDofPosition(), this->tolerance); - check(::nlopt_set_xtol_abs(opt.get(), tolerance.data())); - check(::nlopt_set_min_objective(opt.get(), &NloptInverseKinematics::f, this)); - check(::nlopt_set_lower_bounds(opt.get(), lb.data())); - check(::nlopt_set_upper_bounds(opt.get(), ub.data())); + if (::nlopt_set_xtol_abs(opt.get(), tolerance.data()) < 0) + { + return false; + } + + if (::nlopt_set_min_objective(opt.get(), &NloptInverseKinematics::f, this) < 0) + { + return false; + } + + if (::nlopt_set_lower_bounds(opt.get(), lb.data()) < 0) + { + return false; + } + + if (::nlopt_set_upper_bounds(opt.get(), ub.data()) < 0) + { + return false; + } ::rl::math::Vector rand(this->kinematic->getDof()); ::rl::math::Vector q = this->kinematic->getPosition(); @@ -130,8 +126,15 @@ namespace rl do { - check(::nlopt_set_maxtime(opt.get(), remaining)); - check(::nlopt_optimize(opt.get(), q.data(), &optF)); + if (::nlopt_set_maxtime(opt.get(), remaining) < 0) + { + return false; + } + + if (::nlopt_optimize(opt.get(), q.data(), &optF) < 0) + { + return false; + } if (this->error(q) < ::std::numeric_limits< ::rl::math::Real>::epsilon()) { diff --git a/src/rl/mdl/NloptInverseKinematics.h b/src/rl/mdl/NloptInverseKinematics.h index c879b1f9..734fdf1d 100644 --- a/src/rl/mdl/NloptInverseKinematics.h +++ b/src/rl/mdl/NloptInverseKinematics.h @@ -34,8 +34,6 @@ namespace rl protected: private: - static void check(const nlopt_result& ret); - ::rl::math::Real error(const ::rl::math::Vector& q); static ::rl::math::Real f(unsigned n, const double* x, double* grad, void* data); From 3ee8a3b7e51f41626b8c500a74492e0291d6f72a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Oct 2018 18:34:05 +0200 Subject: [PATCH 049/546] Retry solving on NLOPT_FAILURE error code --- src/rl/mdl/NloptInverseKinematics.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index eb6c90ba..30716f5a 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -131,7 +131,7 @@ namespace rl return false; } - if (::nlopt_optimize(opt.get(), q.data(), &optF) < 0) + if (::nlopt_optimize(opt.get(), q.data(), &optF) < -1) { return false; } From e2a83c295e5c88d0576d64b1927bdfacc20de2c0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 11 Oct 2018 20:22:50 +0200 Subject: [PATCH 050/546] Return JointMode enum instead of int32 --- src/rl/hal/UniversalRobotsRtde.cpp | 4 ++-- src/rl/hal/UniversalRobotsRtde.h | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 63f65d3d..1e9ed63c 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -404,11 +404,11 @@ namespace rl return i; } - ::std::int32_t + UniversalRobotsRtde::JointMode UniversalRobotsRtde::getJointMode(const ::std::size_t& i) const { assert(i < 6); - return this->output.jointMode[i]; + return static_cast(this->output.jointMode[i]); } ::rl::math::Vector diff --git a/src/rl/hal/UniversalRobotsRtde.h b/src/rl/hal/UniversalRobotsRtde.h index 9ffd8ee4..bc922de5 100644 --- a/src/rl/hal/UniversalRobotsRtde.h +++ b/src/rl/hal/UniversalRobotsRtde.h @@ -211,7 +211,7 @@ namespace rl ::rl::math::Vector getJointCurrent() const; - ::std::int32_t getJointMode(const ::std::size_t& i) const; + JointMode getJointMode(const ::std::size_t& i) const; ::rl::math::Vector getJointPosition() const; From 9941691be24572c87ca0901ee21a3415cbfc35bc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 11 Oct 2018 20:26:22 +0200 Subject: [PATCH 051/546] Cleanup --- src/rl/hal/UniversalRobotsRealtime.cpp | 47 -------------------------- 1 file changed, 47 deletions(-) diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index 6f555c1e..7ae69a3a 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -229,53 +229,6 @@ namespace rl this->socket.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); #endif // __APPLE__ || __QNX__ || WIN32 this->in.unserialize(buffer.data()); - -#if 0 - std::cout << "messageSize: " << this->in.messageSize << std::endl; - std::cout << "time: " << this->in.time << std::endl; - std::cout << "qTarget[0]: " << this->in.qTarget[0] * rl::math::RAD2DEG << std::endl; - std::cout << "qTarget[1]: " << this->in.qTarget[1] * rl::math::RAD2DEG << std::endl; - std::cout << "qTarget[2]: " << this->in.qTarget[2] * rl::math::RAD2DEG << std::endl; - std::cout << "qTarget[3]: " << this->in.qTarget[3] * rl::math::RAD2DEG << std::endl; - std::cout << "qTarget[4]: " << this->in.qTarget[4] * rl::math::RAD2DEG << std::endl; - std::cout << "qTarget[5]: " << this->in.qTarget[5] * rl::math::RAD2DEG << std::endl; - std::cout << "qdTarget[0]: " << this->in.qdTarget[0] * rl::math::RAD2DEG << std::endl; - std::cout << "qdTarget[1]: " << this->in.qdTarget[1] * rl::math::RAD2DEG << std::endl; - std::cout << "qdTarget[2]: " << this->in.qdTarget[2] * rl::math::RAD2DEG << std::endl; - std::cout << "qdTarget[3]: " << this->in.qdTarget[3] * rl::math::RAD2DEG << std::endl; - std::cout << "qdTarget[4]: " << this->in.qdTarget[4] * rl::math::RAD2DEG << std::endl; - std::cout << "qdTarget[5]: " << this->in.qdTarget[5] * rl::math::RAD2DEG << std::endl; - std::cout << "qddTarget[0]: " << this->in.qddTarget[0] * rl::math::RAD2DEG << std::endl; - std::cout << "qddTarget[1]: " << this->in.qddTarget[1] * rl::math::RAD2DEG << std::endl; - std::cout << "qddTarget[2]: " << this->in.qddTarget[2] * rl::math::RAD2DEG << std::endl; - std::cout << "qddTarget[3]: " << this->in.qddTarget[3] * rl::math::RAD2DEG << std::endl; - std::cout << "qddTarget[4]: " << this->in.qddTarget[4] * rl::math::RAD2DEG << std::endl; - std::cout << "qddTarget[5]: " << this->in.qddTarget[5] * rl::math::RAD2DEG << std::endl; - std::cout << "iTarget[0]: " << this->in.iTarget[0] << std::endl; - std::cout << "iTarget[1]: " << this->in.iTarget[1] << std::endl; - std::cout << "iTarget[2]: " << this->in.iTarget[2] << std::endl; - std::cout << "iTarget[3]: " << this->in.iTarget[3] << std::endl; - std::cout << "iTarget[4]: " << this->in.iTarget[4] << std::endl; - std::cout << "iTarget[5]: " << this->in.iTarget[5] << std::endl; - std::cout << "mTarget[0]: " << this->in.mTarget[0] << std::endl; - std::cout << "mTarget[1]: " << this->in.mTarget[1] << std::endl; - std::cout << "mTarget[2]: " << this->in.mTarget[2] << std::endl; - std::cout << "mTarget[3]: " << this->in.mTarget[3] << std::endl; - std::cout << "mTarget[4]: " << this->in.mTarget[4] << std::endl; - std::cout << "mTarget[5]: " << this->in.mTarget[5] << std::endl; - std::cout << "qActual[0]: " << this->in.qActual[0] * rl::math::RAD2DEG << std::endl; - std::cout << "qActual[1]: " << this->in.qActual[1] * rl::math::RAD2DEG << std::endl; - std::cout << "qActual[2]: " << this->in.qActual[2] * rl::math::RAD2DEG << std::endl; - std::cout << "qActual[3]: " << this->in.qActual[3] * rl::math::RAD2DEG << std::endl; - std::cout << "qActual[4]: " << this->in.qActual[4] * rl::math::RAD2DEG << std::endl; - std::cout << "qActual[5]: " << this->in.qActual[5] * rl::math::RAD2DEG << std::endl; - std::cout << "qdActual[0]: " << this->in.qdActual[0] * rl::math::RAD2DEG << std::endl; - std::cout << "qdActual[1]: " << this->in.qdActual[1] * rl::math::RAD2DEG << std::endl; - std::cout << "qdActual[2]: " << this->in.qdActual[2] * rl::math::RAD2DEG << std::endl; - std::cout << "qdActual[3]: " << this->in.qdActual[3] * rl::math::RAD2DEG << std::endl; - std::cout << "qdActual[4]: " << this->in.qdActual[4] * rl::math::RAD2DEG << std::endl; - std::cout << "qdActual[5]: " << this->in.qdActual[5] * rl::math::RAD2DEG << std::endl; -#endif } void From ab48448bcc977e558c478ef12baed86413201e37 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 11 Oct 2018 20:26:49 +0200 Subject: [PATCH 052/546] Add robot status enums and functions --- src/rl/hal/UniversalRobotsRealtime.cpp | 24 ++++++++++ src/rl/hal/UniversalRobotsRealtime.h | 61 ++++++++++++++++++++++++++ 2 files changed, 85 insertions(+) diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index 7ae69a3a..d39490b1 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -179,6 +179,12 @@ namespace rl return i; } + UniversalRobotsRealtime::JointMode + UniversalRobotsRealtime::getJointMode(const ::std::size_t& i) const + { + return static_cast(static_cast(this->in.jointModes[i])); + } + ::rl::math::Vector UniversalRobotsRealtime::getJointPosition() const { @@ -205,6 +211,24 @@ namespace rl return qd; } + UniversalRobotsRealtime::ProgramState + UniversalRobotsRealtime::getProgramState() const + { + return static_cast(static_cast(this->in.programState)); + } + + UniversalRobotsRealtime::RobotMode + UniversalRobotsRealtime::getRobotMode() const + { + return static_cast(static_cast(this->in.robotMode)); + } + + UniversalRobotsRealtime::SafetyMode + UniversalRobotsRealtime::getSafetyMode() const + { + return static_cast(static_cast(this->in.safetyMode)); + } + void UniversalRobotsRealtime::open() { diff --git a/src/rl/hal/UniversalRobotsRealtime.h b/src/rl/hal/UniversalRobotsRealtime.h index 5864c50b..d0980d69 100644 --- a/src/rl/hal/UniversalRobotsRealtime.h +++ b/src/rl/hal/UniversalRobotsRealtime.h @@ -60,6 +60,59 @@ namespace rl public JointVelocitySensor { public: + enum JointMode + { + JOINT_MODE_SHUTTING_DOWN = 236, + JOINT_MODE_PART_D_CALIBRATION = 237, + JOINT_MODE_BACKDRIVE = 238, + JOINT_MODE_POWER_OFF = 239, + JOINT_MODE_NOT_RESPONDING = 245, + JOINT_MODE_MOTOR_INITIALISATION = 246, + JOINT_MODE_BOOTING = 247, + JOINT_MODE_PART_D_CALIBRATION_ERROR = 248, + JOINT_MODE_BOOTLOADER = 249, + JOINT_MODE_CALIBRATION = 250, + JOINT_MODE_FAULT = 252, + JOINT_MODE_RUNNING = 253, + JOINT_MODE_IDLE_MODE = 255 + }; + + enum ProgramState + { + PROGRAM_STATE_STOPPING = 0, + PROGRAM_STATE_STOPPED = 1, + PROGRAM_STATE_PLAYING = 2, + PROGRAM_STATE_PAUSING = 3, + PROGRAM_STATE_PAUSED = 4, + PROGRAM_STATE_RESUMING = 5 + }; + + enum RobotMode + { + ROBOT_MODE_DISCONNECTED = 0, + ROBOT_MODE_CONFIRM_SAFETY = 1, + ROBOT_MODE_BOOTING = 2, + ROBOT_MODE_POWER_OFF = 3, + ROBOT_MODE_POWER_ON = 4, + ROBOT_MODE_IDLE = 5, + ROBOT_MODE_BACKDRIVE = 6, + ROBOT_MODE_RUNNING = 7, + ROBOT_MODE_UPDATING_FIRMWARE = 8 + }; + + enum SafetyMode + { + SAFETY_MODE_NORMAL = 1, + SAFETY_MODE_REDUCED = 2, + SAFETY_MODE_PROTECTIVE_STOP = 3, + SAFETY_MODE_RECOVERY = 4, + SAFETY_MODE_SAFEGUARD_STOP = 5, + SAFETY_MODE_SYSTEM_EMERGENCY_STOP = 6, + SAFETY_MODE_ROBOT_EMERGENCY_STOP = 7, + SAFETY_MODE_VIOLATION = 8, + SAFETY_MODE_FAULT = 9 + }; + UniversalRobotsRealtime(const ::std::string& address); virtual ~UniversalRobotsRealtime(); @@ -88,10 +141,18 @@ namespace rl ::rl::math::Vector getJointCurrent() const; + JointMode getJointMode(const ::std::size_t& i) const; + ::rl::math::Vector getJointPosition() const; ::rl::math::Vector getJointVelocity() const; + ProgramState getProgramState() const; + + RobotMode getRobotMode() const; + + SafetyMode getSafetyMode() const; + void open(); void start(); From 9a8b8ae6a2bd72d15c21bf0c2ddf97d892453f23 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 1 Nov 2018 20:06:33 +0100 Subject: [PATCH 053/546] Update Coin3D external projects --- 3rdparty/CMakeLists.txt | 11 ++++++++--- .../boost-header-libs-full/CMakeLists.txt | 12 ++++++++++++ 3rdparty/{ => coin3d}/coin/CMakeLists.txt | 16 +++------------- 3rdparty/coin3d/cpack.d/CMakeLists.txt | 12 ++++++++++++ 3rdparty/{ => coin3d}/simage/CMakeLists.txt | 7 +++---- 3rdparty/coin3d/soanydata/CMakeLists.txt | 12 ++++++++++++ 3rdparty/coin3d/sogui/CMakeLists.txt | 12 ++++++++++++ 3rdparty/{ => coin3d}/soqt/CMakeLists.txt | 17 ++++------------- 8 files changed, 66 insertions(+), 33 deletions(-) create mode 100644 3rdparty/coin3d/boost-header-libs-full/CMakeLists.txt rename 3rdparty/{ => coin3d}/coin/CMakeLists.txt (55%) create mode 100644 3rdparty/coin3d/cpack.d/CMakeLists.txt rename 3rdparty/{ => coin3d}/simage/CMakeLists.txt (77%) create mode 100644 3rdparty/coin3d/soanydata/CMakeLists.txt create mode 100644 3rdparty/coin3d/sogui/CMakeLists.txt rename 3rdparty/{ => coin3d}/soqt/CMakeLists.txt (59%) diff --git a/3rdparty/CMakeLists.txt b/3rdparty/CMakeLists.txt index 7854eb6a..5c210820 100644 --- a/3rdparty/CMakeLists.txt +++ b/3rdparty/CMakeLists.txt @@ -28,6 +28,11 @@ else() set(PATCH_EXECUTABLE patch) endif() +add_subdirectory(coin3d/boost-header-libs-full) +add_subdirectory(coin3d/cpack.d) +add_subdirectory(coin3d/soanydata) +add_subdirectory(coin3d/sogui) + add_subdirectory(atidaq) add_subdirectory(boost) add_subdirectory(bullet) @@ -36,15 +41,15 @@ add_subdirectory(libiconv) add_subdirectory(nlopt) add_subdirectory(ode) add_subdirectory(pqp) -add_subdirectory(simage) +add_subdirectory(coin3d/simage) add_subdirectory(solid) add_subdirectory(zlib) add_subdirectory(libxml2) -add_subdirectory(coin) +add_subdirectory(coin3d/coin) add_subdirectory(libxslt) -add_subdirectory(soqt) +add_subdirectory(coin3d/soqt) set( CPACK_INSTALL_CMAKE_PROJECTS diff --git a/3rdparty/coin3d/boost-header-libs-full/CMakeLists.txt b/3rdparty/coin3d/boost-header-libs-full/CMakeLists.txt new file mode 100644 index 00000000..57eaf0ab --- /dev/null +++ b/3rdparty/coin3d/boost-header-libs-full/CMakeLists.txt @@ -0,0 +1,12 @@ +include(ExternalProject) + +ExternalProject_Add( + boost-header-libs-full + #HG_REPOSITORY https://bitbucket.org/Coin3D/boost-header-libs-full + #HG_TAG default + URL https://bitbucket.org/Coin3D/boost-header-libs-full/get/default.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + CONFIGURE_COMMAND "" + BUILD_COMMAND "" + INSTALL_COMMAND "" +) diff --git a/3rdparty/coin/CMakeLists.txt b/3rdparty/coin3d/coin/CMakeLists.txt similarity index 55% rename from 3rdparty/coin/CMakeLists.txt rename to 3rdparty/coin3d/coin/CMakeLists.txt index 075179fb..90534031 100644 --- a/3rdparty/coin/CMakeLists.txt +++ b/3rdparty/coin3d/coin/CMakeLists.txt @@ -1,27 +1,17 @@ include(ExternalProject) -ExternalProject_Add( - boost-header-libs-full - #HG_REPOSITORY https://bitbucket.org/Coin3D/boost-header-libs-full - #HG_TAG default - URL https://bitbucket.org/Coin3D/boost-header-libs-full/get/default.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" -) - list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) ExternalProject_Add( coin - DEPENDS boost-header-libs-full simage + DEPENDS boost-header-libs-full cpack.d simage #HG_REPOSITORY https://bitbucket.org/Coin3D/coin #HG_TAG default URL https://bitbucket.org/Coin3D/coin/get/default.tar.bz2 #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 PATCH_COMMAND - ${CMAKE_COMMAND} -E rename ${CMAKE_CURRENT_BINARY_DIR}/boost-header-libs-full-prefix/src/boost-header-libs-full /include/boost + ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d && + ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../boost-header-libs-full/boost-header-libs-full-prefix/src/boost-header-libs-full /include/boost CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DCOIN_BUILD_DOCUMENTATION=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) diff --git a/3rdparty/coin3d/cpack.d/CMakeLists.txt b/3rdparty/coin3d/cpack.d/CMakeLists.txt new file mode 100644 index 00000000..ee361662 --- /dev/null +++ b/3rdparty/coin3d/cpack.d/CMakeLists.txt @@ -0,0 +1,12 @@ +include(ExternalProject) + +ExternalProject_Add( + cpack.d + #HG_REPOSITORY https://bitbucket.org/Coin3D/cpack.d + #HG_TAG default + URL https://bitbucket.org/Coin3D/cpack.d/get/default.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + CONFIGURE_COMMAND "" + BUILD_COMMAND "" + INSTALL_COMMAND "" +) diff --git a/3rdparty/simage/CMakeLists.txt b/3rdparty/coin3d/simage/CMakeLists.txt similarity index 77% rename from 3rdparty/simage/CMakeLists.txt rename to 3rdparty/coin3d/simage/CMakeLists.txt index c115a530..3b23dd5f 100644 --- a/3rdparty/simage/CMakeLists.txt +++ b/3rdparty/coin3d/simage/CMakeLists.txt @@ -1,15 +1,14 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(simage) - include(ExternalProject) ExternalProject_Add( simage + DEPENDS cpack.d #HG_REPOSITORY https://bitbucket.org/Coin3D/simage #HG_TAG default URL https://bitbucket.org/Coin3D/simage/get/default.tar.bz2 #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + PATCH_COMMAND + ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) diff --git a/3rdparty/coin3d/soanydata/CMakeLists.txt b/3rdparty/coin3d/soanydata/CMakeLists.txt new file mode 100644 index 00000000..7519ad02 --- /dev/null +++ b/3rdparty/coin3d/soanydata/CMakeLists.txt @@ -0,0 +1,12 @@ +include(ExternalProject) + +ExternalProject_Add( + soanydata + #HG_REPOSITORY https://bitbucket.org/Coin3D/soanydata + #HG_TAG default + URL https://bitbucket.org/Coin3D/soanydata/get/default.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + CONFIGURE_COMMAND "" + BUILD_COMMAND "" + INSTALL_COMMAND "" +) diff --git a/3rdparty/coin3d/sogui/CMakeLists.txt b/3rdparty/coin3d/sogui/CMakeLists.txt new file mode 100644 index 00000000..782e7a59 --- /dev/null +++ b/3rdparty/coin3d/sogui/CMakeLists.txt @@ -0,0 +1,12 @@ +include(ExternalProject) + +ExternalProject_Add( + sogui + #HG_REPOSITORY https://bitbucket.org/Coin3D/sogui + #HG_TAG default + URL https://bitbucket.org/Coin3D/sogui/get/default.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + CONFIGURE_COMMAND "" + BUILD_COMMAND "" + INSTALL_COMMAND "" +) diff --git a/3rdparty/soqt/CMakeLists.txt b/3rdparty/coin3d/soqt/CMakeLists.txt similarity index 59% rename from 3rdparty/soqt/CMakeLists.txt rename to 3rdparty/coin3d/soqt/CMakeLists.txt index 2f689c7b..4400e0a6 100644 --- a/3rdparty/soqt/CMakeLists.txt +++ b/3rdparty/coin3d/soqt/CMakeLists.txt @@ -1,27 +1,18 @@ include(ExternalProject) -ExternalProject_Add( - sogui - #HG_REPOSITORY https://bitbucket.org/Coin3D/sogui - #HG_TAG default - URL https://bitbucket.org/Coin3D/sogui/get/default.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" -) - list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) ExternalProject_Add( soqt - DEPENDS sogui coin + DEPENDS cpack.d soanydata sogui coin #HG_REPOSITORY https://bitbucket.org/Coin3D/soqt #HG_TAG default URL https://bitbucket.org/Coin3D/soqt/get/default.tar.bz2 #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 PATCH_COMMAND - ${CMAKE_COMMAND} -E rename ${CMAKE_CURRENT_BINARY_DIR}/sogui-prefix/src/sogui /src/Inventor/Qt/common + ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d && + ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../soanydata/soanydata-prefix/src/soanydata /data && + ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../sogui/sogui-prefix/src/sogui /src/Inventor/Qt/common CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DSOQT_BUILD_DOCUMENTATION=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From cf069adf69f6dbccc608ee26cfdea4c55441ebc8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 2 Nov 2018 16:27:47 +0100 Subject: [PATCH 054/546] Fix variable names in FindNLopt.cmake --- cmake/FindNLopt.cmake | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/cmake/FindNLopt.cmake b/cmake/FindNLopt.cmake index 1a57094e..a33aed58 100644 --- a/cmake/FindNLopt.cmake +++ b/cmake/FindNLopt.cmake @@ -9,12 +9,12 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} ${PATH}/NLopt*/${CMAKE_INSTALL_INCLUDEDIR} ) - list(APPEND NLopt_INCLUDE_HINTS ${HINTS}) + list(APPEND NLOPT_INCLUDE_HINTS ${HINTS}) endforeach() list( APPEND - NLopt_INCLUDE_HINTS + NLOPT_INCLUDE_HINTS $ENV{NLopt_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) @@ -25,7 +25,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} ${PATH}/NLopt*/${CMAKE_INSTALL_INCLUDEDIR} ) - list(APPEND NLopt_INCLUDE_HINTS ${HINTS}) + list(APPEND NLOPT_INCLUDE_HINTS ${HINTS}) endforeach() foreach(PATH $ENV{PATH}) @@ -34,7 +34,7 @@ foreach(PATH $ENV{PATH}) HINTS ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} ) - list(APPEND NLopt_INCLUDE_HINTS ${HINTS}) + list(APPEND NLOPT_INCLUDE_HINTS ${HINTS}) endforeach() file( @@ -65,12 +65,12 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_LIBDIR} ${PATH}/NLopt*/${CMAKE_INSTALL_LIBDIR} ) - list(APPEND NLopt_LIBRARY_HINTS ${HINTS}) + list(APPEND NLOPT_LIBRARY_HINTS ${HINTS}) endforeach() list( APPEND - NLopt_LIBRARY_HINTS + NLOPT_LIBRARY_HINTS $ENV{NLopt_DIR}/${CMAKE_INSTALL_LIBDIR} ) @@ -81,7 +81,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_LIBDIR} ${PATH}/NLopt*/${CMAKE_INSTALL_LIBDIR} ) - list(APPEND NLopt_LIBRARY_HINTS ${HINTS}) + list(APPEND NLOPT_LIBRARY_HINTS ${HINTS}) endforeach() foreach(PATH $ENV{PATH}) @@ -90,7 +90,7 @@ foreach(PATH $ENV{PATH}) HINTS ${PATH}/../${CMAKE_INSTALL_LIBDIR} ) - list(APPEND NLopt_LIBRARY_HINTS ${HINTS}) + list(APPEND NLOPT_LIBRARY_HINTS ${HINTS}) endforeach() file( From 8a07851f6d5dc3566cb4a37ef5884de00532c96d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 2 Nov 2018 16:30:30 +0100 Subject: [PATCH 055/546] Update NLopt external project --- 3rdparty/nlopt/CMakeLists.txt | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/3rdparty/nlopt/CMakeLists.txt b/3rdparty/nlopt/CMakeLists.txt index 6792dd79..62916a00 100644 --- a/3rdparty/nlopt/CMakeLists.txt +++ b/3rdparty/nlopt/CMakeLists.txt @@ -7,10 +7,10 @@ include(ExternalProject) ExternalProject_Add( nlopt #GIT_REPOSITORY git://github.com/stevengj/nlopt.git - #GIT_TAG 2.4.2 - URL https://github.com/roboticslibrary/nlopt/archive/patch.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/nlopt-2.4.2.zip - #URL_MD5 b2b4f009759c5e33e4c27d6c980419d7 - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_SHARED_LIBS=ON -DNLOPT_GUILE=OFF -DNLOPT_MATLAB=OFF -DNLOPT_OCTAVE=OFF -DNLOPT_PYTHON=OFF + #GIT_TAG 2.5.0 + URL https://github.com/stevengj/nlopt/archive/v2.5.0.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/nlopt-2.5.0.zip + URL_MD5 229ac19157563c76b1b1c28ef3f3f7d0 + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_DEBUG_POSTFIX=d -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_SHARED_LIBS=ON -DNLOPT_GUILE=OFF -DNLOPT_MATLAB=OFF -DNLOPT_OCTAVE=OFF -DNLOPT_PYTHON=OFF -DNLOPT_SWIG=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From 46cd9a401652e0407b7707aa36c7f794ffdc379a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 19 Mar 2018 22:20:45 +0100 Subject: [PATCH 056/546] Remove extra white space --- demos/rlCoachKin/ConfigurationDelegate.h | 2 +- demos/rlCoachKin/ConfigurationModel.h | 2 +- demos/rlCoachKin/OperationalDelegate.h | 2 +- demos/rlCoachKin/OperationalModel.h | 2 +- demos/rlCoachMdl/ConfigurationDelegate.h | 2 +- demos/rlCoachMdl/ConfigurationModel.h | 2 +- demos/rlCoachMdl/OperationalDelegate.h | 2 +- demos/rlCoachMdl/OperationalModel.h | 2 +- demos/rlCollisionDemo/BodyDelegate.h | 2 +- demos/rlPlanDemo/ConfigurationDelegate.h | 2 +- demos/rlSimulator/ConfigurationDelegate.h | 2 +- demos/rlSimulator/ConfigurationModel.h | 2 +- demos/rlSimulator/OperationalDelegate.h | 2 +- demos/rlSimulator/OperationalModel.h | 2 +- extras/tris2wrl/tris2wrl.cpp | 2 +- src/rl/math/SplineQuaternion.h | 2 +- tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp | 2 +- tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp | 2 +- 18 files changed, 18 insertions(+), 18 deletions(-) diff --git a/demos/rlCoachKin/ConfigurationDelegate.h b/demos/rlCoachKin/ConfigurationDelegate.h index 8e1c1b07..13c33321 100644 --- a/demos/rlCoachKin/ConfigurationDelegate.h +++ b/demos/rlCoachKin/ConfigurationDelegate.h @@ -44,7 +44,7 @@ class ConfigurationDelegate : public QItemDelegate void setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const; - void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; + void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; std::size_t id; diff --git a/demos/rlCoachKin/ConfigurationModel.h b/demos/rlCoachKin/ConfigurationModel.h index c29f068f..dc09e3d2 100644 --- a/demos/rlCoachKin/ConfigurationModel.h +++ b/demos/rlCoachKin/ConfigurationModel.h @@ -56,7 +56,7 @@ class ConfigurationModel : public QAbstractTableModel std::size_t id; public slots: - void operationalChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void operationalChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); protected: diff --git a/demos/rlCoachKin/OperationalDelegate.h b/demos/rlCoachKin/OperationalDelegate.h index 2e1f4108..52a07454 100644 --- a/demos/rlCoachKin/OperationalDelegate.h +++ b/demos/rlCoachKin/OperationalDelegate.h @@ -44,7 +44,7 @@ class OperationalDelegate : public QItemDelegate void setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const; - void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; + void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; public slots: void valueChanged(double d); diff --git a/demos/rlCoachKin/OperationalModel.h b/demos/rlCoachKin/OperationalModel.h index 2f4bfb0c..b24153dd 100644 --- a/demos/rlCoachKin/OperationalModel.h +++ b/demos/rlCoachKin/OperationalModel.h @@ -53,7 +53,7 @@ class OperationalModel : public QAbstractTableModel std::size_t id; public slots: - void configurationChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void configurationChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); protected: diff --git a/demos/rlCoachMdl/ConfigurationDelegate.h b/demos/rlCoachMdl/ConfigurationDelegate.h index 8e1c1b07..13c33321 100644 --- a/demos/rlCoachMdl/ConfigurationDelegate.h +++ b/demos/rlCoachMdl/ConfigurationDelegate.h @@ -44,7 +44,7 @@ class ConfigurationDelegate : public QItemDelegate void setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const; - void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; + void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; std::size_t id; diff --git a/demos/rlCoachMdl/ConfigurationModel.h b/demos/rlCoachMdl/ConfigurationModel.h index c29f068f..dc09e3d2 100644 --- a/demos/rlCoachMdl/ConfigurationModel.h +++ b/demos/rlCoachMdl/ConfigurationModel.h @@ -56,7 +56,7 @@ class ConfigurationModel : public QAbstractTableModel std::size_t id; public slots: - void operationalChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void operationalChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); protected: diff --git a/demos/rlCoachMdl/OperationalDelegate.h b/demos/rlCoachMdl/OperationalDelegate.h index 2e1f4108..52a07454 100644 --- a/demos/rlCoachMdl/OperationalDelegate.h +++ b/demos/rlCoachMdl/OperationalDelegate.h @@ -44,7 +44,7 @@ class OperationalDelegate : public QItemDelegate void setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const; - void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; + void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; public slots: void valueChanged(double d); diff --git a/demos/rlCoachMdl/OperationalModel.h b/demos/rlCoachMdl/OperationalModel.h index 2f4bfb0c..b24153dd 100644 --- a/demos/rlCoachMdl/OperationalModel.h +++ b/demos/rlCoachMdl/OperationalModel.h @@ -53,7 +53,7 @@ class OperationalModel : public QAbstractTableModel std::size_t id; public slots: - void configurationChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void configurationChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); protected: diff --git a/demos/rlCollisionDemo/BodyDelegate.h b/demos/rlCollisionDemo/BodyDelegate.h index 3f75cb78..bc040c95 100644 --- a/demos/rlCollisionDemo/BodyDelegate.h +++ b/demos/rlCollisionDemo/BodyDelegate.h @@ -44,7 +44,7 @@ class BodyDelegate : public QItemDelegate void setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const; - void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; + void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; public slots: void valueChanged(double d); diff --git a/demos/rlPlanDemo/ConfigurationDelegate.h b/demos/rlPlanDemo/ConfigurationDelegate.h index 6f57063c..8b29035b 100644 --- a/demos/rlPlanDemo/ConfigurationDelegate.h +++ b/demos/rlPlanDemo/ConfigurationDelegate.h @@ -44,7 +44,7 @@ class ConfigurationDelegate : public QItemDelegate void setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const; - void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; + void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; public slots: void valueChanged(double d); diff --git a/demos/rlSimulator/ConfigurationDelegate.h b/demos/rlSimulator/ConfigurationDelegate.h index f2e4c5d2..7d53ad99 100644 --- a/demos/rlSimulator/ConfigurationDelegate.h +++ b/demos/rlSimulator/ConfigurationDelegate.h @@ -44,7 +44,7 @@ class ConfigurationDelegate : public QItemDelegate void setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const; - void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; + void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; std::size_t id; diff --git a/demos/rlSimulator/ConfigurationModel.h b/demos/rlSimulator/ConfigurationModel.h index f4c377b1..c6e38c68 100644 --- a/demos/rlSimulator/ConfigurationModel.h +++ b/demos/rlSimulator/ConfigurationModel.h @@ -54,7 +54,7 @@ class ConfigurationModel : public QAbstractTableModel bool setData(const rl::math::Vector& q); public slots: - void operationalChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void operationalChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); protected: diff --git a/demos/rlSimulator/OperationalDelegate.h b/demos/rlSimulator/OperationalDelegate.h index 2e1f4108..52a07454 100644 --- a/demos/rlSimulator/OperationalDelegate.h +++ b/demos/rlSimulator/OperationalDelegate.h @@ -44,7 +44,7 @@ class OperationalDelegate : public QItemDelegate void setModelData(QWidget* editor, QAbstractItemModel* model, const QModelIndex& index) const; - void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; + void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; public slots: void valueChanged(double d); diff --git a/demos/rlSimulator/OperationalModel.h b/demos/rlSimulator/OperationalModel.h index c1683fa4..b52ec802 100644 --- a/demos/rlSimulator/OperationalModel.h +++ b/demos/rlSimulator/OperationalModel.h @@ -50,7 +50,7 @@ class OperationalModel : public QAbstractTableModel bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); public slots: - void configurationChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void configurationChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); protected: diff --git a/extras/tris2wrl/tris2wrl.cpp b/extras/tris2wrl/tris2wrl.cpp index c0d19a35..5c5aba17 100644 --- a/extras/tris2wrl/tris2wrl.cpp +++ b/extras/tris2wrl/tris2wrl.cpp @@ -155,5 +155,5 @@ main(int argc, char** argv) fclose(f); - return EXIT_SUCCESS; + return EXIT_SUCCESS; } diff --git a/src/rl/math/SplineQuaternion.h b/src/rl/math/SplineQuaternion.h index ec8a1ef5..782b57c1 100644 --- a/src/rl/math/SplineQuaternion.h +++ b/src/rl/math/SplineQuaternion.h @@ -255,7 +255,7 @@ namespace rl for (; x > x0 + this->polynomials[i].duration() && i < this->polynomials.size(); ++i) { - x0 += this->polynomials[i].duration(); + x0 += this->polynomials[i].duration(); } return this->polynomials[i](x - x0, derivative); diff --git a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp index ca844950..784f6ccc 100644 --- a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp +++ b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp @@ -46,7 +46,7 @@ main(int argc, char** argv) std::mt19937 randomGenerator(0); std::uniform_real_distribution randomDistribution(-180 * rl::math::DEG2RAD, 180 * rl::math::DEG2RAD); - std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[1])); + std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[1])); std::size_t nTests; diff --git a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp index ad551649..45dc3919 100644 --- a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp +++ b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp @@ -48,7 +48,7 @@ main(int argc, char** argv) rl::mdl::XmlFactory factory; std::shared_ptr model(factory.create(argv[1])); - rl::mdl::Kinematic* kinematics = dynamic_cast(model.get()); + rl::mdl::Kinematic* kinematics = dynamic_cast(model.get()); std::size_t nTests; From be0fc9a3518940c983a35a3a1749fa7727943ac3 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 20 Mar 2018 21:22:40 +0100 Subject: [PATCH 057/546] Add rotation conversion demo --- demos/CMakeLists.txt | 1 + .../AngleAxisModel.cpp | 177 ++++++ .../rlRotationConverterDemo/AngleAxisModel.h | 66 +++ demos/rlRotationConverterDemo/CMakeLists.txt | 109 ++++ .../EulerAnglesModel.cpp | 149 +++++ .../EulerAnglesModel.h | 69 +++ demos/rlRotationConverterDemo/MainWindow.cpp | 531 ++++++++++++++++++ demos/rlRotationConverterDemo/MainWindow.h | 113 ++++ .../QuaternionModel.cpp | 175 ++++++ .../rlRotationConverterDemo/QuaternionModel.h | 64 +++ .../RotationMatrixModel.cpp | 133 +++++ .../RotationMatrixModel.h | 64 +++ demos/rlRotationConverterDemo/TableView.cpp | 106 ++++ demos/rlRotationConverterDemo/TableView.h | 50 ++ .../rlRotationConverterDemo.cpp | 53 ++ .../rlRotationConverterDemo.desktop.in | 8 + 16 files changed, 1868 insertions(+) create mode 100644 demos/rlRotationConverterDemo/AngleAxisModel.cpp create mode 100644 demos/rlRotationConverterDemo/AngleAxisModel.h create mode 100644 demos/rlRotationConverterDemo/CMakeLists.txt create mode 100644 demos/rlRotationConverterDemo/EulerAnglesModel.cpp create mode 100644 demos/rlRotationConverterDemo/EulerAnglesModel.h create mode 100644 demos/rlRotationConverterDemo/MainWindow.cpp create mode 100644 demos/rlRotationConverterDemo/MainWindow.h create mode 100644 demos/rlRotationConverterDemo/QuaternionModel.cpp create mode 100644 demos/rlRotationConverterDemo/QuaternionModel.h create mode 100644 demos/rlRotationConverterDemo/RotationMatrixModel.cpp create mode 100644 demos/rlRotationConverterDemo/RotationMatrixModel.h create mode 100644 demos/rlRotationConverterDemo/TableView.cpp create mode 100644 demos/rlRotationConverterDemo/TableView.h create mode 100644 demos/rlRotationConverterDemo/rlRotationConverterDemo.cpp create mode 100644 demos/rlRotationConverterDemo/rlRotationConverterDemo.desktop.in diff --git a/demos/CMakeLists.txt b/demos/CMakeLists.txt index 55fa3654..bf194a6c 100644 --- a/demos/CMakeLists.txt +++ b/demos/CMakeLists.txt @@ -6,6 +6,7 @@ if(BUILD_RL_MATH) add_subdirectory(rlPcaDemo) add_subdirectory(rlQuaternionDemo) add_subdirectory(rlPolynomialRootsDemo) + add_subdirectory(rlRotationConverterDemo) add_subdirectory(rlSpatialDemo) add_subdirectory(rlTrapezoidalVelocityDemo) endif() diff --git a/demos/rlRotationConverterDemo/AngleAxisModel.cpp b/demos/rlRotationConverterDemo/AngleAxisModel.cpp new file mode 100644 index 00000000..b52d9aa8 --- /dev/null +++ b/demos/rlRotationConverterDemo/AngleAxisModel.cpp @@ -0,0 +1,177 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "AngleAxisModel.h" +#include "MainWindow.h" + +AngleAxisModel::AngleAxisModel(QObject* parent) : + QAbstractTableModel(parent), + angleAxis(nullptr), + angleRadians(nullptr) +{ +} + +AngleAxisModel::~AngleAxisModel() +{ +} + +int +AngleAxisModel::columnCount(const QModelIndex& parent) const +{ + return 4; +} + +QVariant +AngleAxisModel::data(const QModelIndex& index, int role) const +{ + if (nullptr == this->angleAxis || nullptr == this->angleRadians) + { + return QVariant(); + } + + if (!index.isValid()) + { + return QVariant(); + } + + switch (role) + { + case Qt::DisplayRole: + case Qt::EditRole: + switch (index.column()) + { + case 0: + case 1: + case 2: + return this->angleAxis->axis()(index.column()); + break; + case 3: + return *this->angleRadians ? this->angleAxis->angle() : this->angleAxis->angle() * rl::math::RAD2DEG; + break; + default: + break; + } + break; + case Qt::TextAlignmentRole: + return QVariant(Qt::AlignRight | Qt::AlignVCenter); + break; + default: + break; + } + + return QVariant(); +} + +Qt::ItemFlags +AngleAxisModel::flags(const QModelIndex &index) const +{ + if (!index.isValid()) + { + return Qt::NoItemFlags; + } + + return QAbstractItemModel::flags(index) | Qt::ItemIsEditable; +} + +QVariant +AngleAxisModel::headerData(int section, Qt::Orientation orientation, int role) const +{ + if (nullptr == this->angleAxis || nullptr == this->angleRadians) + { + return QVariant(); + } + + if (Qt::DisplayRole == role && Qt::Horizontal == orientation) + { + switch (section) + { + case 0: + return "X"; + break; + case 1: + return "Y"; + break; + case 2: + return "Z"; + break; + case 3: + return "Angle"; + break; + default: + break; + } + } + + return QVariant(); +} + +void +AngleAxisModel::invalidate() +{ + this->beginResetModel(); + this->endResetModel(); +} + +int +AngleAxisModel::rowCount(const QModelIndex& parent) const +{ + return 1; +} + +bool +AngleAxisModel::setData(const QModelIndex& index, const QVariant& value, int role) +{ + if (nullptr == this->angleAxis || nullptr == this->angleRadians) + { + return false; + } + + if (index.isValid() && Qt::EditRole == role) + { + switch (index.column()) + { + case 0: + case 1: + case 2: + this->angleAxis->axis()(index.column()) = value.value(); + break; + case 3: + this->angleAxis->angle() = *this->angleRadians ? value.value() : value.value() * rl::math::DEG2RAD; + break; + default: + break; + } + + emit dataChanged(this->createIndex(index.row(), index.column()), this->createIndex(index.row(), index.column())); + + return true; + } + + return false; +} diff --git a/demos/rlRotationConverterDemo/AngleAxisModel.h b/demos/rlRotationConverterDemo/AngleAxisModel.h new file mode 100644 index 00000000..1969f78e --- /dev/null +++ b/demos/rlRotationConverterDemo/AngleAxisModel.h @@ -0,0 +1,66 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 ANGLEAXISMODEL_H +#define ANGLEAXISMODEL_H + +#include +#include + +class AngleAxisModel : public QAbstractTableModel +{ + Q_OBJECT + +public: + AngleAxisModel(QObject* parent = nullptr); + + virtual ~AngleAxisModel(); + + int columnCount(const QModelIndex& parent = QModelIndex()) const; + + QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + + Qt::ItemFlags flags(const QModelIndex &index) const; + + QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const; + + void invalidate(); + + int rowCount(const QModelIndex& parent = QModelIndex()) const; + + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + + rl::math::AngleAxis* angleAxis; + + bool* angleRadians; + +protected: + +private: + +}; + +#endif // ANGLEAXISMODEL_H diff --git a/demos/rlRotationConverterDemo/CMakeLists.txt b/demos/rlRotationConverterDemo/CMakeLists.txt new file mode 100644 index 00000000..a6667687 --- /dev/null +++ b/demos/rlRotationConverterDemo/CMakeLists.txt @@ -0,0 +1,109 @@ +if(USE_QT5) + find_package(Qt5 COMPONENTS Core Gui Widgets QUIET) +endif() + +if(Qt5_FOUND) + set(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5Widgets_LIBRARIES}) + set(QT_FOUND Qt5_FOUND) +else() + set(QT_USE_IMPORTED_TARGETS ON) + find_package(Qt4 COMPONENTS QtCore QtGui) + set(QT_USE_QTMAIN ON) + include(${QT_USE_FILE}) +endif() + +set(CMAKE_AUTOMOC ON) +set(CMAKE_INCLUDE_CURRENT_DIR ON) + +if(QT_FOUND) + set( + HDRS + AngleAxisModel.h + EulerAnglesModel.h + MainWindow.h + QuaternionModel.h + RotationMatrixModel.h + TableView.h + ) + + set( + SRCS + AngleAxisModel.cpp + EulerAnglesModel.cpp + MainWindow.cpp + QuaternionModel.cpp + rlRotationConverterDemo.cpp + RotationMatrixModel.cpp + TableView.cpp + ${rl_SOURCE_DIR}/robotics-library.rc + ) + add_executable( + rlRotationConverterDemo + WIN32 + ${HDRS} + ${SRCS} + ) + + target_link_libraries( + rlRotationConverterDemo + math + ${QT_LIBRARIES} + ) + + set_target_properties( + rlRotationConverterDemo + PROPERTIES + VERSION ${VERSION} + ) + + if(WIN32) + set_target_properties( + rlRotationConverterDemo + PROPERTIES + DEBUG_POSTFIX d + ) + endif() + + install( + TARGETS rlRotationConverterDemo + COMPONENT demos + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} + ) + + if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) + install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) + endif() + + if(UNIX) + configure_file(rlRotationConverterDemo.desktop.in rlRotationConverterDemo.desktop @ONLY) + install(FILES ${CMAKE_CURRENT_BINARY_DIR}/rlRotationConverterDemo.desktop DESTINATION ${CMAKE_INSTALL_DATADIR}/applications COMPONENT demos) + endif() + + set( + CPACK_NSIS_CREATE_ICONS_EXTRA + ${CPACK_NSIS_CREATE_ICONS_EXTRA} + "CreateShortCut \\\\ + \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlRotationConverterDemo.lnk\\\" \\\\ + \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlRotationConverterDemo.exe\\\" \\\\ + \\\"\\\" \\\\ + \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ + \\\"Rotation conversion demo\\\"" + PARENT_SCOPE + ) + set(CPACK_NSIS_DELETE_ICONS_EXTRA ${CPACK_NSIS_DELETE_ICONS_EXTRA} "Delete \\\"$SMPROGRAMS\\\\$START_MENU\\\\rlRotationConverterDemo.lnk\\\"" PARENT_SCOPE) + + set( + WIX_SHORTCUTS + ${WIX_SHORTCUTS} + "" + PARENT_SCOPE + ) +endif() diff --git a/demos/rlRotationConverterDemo/EulerAnglesModel.cpp b/demos/rlRotationConverterDemo/EulerAnglesModel.cpp new file mode 100644 index 00000000..4023b268 --- /dev/null +++ b/demos/rlRotationConverterDemo/EulerAnglesModel.cpp @@ -0,0 +1,149 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "EulerAnglesModel.h" +#include "MainWindow.h" + +EulerAnglesModel::EulerAnglesModel(QObject* parent) : + QAbstractTableModel(parent), + eulerAngles(nullptr), + eulerAnglesRadians(nullptr), + eulerAxes(nullptr) +{ +} + +EulerAnglesModel::~EulerAnglesModel() +{ +} + +int +EulerAnglesModel::columnCount(const QModelIndex& parent) const +{ + return 3; +} + +QVariant +EulerAnglesModel::data(const QModelIndex& index, int role) const +{ + if (nullptr == this->eulerAngles || nullptr == this->eulerAnglesRadians || nullptr == this->eulerAxes) + { + return QVariant(); + } + + if (!index.isValid()) + { + return QVariant(); + } + + switch (role) + { + case Qt::DisplayRole: + case Qt::EditRole: + return *this->eulerAnglesRadians ? (*this->eulerAngles)(index.column()) : (*this->eulerAngles)(index.column()) * rl::math::RAD2DEG; + break; + case Qt::TextAlignmentRole: + return QVariant(Qt::AlignRight | Qt::AlignVCenter); + break; + default: + break; + } + + return QVariant(); +} + +Qt::ItemFlags +EulerAnglesModel::flags(const QModelIndex &index) const +{ + if (!index.isValid()) + { + return Qt::NoItemFlags; + } + + return QAbstractItemModel::flags(index) | Qt::ItemIsEditable; +} + +QVariant +EulerAnglesModel::headerData(int section, Qt::Orientation orientation, int role) const +{ + if (nullptr == this->eulerAngles || nullptr == this->eulerAnglesRadians || nullptr == this->eulerAxes) + { + return QVariant(); + } + + if (Qt::DisplayRole == role && Qt::Horizontal == orientation) + { + switch ((*this->eulerAxes)[section]) + { + case 0: + return "X"; + break; + case 1: + return "Y"; + break; + case 2: + return "Z"; + break; + default: + break; + } + } + + return QVariant(); +} + +void +EulerAnglesModel::invalidate() +{ + this->beginResetModel(); + this->endResetModel(); +} + +int +EulerAnglesModel::rowCount(const QModelIndex& parent) const +{ + return 1; +} + +bool +EulerAnglesModel::setData(const QModelIndex& index, const QVariant& value, int role) +{ + if (nullptr == this->eulerAngles || nullptr == this->eulerAnglesRadians || nullptr == this->eulerAxes) + { + return false; + } + + if (index.isValid() && Qt::EditRole == role) + { + (*this->eulerAngles)(index.column()) = *this->eulerAnglesRadians ? value.value() : value.value() * rl::math::DEG2RAD; + emit dataChanged(this->createIndex(index.row(), index.column()), this->createIndex(index.row(), index.column())); + return true; + } + + return false; +} diff --git a/demos/rlRotationConverterDemo/EulerAnglesModel.h b/demos/rlRotationConverterDemo/EulerAnglesModel.h new file mode 100644 index 00000000..f100d678 --- /dev/null +++ b/demos/rlRotationConverterDemo/EulerAnglesModel.h @@ -0,0 +1,69 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 EULERANGLESMODEL_H +#define EULERANGLESMODEL_H + +#include +#include +#include + +class EulerAnglesModel : public QAbstractTableModel +{ + Q_OBJECT + +public: + EulerAnglesModel(QObject* parent = nullptr); + + virtual ~EulerAnglesModel(); + + int columnCount(const QModelIndex& parent = QModelIndex()) const; + + QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + + Qt::ItemFlags flags(const QModelIndex &index) const; + + QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const; + + void invalidate(); + + int rowCount(const QModelIndex& parent = QModelIndex()) const; + + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + + rl::math::Vector3* eulerAngles; + + bool* eulerAnglesRadians; + + std::array* eulerAxes; + +protected: + +private: + +}; + +#endif // EULERANGLESMODEL_H diff --git a/demos/rlRotationConverterDemo/MainWindow.cpp b/demos/rlRotationConverterDemo/MainWindow.cpp new file mode 100644 index 00000000..8bf4eb04 --- /dev/null +++ b/demos/rlRotationConverterDemo/MainWindow.cpp @@ -0,0 +1,531 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include + +#include "AngleAxisModel.h" +#include "EulerAnglesModel.h" +#include "MainWindow.h" +#include "QuaternionModel.h" +#include "RotationMatrixModel.h" +#include "TableView.h" + +MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : + QMainWindow(parent, f), + inputAngleAxis(0, rl::math::Vector3::UnitZ()), + inputAngleAxisModel(new AngleAxisModel(this)), + inputEulerAngles(rl::math::Vector3::Zero()), + inputEulerAnglesModel(new EulerAnglesModel(this)), + inputEulerAxes(), + inputQuaternion(rl::math::Quaternion::Identity()), + inputRotationMatrix(rl::math::Rotation::Identity()), + inputUnitRadians(false), + outputAngleAxis(0, rl::math::Vector3::UnitZ()), + outputAngleAxisModel(new AngleAxisModel(this)), + outputEulerAngles(rl::math::Vector3::Zero()), + outputEulerAnglesModel(new EulerAnglesModel(this)), + outputEulerAxes(), + outputQuaternion(rl::math::Quaternion::Identity()), + outputQuaternionModel(new QuaternionModel(this)), + outputRotationMatrix(rl::math::Rotation::Identity()), + outputRotationMatrixModel(new RotationMatrixModel(this)), + outputUnitRadians(false) +{ + MainWindow::singleton = this; + + this->inputEulerAxes[0] = 0; + this->inputEulerAxes[1] = 1; + this->inputEulerAxes[2] = 2; + + this->outputEulerAxes[0] = 0; + this->outputEulerAxes[1] = 1; + this->outputEulerAxes[2] = 2; + + QWidget* centralWidget = new QWidget(this); + this->setCentralWidget(centralWidget); + + QGridLayout* gridLayout = new QGridLayout(centralWidget); + + // settings + + QGroupBox* inputSettingsGroupBox = new QGroupBox(this); + inputSettingsGroupBox->setFlat(true); + inputSettingsGroupBox->setTitle("Settings (Input)"); + gridLayout->addWidget(inputSettingsGroupBox, gridLayout->rowCount(), 0); + + QComboBox* inputUnitComboBox = new QComboBox(this); + inputUnitComboBox->addItem("Degrees"); + inputUnitComboBox->addItem("Radians"); + + QComboBox* inputEulerAxesComboBox = new QComboBox(this); + + QHBoxLayout* inputSettingsLayout = new QHBoxLayout(inputSettingsGroupBox); + inputSettingsLayout->addWidget(inputUnitComboBox); + inputSettingsLayout->addWidget(inputEulerAxesComboBox); + + QObject::connect( + inputUnitComboBox, + SIGNAL(currentIndexChanged(int)), + this, + SLOT(inputUnitChanged(int)) + ); + + QObject::connect( + inputEulerAxesComboBox, + SIGNAL(currentIndexChanged(int)), + this, + SLOT(inputEulerAxesChanged(int)) + ); + + QGroupBox* outputSettingsGroupBox = new QGroupBox(this); + outputSettingsGroupBox->setFlat(true); + outputSettingsGroupBox->setTitle("Settings (Output)"); + gridLayout->addWidget(outputSettingsGroupBox, gridLayout->rowCount() - 1, 1); + + QComboBox* outputUnitComboBox = new QComboBox(this); + outputUnitComboBox->addItem("Degrees"); + outputUnitComboBox->addItem("Radians"); + + QComboBox* outputEulerAxesComboBox = new QComboBox(this); + + QHBoxLayout* outputSettingsLayout = new QHBoxLayout(outputSettingsGroupBox); + outputSettingsLayout->addWidget(outputUnitComboBox); + outputSettingsLayout->addWidget(outputEulerAxesComboBox); + + QObject::connect( + outputUnitComboBox, + SIGNAL(currentIndexChanged(int)), + this, + SLOT(outputUnitChanged(int)) + ); + + QObject::connect( + outputEulerAxesComboBox, + SIGNAL(currentIndexChanged(int)), + this, + SLOT(outputEulerAxesChanged(int)) + ); + + for (std::size_t i = 0; i < 12; ++i) + { + QString text = "Euler "; + + for (std::size_t j = 0; j < 3; ++j) + { + if (j > 0) + { + text += "-"; + } + + switch (MainWindow::EULER_ANGLES[i][j]) + { + case 0: + text += "X"; + break; + case 1: + text += "Y"; + break; + case 2: + text += "Z"; + break; + default: + break; + } + } + + inputEulerAxesComboBox->addItem(text); + outputEulerAxesComboBox->addItem(text); + } + + // rotation matrix + + QGroupBox* inputRotationMatrixGroupBox = new QGroupBox(this); + inputRotationMatrixGroupBox->setFlat(true); + inputRotationMatrixGroupBox->setTitle("Rotation Matrix (Input)"); + gridLayout->addWidget(inputRotationMatrixGroupBox, gridLayout->rowCount(), 0); + + RotationMatrixModel* inputRotationMatrixModel = new RotationMatrixModel(this); + inputRotationMatrixModel->rotation = &this->inputRotationMatrix; + + TableView* inputRotationMatrixTableView = new TableView(this); + inputRotationMatrixTableView->setModel(inputRotationMatrixModel); + inputRotationMatrixTableView->verticalHeader()->setMinimumWidth(20); + + QVBoxLayout* inputRotationMatrixLayout = new QVBoxLayout(inputRotationMatrixGroupBox); + inputRotationMatrixLayout->addWidget(inputRotationMatrixTableView); + + QObject::connect( + inputRotationMatrixModel, + SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), + this, + SLOT(rotationMatrixChanged(const QModelIndex&, const QModelIndex&)) + ); + + QGroupBox* outputRotationMatrixGroupBox = new QGroupBox(this); + outputRotationMatrixGroupBox->setFlat(true); + outputRotationMatrixGroupBox->setTitle("Rotation Matrix (Output)"); + gridLayout->addWidget(outputRotationMatrixGroupBox, gridLayout->rowCount() - 1, 1); + + outputRotationMatrixModel->rotation = &this->outputRotationMatrix; + + TableView* outputRotationMatrixTableView = new TableView(this); + outputRotationMatrixTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); + outputRotationMatrixTableView->setModel(outputRotationMatrixModel); + outputRotationMatrixTableView->verticalHeader()->setMinimumWidth(20); + + QVBoxLayout* outputRotationMatrixLayout = new QVBoxLayout(outputRotationMatrixGroupBox); + outputRotationMatrixLayout->addWidget(outputRotationMatrixTableView); + + // angle axis + + QGroupBox* inputAngleAxisGroupBox = new QGroupBox(this); + inputAngleAxisGroupBox->setFlat(true); + inputAngleAxisGroupBox->setTitle("Angle Axis (Input)"); + gridLayout->addWidget(inputAngleAxisGroupBox, gridLayout->rowCount(), 0); + + inputAngleAxisModel->angleAxis = &this->inputAngleAxis; + inputAngleAxisModel->angleRadians = &this->inputUnitRadians; + + TableView* inputAngleAxisTableView = new TableView(this); + inputAngleAxisTableView->setModel(inputAngleAxisModel); + inputAngleAxisTableView->verticalHeader()->setMinimumWidth(20); + + QVBoxLayout* inputAngleAxisLayout = new QVBoxLayout(inputAngleAxisGroupBox); + inputAngleAxisLayout->addWidget(inputAngleAxisTableView); + + QObject::connect( + inputAngleAxisModel, + SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), + this, + SLOT(angleAxisChanged(const QModelIndex&, const QModelIndex&)) + ); + + QGroupBox* outputAngleAxisGroupBox = new QGroupBox(this); + outputAngleAxisGroupBox->setFlat(true); + outputAngleAxisGroupBox->setTitle("Angle Axis (Output)"); + gridLayout->addWidget(outputAngleAxisGroupBox, gridLayout->rowCount() - 1, 1); + + outputAngleAxisModel->angleAxis = &this->outputAngleAxis; + outputAngleAxisModel->angleRadians = &this->outputUnitRadians; + + TableView* outputAngleAxisTableView = new TableView(this); + outputAngleAxisTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); + outputAngleAxisTableView->setModel(outputAngleAxisModel); + outputAngleAxisTableView->verticalHeader()->setMinimumWidth(20); + + QVBoxLayout* outputAngleAxisLayout = new QVBoxLayout(outputAngleAxisGroupBox); + outputAngleAxisLayout->addWidget(outputAngleAxisTableView); + + // quaternion + + QGroupBox* inputQuaternionGroupBox = new QGroupBox(this); + inputQuaternionGroupBox->setFlat(true); + inputQuaternionGroupBox->setTitle("Quaternion (Input)"); + gridLayout->addWidget(inputQuaternionGroupBox, gridLayout->rowCount(), 0); + + QuaternionModel* inputQuaternionModel = new QuaternionModel(this); + inputQuaternionModel->quaternion = &this->inputQuaternion; + + TableView* inputQuaternionTableView = new TableView(this); + inputQuaternionTableView->setModel(inputQuaternionModel); + inputQuaternionTableView->verticalHeader()->setMinimumWidth(20); + + QVBoxLayout* inputQuaternionLayout = new QVBoxLayout(inputQuaternionGroupBox); + inputQuaternionLayout->addWidget(inputQuaternionTableView); + + QObject::connect( + inputQuaternionModel, + SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), + this, + SLOT(quaternionChanged(const QModelIndex&, const QModelIndex&)) + ); + + QGroupBox* outputQuaternionGroupBox = new QGroupBox(this); + outputQuaternionGroupBox->setFlat(true); + outputQuaternionGroupBox->setTitle("Quaternion (Output)"); + gridLayout->addWidget(outputQuaternionGroupBox, gridLayout->rowCount() - 1, 1); + + outputQuaternionModel->quaternion = &this->outputQuaternion; + + TableView* outputQuaternionTableView = new TableView(this); + outputQuaternionTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); + outputQuaternionTableView->setModel(outputQuaternionModel); + outputQuaternionTableView->verticalHeader()->setMinimumWidth(20); + + QVBoxLayout* outputQuaternionLayout = new QVBoxLayout(outputQuaternionGroupBox); + outputQuaternionLayout->addWidget(outputQuaternionTableView); + + // eulerAngles + + QGroupBox* inputEulerAnglesGroupBox = new QGroupBox(this); + inputEulerAnglesGroupBox->setFlat(true); + inputEulerAnglesGroupBox->setTitle("Euler Angles (Input)"); + gridLayout->addWidget(inputEulerAnglesGroupBox, gridLayout->rowCount(), 0); + + inputEulerAnglesModel->eulerAngles = &this->inputEulerAngles; + inputEulerAnglesModel->eulerAnglesRadians = &this->inputUnitRadians; + inputEulerAnglesModel->eulerAxes = &this->inputEulerAxes; + + TableView* inputEulerAnglesTableView = new TableView(this); + inputEulerAnglesTableView->setModel(inputEulerAnglesModel); + inputEulerAnglesTableView->verticalHeader()->setMinimumWidth(20); + + QVBoxLayout* inputEulerAnglesLayout = new QVBoxLayout(inputEulerAnglesGroupBox); + inputEulerAnglesLayout->addWidget(inputEulerAnglesTableView); + + QObject::connect( + inputEulerAnglesModel, + SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), + this, + SLOT(eulerAnglesChanged(const QModelIndex&, const QModelIndex&)) + ); + + QGroupBox* outputEulerAnglesGroupBox = new QGroupBox(this); + outputEulerAnglesGroupBox->setFlat(true); + outputEulerAnglesGroupBox->setTitle("Euler Angles (Output)"); + gridLayout->addWidget(outputEulerAnglesGroupBox, gridLayout->rowCount() - 1, 1); + + outputEulerAnglesModel->eulerAngles = &this->outputEulerAngles; + outputEulerAnglesModel->eulerAnglesRadians = &this->outputUnitRadians; + outputEulerAnglesModel->eulerAxes = &this->outputEulerAxes; + + TableView* outputEulerAnglesTableView = new TableView(this); + outputEulerAnglesTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); + outputEulerAnglesTableView->setModel(outputEulerAnglesModel); + outputEulerAnglesTableView->verticalHeader()->setMinimumWidth(20); + + QVBoxLayout* outputEulerAnglesLayout = new QVBoxLayout(outputEulerAnglesGroupBox); + outputEulerAnglesLayout->addWidget(outputEulerAnglesTableView); +} + +MainWindow::~MainWindow() +{ + MainWindow::singleton = nullptr; +} + +void +MainWindow::angleAxisChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) +{ + this->outputAngleAxis = this->inputAngleAxis; + this->outputQuaternion = this->inputAngleAxis; + this->outputRotationMatrix = this->inputAngleAxis; + + this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); + + this->outputAngleAxisModel->invalidate(); + this->outputEulerAnglesModel->invalidate(); + this->outputQuaternionModel->invalidate(); + this->outputRotationMatrixModel->invalidate(); +} + +void +MainWindow::eulerAnglesChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) +{ + this->outputQuaternion = rl::math::AngleAxis( + this->inputEulerAngles[0], + rl::math::Vector3::Unit(this->inputEulerAxes[0]) + ) * rl::math::AngleAxis( + this->inputEulerAngles[1], + rl::math::Vector3::Unit(this->inputEulerAxes[1]) + ) * rl::math::AngleAxis( + this->inputEulerAngles[2], + rl::math::Vector3::Unit(this->inputEulerAxes[2]) + ); + + this->outputAngleAxis = this->outputQuaternion; + this->outputRotationMatrix = this->outputQuaternion; + + this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); + + this->outputAngleAxisModel->invalidate(); + this->outputEulerAnglesModel->invalidate(); + this->outputQuaternionModel->invalidate(); + this->outputRotationMatrixModel->invalidate(); +} + +void +MainWindow::inputEulerAxesChanged(int index) +{ + if (index < 0 || index > 11) + { + return; + } + + for (std::size_t i = 0; i < 3; ++i) + { + this->inputEulerAxes[i] = MainWindow::EULER_ANGLES[index][i]; + } + + this->inputEulerAnglesModel->invalidate(); + + this->outputQuaternion = rl::math::AngleAxis( + this->inputEulerAngles[0], + rl::math::Vector3::Unit(this->inputEulerAxes[0]) + ) * rl::math::AngleAxis( + this->inputEulerAngles[1], + rl::math::Vector3::Unit(this->inputEulerAxes[1]) + ) * rl::math::AngleAxis( + this->inputEulerAngles[2], + rl::math::Vector3::Unit(this->inputEulerAxes[2]) + ); + + this->outputAngleAxis = this->outputQuaternion; + this->outputRotationMatrix = this->outputQuaternion; + + this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); + + this->outputAngleAxisModel->invalidate(); + this->outputEulerAnglesModel->invalidate(); + this->outputQuaternionModel->invalidate(); + this->outputRotationMatrixModel->invalidate(); +} + +void +MainWindow::inputUnitChanged(int index) +{ + if (index < 0 || index > 1) + { + return; + } + + switch (index) + { + case 0: + this->inputUnitRadians = false; + break; + case 1: + this->inputUnitRadians = true; + break; + default: + break; + } + + this->inputAngleAxisModel->invalidate(); + this->inputEulerAnglesModel->invalidate(); +} + +MainWindow* +MainWindow::instance() +{ + if (nullptr == MainWindow::singleton) + { + new MainWindow(); + } + + return MainWindow::singleton; +} + +void +MainWindow::outputEulerAxesChanged(int index) +{ + if (index < 0 || index > 11) + { + return; + } + + for (std::size_t i = 0; i < 3; ++i) + { + this->outputEulerAxes[i] = MainWindow::EULER_ANGLES[index][i]; + } + + this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); + + this->outputEulerAnglesModel->invalidate(); +} + +void +MainWindow::outputUnitChanged(int index) +{ + if (index < 0 || index > 1) + { + return; + } + + switch (index) + { + case 0: + this->outputUnitRadians = false; + break; + case 1: + this->outputUnitRadians = true; + break; + default: + break; + } + + this->outputAngleAxisModel->invalidate(); + this->outputEulerAnglesModel->invalidate(); +} + +void +MainWindow::quaternionChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) +{ + this->outputAngleAxis = this->inputQuaternion; + this->outputQuaternion = this->inputQuaternion; + this->outputRotationMatrix = this->inputQuaternion; + + this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); + + this->outputAngleAxisModel->invalidate(); + this->outputEulerAnglesModel->invalidate(); + this->outputQuaternionModel->invalidate(); + this->outputRotationMatrixModel->invalidate(); +} + +void +MainWindow::rotationMatrixChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) +{ + this->outputAngleAxis = this->inputRotationMatrix; + this->outputQuaternion = this->inputRotationMatrix; + this->outputRotationMatrix = this->inputRotationMatrix; + + this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); + + this->outputAngleAxisModel->invalidate(); + this->outputEulerAnglesModel->invalidate(); + this->outputQuaternionModel->invalidate(); + this->outputRotationMatrixModel->invalidate(); +} + +std::size_t MainWindow::EULER_ANGLES[12][3] = { + {0, 1, 0}, + {0, 2, 0}, + {1, 0, 1}, + {1, 2, 1}, + {2, 0, 2}, + {2, 1, 2}, + {0, 1, 2}, + {0, 2, 1}, + {1, 0, 2}, + {1, 2, 0}, + {2, 0, 1}, + {2, 1, 0} +}; diff --git a/demos/rlRotationConverterDemo/MainWindow.h b/demos/rlRotationConverterDemo/MainWindow.h new file mode 100644 index 00000000..ceb6902f --- /dev/null +++ b/demos/rlRotationConverterDemo/MainWindow.h @@ -0,0 +1,113 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 MAINWINDOW_H +#define MAINWINDOW_H + +#include +#include +#include +#include +#include +#include + +class AngleAxisModel; +class EulerAnglesModel; +class QuaternionModel; +class RotationMatrixModel; + +class MainWindow : public QMainWindow +{ + Q_OBJECT + +public: + virtual ~MainWindow(); + + static MainWindow* instance(); + +public slots: + void angleAxisChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + + void eulerAnglesChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + + void inputEulerAxesChanged(int index); + + void inputUnitChanged(int index); + + void outputEulerAxesChanged(int index); + + void outputUnitChanged(int index); + + void quaternionChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + + void rotationMatrixChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + +protected: + MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); + +private: + static std::size_t EULER_ANGLES[12][3]; + + rl::math::AngleAxis inputAngleAxis; + + AngleAxisModel* inputAngleAxisModel; + + rl::math::Vector3 inputEulerAngles; + + EulerAnglesModel* inputEulerAnglesModel; + + std::array inputEulerAxes; + + rl::math::Quaternion inputQuaternion; + + rl::math::Rotation inputRotationMatrix; + + bool inputUnitRadians; + + rl::math::AngleAxis outputAngleAxis; + + AngleAxisModel* outputAngleAxisModel; + + rl::math::Vector3 outputEulerAngles; + + EulerAnglesModel* outputEulerAnglesModel; + + std::array outputEulerAxes; + + rl::math::Quaternion outputQuaternion; + + QuaternionModel* outputQuaternionModel; + + rl::math::Rotation outputRotationMatrix; + + RotationMatrixModel* outputRotationMatrixModel; + + bool outputUnitRadians; + + static MainWindow* singleton; +}; + +#endif // MAINWINDOW_H diff --git a/demos/rlRotationConverterDemo/QuaternionModel.cpp b/demos/rlRotationConverterDemo/QuaternionModel.cpp new file mode 100644 index 00000000..e2b7e52d --- /dev/null +++ b/demos/rlRotationConverterDemo/QuaternionModel.cpp @@ -0,0 +1,175 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "MainWindow.h" +#include "QuaternionModel.h" + +QuaternionModel::QuaternionModel(QObject* parent) : + QAbstractTableModel(parent), + quaternion(nullptr) +{ +} + +QuaternionModel::~QuaternionModel() +{ +} + +int +QuaternionModel::columnCount(const QModelIndex& parent) const +{ + return 4; +} + +QVariant +QuaternionModel::data(const QModelIndex& index, int role) const +{ + if (nullptr == this->quaternion) + { + return QVariant(); + } + + if (!index.isValid()) + { + return QVariant(); + } + + switch (role) + { + case Qt::DisplayRole: + case Qt::EditRole: + switch (index.column()) + { + case 0: + case 1: + case 2: + return this->quaternion->vec()(index.column()); + break; + case 3: + return this->quaternion->w(); + break; + default: + break; + } + break; + case Qt::TextAlignmentRole: + return QVariant(Qt::AlignRight | Qt::AlignVCenter); + break; + default: + break; + } + + return QVariant(); +} + +Qt::ItemFlags +QuaternionModel::flags(const QModelIndex &index) const +{ + if (!index.isValid()) + { + return Qt::NoItemFlags; + } + + return QAbstractItemModel::flags(index) | Qt::ItemIsEditable; +} + +QVariant +QuaternionModel::headerData(int section, Qt::Orientation orientation, int role) const +{ + if (nullptr == this->quaternion) + { + return QVariant(); + } + + if (Qt::DisplayRole == role && Qt::Horizontal == orientation) + { + switch (section) + { + case 0: + return "X"; + break; + case 1: + return "Y"; + break; + case 2: + return "Z"; + break; + case 3: + return "W"; + break; + default: + break; + } + } + + return QVariant(); +} + +void +QuaternionModel::invalidate() +{ + this->beginResetModel(); + this->endResetModel(); +} + +int +QuaternionModel::rowCount(const QModelIndex& parent) const +{ + return 1; +} + +bool +QuaternionModel::setData(const QModelIndex& index, const QVariant& value, int role) +{ + if (nullptr == this->quaternion) + { + return false; + } + + if (index.isValid() && Qt::EditRole == role) + { + switch (index.column()) + { + case 0: + case 1: + case 2: + this->quaternion->vec()(index.column()) = value.value(); + break; + case 3: + this->quaternion->w() = value.value(); + break; + default: + break; + } + + emit dataChanged(this->createIndex(index.row(), index.column()), this->createIndex(index.row(), index.column())); + + return true; + } + + return false; +} diff --git a/demos/rlRotationConverterDemo/QuaternionModel.h b/demos/rlRotationConverterDemo/QuaternionModel.h new file mode 100644 index 00000000..c8c6f857 --- /dev/null +++ b/demos/rlRotationConverterDemo/QuaternionModel.h @@ -0,0 +1,64 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 QUATERNIONMODEL_H +#define QUATERNIONMODEL_H + +#include +#include + +class QuaternionModel : public QAbstractTableModel +{ + Q_OBJECT + +public: + QuaternionModel(QObject* parent = nullptr); + + virtual ~QuaternionModel(); + + int columnCount(const QModelIndex& parent = QModelIndex()) const; + + QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + + Qt::ItemFlags flags(const QModelIndex &index) const; + + QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const; + + void invalidate(); + + int rowCount(const QModelIndex& parent = QModelIndex()) const; + + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + + rl::math::Quaternion* quaternion; + +protected: + +private: + +}; + +#endif // QUATERNIONMODEL_H diff --git a/demos/rlRotationConverterDemo/RotationMatrixModel.cpp b/demos/rlRotationConverterDemo/RotationMatrixModel.cpp new file mode 100644 index 00000000..e0f64b8a --- /dev/null +++ b/demos/rlRotationConverterDemo/RotationMatrixModel.cpp @@ -0,0 +1,133 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "MainWindow.h" +#include "RotationMatrixModel.h" + +RotationMatrixModel::RotationMatrixModel(QObject* parent) : + QAbstractTableModel(parent), + rotation(nullptr) +{ +} + +RotationMatrixModel::~RotationMatrixModel() +{ +} + +int +RotationMatrixModel::columnCount(const QModelIndex& parent) const +{ + return 3; +} + +QVariant +RotationMatrixModel::data(const QModelIndex& index, int role) const +{ + if (nullptr == this->rotation) + { + return QVariant(); + } + + if (!index.isValid()) + { + return QVariant(); + } + + switch (role) + { + case Qt::DisplayRole: + case Qt::EditRole: + return (*this->rotation)(index.row(), index.column()); + break; + case Qt::TextAlignmentRole: + return QVariant(Qt::AlignRight | Qt::AlignVCenter); + break; + default: + break; + } + + return QVariant(); +} + +Qt::ItemFlags +RotationMatrixModel::flags(const QModelIndex &index) const +{ + if (!index.isValid()) + { + return Qt::NoItemFlags; + } + + return QAbstractItemModel::flags(index) | Qt::ItemIsEditable; +} + +QVariant +RotationMatrixModel::headerData(int section, Qt::Orientation orientation, int role) const +{ + if (nullptr == this->rotation) + { + return QVariant(); + } + + if (Qt::DisplayRole == role) + { + return section; + } + + return QVariant(); +} + +void +RotationMatrixModel::invalidate() +{ + this->beginResetModel(); + this->endResetModel(); +} + +int +RotationMatrixModel::rowCount(const QModelIndex& parent) const +{ + return 3; +} + +bool +RotationMatrixModel::setData(const QModelIndex& index, const QVariant& value, int role) +{ + if (nullptr == this->rotation) + { + return false; + } + + if (index.isValid() && Qt::EditRole == role) + { + (*this->rotation)(index.row(), index.column()) = value.value(); + emit dataChanged(this->createIndex(index.row(), index.column()), this->createIndex(index.row(), index.column())); + return true; + } + + return false; +} diff --git a/demos/rlRotationConverterDemo/RotationMatrixModel.h b/demos/rlRotationConverterDemo/RotationMatrixModel.h new file mode 100644 index 00000000..aee8c0aa --- /dev/null +++ b/demos/rlRotationConverterDemo/RotationMatrixModel.h @@ -0,0 +1,64 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 ROTATIONMATRIXMODEL_H +#define ROTATIONMATRIXMODEL_H + +#include +#include + +class RotationMatrixModel : public QAbstractTableModel +{ + Q_OBJECT + +public: + RotationMatrixModel(QObject* parent = nullptr); + + virtual ~RotationMatrixModel(); + + int columnCount(const QModelIndex& parent = QModelIndex()) const; + + QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + + Qt::ItemFlags flags(const QModelIndex &index) const; + + QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const; + + void invalidate(); + + int rowCount(const QModelIndex& parent = QModelIndex()) const; + + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + + rl::math::Rotation* rotation; + +protected: + +private: + +}; + +#endif // ROTATIONMATRIXMODEL_H diff --git a/demos/rlRotationConverterDemo/TableView.cpp b/demos/rlRotationConverterDemo/TableView.cpp new file mode 100644 index 00000000..c52124ba --- /dev/null +++ b/demos/rlRotationConverterDemo/TableView.cpp @@ -0,0 +1,106 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include + +#include "TableView.h" + +TableView::TableView(QWidget* parent) : + QTableView(parent) +{ +} + +TableView::~TableView() +{ +} + +void +TableView::keyPressEvent(QKeyEvent* event) +{ + if (event->matches(QKeySequence::Copy)) + { + QString text; + + QModelIndexList indices = this->selectedIndexes(); + QModelIndexList::iterator i = indices.begin(); + QModelIndexList::iterator j = ++indices.begin(); + + for (; i != indices.end(); ++i, ++j) + { + text += i->data().toString(); + + if (j != indices.end() && j->row() > i->row()) + { + text += "\n"; + } + else if (j != indices.end() && j->column() > i->column()) + { + text += " "; + } + } + + QApplication::clipboard()->setText(text); + } + + QTableView::keyPressEvent(event); +} + +QSize +TableView::minimumSizeHint() const +{ + return this->sizeHint(); +} + +QSize +TableView::sizeHint() const +{ + int horizontalScrollBarHeight = this->horizontalScrollBar()->isVisible() ? this->horizontalScrollBar()->height() : 2; + int horizontalHeaderHeight = this->horizontalHeader()->height(); + int rowTotalHeight = 0; + + for (int i = 0; i < this->verticalHeader()->count(); ++i) + { + rowTotalHeight += this->verticalHeader()->sectionSize(i); + } + + int verticalScrollBarWidth = this->verticalScrollBar()->isVisible() ? this->verticalScrollBar()->width() : 2; + int verticalHeaderWidth = this->verticalHeader()->width(); + int columnTotalWidth = 0; + + for (int i = 0; i < this->horizontalHeader()->count(); ++i) + { + columnTotalWidth += this->horizontalHeader()->sectionSize(i); + } + + return QSize( + verticalHeaderWidth + columnTotalWidth + verticalScrollBarWidth, + horizontalHeaderHeight + rowTotalHeight + horizontalScrollBarHeight + ); +} diff --git a/demos/rlRotationConverterDemo/TableView.h b/demos/rlRotationConverterDemo/TableView.h new file mode 100644 index 00000000..51cf693b --- /dev/null +++ b/demos/rlRotationConverterDemo/TableView.h @@ -0,0 +1,50 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 TABLEVIEW_H +#define TABLEVIEW_H + +#include + +class TableView : public QTableView +{ +public: + TableView(QWidget* parent = nullptr); + + virtual ~TableView(); + + virtual QSize minimumSizeHint() const; + + virtual QSize sizeHint() const; + +protected: + virtual void keyPressEvent(QKeyEvent* event); + +private: + +}; + +#endif // TABLEVIEW_H diff --git a/demos/rlRotationConverterDemo/rlRotationConverterDemo.cpp b/demos/rlRotationConverterDemo/rlRotationConverterDemo.cpp new file mode 100644 index 00000000..0e0a08cd --- /dev/null +++ b/demos/rlRotationConverterDemo/rlRotationConverterDemo.cpp @@ -0,0 +1,53 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 + +#include "MainWindow.h" + +MainWindow* MainWindow::singleton = nullptr; + +int +main(int argc, char** argv) +{ + try + { + QApplication application(argc, argv); + + QObject::connect(&application, SIGNAL(lastWindowClosed()), &application, SLOT(quit())); + + MainWindow::instance()->show(); + + return application.exec(); + } + catch (const std::exception& e) + { + std::cerr << e.what() << std::endl; + return EXIT_FAILURE; + } +} diff --git a/demos/rlRotationConverterDemo/rlRotationConverterDemo.desktop.in b/demos/rlRotationConverterDemo/rlRotationConverterDemo.desktop.in new file mode 100644 index 00000000..7a79260f --- /dev/null +++ b/demos/rlRotationConverterDemo/rlRotationConverterDemo.desktop.in @@ -0,0 +1,8 @@ +[Desktop Entry] +Categories=Science;Robotics; +Comment=Rotation conversion demo +Exec=rlRotationConverterDemo +Icon=robotics-library +Name=Robotics Library (rlRotationConverterDemo) +Type=Application +X-Unity-IconBackgroundColor=#ffffff From 17d9c6463dc855da48382dd31fc95f1458c4ecb1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 21 Mar 2018 16:32:52 +0100 Subject: [PATCH 058/546] Sort indices in rlRotationConverterDemo for Qt4 --- demos/rlRotationConverterDemo/TableView.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/demos/rlRotationConverterDemo/TableView.cpp b/demos/rlRotationConverterDemo/TableView.cpp index c52124ba..88328550 100644 --- a/demos/rlRotationConverterDemo/TableView.cpp +++ b/demos/rlRotationConverterDemo/TableView.cpp @@ -49,6 +49,8 @@ TableView::keyPressEvent(QKeyEvent* event) QString text; QModelIndexList indices = this->selectedIndexes(); + qSort(indices); + QModelIndexList::iterator i = indices.begin(); QModelIndexList::iterator j = ++indices.begin(); From 3a3529f3b8aafeeef9a54c55aab946f80ca09ab5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 21 Mar 2018 16:33:32 +0100 Subject: [PATCH 059/546] Use tabs to divide cells in rlRotationConverterDemo for Excel --- demos/rlRotationConverterDemo/TableView.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/rlRotationConverterDemo/TableView.cpp b/demos/rlRotationConverterDemo/TableView.cpp index 88328550..2cda4295 100644 --- a/demos/rlRotationConverterDemo/TableView.cpp +++ b/demos/rlRotationConverterDemo/TableView.cpp @@ -64,7 +64,7 @@ TableView::keyPressEvent(QKeyEvent* event) } else if (j != indices.end() && j->column() > i->column()) { - text += " "; + text += "\t"; } } From 63fe7da890ddc2819a60f2abb7d8c7b42b277373 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 21 Mar 2018 18:04:35 +0100 Subject: [PATCH 060/546] Show active input in rlRotationConverterDemo --- demos/rlRotationConverterDemo/CMakeLists.txt | 2 + demos/rlRotationConverterDemo/GroupBox.cpp | 42 ++++ demos/rlRotationConverterDemo/GroupBox.h | 46 ++++ demos/rlRotationConverterDemo/MainWindow.cpp | 223 +++++++++++++++---- demos/rlRotationConverterDemo/MainWindow.h | 34 +++ 5 files changed, 298 insertions(+), 49 deletions(-) create mode 100644 demos/rlRotationConverterDemo/GroupBox.cpp create mode 100644 demos/rlRotationConverterDemo/GroupBox.h diff --git a/demos/rlRotationConverterDemo/CMakeLists.txt b/demos/rlRotationConverterDemo/CMakeLists.txt index a6667687..2b5c84cf 100644 --- a/demos/rlRotationConverterDemo/CMakeLists.txt +++ b/demos/rlRotationConverterDemo/CMakeLists.txt @@ -20,6 +20,7 @@ if(QT_FOUND) HDRS AngleAxisModel.h EulerAnglesModel.h + GroupBox.h MainWindow.h QuaternionModel.h RotationMatrixModel.h @@ -30,6 +31,7 @@ if(QT_FOUND) SRCS AngleAxisModel.cpp EulerAnglesModel.cpp + GroupBox.cpp MainWindow.cpp QuaternionModel.cpp rlRotationConverterDemo.cpp diff --git a/demos/rlRotationConverterDemo/GroupBox.cpp b/demos/rlRotationConverterDemo/GroupBox.cpp new file mode 100644 index 00000000..c183a8ff --- /dev/null +++ b/demos/rlRotationConverterDemo/GroupBox.cpp @@ -0,0 +1,42 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "GroupBox.h" + +GroupBox::GroupBox(QWidget* parent) : + QGroupBox(parent) +{ +} + +GroupBox::~GroupBox() +{ +} + +void +GroupBox::mousePressEvent(QMouseEvent* event) +{ + this->setChecked(!this->isChecked()); +} diff --git a/demos/rlRotationConverterDemo/GroupBox.h b/demos/rlRotationConverterDemo/GroupBox.h new file mode 100644 index 00000000..173ec9c2 --- /dev/null +++ b/demos/rlRotationConverterDemo/GroupBox.h @@ -0,0 +1,46 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 GROUPBOX_H +#define GROUPBOX_H + +#include + +class GroupBox : public QGroupBox +{ +public: + GroupBox(QWidget* parent = nullptr); + + virtual ~GroupBox(); + +protected: + virtual void mousePressEvent(QMouseEvent* event); + +private: + +}; + +#endif // GROUPBOX_H diff --git a/demos/rlRotationConverterDemo/MainWindow.cpp b/demos/rlRotationConverterDemo/MainWindow.cpp index 8bf4eb04..90de56e3 100644 --- a/demos/rlRotationConverterDemo/MainWindow.cpp +++ b/demos/rlRotationConverterDemo/MainWindow.cpp @@ -33,6 +33,7 @@ #include "AngleAxisModel.h" #include "EulerAnglesModel.h" +#include "GroupBox.h" #include "MainWindow.h" #include "QuaternionModel.h" #include "RotationMatrixModel.h" @@ -41,12 +42,20 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QMainWindow(parent, f), inputAngleAxis(0, rl::math::Vector3::UnitZ()), + inputAngleAxisGroupBox(new GroupBox(this)), inputAngleAxisModel(new AngleAxisModel(this)), + inputAngleAxisTableView(new TableView(this)), inputEulerAngles(rl::math::Vector3::Zero()), + inputEulerAnglesGroupBox(new GroupBox(this)), inputEulerAnglesModel(new EulerAnglesModel(this)), + inputEulerAnglesTableView(new TableView(this)), inputEulerAxes(), inputQuaternion(rl::math::Quaternion::Identity()), + inputQuaternionGroupBox(new GroupBox(this)), + inputQuaternionTableView(new TableView(this)), inputRotationMatrix(rl::math::Rotation::Identity()), + inputRotationMatrixGroupBox(new GroupBox(this)), + inputRotationMatrixTableView(new TableView(this)), inputUnitRadians(false), outputAngleAxis(0, rl::math::Vector3::UnitZ()), outputAngleAxisModel(new AngleAxisModel(this)), @@ -167,7 +176,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : // rotation matrix - QGroupBox* inputRotationMatrixGroupBox = new QGroupBox(this); + inputRotationMatrixGroupBox->setCheckable(true); inputRotationMatrixGroupBox->setFlat(true); inputRotationMatrixGroupBox->setTitle("Rotation Matrix (Input)"); gridLayout->addWidget(inputRotationMatrixGroupBox, gridLayout->rowCount(), 0); @@ -175,13 +184,19 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : RotationMatrixModel* inputRotationMatrixModel = new RotationMatrixModel(this); inputRotationMatrixModel->rotation = &this->inputRotationMatrix; - TableView* inputRotationMatrixTableView = new TableView(this); inputRotationMatrixTableView->setModel(inputRotationMatrixModel); inputRotationMatrixTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* inputRotationMatrixLayout = new QVBoxLayout(inputRotationMatrixGroupBox); inputRotationMatrixLayout->addWidget(inputRotationMatrixTableView); + QObject::connect( + inputRotationMatrixGroupBox, + SIGNAL(toggled(bool)), + this, + SLOT(rotationMatrixToggled(bool)) + ); + QObject::connect( inputRotationMatrixModel, SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), @@ -206,7 +221,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : // angle axis - QGroupBox* inputAngleAxisGroupBox = new QGroupBox(this); + inputAngleAxisGroupBox->setCheckable(true); inputAngleAxisGroupBox->setFlat(true); inputAngleAxisGroupBox->setTitle("Angle Axis (Input)"); gridLayout->addWidget(inputAngleAxisGroupBox, gridLayout->rowCount(), 0); @@ -214,13 +229,19 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputAngleAxisModel->angleAxis = &this->inputAngleAxis; inputAngleAxisModel->angleRadians = &this->inputUnitRadians; - TableView* inputAngleAxisTableView = new TableView(this); inputAngleAxisTableView->setModel(inputAngleAxisModel); inputAngleAxisTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* inputAngleAxisLayout = new QVBoxLayout(inputAngleAxisGroupBox); inputAngleAxisLayout->addWidget(inputAngleAxisTableView); + QObject::connect( + inputAngleAxisGroupBox, + SIGNAL(toggled(bool)), + this, + SLOT(angleAxisToggled(bool)) + ); + QObject::connect( inputAngleAxisModel, SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), @@ -246,7 +267,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : // quaternion - QGroupBox* inputQuaternionGroupBox = new QGroupBox(this); + inputQuaternionGroupBox->setCheckable(true); inputQuaternionGroupBox->setFlat(true); inputQuaternionGroupBox->setTitle("Quaternion (Input)"); gridLayout->addWidget(inputQuaternionGroupBox, gridLayout->rowCount(), 0); @@ -254,13 +275,19 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QuaternionModel* inputQuaternionModel = new QuaternionModel(this); inputQuaternionModel->quaternion = &this->inputQuaternion; - TableView* inputQuaternionTableView = new TableView(this); inputQuaternionTableView->setModel(inputQuaternionModel); inputQuaternionTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* inputQuaternionLayout = new QVBoxLayout(inputQuaternionGroupBox); inputQuaternionLayout->addWidget(inputQuaternionTableView); + QObject::connect( + inputQuaternionGroupBox, + SIGNAL(toggled(bool)), + this, + SLOT(quaternionToggled(bool)) + ); + QObject::connect( inputQuaternionModel, SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), @@ -285,7 +312,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : // eulerAngles - QGroupBox* inputEulerAnglesGroupBox = new QGroupBox(this); + inputEulerAnglesGroupBox->setCheckable(true); inputEulerAnglesGroupBox->setFlat(true); inputEulerAnglesGroupBox->setTitle("Euler Angles (Input)"); gridLayout->addWidget(inputEulerAnglesGroupBox, gridLayout->rowCount(), 0); @@ -294,13 +321,19 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputEulerAnglesModel->eulerAnglesRadians = &this->inputUnitRadians; inputEulerAnglesModel->eulerAxes = &this->inputEulerAxes; - TableView* inputEulerAnglesTableView = new TableView(this); inputEulerAnglesTableView->setModel(inputEulerAnglesModel); inputEulerAnglesTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* inputEulerAnglesLayout = new QVBoxLayout(inputEulerAnglesGroupBox); inputEulerAnglesLayout->addWidget(inputEulerAnglesTableView); + QObject::connect( + inputEulerAnglesGroupBox, + SIGNAL(toggled(bool)), + this, + SLOT(eulerAnglesToggled(bool)) + ); + QObject::connect( inputEulerAnglesModel, SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), @@ -324,6 +357,10 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QVBoxLayout* outputEulerAnglesLayout = new QVBoxLayout(outputEulerAnglesGroupBox); outputEulerAnglesLayout->addWidget(outputEulerAnglesTableView); + + inputAngleAxisGroupBox->setChecked(false); + inputQuaternionGroupBox->setChecked(false); + inputEulerAnglesGroupBox->setChecked(false); } MainWindow::~MainWindow() @@ -333,6 +370,58 @@ MainWindow::~MainWindow() void MainWindow::angleAxisChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) +{ + this->fromAngleAxis(); +} + +void +MainWindow::angleAxisToggled(bool on) +{ + if (on) + { + this->inputEulerAnglesGroupBox->setChecked(false); + this->inputEulerAnglesTableView->clearSelection(); + this->inputQuaternionGroupBox->setChecked(false); + this->inputQuaternionTableView->clearSelection(); + this->inputRotationMatrixGroupBox->setChecked(false); + this->inputRotationMatrixTableView->clearSelection(); + + this->fromAngleAxis(); + } + else + { + this->inputAngleAxisTableView->clearSelection(); + } +} + +void +MainWindow::eulerAnglesChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) +{ + this->fromEulerAngles(); +} + +void +MainWindow::eulerAnglesToggled(bool on) +{ + if (on) + { + this->inputAngleAxisGroupBox->setChecked(false); + this->inputAngleAxisTableView->clearSelection(); + this->inputQuaternionGroupBox->setChecked(false); + this->inputQuaternionTableView->clearSelection(); + this->inputRotationMatrixGroupBox->setChecked(false); + this->inputRotationMatrixTableView->clearSelection(); + + this->fromEulerAngles(); + } + else + { + this->inputEulerAnglesTableView->clearSelection(); + } +} + +void +MainWindow::fromAngleAxis() { this->outputAngleAxis = this->inputAngleAxis; this->outputQuaternion = this->inputAngleAxis; @@ -347,7 +436,7 @@ MainWindow::angleAxisChanged(const QModelIndex& topLeft, const QModelIndex& bott } void -MainWindow::eulerAnglesChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) +MainWindow::fromEulerAngles() { this->outputQuaternion = rl::math::AngleAxis( this->inputEulerAngles[0], @@ -371,6 +460,36 @@ MainWindow::eulerAnglesChanged(const QModelIndex& topLeft, const QModelIndex& bo this->outputRotationMatrixModel->invalidate(); } +void +MainWindow::fromQuaternion() +{ + this->outputAngleAxis = this->inputQuaternion; + this->outputQuaternion = this->inputQuaternion; + this->outputRotationMatrix = this->inputQuaternion; + + this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); + + this->outputAngleAxisModel->invalidate(); + this->outputEulerAnglesModel->invalidate(); + this->outputQuaternionModel->invalidate(); + this->outputRotationMatrixModel->invalidate(); +} + +void +MainWindow::fromRotationMatrix() +{ + this->outputAngleAxis = this->inputRotationMatrix; + this->outputQuaternion = this->inputRotationMatrix; + this->outputRotationMatrix = this->inputRotationMatrix; + + this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); + + this->outputAngleAxisModel->invalidate(); + this->outputEulerAnglesModel->invalidate(); + this->outputQuaternionModel->invalidate(); + this->outputRotationMatrixModel->invalidate(); +} + void MainWindow::inputEulerAxesChanged(int index) { @@ -386,26 +505,10 @@ MainWindow::inputEulerAxesChanged(int index) this->inputEulerAnglesModel->invalidate(); - this->outputQuaternion = rl::math::AngleAxis( - this->inputEulerAngles[0], - rl::math::Vector3::Unit(this->inputEulerAxes[0]) - ) * rl::math::AngleAxis( - this->inputEulerAngles[1], - rl::math::Vector3::Unit(this->inputEulerAxes[1]) - ) * rl::math::AngleAxis( - this->inputEulerAngles[2], - rl::math::Vector3::Unit(this->inputEulerAxes[2]) - ); - - this->outputAngleAxis = this->outputQuaternion; - this->outputRotationMatrix = this->outputQuaternion; - - this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); - - this->outputAngleAxisModel->invalidate(); - this->outputEulerAnglesModel->invalidate(); - this->outputQuaternionModel->invalidate(); - this->outputRotationMatrixModel->invalidate(); + if (this->inputEulerAnglesGroupBox->isChecked()) + { + this->fromEulerAngles(); + } } void @@ -488,31 +591,53 @@ MainWindow::outputUnitChanged(int index) void MainWindow::quaternionChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) { - this->outputAngleAxis = this->inputQuaternion; - this->outputQuaternion = this->inputQuaternion; - this->outputRotationMatrix = this->inputQuaternion; - - this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); - - this->outputAngleAxisModel->invalidate(); - this->outputEulerAnglesModel->invalidate(); - this->outputQuaternionModel->invalidate(); - this->outputRotationMatrixModel->invalidate(); + this->fromQuaternion(); +} + +void +MainWindow::quaternionToggled(bool on) +{ + if (on) + { + this->inputAngleAxisGroupBox->setChecked(false); + this->inputAngleAxisTableView->clearSelection(); + this->inputEulerAnglesGroupBox->setChecked(false); + this->inputEulerAnglesTableView->clearSelection(); + this->inputRotationMatrixGroupBox->setChecked(false); + this->inputRotationMatrixTableView->clearSelection(); + + this->fromQuaternion(); + } + else + { + this->inputQuaternionTableView->clearSelection(); + } } void MainWindow::rotationMatrixChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight) { - this->outputAngleAxis = this->inputRotationMatrix; - this->outputQuaternion = this->inputRotationMatrix; - this->outputRotationMatrix = this->inputRotationMatrix; - - this->outputEulerAngles = this->outputRotationMatrix.eulerAngles(this->outputEulerAxes[0], this->outputEulerAxes[1], this->outputEulerAxes[2]); - - this->outputAngleAxisModel->invalidate(); - this->outputEulerAnglesModel->invalidate(); - this->outputQuaternionModel->invalidate(); - this->outputRotationMatrixModel->invalidate(); + this->fromRotationMatrix(); +} + +void +MainWindow::rotationMatrixToggled(bool on) +{ + if (on) + { + this->inputAngleAxisGroupBox->setChecked(false); + this->inputAngleAxisTableView->clearSelection(); + this->inputEulerAnglesGroupBox->setChecked(false); + this->inputEulerAnglesTableView->clearSelection(); + this->inputQuaternionGroupBox->setChecked(false); + this->inputQuaternionTableView->clearSelection(); + + this->fromRotationMatrix(); + } + else + { + this->inputRotationMatrixTableView->clearSelection(); + } } std::size_t MainWindow::EULER_ANGLES[12][3] = { diff --git a/demos/rlRotationConverterDemo/MainWindow.h b/demos/rlRotationConverterDemo/MainWindow.h index ceb6902f..cbe53fae 100644 --- a/demos/rlRotationConverterDemo/MainWindow.h +++ b/demos/rlRotationConverterDemo/MainWindow.h @@ -36,8 +36,10 @@ class AngleAxisModel; class EulerAnglesModel; +class GroupBox; class QuaternionModel; class RotationMatrixModel; +class TableView; class MainWindow : public QMainWindow { @@ -51,8 +53,12 @@ class MainWindow : public QMainWindow public slots: void angleAxisChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void angleAxisToggled(bool on); + void eulerAnglesChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void eulerAnglesToggled(bool on); + void inputEulerAxesChanged(int index); void inputUnitChanged(int index); @@ -63,28 +69,56 @@ public slots: void quaternionChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void quaternionToggled(bool on); + void rotationMatrixChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); + void rotationMatrixToggled(bool on); + protected: MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); private: + void fromAngleAxis(); + + void fromEulerAngles(); + + void fromQuaternion(); + + void fromRotationMatrix(); + static std::size_t EULER_ANGLES[12][3]; rl::math::AngleAxis inputAngleAxis; + GroupBox* inputAngleAxisGroupBox; + AngleAxisModel* inputAngleAxisModel; + TableView* inputAngleAxisTableView; + rl::math::Vector3 inputEulerAngles; + GroupBox* inputEulerAnglesGroupBox; + EulerAnglesModel* inputEulerAnglesModel; + TableView* inputEulerAnglesTableView; + std::array inputEulerAxes; rl::math::Quaternion inputQuaternion; + GroupBox* inputQuaternionGroupBox; + + TableView* inputQuaternionTableView; + rl::math::Rotation inputRotationMatrix; + GroupBox* inputRotationMatrixGroupBox; + + TableView* inputRotationMatrixTableView; + bool inputUnitRadians; rl::math::AngleAxis outputAngleAxis; From 32eaa0831a282fa40939b1cd829dbcde5a1e5ca6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 21 Mar 2018 18:46:16 +0100 Subject: [PATCH 061/546] Add paste functionality to rlRotationConverterDemo --- demos/rlRotationConverterDemo/TableView.cpp | 42 ++++++++++++++------- 1 file changed, 28 insertions(+), 14 deletions(-) diff --git a/demos/rlRotationConverterDemo/TableView.cpp b/demos/rlRotationConverterDemo/TableView.cpp index 2cda4295..4f39ad9e 100644 --- a/demos/rlRotationConverterDemo/TableView.cpp +++ b/demos/rlRotationConverterDemo/TableView.cpp @@ -44,32 +44,46 @@ TableView::~TableView() void TableView::keyPressEvent(QKeyEvent* event) { - if (event->matches(QKeySequence::Copy)) + if (event->matches(QKeySequence::Copy) && this->selectionModel()->hasSelection()) { QString text; - QModelIndexList indices = this->selectedIndexes(); - qSort(indices); + QItemSelectionRange range = this->selectionModel()->selection().first(); - QModelIndexList::iterator i = indices.begin(); - QModelIndexList::iterator j = ++indices.begin(); - - for (; i != indices.end(); ++i, ++j) + for (int i = range.top(); i <= range.bottom(); ++i) { - text += i->data().toString(); + QStringList rowContents; - if (j != indices.end() && j->row() > i->row()) - { - text += "\n"; - } - else if (j != indices.end() && j->column() > i->column()) + for (int j = range.left(); j <= range.right(); ++j) { - text += "\t"; + rowContents << this->model()->index(i, j).data().toString(); } + + text += rowContents.join("\t"); + text += "\n"; } QApplication::clipboard()->setText(text); } + else if (event->matches(QKeySequence::Paste) && this->selectionModel()->hasSelection() && QAbstractItemView::NoEditTriggers != this->editTriggers()) + { + QString text = QApplication::clipboard()->text(); + + QStringList rowContents = text.split("\n", QString::SkipEmptyParts); + + QModelIndex first = this->selectedIndexes().first(); + QItemSelectionRange range = this->selectionModel()->selection().first(); + + for (int i = 0; i < std::min(rowContents.size(), range.height()); ++i) + { + QStringList columnContents = rowContents.at(i).split("\t"); + + for (int j = 0; j < std::min(columnContents.size(), range.width()); ++j) + { + this->model()->setData(this->model()->index(first.row() + i, first.column() + j), columnContents[j]); + } + } + } QTableView::keyPressEvent(event); } From d3b231f7d25ffc09186a9a69a10b602f593d7ae7 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 21 Mar 2018 19:30:14 +0100 Subject: [PATCH 062/546] Fix input focus in rlRotationConverterDemo --- demos/rlRotationConverterDemo/MainWindow.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/demos/rlRotationConverterDemo/MainWindow.cpp b/demos/rlRotationConverterDemo/MainWindow.cpp index 90de56e3..3b666851 100644 --- a/demos/rlRotationConverterDemo/MainWindow.cpp +++ b/demos/rlRotationConverterDemo/MainWindow.cpp @@ -379,6 +379,7 @@ MainWindow::angleAxisToggled(bool on) { if (on) { + this->inputAngleAxisTableView->setFocus(); this->inputEulerAnglesGroupBox->setChecked(false); this->inputEulerAnglesTableView->clearSelection(); this->inputQuaternionGroupBox->setChecked(false); @@ -407,6 +408,7 @@ MainWindow::eulerAnglesToggled(bool on) { this->inputAngleAxisGroupBox->setChecked(false); this->inputAngleAxisTableView->clearSelection(); + this->inputEulerAnglesTableView->setFocus(); this->inputQuaternionGroupBox->setChecked(false); this->inputQuaternionTableView->clearSelection(); this->inputRotationMatrixGroupBox->setChecked(false); @@ -603,6 +605,7 @@ MainWindow::quaternionToggled(bool on) this->inputAngleAxisTableView->clearSelection(); this->inputEulerAnglesGroupBox->setChecked(false); this->inputEulerAnglesTableView->clearSelection(); + this->inputQuaternionTableView->setFocus(); this->inputRotationMatrixGroupBox->setChecked(false); this->inputRotationMatrixTableView->clearSelection(); @@ -631,6 +634,7 @@ MainWindow::rotationMatrixToggled(bool on) this->inputEulerAnglesTableView->clearSelection(); this->inputQuaternionGroupBox->setChecked(false); this->inputQuaternionTableView->clearSelection(); + this->inputRotationMatrixTableView->setFocus(); this->fromRotationMatrix(); } From d27451c590c730eb3ffbc625e6b3bd053b70cd65 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 23 Mar 2018 23:38:56 +0100 Subject: [PATCH 063/546] Add precision setting to rlRotationConverterDemo --- demos/rlRotationConverterDemo/CMakeLists.txt | 2 + demos/rlRotationConverterDemo/Delegate.cpp | 56 ++++++++++++++ demos/rlRotationConverterDemo/Delegate.h | 53 +++++++++++++ demos/rlRotationConverterDemo/MainWindow.cpp | 78 +++++++++++++++++++- demos/rlRotationConverterDemo/MainWindow.h | 12 +++ demos/rlRotationConverterDemo/TableView.cpp | 5 +- demos/rlRotationConverterDemo/TableView.h | 2 + 7 files changed, 204 insertions(+), 4 deletions(-) create mode 100644 demos/rlRotationConverterDemo/Delegate.cpp create mode 100644 demos/rlRotationConverterDemo/Delegate.h diff --git a/demos/rlRotationConverterDemo/CMakeLists.txt b/demos/rlRotationConverterDemo/CMakeLists.txt index 2b5c84cf..1f8bdb25 100644 --- a/demos/rlRotationConverterDemo/CMakeLists.txt +++ b/demos/rlRotationConverterDemo/CMakeLists.txt @@ -19,6 +19,7 @@ if(QT_FOUND) set( HDRS AngleAxisModel.h + Delegate.h EulerAnglesModel.h GroupBox.h MainWindow.h @@ -30,6 +31,7 @@ if(QT_FOUND) set( SRCS AngleAxisModel.cpp + Delegate.cpp EulerAnglesModel.cpp GroupBox.cpp MainWindow.cpp diff --git a/demos/rlRotationConverterDemo/Delegate.cpp b/demos/rlRotationConverterDemo/Delegate.cpp new file mode 100644 index 00000000..7ae58ac6 --- /dev/null +++ b/demos/rlRotationConverterDemo/Delegate.cpp @@ -0,0 +1,56 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Delegate.h" + +Delegate::Delegate(QObject* parent) : + QStyledItemDelegate(parent), + precision(nullptr) +{ +} + +Delegate::~Delegate() +{ +} + +QWidget* +Delegate::createEditor(QWidget* parent, const QStyleOptionViewItem& option, const QModelIndex& index) const +{ + QDoubleSpinBox* editor = new QDoubleSpinBox(parent); + editor->setDecimals(std::numeric_limits::digits10); + editor->setMaximum(std::numeric_limits::max()); + editor->setMinimum(-std::numeric_limits::max()); + return editor; +} + +QString +Delegate::displayText(const QVariant& value, const QLocale& locale) const +{ + return QString::number(value.toDouble(), 'g', nullptr != this->precision ? *this->precision : 8); +} diff --git a/demos/rlRotationConverterDemo/Delegate.h b/demos/rlRotationConverterDemo/Delegate.h new file mode 100644 index 00000000..27391130 --- /dev/null +++ b/demos/rlRotationConverterDemo/Delegate.h @@ -0,0 +1,53 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 DELEGATE_H +#define DELEGATE_H + +#include + +class Delegate : public QStyledItemDelegate +{ + Q_OBJECT + +public: + Delegate(QObject* parent = nullptr); + + virtual ~Delegate(); + + QWidget* createEditor(QWidget* parent, const QStyleOptionViewItem& option, const QModelIndex& index) const; + + virtual QString displayText(const QVariant& value, const QLocale& locale) const; + + int* precision; + +protected: + +private: + +}; + +#endif // DELEGATE_H diff --git a/demos/rlRotationConverterDemo/MainWindow.cpp b/demos/rlRotationConverterDemo/MainWindow.cpp index 3b666851..6e964127 100644 --- a/demos/rlRotationConverterDemo/MainWindow.cpp +++ b/demos/rlRotationConverterDemo/MainWindow.cpp @@ -29,9 +29,11 @@ #include #include #include +#include #include #include "AngleAxisModel.h" +#include "Delegate.h" #include "EulerAnglesModel.h" #include "GroupBox.h" #include "MainWindow.h" @@ -50,11 +52,14 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputEulerAnglesModel(new EulerAnglesModel(this)), inputEulerAnglesTableView(new TableView(this)), inputEulerAxes(), + inputPrecision(8), inputQuaternion(rl::math::Quaternion::Identity()), inputQuaternionGroupBox(new GroupBox(this)), + inputQuaternionModel(new QuaternionModel(this)), inputQuaternionTableView(new TableView(this)), inputRotationMatrix(rl::math::Rotation::Identity()), inputRotationMatrixGroupBox(new GroupBox(this)), + inputRotationMatrixModel(new RotationMatrixModel(this)), inputRotationMatrixTableView(new TableView(this)), inputUnitRadians(false), outputAngleAxis(0, rl::math::Vector3::UnitZ()), @@ -62,6 +67,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputEulerAngles(rl::math::Vector3::Zero()), outputEulerAnglesModel(new EulerAnglesModel(this)), outputEulerAxes(), + outputPrecision(8), outputQuaternion(rl::math::Quaternion::Identity()), outputQuaternionModel(new QuaternionModel(this)), outputRotationMatrix(rl::math::Rotation::Identity()), @@ -83,6 +89,12 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QGridLayout* gridLayout = new QGridLayout(centralWidget); + Delegate* inputDelegate = new Delegate(this); + inputDelegate->precision = &this->inputPrecision; + + Delegate* outputDelegate = new Delegate(this); + outputDelegate->precision = &this->outputPrecision; + // settings QGroupBox* inputSettingsGroupBox = new QGroupBox(this); @@ -96,9 +108,15 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QComboBox* inputEulerAxesComboBox = new QComboBox(this); + QSpinBox* inputPrecisionSpinBox = new QSpinBox(this); + inputPrecisionSpinBox->setMaximum(std::numeric_limits::digits10); + inputPrecisionSpinBox->setSuffix(" Digits"); + inputPrecisionSpinBox->setValue(this->inputPrecision); + QHBoxLayout* inputSettingsLayout = new QHBoxLayout(inputSettingsGroupBox); inputSettingsLayout->addWidget(inputUnitComboBox); inputSettingsLayout->addWidget(inputEulerAxesComboBox); + inputSettingsLayout->addWidget(inputPrecisionSpinBox); QObject::connect( inputUnitComboBox, @@ -114,6 +132,13 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SLOT(inputEulerAxesChanged(int)) ); + QObject::connect( + inputPrecisionSpinBox, + SIGNAL(valueChanged(int)), + this, + SLOT(inputPrecisionChanged(int)) + ); + QGroupBox* outputSettingsGroupBox = new QGroupBox(this); outputSettingsGroupBox->setFlat(true); outputSettingsGroupBox->setTitle("Settings (Output)"); @@ -125,9 +150,15 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QComboBox* outputEulerAxesComboBox = new QComboBox(this); + QSpinBox* outputPrecisionSpinBox = new QSpinBox(this); + outputPrecisionSpinBox->setMaximum(std::numeric_limits::digits10); + outputPrecisionSpinBox->setSuffix(" Digits"); + outputPrecisionSpinBox->setValue(this->outputPrecision); + QHBoxLayout* outputSettingsLayout = new QHBoxLayout(outputSettingsGroupBox); outputSettingsLayout->addWidget(outputUnitComboBox); outputSettingsLayout->addWidget(outputEulerAxesComboBox); + outputSettingsLayout->addWidget(outputPrecisionSpinBox); QObject::connect( outputUnitComboBox, @@ -143,6 +174,13 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SLOT(outputEulerAxesChanged(int)) ); + QObject::connect( + outputPrecisionSpinBox, + SIGNAL(valueChanged(int)), + this, + SLOT(outputPrecisionChanged(int)) + ); + for (std::size_t i = 0; i < 12; ++i) { QString text = "Euler "; @@ -181,9 +219,10 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputRotationMatrixGroupBox->setTitle("Rotation Matrix (Input)"); gridLayout->addWidget(inputRotationMatrixGroupBox, gridLayout->rowCount(), 0); - RotationMatrixModel* inputRotationMatrixModel = new RotationMatrixModel(this); inputRotationMatrixModel->rotation = &this->inputRotationMatrix; + inputRotationMatrixTableView->precision = &this->inputPrecision; + inputRotationMatrixTableView->setItemDelegate(inputDelegate); inputRotationMatrixTableView->setModel(inputRotationMatrixModel); inputRotationMatrixTableView->verticalHeader()->setMinimumWidth(20); @@ -212,7 +251,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputRotationMatrixModel->rotation = &this->outputRotationMatrix; TableView* outputRotationMatrixTableView = new TableView(this); + outputRotationMatrixTableView->precision = &this->outputPrecision; outputRotationMatrixTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); + outputRotationMatrixTableView->setItemDelegate(outputDelegate); outputRotationMatrixTableView->setModel(outputRotationMatrixModel); outputRotationMatrixTableView->verticalHeader()->setMinimumWidth(20); @@ -229,6 +270,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputAngleAxisModel->angleAxis = &this->inputAngleAxis; inputAngleAxisModel->angleRadians = &this->inputUnitRadians; + inputAngleAxisTableView->precision = &this->inputPrecision; + inputAngleAxisTableView->setItemDelegate(inputDelegate); inputAngleAxisTableView->setModel(inputAngleAxisModel); inputAngleAxisTableView->verticalHeader()->setMinimumWidth(20); @@ -258,7 +301,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputAngleAxisModel->angleRadians = &this->outputUnitRadians; TableView* outputAngleAxisTableView = new TableView(this); + outputAngleAxisTableView->precision = &this->outputPrecision; outputAngleAxisTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); + outputAngleAxisTableView->setItemDelegate(outputDelegate); outputAngleAxisTableView->setModel(outputAngleAxisModel); outputAngleAxisTableView->verticalHeader()->setMinimumWidth(20); @@ -272,9 +317,10 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputQuaternionGroupBox->setTitle("Quaternion (Input)"); gridLayout->addWidget(inputQuaternionGroupBox, gridLayout->rowCount(), 0); - QuaternionModel* inputQuaternionModel = new QuaternionModel(this); inputQuaternionModel->quaternion = &this->inputQuaternion; + inputQuaternionTableView->precision = &this->inputPrecision; + inputQuaternionTableView->setItemDelegate(inputDelegate); inputQuaternionTableView->setModel(inputQuaternionModel); inputQuaternionTableView->verticalHeader()->setMinimumWidth(20); @@ -303,7 +349,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputQuaternionModel->quaternion = &this->outputQuaternion; TableView* outputQuaternionTableView = new TableView(this); + outputQuaternionTableView->precision = &this->outputPrecision; outputQuaternionTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); + outputQuaternionTableView->setItemDelegate(outputDelegate); outputQuaternionTableView->setModel(outputQuaternionModel); outputQuaternionTableView->verticalHeader()->setMinimumWidth(20); @@ -321,6 +369,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputEulerAnglesModel->eulerAnglesRadians = &this->inputUnitRadians; inputEulerAnglesModel->eulerAxes = &this->inputEulerAxes; + inputEulerAnglesTableView->precision = &this->inputPrecision; + inputEulerAnglesTableView->setItemDelegate(inputDelegate); inputEulerAnglesTableView->setModel(inputEulerAnglesModel); inputEulerAnglesTableView->verticalHeader()->setMinimumWidth(20); @@ -351,7 +401,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputEulerAnglesModel->eulerAxes = &this->outputEulerAxes; TableView* outputEulerAnglesTableView = new TableView(this); + outputEulerAnglesTableView->precision = &this->outputPrecision; outputEulerAnglesTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); + outputEulerAnglesTableView->setItemDelegate(outputDelegate); outputEulerAnglesTableView->setModel(outputEulerAnglesModel); outputEulerAnglesTableView->verticalHeader()->setMinimumWidth(20); @@ -513,6 +565,17 @@ MainWindow::inputEulerAxesChanged(int index) } } +void +MainWindow::inputPrecisionChanged(int precision) +{ + this->inputPrecision = precision; + + this->inputAngleAxisModel->invalidate(); + this->inputEulerAnglesModel->invalidate(); + this->inputQuaternionModel->invalidate(); + this->inputRotationMatrixModel->invalidate(); +} + void MainWindow::inputUnitChanged(int index) { @@ -566,6 +629,17 @@ MainWindow::outputEulerAxesChanged(int index) this->outputEulerAnglesModel->invalidate(); } +void +MainWindow::outputPrecisionChanged(int precision) +{ + this->outputPrecision = precision; + + this->outputAngleAxisModel->invalidate(); + this->outputEulerAnglesModel->invalidate(); + this->outputQuaternionModel->invalidate(); + this->outputRotationMatrixModel->invalidate(); +} + void MainWindow::outputUnitChanged(int index) { diff --git a/demos/rlRotationConverterDemo/MainWindow.h b/demos/rlRotationConverterDemo/MainWindow.h index cbe53fae..5ee6cebd 100644 --- a/demos/rlRotationConverterDemo/MainWindow.h +++ b/demos/rlRotationConverterDemo/MainWindow.h @@ -61,10 +61,14 @@ public slots: void inputEulerAxesChanged(int index); + void inputPrecisionChanged(int precision); + void inputUnitChanged(int index); void outputEulerAxesChanged(int index); + void outputPrecisionChanged(int precision); + void outputUnitChanged(int index); void quaternionChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); @@ -107,16 +111,22 @@ public slots: std::array inputEulerAxes; + int inputPrecision; + rl::math::Quaternion inputQuaternion; GroupBox* inputQuaternionGroupBox; + QuaternionModel* inputQuaternionModel; + TableView* inputQuaternionTableView; rl::math::Rotation inputRotationMatrix; GroupBox* inputRotationMatrixGroupBox; + RotationMatrixModel* inputRotationMatrixModel; + TableView* inputRotationMatrixTableView; bool inputUnitRadians; @@ -131,6 +141,8 @@ public slots: std::array outputEulerAxes; + int outputPrecision; + rl::math::Quaternion outputQuaternion; QuaternionModel* outputQuaternionModel; diff --git a/demos/rlRotationConverterDemo/TableView.cpp b/demos/rlRotationConverterDemo/TableView.cpp index 4f39ad9e..1da65b08 100644 --- a/demos/rlRotationConverterDemo/TableView.cpp +++ b/demos/rlRotationConverterDemo/TableView.cpp @@ -33,7 +33,8 @@ #include "TableView.h" TableView::TableView(QWidget* parent) : - QTableView(parent) + QTableView(parent), + precision(nullptr) { } @@ -56,7 +57,7 @@ TableView::keyPressEvent(QKeyEvent* event) for (int j = range.left(); j <= range.right(); ++j) { - rowContents << this->model()->index(i, j).data().toString(); + rowContents << QString::number(this->model()->index(i, j).data().toDouble(), 'g', nullptr != this->precision ? *this->precision : 8); } text += rowContents.join("\t"); diff --git a/demos/rlRotationConverterDemo/TableView.h b/demos/rlRotationConverterDemo/TableView.h index 51cf693b..a66ef012 100644 --- a/demos/rlRotationConverterDemo/TableView.h +++ b/demos/rlRotationConverterDemo/TableView.h @@ -40,6 +40,8 @@ class TableView : public QTableView virtual QSize sizeHint() const; + int* precision; + protected: virtual void keyPressEvent(QKeyEvent* event); From 609f6d9bfa9a6d5d71d8032117029ed577b900a2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 23 Mar 2018 23:39:14 +0100 Subject: [PATCH 064/546] Update copy and paste behavior in rlRotationConverterDemo --- demos/rlRotationConverterDemo/TableView.cpp | 19 ++++++++++++++----- 1 file changed, 14 insertions(+), 5 deletions(-) diff --git a/demos/rlRotationConverterDemo/TableView.cpp b/demos/rlRotationConverterDemo/TableView.cpp index 1da65b08..ddba8c4f 100644 --- a/demos/rlRotationConverterDemo/TableView.cpp +++ b/demos/rlRotationConverterDemo/TableView.cpp @@ -45,10 +45,15 @@ TableView::~TableView() void TableView::keyPressEvent(QKeyEvent* event) { - if (event->matches(QKeySequence::Copy) && this->selectionModel()->hasSelection()) + if (event->matches(QKeySequence::Copy)) { QString text; + if (!this->selectionModel()->hasSelection()) + { + this->selectAll(); + } + QItemSelectionRange range = this->selectionModel()->selection().first(); for (int i = range.top(); i <= range.bottom(); ++i) @@ -66,20 +71,24 @@ TableView::keyPressEvent(QKeyEvent* event) QApplication::clipboard()->setText(text); } - else if (event->matches(QKeySequence::Paste) && this->selectionModel()->hasSelection() && QAbstractItemView::NoEditTriggers != this->editTriggers()) + else if (event->matches(QKeySequence::Paste) && QAbstractItemView::NoEditTriggers != this->editTriggers()) { QString text = QApplication::clipboard()->text(); QStringList rowContents = text.split("\n", QString::SkipEmptyParts); + if (!this->selectionModel()->hasSelection()) + { + this->selectAll(); + } + QModelIndex first = this->selectedIndexes().first(); - QItemSelectionRange range = this->selectionModel()->selection().first(); - for (int i = 0; i < std::min(rowContents.size(), range.height()); ++i) + for (int i = 0; i < rowContents.size(); ++i) { QStringList columnContents = rowContents.at(i).split("\t"); - for (int j = 0; j < std::min(columnContents.size(), range.width()); ++j) + for (int j = 0; j < columnContents.size(); ++j) { this->model()->setData(this->model()->index(first.row() + i, first.column() + j), columnContents[j]); } From e4304b4506de162714d629e49a9b28b230f720bd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 4 Apr 2018 17:02:39 +0200 Subject: [PATCH 065/546] Add radius query to rl::plan::NearestNeighbors --- src/rl/plan/GnatNearestNeighbors.cpp | 6 ++++++ src/rl/plan/GnatNearestNeighbors.h | 2 ++ src/rl/plan/KdtreeBoundingBoxNearestNeighbors.cpp | 6 ++++++ src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h | 2 ++ src/rl/plan/KdtreeNearestNeighbors.cpp | 6 ++++++ src/rl/plan/KdtreeNearestNeighbors.h | 2 ++ src/rl/plan/LinearNearestNeighbors.cpp | 6 ++++++ src/rl/plan/LinearNearestNeighbors.h | 2 ++ src/rl/plan/NearestNeighbors.h | 2 ++ 9 files changed, 34 insertions(+) diff --git a/src/rl/plan/GnatNearestNeighbors.cpp b/src/rl/plan/GnatNearestNeighbors.cpp index 47f065a2..9654f618 100644 --- a/src/rl/plan/GnatNearestNeighbors.cpp +++ b/src/rl/plan/GnatNearestNeighbors.cpp @@ -95,6 +95,12 @@ namespace rl this->container.push(value); } + ::std::vector + GnatNearestNeighbors::radius(const NearestNeighbors::Value& query, const Distance& radius, const bool& sorted) const + { + return this->container.radius(query, radius, sorted); + } + void GnatNearestNeighbors::seed(const ::std::mt19937::result_type& value) { diff --git a/src/rl/plan/GnatNearestNeighbors.h b/src/rl/plan/GnatNearestNeighbors.h index b0db1421..d4c54146 100644 --- a/src/rl/plan/GnatNearestNeighbors.h +++ b/src/rl/plan/GnatNearestNeighbors.h @@ -62,6 +62,8 @@ namespace rl void push(const NearestNeighbors::Value& value); + ::std::vector radius(const Value& query, const Distance& radius, const bool& sorted = true) const; + void seed(const ::std::mt19937::result_type& value); void setChecks(const ::boost::optional< ::std::size_t>& checks); diff --git a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.cpp b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.cpp index ec9cf0de..48e6c56b 100644 --- a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.cpp +++ b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.cpp @@ -77,6 +77,12 @@ namespace rl this->container.push(value); } + ::std::vector + KdtreeBoundingBoxNearestNeighbors::radius(const NearestNeighbors::Value& query, const Distance& radius, const bool& sorted) const + { + return this->container.radius(query, radius, sorted); + } + void KdtreeBoundingBoxNearestNeighbors::setChecks(const ::boost::optional< ::std::size_t>& checks) { diff --git a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h index 5287253d..abdad1ca 100644 --- a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h @@ -56,6 +56,8 @@ namespace rl void push(const NearestNeighbors::Value& value); + ::std::vector radius(const Value& query, const Distance& radius, const bool& sorted = true) const; + void setChecks(const ::boost::optional< ::std::size_t>& checks); void setNodeDataMax(const ::std::size_t& nodeDataMax); diff --git a/src/rl/plan/KdtreeNearestNeighbors.cpp b/src/rl/plan/KdtreeNearestNeighbors.cpp index 6fdb86b5..4dedb16a 100644 --- a/src/rl/plan/KdtreeNearestNeighbors.cpp +++ b/src/rl/plan/KdtreeNearestNeighbors.cpp @@ -77,6 +77,12 @@ namespace rl this->container.push(value); } + ::std::vector + KdtreeNearestNeighbors::radius(const NearestNeighbors::Value& query, const Distance& radius, const bool& sorted) const + { + return this->container.radius(query, radius, sorted); + } + void KdtreeNearestNeighbors::setChecks(const ::boost::optional< ::std::size_t>& checks) { diff --git a/src/rl/plan/KdtreeNearestNeighbors.h b/src/rl/plan/KdtreeNearestNeighbors.h index 5a360bfa..efc8eef2 100644 --- a/src/rl/plan/KdtreeNearestNeighbors.h +++ b/src/rl/plan/KdtreeNearestNeighbors.h @@ -56,6 +56,8 @@ namespace rl void push(const NearestNeighbors::Value& value); + ::std::vector radius(const Value& query, const Distance& radius, const bool& sorted = true) const; + void setChecks(const ::boost::optional< ::std::size_t>& checks); void setSamples(const ::std::size_t& samples); diff --git a/src/rl/plan/LinearNearestNeighbors.cpp b/src/rl/plan/LinearNearestNeighbors.cpp index 5f3ce034..cf2636ba 100644 --- a/src/rl/plan/LinearNearestNeighbors.cpp +++ b/src/rl/plan/LinearNearestNeighbors.cpp @@ -65,6 +65,12 @@ namespace rl this->container.push(value); } + ::std::vector + LinearNearestNeighbors::radius(const NearestNeighbors::Value& query, const Distance& radius, const bool& sorted) const + { + return this->container.radius(query, radius, sorted); + } + ::std::size_t LinearNearestNeighbors::size() const { diff --git a/src/rl/plan/LinearNearestNeighbors.h b/src/rl/plan/LinearNearestNeighbors.h index 3bb6b37b..7d2c9833 100644 --- a/src/rl/plan/LinearNearestNeighbors.h +++ b/src/rl/plan/LinearNearestNeighbors.h @@ -50,6 +50,8 @@ namespace rl ::std::vector nearest(const NearestNeighbors::Value& query, const ::std::size_t& k, const bool& sorted = true) const; + ::std::vector radius(const Value& query, const Distance& radius, const bool& sorted = true) const; + void push(const NearestNeighbors::Value& value); ::std::size_t size() const; diff --git a/src/rl/plan/NearestNeighbors.h b/src/rl/plan/NearestNeighbors.h index 373bdd42..dfac3bd5 100644 --- a/src/rl/plan/NearestNeighbors.h +++ b/src/rl/plan/NearestNeighbors.h @@ -61,6 +61,8 @@ namespace rl virtual void push(const Value& value) = 0; + virtual ::std::vector radius(const Value& query, const Distance& radius, const bool& sorted = true) const = 0; + virtual ::std::size_t size() const = 0; protected: From aba05aa26f05e06808b6b3dc0ebedf7955a6b11e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 10 Apr 2018 21:44:03 +0200 Subject: [PATCH 066/546] Use QMessageBox for WIN32 demos --- demos/rlCoachKin/rlCoachKin.cpp | 10 +++++----- demos/rlCoachMdl/rlCoachMdl.cpp | 9 +++++---- .../rlRotationConverterDemo.cpp | 5 +++-- demos/rlSimulator/rlSimulator.cpp | 11 +++++------ 4 files changed, 18 insertions(+), 17 deletions(-) diff --git a/demos/rlCoachKin/rlCoachKin.cpp b/demos/rlCoachKin/rlCoachKin.cpp index 380ce0f2..430eea10 100644 --- a/demos/rlCoachKin/rlCoachKin.cpp +++ b/demos/rlCoachKin/rlCoachKin.cpp @@ -24,8 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include #include +#include #include #include "MainWindow.h" @@ -35,16 +35,16 @@ MainWindow* MainWindow::singleton = nullptr; int main(int argc, char** argv) { + QApplication application(argc, argv); + if (argc < 3) { - std::cout << "Usage: rlCoachKin SCENEFILE KINEMATICSFILE1 ... KINEMATICSFILEn" << std::endl; + QMessageBox::information(nullptr, "Usage", "rlCoachKin SCENEFILE KINEMATICSFILE1 ... KINEMATICSFILEn"); return EXIT_FAILURE; } try { - QApplication application(argc, argv); - QObject::connect(&application, SIGNAL(lastWindowClosed()), &application, SLOT(quit())); MainWindow::instance()->show(); @@ -53,7 +53,7 @@ main(int argc, char** argv) } catch (const std::exception& e) { - std::cerr << e.what() << std::endl; + QMessageBox::critical(nullptr, "Error", e.what()); return EXIT_FAILURE; } } diff --git a/demos/rlCoachMdl/rlCoachMdl.cpp b/demos/rlCoachMdl/rlCoachMdl.cpp index 34dd0519..45be1807 100644 --- a/demos/rlCoachMdl/rlCoachMdl.cpp +++ b/demos/rlCoachMdl/rlCoachMdl.cpp @@ -24,8 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include #include +#include #include #include "MainWindow.h" @@ -35,15 +35,16 @@ MainWindow* MainWindow::singleton = nullptr; int main(int argc, char** argv) { + QApplication application(argc, argv); + if (argc < 3) { - std::cout << "Usage: rlCoachMdl SCENEFILE MODELFILE1 ... MODELFILEn" << std::endl; + QMessageBox::information(nullptr, "Usage", "rlCoachMdl SCENEFILE MODELFILE1 ... MODELFILEn"); return EXIT_FAILURE; } try { - QApplication application(argc, argv); application.setStyleSheet("\ QStatusBar QComboBox { background: transparent; border: none; }\ QStatusBar QComboBox::drop-down { border: none; }\ @@ -58,7 +59,7 @@ main(int argc, char** argv) } catch (const std::exception& e) { - std::cerr << e.what() << std::endl; + QMessageBox::critical(nullptr, "Error", e.what()); return EXIT_FAILURE; } } diff --git a/demos/rlRotationConverterDemo/rlRotationConverterDemo.cpp b/demos/rlRotationConverterDemo/rlRotationConverterDemo.cpp index 0e0a08cd..1e679706 100644 --- a/demos/rlRotationConverterDemo/rlRotationConverterDemo.cpp +++ b/demos/rlRotationConverterDemo/rlRotationConverterDemo.cpp @@ -24,8 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include #include +#include #include #include "MainWindow.h" @@ -47,7 +47,8 @@ main(int argc, char** argv) } catch (const std::exception& e) { - std::cerr << e.what() << std::endl; + QApplication application(argc, argv); + QMessageBox::critical(nullptr, "Error", e.what()); return EXIT_FAILURE; } } diff --git a/demos/rlSimulator/rlSimulator.cpp b/demos/rlSimulator/rlSimulator.cpp index 912f0467..50b5d9fa 100644 --- a/demos/rlSimulator/rlSimulator.cpp +++ b/demos/rlSimulator/rlSimulator.cpp @@ -24,8 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include #include +#include #include #include "MainWindow.h" @@ -35,16 +35,16 @@ MainWindow* MainWindow::singleton = nullptr; int main(int argc, char** argv) { + QApplication application(argc, argv); + if (argc < 3) { - std::cout << "Usage: rlSimulator SCENEFILE MODELFILE" << std::endl; + QMessageBox::information(nullptr, "Usage", "rlSimulator SCENEFILE MODELFILE"); return EXIT_FAILURE; } try { - QApplication application(argc, argv); - QObject::connect(&application, SIGNAL(lastWindowClosed()), &application, SLOT(quit())); MainWindow::instance()->show(); @@ -53,8 +53,7 @@ main(int argc, char** argv) } catch (const std::exception& e) { - std::cerr << e.what() << std::endl; + QMessageBox::critical(nullptr, "Error", e.what()); return EXIT_FAILURE; } } - From 73565a705cdf2baac6e555b8ee57def4778f372d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 15 Apr 2018 22:41:20 +0200 Subject: [PATCH 067/546] Use Eigen::Ref in rl::mdl::Joint --- src/rl/mdl/Cylindrical.cpp | 2 +- src/rl/mdl/Cylindrical.h | 2 +- src/rl/mdl/Helical.cpp | 2 +- src/rl/mdl/Helical.h | 2 +- src/rl/mdl/Joint.cpp | 20 ++++++++++---------- src/rl/mdl/Joint.h | 22 +++++++++++----------- src/rl/mdl/Metric.cpp | 16 ++++++++-------- src/rl/mdl/Prismatic.cpp | 2 +- src/rl/mdl/Prismatic.h | 2 +- src/rl/mdl/Revolute.cpp | 10 +++++----- src/rl/mdl/Revolute.h | 10 +++++----- src/rl/mdl/Spherical.cpp | 14 +++++++------- src/rl/mdl/Spherical.h | 14 +++++++------- 13 files changed, 59 insertions(+), 59 deletions(-) diff --git a/src/rl/mdl/Cylindrical.cpp b/src/rl/mdl/Cylindrical.cpp index 00daaf99..e76a2c88 100644 --- a/src/rl/mdl/Cylindrical.cpp +++ b/src/rl/mdl/Cylindrical.cpp @@ -54,7 +54,7 @@ namespace rl } void - Cylindrical::setPosition(const ::rl::math::Vector& q) + Cylindrical::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; this->t = ::rl::math::AngleAxis(this->q(0) + this->offset(0), this->S.block<3, 1>(0, 0)); diff --git a/src/rl/mdl/Cylindrical.h b/src/rl/mdl/Cylindrical.h index a803577a..2e39caef 100644 --- a/src/rl/mdl/Cylindrical.h +++ b/src/rl/mdl/Cylindrical.h @@ -40,7 +40,7 @@ namespace rl virtual ~Cylindrical(); - void setPosition(const ::rl::math::Vector& q); + void setPosition(const ::rl::math::ConstVectorRef& q); protected: diff --git a/src/rl/mdl/Helical.cpp b/src/rl/mdl/Helical.cpp index 0be18eb3..7b888648 100644 --- a/src/rl/mdl/Helical.cpp +++ b/src/rl/mdl/Helical.cpp @@ -64,7 +64,7 @@ namespace rl } void - Helical::setPosition(const ::rl::math::Vector& q) + Helical::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; this->t = ::rl::math::AngleAxis(this->q(0), this->S.block<3, 1>(0, 0)); diff --git a/src/rl/mdl/Helical.h b/src/rl/mdl/Helical.h index 4aaa38ad..b3f196b6 100644 --- a/src/rl/mdl/Helical.h +++ b/src/rl/mdl/Helical.h @@ -44,7 +44,7 @@ namespace rl void setPitch(const ::rl::math::Real& h); - void setPosition(const ::rl::math::Vector& q); + void setPosition(const ::rl::math::ConstVectorRef& q); protected: diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index ae9e71a7..e0334ddb 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -77,7 +77,7 @@ namespace rl } void - Joint::clip(::rl::math::Vector& q) const + Joint::clip(::rl::math::VectorRef q) const { for (::std::size_t i = 0; i < this->getDofPosition(); ++i) { @@ -107,7 +107,7 @@ namespace rl } ::rl::math::Real - Joint::distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + Joint::distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const { return (q2 - q1).norm(); } @@ -282,7 +282,7 @@ namespace rl } void - Joint::interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q) const + Joint::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { q = (1.0f - alpha) * q1 + alpha * q2; } @@ -298,7 +298,7 @@ namespace rl } bool - Joint::isValid(const ::rl::math::Vector& q) const + Joint::isValid(const ::rl::math::ConstVectorRef& q) const { for (::std::size_t i = 0; i < this->getDofPosition(); ++i) { @@ -312,12 +312,12 @@ namespace rl } void - Joint::normalize(::rl::math::Vector& q) const + Joint::normalize(::rl::math::VectorRef q) const { } void - Joint::setAcceleration(const ::rl::math::Vector& qdd) + Joint::setAcceleration(const ::rl::math::ConstVectorRef& qdd) { this->qdd = qdd; @@ -326,13 +326,13 @@ namespace rl } void - Joint::setTorque(const ::rl::math::Vector& tau) + Joint::setTorque(const ::rl::math::ConstVectorRef& tau) { this->tau = tau; } void - Joint::setVelocity(const ::rl::math::Vector& qd) + Joint::setVelocity(const ::rl::math::ConstVectorRef& qd) { this->qd = qd; @@ -341,14 +341,14 @@ namespace rl } void - Joint::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const + Joint::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const { q2 = q1 + qdot; this->clip(q2); } ::rl::math::Real - Joint::transformedDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + Joint::transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const { return (q2 - q1).squaredNorm(); } diff --git a/src/rl/mdl/Joint.h b/src/rl/mdl/Joint.h index 802dad2b..9ca65e5b 100644 --- a/src/rl/mdl/Joint.h +++ b/src/rl/mdl/Joint.h @@ -43,9 +43,9 @@ namespace rl virtual ~Joint(); - virtual void clip(::rl::math::Vector& q) const; + virtual void clip(::rl::math::VectorRef q) const; - virtual ::rl::math::Real distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + virtual ::rl::math::Real distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; void forwardAcceleration(); @@ -89,25 +89,25 @@ namespace rl const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& getVelocityUnits() const; - virtual void interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q) const; + virtual void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; void inverseForce(); - virtual bool isValid(const ::rl::math::Vector& q) const; + virtual bool isValid(const ::rl::math::ConstVectorRef& q) const; - virtual void normalize(::rl::math::Vector& q) const; + virtual void normalize(::rl::math::VectorRef q) const; - void setAcceleration(const ::rl::math::Vector& qdd); + void setAcceleration(const ::rl::math::ConstVectorRef& qdd); - virtual void setPosition(const ::rl::math::Vector& q) = 0; + virtual void setPosition(const ::rl::math::ConstVectorRef& q) = 0; - void setTorque(const ::rl::math::Vector& tau); + void setTorque(const ::rl::math::ConstVectorRef& tau); - void setVelocity(const ::rl::math::Vector& qd); + void setVelocity(const ::rl::math::ConstVectorRef& qd); - virtual void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const; + virtual void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const; - virtual ::rl::math::Real transformedDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + virtual ::rl::math::Real transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; ::rl::math::MotionVector a; diff --git a/src/rl/mdl/Metric.cpp b/src/rl/mdl/Metric.cpp index a45b13f4..3379dfca 100644 --- a/src/rl/mdl/Metric.cpp +++ b/src/rl/mdl/Metric.cpp @@ -47,9 +47,9 @@ namespace rl for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { - ::rl::math::Vector qi = q.segment(j, this->joints[i]->getDofPosition()); // TODO + ::rl::math::VectorBlock qi = q.segment(j, this->joints[i]->getDofPosition()); this->joints[i]->clip(qi); - q.segment(j, this->joints[i]->getDofPosition()) = qi; // TODO + q.segment(j, this->joints[i]->getDofPosition()) = qi; } } @@ -89,7 +89,7 @@ namespace rl for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { - ::rl::math::Vector qi = q.segment(j, this->joints[i]->getDofPosition()); // TODO + ::rl::math::VectorBlock qi = q.segment(j, this->joints[i]->getDofPosition()); this->joints[i]->interpolate( q1.segment(j, this->joints[i]->getDofPosition()), @@ -98,7 +98,7 @@ namespace rl qi ); - q.segment(j, this->joints[i]->getDofPosition()) = qi; // TODO + q.segment(j, this->joints[i]->getDofPosition()) = qi; } } @@ -206,9 +206,9 @@ namespace rl for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { - ::rl::math::Vector qi = q.segment(j, this->joints[i]->getDofPosition()); // TODO + ::rl::math::VectorBlock qi = q.segment(j, this->joints[i]->getDofPosition()); this->joints[i]->normalize(qi); - q.segment(j, this->joints[i]->getDofPosition()) = qi; // TODO + q.segment(j, this->joints[i]->getDofPosition()) = qi; } } @@ -221,7 +221,7 @@ namespace rl for (::std::size_t i = 0, j = 0, k = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), k += this->joints[i]->getDof(), ++i) { - ::rl::math::Vector q2i = q2.segment(j, this->joints[i]->getDofPosition()); // TODO + ::rl::math::VectorBlock q2i = q2.segment(j, this->joints[i]->getDofPosition()); this->joints[i]->step( q1.segment(j, this->joints[i]->getDofPosition()), @@ -229,7 +229,7 @@ namespace rl q2i ); - q2.segment(j, this->joints[i]->getDofPosition()) = q2i; // TODO + q2.segment(j, this->joints[i]->getDofPosition()) = q2i; } } diff --git a/src/rl/mdl/Prismatic.cpp b/src/rl/mdl/Prismatic.cpp index aee8fa81..3b5a9269 100644 --- a/src/rl/mdl/Prismatic.cpp +++ b/src/rl/mdl/Prismatic.cpp @@ -46,7 +46,7 @@ namespace rl } void - Prismatic::setPosition(const ::rl::math::Vector& q) + Prismatic::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; this->t.translation() = this->S.block<3, 1>(3, 0) * (this->q(0) + this->offset(0)); diff --git a/src/rl/mdl/Prismatic.h b/src/rl/mdl/Prismatic.h index f98de971..c2cb043e 100644 --- a/src/rl/mdl/Prismatic.h +++ b/src/rl/mdl/Prismatic.h @@ -40,7 +40,7 @@ namespace rl virtual ~Prismatic(); - void setPosition(const ::rl::math::Vector& q); + void setPosition(const ::rl::math::ConstVectorRef& q); protected: diff --git a/src/rl/mdl/Revolute.cpp b/src/rl/mdl/Revolute.cpp index 94141428..48449d20 100644 --- a/src/rl/mdl/Revolute.cpp +++ b/src/rl/mdl/Revolute.cpp @@ -48,7 +48,7 @@ namespace rl } ::rl::math::Real - Revolute::distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + Revolute::distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const { ::rl::math::Real delta = ::std::abs(q2(0) - q1(0)); @@ -64,7 +64,7 @@ namespace rl } void - Revolute::interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q) const + Revolute::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { if (this->wraparound(0)) { @@ -104,7 +104,7 @@ namespace rl } void - Revolute::normalize(::rl::math::Vector& q) const + Revolute::normalize(::rl::math::VectorRef q) const { q(0) = ::std::fmod(q(0), 2.0f * static_cast< ::rl::math::Real>(M_PI)); @@ -119,7 +119,7 @@ namespace rl } void - Revolute::setPosition(const ::rl::math::Vector& q) + Revolute::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; this->t = ::rl::math::AngleAxis(this->q(0) + this->offset(0), this->S.block<3, 1>(0, 0)); @@ -127,7 +127,7 @@ namespace rl } ::rl::math::Real - Revolute::transformedDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + Revolute::transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const { ::rl::math::Real delta = ::std::abs(q2(0) - q1(0)); diff --git a/src/rl/mdl/Revolute.h b/src/rl/mdl/Revolute.h index 4790348b..338f47aa 100644 --- a/src/rl/mdl/Revolute.h +++ b/src/rl/mdl/Revolute.h @@ -40,15 +40,15 @@ namespace rl virtual ~Revolute(); - ::rl::math::Real distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + ::rl::math::Real distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; - void interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q) const; + void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; - void normalize(::rl::math::Vector& q) const; + void normalize(::rl::math::VectorRef q) const; - void setPosition(const ::rl::math::Vector& q); + void setPosition(const ::rl::math::ConstVectorRef& q); - ::rl::math::Real transformedDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + ::rl::math::Real transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; protected: diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 7df08d68..ce4697a2 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -61,13 +61,13 @@ namespace rl } void - Spherical::clip(::rl::math::Vector& q) const + Spherical::clip(::rl::math::VectorRef q) const { ::Eigen::Map< ::rl::math::Quaternion>(q.data()).normalize(); } ::rl::math::Real - Spherical::distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + Spherical::distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const { ::Eigen::Map quaternion1(q1.data()); ::Eigen::Map quaternion2(q2.data()); @@ -91,7 +91,7 @@ namespace rl } void - Spherical::interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q) const + Spherical::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { ::Eigen::Map quaternion1(q1.data()); ::Eigen::Map quaternion2(q2.data()); @@ -99,7 +99,7 @@ namespace rl } void - Spherical::normalize(::rl::math::Vector& q) const + Spherical::normalize(::rl::math::VectorRef q) const { ::Eigen::Map< ::rl::math::Quaternion> quaternion(q.data()); @@ -114,7 +114,7 @@ namespace rl } void - Spherical::setPosition(const ::rl::math::Vector& q) + Spherical::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; this->t = ::Eigen::Map(this->q.data()); @@ -122,14 +122,14 @@ namespace rl } void - Spherical::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const + Spherical::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const { ::Eigen::Map quaternion1(q1.data()); q2 = (quaternion1 * ::rl::math::AngleAxis(qdot.norm(), qdot.normalized())).coeffs(); } ::rl::math::Real - Spherical::transformedDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const + Spherical::transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const { return ::std::pow(this->distance(q1, q2), 2); } diff --git a/src/rl/mdl/Spherical.h b/src/rl/mdl/Spherical.h index 4ff25998..440164ed 100644 --- a/src/rl/mdl/Spherical.h +++ b/src/rl/mdl/Spherical.h @@ -40,23 +40,23 @@ namespace rl virtual ~Spherical(); - void clip(::rl::math::Vector& q) const; + void clip(::rl::math::VectorRef q) const; - ::rl::math::Real distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + ::rl::math::Real distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; ::rl::math::Vector generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma) const; ::rl::math::Vector generatePositionUniform(const ::rl::math::ConstVectorRef& rand) const; - void interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q) const; + void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; - void normalize(::rl::math::Vector& q) const; + void normalize(::rl::math::VectorRef q) const; - void setPosition(const ::rl::math::Vector& q); + void setPosition(const ::rl::math::ConstVectorRef& q); - void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const; + void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const; - ::rl::math::Real transformedDistance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; + ::rl::math::Real transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; protected: From 2a594756e8efd149e779b9f5d5f3f9a020598b04 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 15 Apr 2018 23:18:50 +0200 Subject: [PATCH 068/546] Remove unused functions --- src/rl/kin/Kinematics.cpp | 66 ---------------------------------- src/rl/kin/Kinematics.h | 8 ----- src/rl/mdl/Metric.cpp | 75 --------------------------------------- src/rl/mdl/Metric.h | 8 ----- src/rl/plan/Model.cpp | 52 --------------------------- src/rl/plan/Model.h | 8 ----- 6 files changed, 217 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index c631b7c1..144a8bbf 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -841,72 +841,6 @@ namespace rl return true; } - ::rl::math::Real - Kinematics::maxDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const - { - ::rl::math::Real d = 0; - - for (::std::size_t i = 0; i < this->getDof(); ++i) - { - ::rl::math::Real delta = ::std::max(::std::abs(q(i) - min(i)), ::std::abs(q(i) - max(i))); - - if (this->joints[i]->wraparound) - { - ::rl::math::Real range = ::std::abs(this->joints[i]->max - this->joints[i]->min); - d += this->transformedDistance(::std::max(delta, ::std::abs(range - delta))); - } - else - { - d += this->transformedDistance(delta); - } - } - - return d; - } - - ::rl::math::Real - Kinematics::minDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const - { - ::rl::math::Real d = 0; - - for (::std::size_t i = 0; i < this->getDof(); ++i) - { - d += this->transformedDistance(this->minDistanceToRectangle(q(i), min(i), max(i), i)); - } - - return d; - } - - ::rl::math::Real - Kinematics::minDistanceToRectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cuttingDimension) const - { - ::rl::math::Real d = 0; - - if (q < min || q > max) - { - ::rl::math::Real delta = ::std::min(::std::abs(q - min), ::std::abs(q - max)); - - if (this->joints[cuttingDimension]->wraparound) - { - ::rl::math::Real range = ::std::abs(this->joints[cuttingDimension]->max - this->joints[cuttingDimension]->min); - ::rl::math::Real size = ::std::abs(max - min); - d += ::std::min(delta, ::std::abs(range - size - delta)); - } - else - { - d += delta; - } - } - - return d; - } - - ::rl::math::Real - Kinematics::newDistance(const ::rl::math::Real& dist, const ::rl::math::Real& oldOff, const ::rl::math::Real& newOff, const int& cuttingDimension) const - { - return dist - this->transformedDistance(oldOff) + this->transformedDistance(newOff); - } - void Kinematics::setColliding(const ::std::size_t& i, const bool& doesCollide) { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index db93f988..4290df41 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -246,14 +246,6 @@ namespace rl */ virtual bool isValid(const ::rl::math::Vector& q) const; - virtual ::rl::math::Real maxDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; - - virtual ::rl::math::Real minDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; - - virtual ::rl::math::Real minDistanceToRectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cuttingDimension) const; - - virtual ::rl::math::Real newDistance(const ::rl::math::Real& dist, const ::rl::math::Real& oldOff, const ::rl::math::Real& newOff, const int& cuttingDimension) const; - /** * Set if specified body should be tested for collisions with the environment. */ diff --git a/src/rl/mdl/Metric.cpp b/src/rl/mdl/Metric.cpp index 3379dfca..c9716379 100644 --- a/src/rl/mdl/Metric.cpp +++ b/src/rl/mdl/Metric.cpp @@ -124,81 +124,6 @@ namespace rl return true; } - ::rl::math::Real - Metric::maxDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const - { - ::rl::math::Real d = 0; - - ::std::size_t k = 0; - - for (::std::size_t i = 0; i < this->joints.size(); ++i) - { - for (::std::size_t j = 0; j < this->joints[i]->getDofPosition(); ++j) - { - ::rl::math::Real delta = ::std::max(::std::abs(q(k) - min(k)), ::std::abs(q(k) - max(k))); - - if (this->joints[i]->wraparound(j)) - { - ::rl::math::Real range = ::std::abs(this->joints[i]->max(j) - this->joints[i]->min(j)); - d += this->transformedDistance(::std::max(delta, ::std::abs(range - delta))); - } - else - { - d += this->transformedDistance(delta); - } - - ++k; - } - } - - return d; - } - - ::rl::math::Real - Metric::minDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const - { - ::rl::math::Real d = 0; - - for (::std::size_t i = 0; i < this->getDofPosition(); ++i) - { - d += this->transformedDistance(this->minDistanceToRectangle(q(i), min(i), max(i), i)); - } - - return d; - } - - ::rl::math::Real - Metric::minDistanceToRectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cuttingDimension) const - { - ::rl::math::Real d = 0; -#if 0 // TODO - - if (q < min || q > max) - { - ::rl::math::Real delta = ::std::min(::std::abs(q - min), ::std::abs(q - max)); - - if (this->joints[cuttingDimension]->wraparound) - { - ::rl::math::Real range = ::std::abs(this->joints[cuttingDimension]->max - this->joints[cuttingDimension]->min); - ::rl::math::Real size = ::std::abs(max - min); - d += ::std::min(delta, ::std::abs(range - size - delta)); - } - else - { - d += delta; - } - } - -#endif - return d; - } - - ::rl::math::Real - Metric::newDistance(const ::rl::math::Real& dist, const ::rl::math::Real& oldOff, const ::rl::math::Real& newOff, const int& cuttingDimension) const - { - return dist - this->transformedDistance(oldOff) + this->transformedDistance(newOff); - } - void Metric::normalize(::rl::math::Vector& q) const { diff --git a/src/rl/mdl/Metric.h b/src/rl/mdl/Metric.h index e887996a..c21f6e3f 100644 --- a/src/rl/mdl/Metric.h +++ b/src/rl/mdl/Metric.h @@ -52,14 +52,6 @@ namespace rl bool isValid(const ::rl::math::Vector& q) const; - ::rl::math::Real maxDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; - - ::rl::math::Real minDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; - - ::rl::math::Real minDistanceToRectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cuttingDimension) const; - - ::rl::math::Real newDistance(const ::rl::math::Real& dist, const ::rl::math::Real& oldOff, const ::rl::math::Real& newOff, const int& cuttingDimension) const; - void normalize(::rl::math::Vector& q) const; void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const; diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index 2fb24e1a..d65ada6e 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -413,58 +413,6 @@ namespace rl } } - ::rl::math::Real - Model::maxDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const - { - if (nullptr != this->kin) - { - return this->kin->maxDistanceToRectangle(q, min, max); - } - else - { - return this->mdl->maxDistanceToRectangle(q, min, max); - } - } - - ::rl::math::Real - Model::minDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const - { - if (nullptr != this->kin) - { - return this->kin->minDistanceToRectangle(q, min, max); - } - else - { - return this->mdl->minDistanceToRectangle(q, min, max); - } - } - - ::rl::math::Real - Model::minDistanceToRectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cuttingDimension) const - { - if (nullptr != this->kin) - { - return this->kin->minDistanceToRectangle(q, min, max, cuttingDimension); - } - else - { - return this->mdl->minDistanceToRectangle(q, min, max, cuttingDimension); - } - } - - ::rl::math::Real - Model::newDistance(const ::rl::math::Real& dist, const ::rl::math::Real& oldOff, const ::rl::math::Real& newOff, const int& cuttingDimension) const - { - if (nullptr != this->kin) - { - return this->kin->newDistance(dist, oldOff, newOff, cuttingDimension); - } - else - { - return this->mdl->newDistance(dist, oldOff, newOff, cuttingDimension); - } - } - void Model::reset() { diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 435590c1..1685a324 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -103,14 +103,6 @@ namespace rl virtual bool isValid(const ::rl::math::Vector& q) const; - virtual ::rl::math::Real maxDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; - - virtual ::rl::math::Real minDistanceToRectangle(const ::rl::math::Vector& q, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; - - virtual ::rl::math::Real minDistanceToRectangle(const ::rl::math::Real& q, const ::rl::math::Real& min, const ::rl::math::Real& max, const ::std::size_t& cuttingDimension) const; - - virtual ::rl::math::Real newDistance(const ::rl::math::Real& dist, const ::rl::math::Real& oldOff, const ::rl::math::Real& newOff, const int& cuttingDimension) const; - virtual void reset(); virtual void setPosition(const ::rl::math::Vector& q); From 6f69d19c7609db3fc8b997d42d1363eba0e27732 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 16 Apr 2018 21:41:05 +0200 Subject: [PATCH 069/546] Use separate signal for rl::plan::Thread status changes --- demos/rlPlanDemo/MainWindow.cpp | 2 ++ demos/rlPlanDemo/Thread.cpp | 37 ++++++++++++++++++++------------- demos/rlPlanDemo/Thread.h | 2 ++ 3 files changed, 27 insertions(+), 14 deletions(-) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 54d1cb84..fedc64e0 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -259,6 +259,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->init(); + QObject::connect(this->thread, SIGNAL(statusChanged(const QString&)), this->statusBar(), SLOT(showMessage(const QString&))); + QStringList engines; #ifdef RL_SG_FCL engines.push_back("fcl"); diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index bca574d0..5b285c72 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -170,21 +170,19 @@ Thread::run() this->running = true; - this->showMessage("Showing start configuration."); - this->drawConfiguration(*MainWindow::instance()->planner->start); - if (nullptr != MainWindow::instance()->planner->viewer) { + emit statusChanged("Showing start configuration."); + this->drawConfiguration(*MainWindow::instance()->planner->start); usleep(static_cast(2.0f * 1000.0f * 1000.0f)); } if (!this->running) return; - this->showMessage("Showing goal configuration."); - this->drawConfiguration(*MainWindow::instance()->planner->goal); - if (nullptr != MainWindow::instance()->planner->viewer) { + emit statusChanged("Showing goal configuration."); + this->drawConfiguration(*MainWindow::instance()->planner->goal); usleep(static_cast(2.0f * 1000.0f * 1000.0f)); } @@ -192,11 +190,11 @@ Thread::run() if (!MainWindow::instance()->planner->verify()) { - this->showMessage("Invalid start or goal configuration."); + emit statusChanged("Invalid start or goal configuration."); return; } - this->showMessage("Solving..."); + emit statusChanged("Solving..."); std::chrono::steady_clock::time_point start = std::chrono::steady_clock::now(); bool solved = MainWindow::instance()->planner->solve(); @@ -204,7 +202,7 @@ Thread::run() double plannerDuration = std::chrono::duration_cast>(stop - start).count() * 1000; - this->showMessage("Planner " + std::string(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration).toStdString() + " ms."); + emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration) + " ms."); std::fstream benchmark; benchmark.open("benchmark.csv", std::ios::app | std::ios::in | std::ios::out); @@ -347,15 +345,21 @@ Thread::run() if (solved) { - this->drawConfigurationPath(path); + if (nullptr != MainWindow::instance()->planner->viewer) + { + this->drawConfigurationPath(path); + } if (!this->running) return; if (nullptr != MainWindow::instance()->optimizer) { - usleep(static_cast(2.0f * 1000.0f * 1000.0f)); + if (nullptr != MainWindow::instance()->planner->viewer) + { + usleep(static_cast(2.0f * 1000.0f * 1000.0f)); + } - this->showMessage("Planner " + std::string(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration).toStdString() + " ms. Optimizing..."); + emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration) + " ms. Optimizing..."); start = std::chrono::steady_clock::now(); MainWindow::instance()->optimizer->process(path); @@ -363,11 +367,16 @@ Thread::run() double optimizerDuration = std::chrono::duration_cast>(stop - start).count() * 1000; - this->showMessage("Planner " + std::string(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration).toStdString() + " ms. Optimizer finished in " + QString::number(optimizerDuration).toStdString() + " ms."); + emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration) + " ms. Optimizer finished in " + QString::number(optimizerDuration) + " ms."); - this->drawConfigurationPath(path); + if (nullptr != MainWindow::instance()->planner->viewer) + { + this->drawConfigurationPath(path); + } } + if (nullptr == MainWindow::instance()->planner->viewer) return; + if (this->swept) { this->drawSweptVolume(path); diff --git a/demos/rlPlanDemo/Thread.h b/demos/rlPlanDemo/Thread.h index 24dce565..bb4d9a0b 100644 --- a/demos/rlPlanDemo/Thread.h +++ b/demos/rlPlanDemo/Thread.h @@ -119,6 +119,8 @@ class Thread : public QThread, public rl::plan::Viewer void sphereResetRequested(); + void statusChanged(const QString& message); + void sweptVolumeRequested(const rl::plan::VectorList& path); void vertexResetRequested(); From cd7a3886f930d6e94d61f92c888448753d427885 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 18 Apr 2018 18:16:11 +0200 Subject: [PATCH 070/546] Add 6x6 motion and force cross product matrices for MotionVector --- src/rl/math/spatial/MotionVector.h | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/src/rl/math/spatial/MotionVector.h b/src/rl/math/spatial/MotionVector.h index 9069942a..d41f04f5 100644 --- a/src/rl/math/spatial/MotionVector.h +++ b/src/rl/math/spatial/MotionVector.h @@ -48,6 +48,8 @@ namespace rl typedef Scalar ScalarType; + typedef typename ::Eigen::Matrix CrossType; + typedef typename ::Eigen::Matrix MatrixType; typedef const MatrixType ConstMatrixType; @@ -95,6 +97,26 @@ namespace rl return res; } + CrossType cross66Force() const + { + CrossType res; + res.template topLeftCorner<3, 3>() = angular().cross33(); + res.template topRightCorner<3, 3>() = linear().cross33(); + res.template bottomLeftCorner<3, 3>().setZero(); + res.template bottomRightCorner<3, 3>() = angular().cross33(); + return res; + } + + CrossType cross66Motion() const + { + CrossType res; + res.template topLeftCorner<3, 3>() = angular().cross33(); + res.template topRightCorner<3, 3>().setZero(); + res.template bottomLeftCorner<3, 3>() = linear().cross33(); + res.template bottomRightCorner<3, 3>() = angular().cross33(); + return res; + } + template Scalar dot(const ForceVector& other) const; From b8cfb57e8fd8aeb4913c5e4b2b1a231a893e238c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 18 Apr 2018 18:29:50 +0200 Subject: [PATCH 071/546] Add negate function for spatial motion and force vector --- src/rl/math/spatial/ForceVector.h | 8 ++++++++ src/rl/math/spatial/MotionVector.h | 8 ++++++++ 2 files changed, 16 insertions(+) diff --git a/src/rl/math/spatial/ForceVector.h b/src/rl/math/spatial/ForceVector.h index d774ec08..ed286e83 100644 --- a/src/rl/math/spatial/ForceVector.h +++ b/src/rl/math/spatial/ForceVector.h @@ -118,6 +118,14 @@ namespace rl return res; } + ForceVector operator-() const + { + ForceVector res; + res.moment() = -moment(); + res.force() = -force(); + return res; + } + ForceVector operator-(const ForceVector& other) const { ForceVector res; diff --git a/src/rl/math/spatial/MotionVector.h b/src/rl/math/spatial/MotionVector.h index d41f04f5..5a28282d 100644 --- a/src/rl/math/spatial/MotionVector.h +++ b/src/rl/math/spatial/MotionVector.h @@ -150,6 +150,14 @@ namespace rl return res; } + MotionVector operator-() const + { + MotionVector res; + res.angular() = -angular(); + res.linear() = -linear(); + return res; + } + MotionVector operator-(const MotionVector& other) const { MotionVector res; From a34e6cb3cf7ee387b97b0fb1d06028fc966577e6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 18 Apr 2018 20:11:26 +0200 Subject: [PATCH 072/546] Use EIGEN_USING_STD_MATH and EIGEN_PI in addons --- src/rl/math/QuaternionBaseAddons.h | 34 +++++++++++++++++---------- src/rl/math/TransformAddons.h | 37 +++++++++++++++++++----------- 2 files changed, 45 insertions(+), 26 deletions(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 1ea6ba79..a6e5f152 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -48,9 +48,12 @@ angularAcceleration(const QuaternionBase& qd, const QuaternionBas Quaternion exp() const { + EIGEN_USING_STD_MATH(cos); + EIGEN_USING_STD_MATH(sin); + Scalar theta = this->derived().vec().norm(); - Scalar sinTheta = ::sin(theta); - Scalar cosTheta = ::cos(theta); + Scalar sinTheta = sin(theta); + Scalar cosTheta = cos(theta); Quaternion q; @@ -83,8 +86,11 @@ Quaternion lerp(const Scalar& t, const QuaternionBase& oth Quaternion log() const { - Scalar theta = ::acos(this->derived().w()); - Scalar sinTheta = ::sin(theta); + EIGEN_USING_STD_MATH(acos); + EIGEN_USING_STD_MATH(sin); + + Scalar theta = acos(this->derived().w()); + Scalar sinTheta = sin(theta); Quaternion q; @@ -186,6 +192,10 @@ setFromGaussian(const Vector3& rand, const QuaternionBase& mean, c void setFromUniform(const Vector3& rand) { + EIGEN_USING_STD_MATH(cos); + EIGEN_USING_STD_MATH(sin); + EIGEN_USING_STD_MATH(sqrt); + eigen_assert(rand(0) >= Scalar(0)); eigen_assert(rand(0) <= Scalar(1)); eigen_assert(rand(1) >= Scalar(0)); @@ -193,15 +203,15 @@ setFromUniform(const Vector3& rand) eigen_assert(rand(2) >= Scalar(0)); eigen_assert(rand(2) <= Scalar(1)); - Scalar sigma1 = ::std::sqrt(Scalar(1) - rand(0)); - Scalar sigma2 = ::std::sqrt(rand(0)); - Scalar theta1 = Scalar(2) * static_cast(M_PI) * rand(1); - Scalar theta2 = Scalar(2) * static_cast(M_PI) * rand(2); + Scalar sigma1 = sqrt(Scalar(1) - rand(0)); + Scalar sigma2 = sqrt(rand(0)); + Scalar theta1 = Scalar(2 * EIGEN_PI) * rand(1); + Scalar theta2 = Scalar(2 * EIGEN_PI) * rand(2); - this->derived().w() = ::std::cos(theta2) * sigma2; - this->derived().x() = ::std::sin(theta1) * sigma1; - this->derived().y() = ::std::cos(theta1) * sigma1; - this->derived().z() = ::std::sin(theta2) * sigma2; + this->derived().x() = sin(theta1) * sigma1; + this->derived().y() = cos(theta1) * sigma1; + this->derived().z() = sin(theta2) * sigma2; + this->derived().w() = cos(theta2) * sigma2; } template diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index 5cb38943..e791bf9f 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -36,14 +36,17 @@ inline Scalar distance(const Transform& other, const Scalar& weight = 1) const { + EIGEN_USING_STD_MATH(pow); + EIGEN_USING_STD_MATH(sqrt); + Quaternion q1(rotation()); Quaternion q2(other.rotation()); - return ::std::sqrt( - ::std::pow(other(0, 3) - (*this)(0, 3), 2) + - ::std::pow(other(1, 3) - (*this)(1, 3), 2) + - ::std::pow(other(2, 3) - (*this)(2, 3), 2) + - weight * ::std::pow(q1.angularDistance(q2), 2) + return sqrt( + pow(other(0, 3) - (*this)(0, 3), 2) + + pow(other(1, 3) - (*this)(1, 3), 2) + + pow(other(2, 3) - (*this)(2, 3), 2) + + weight * pow(q1.angularDistance(q2), 2) ); } @@ -92,10 +95,13 @@ inline void fromDenavitHartenbergPaul(const Scalar& d, const Scalar& theta, const Scalar& a, const Scalar& alpha) { - Scalar cosAlpha = ::std::cos(alpha); - Scalar cosTheta = ::std::cos(theta); - Scalar sinAlpha = ::std::sin(alpha); - Scalar sinTheta = ::std::sin(theta); + EIGEN_USING_STD_MATH(cos); + EIGEN_USING_STD_MATH(sin); + + Scalar cosAlpha = cos(alpha); + Scalar cosTheta = cos(theta); + Scalar sinAlpha = sin(alpha); + Scalar sinTheta = sin(theta); (*this)(0, 0) = cosTheta; (*this)(1, 0) = sinTheta; @@ -193,17 +199,20 @@ inline void toDenavitHartenbergPaul(Scalar& d, Scalar& theta, Scalar& a, Scalar& alpha) const { - assert(::std::abs((*this)(2, 0)) <= ::std::numeric_limits::epsilon()); + EIGEN_USING_STD_MATH(abs); + EIGEN_USING_STD_MATH(atan2); + + assert(abs((*this)(2, 0)) <= ::std::numeric_limits::epsilon()); d = (*this)(2, 3); - theta = ::std::atan2((*this)(1, 0), (*this)(0, 0)); + theta = atan2((*this)(1, 0), (*this)(0, 0)); - if (::std::abs((*this)(0, 0)) <= ::std::numeric_limits::epsilon()) + if (abs((*this)(0, 0)) <= ::std::numeric_limits::epsilon()) { a = (*this)(1, 3) / (*this)(1, 0); } - else if (::std::abs((*this)(1, 0)) <= ::std::numeric_limits::epsilon()) + else if (abs((*this)(1, 0)) <= ::std::numeric_limits::epsilon()) { a = (*this)(0, 3) / (*this)(0, 0); } @@ -212,7 +221,7 @@ toDenavitHartenbergPaul(Scalar& d, Scalar& theta, Scalar& a, Scalar& alpha) cons a = ((*this)(1, 3) / (*this)(1, 0) + (*this)(0, 3) / (*this)(0, 0)) * Scalar(0.5); } - alpha = ::std::atan2((*this)(2, 1), (*this)(2, 2)); + alpha = atan2((*this)(2, 1), (*this)(2, 2)); } #ifdef DOXYGEN_SHOULD_PARSE_THIS From f9be8a9688ea04710e2eb5aeda2105d8d30fb268 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 10:45:06 +0200 Subject: [PATCH 073/546] Remove EIGEN_USING_STD_MATH as not supported by Eigen < 3.3.0 --- src/rl/math/QuaternionBaseAddons.h | 14 +++++++------- src/rl/math/TransformAddons.h | 12 ++++++------ 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index a6e5f152..e823ca12 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -48,8 +48,8 @@ angularAcceleration(const QuaternionBase& qd, const QuaternionBas Quaternion exp() const { - EIGEN_USING_STD_MATH(cos); - EIGEN_USING_STD_MATH(sin); + using ::std::cos; + using ::std::sin; Scalar theta = this->derived().vec().norm(); Scalar sinTheta = sin(theta); @@ -86,8 +86,8 @@ Quaternion lerp(const Scalar& t, const QuaternionBase& oth Quaternion log() const { - EIGEN_USING_STD_MATH(acos); - EIGEN_USING_STD_MATH(sin); + using ::std::acos; + using ::std::sin; Scalar theta = acos(this->derived().w()); Scalar sinTheta = sin(theta); @@ -192,9 +192,9 @@ setFromGaussian(const Vector3& rand, const QuaternionBase& mean, c void setFromUniform(const Vector3& rand) { - EIGEN_USING_STD_MATH(cos); - EIGEN_USING_STD_MATH(sin); - EIGEN_USING_STD_MATH(sqrt); + using ::std::cos; + using ::std::sin; + using ::std::sqrt; eigen_assert(rand(0) >= Scalar(0)); eigen_assert(rand(0) <= Scalar(1)); diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index e791bf9f..a9986d6e 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -36,8 +36,8 @@ inline Scalar distance(const Transform& other, const Scalar& weight = 1) const { - EIGEN_USING_STD_MATH(pow); - EIGEN_USING_STD_MATH(sqrt); + using ::std::pow; + using ::std::sqrt; Quaternion q1(rotation()); Quaternion q2(other.rotation()); @@ -95,8 +95,8 @@ inline void fromDenavitHartenbergPaul(const Scalar& d, const Scalar& theta, const Scalar& a, const Scalar& alpha) { - EIGEN_USING_STD_MATH(cos); - EIGEN_USING_STD_MATH(sin); + using ::std::cos; + using ::std::sin; Scalar cosAlpha = cos(alpha); Scalar cosTheta = cos(theta); @@ -199,8 +199,8 @@ inline void toDenavitHartenbergPaul(Scalar& d, Scalar& theta, Scalar& a, Scalar& alpha) const { - EIGEN_USING_STD_MATH(abs); - EIGEN_USING_STD_MATH(atan2); + using ::std::abs; + using ::std::atan2; assert(abs((*this)(2, 0)) <= ::std::numeric_limits::epsilon()); From aa56404be85e5394f20fd9415918a7f9dcda88af Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 10:54:41 +0200 Subject: [PATCH 074/546] Remove EIGEN_PI as not supported by Eigen < 3.3.0 --- src/rl/math/QuaternionBaseAddons.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index e823ca12..b8b297bb 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -205,8 +205,8 @@ setFromUniform(const Vector3& rand) Scalar sigma1 = sqrt(Scalar(1) - rand(0)); Scalar sigma2 = sqrt(rand(0)); - Scalar theta1 = Scalar(2 * EIGEN_PI) * rand(1); - Scalar theta2 = Scalar(2 * EIGEN_PI) * rand(2); + Scalar theta1 = Scalar(2 * M_PI) * rand(1); + Scalar theta2 = Scalar(2 * M_PI) * rand(2); this->derived().x() = sin(theta1) * sigma1; this->derived().y() = cos(theta1) * sigma1; From 0a1eba305222f65a347b9ddc58b6ddd04fc8d4d5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 Apr 2018 18:10:04 +0200 Subject: [PATCH 075/546] Add test for spatial and use rotation of Transform in PlueckerTransform --- src/rl/math/spatial/ArticulatedBodyInertia.h | 12 +- src/rl/math/spatial/ForceVector.h | 14 +- src/rl/math/spatial/MotionVector.h | 12 +- src/rl/math/spatial/PlueckerTransform.h | 54 +- src/rl/math/spatial/PlueckerTransform.hxx | 49 +- src/rl/math/spatial/RigidBodyInertia.h | 12 +- src/rl/mdl/Cylindrical.cpp | 2 +- src/rl/mdl/Helical.cpp | 2 +- src/rl/mdl/Joint.cpp | 9 +- src/rl/mdl/Revolute.cpp | 2 +- src/rl/mdl/Spherical.cpp | 2 +- src/rl/mdl/Transform.cpp | 5 +- src/rl/mdl/XmlFactory.cpp | 3 +- tests/CMakeLists.txt | 1 + tests/rlSpatialTest/CMakeLists.txt | 14 + tests/rlSpatialTest/rlSpatialTest.cpp | 872 +++++++++++++++++++ 16 files changed, 1004 insertions(+), 61 deletions(-) create mode 100644 tests/rlSpatialTest/CMakeLists.txt create mode 100644 tests/rlSpatialTest/rlSpatialTest.cpp diff --git a/src/rl/math/spatial/ArticulatedBodyInertia.h b/src/rl/math/spatial/ArticulatedBodyInertia.h index 444653da..ae6195bf 100644 --- a/src/rl/math/spatial/ArticulatedBodyInertia.h +++ b/src/rl/math/spatial/ArticulatedBodyInertia.h @@ -100,6 +100,12 @@ namespace rl return inertiaData; } + template + bool isApprox(const ArticulatedBodyInertia& other, const typename ::Eigen::NumTraits::Real& prec = ::Eigen::NumTraits::dummy_precision()) const + { + return cog().isApprox(other.cog(), prec) && inertia().isApprox(other.inertia(), prec) && mass().isApprox(other.mass(), prec); + } + MassType& mass() { return massData; @@ -132,7 +138,8 @@ namespace rl template ArticulatedBodyInertia& operator=(const RigidBodyInertia& other); - ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& other) const + template + ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& other) const { ArticulatedBodyInertia res; res.cog() = cog() + other.cog(); @@ -141,7 +148,8 @@ namespace rl return res; } - ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& other) const + template + ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& other) const { ArticulatedBodyInertia res; res.cog() = cog() - other.cog(); diff --git a/src/rl/math/spatial/ForceVector.h b/src/rl/math/spatial/ForceVector.h index ed286e83..46232ec1 100644 --- a/src/rl/math/spatial/ForceVector.h +++ b/src/rl/math/spatial/ForceVector.h @@ -103,6 +103,12 @@ namespace rl return data.template segment<3>(0); } + template + bool isApprox(const ForceVector& other, const typename ::Eigen::NumTraits::Real& prec = ::Eigen::NumTraits::dummy_precision()) const + { + return matrix().isApprox(other.matrix(), prec); + } + template ForceVector& operator=(const ::Eigen::MatrixBase& other) { @@ -110,7 +116,8 @@ namespace rl return *this; } - ForceVector operator+(const ForceVector& other) const + template + ForceVector operator+(const ForceVector& other) const { ForceVector res; res.moment() = moment() + other.moment(); @@ -126,7 +133,8 @@ namespace rl return res; } - ForceVector operator-(const ForceVector& other) const + template + ForceVector operator-(const ForceVector& other) const { ForceVector res; res.moment() = moment() - other.moment(); @@ -152,8 +160,6 @@ namespace rl return res; } - ArticulatedBodyInertia operator*(const ForceVector& other) const; - void setZero() { moment().setZero(); diff --git a/src/rl/math/spatial/MotionVector.h b/src/rl/math/spatial/MotionVector.h index 5a28282d..710993ff 100644 --- a/src/rl/math/spatial/MotionVector.h +++ b/src/rl/math/spatial/MotionVector.h @@ -130,6 +130,12 @@ namespace rl return data.template segment<3>(3); } + template + bool isApprox(const MotionVector& other, const typename ::Eigen::NumTraits::Real& prec = ::Eigen::NumTraits::dummy_precision()) const + { + return matrix().isApprox(other.matrix(), prec); + } + ConstMatrixType& matrix() const { return data; @@ -142,7 +148,8 @@ namespace rl return *this; } - MotionVector operator+(const MotionVector& other) const + template + MotionVector operator+(const MotionVector& other) const { MotionVector res; res.angular() = angular() + other.angular(); @@ -158,7 +165,8 @@ namespace rl return res; } - MotionVector operator-(const MotionVector& other) const + template + MotionVector operator-(const MotionVector& other) const { MotionVector res; res.angular() = angular() - other.angular(); diff --git a/src/rl/math/spatial/PlueckerTransform.h b/src/rl/math/spatial/PlueckerTransform.h index 7ae6a240..7f140201 100644 --- a/src/rl/math/spatial/PlueckerTransform.h +++ b/src/rl/math/spatial/PlueckerTransform.h @@ -74,6 +74,13 @@ namespace rl { } + template + PlueckerTransform(const ::Eigen::Transform& other) : + rotationData(other.linear()), + translationData(other.translation()) + { + } + virtual ~PlueckerTransform() { } @@ -82,61 +89,76 @@ namespace rl { PlueckerTransform res; res.rotation() = rotation().transpose(); - res.translation() = -rotation() * translation(); + res.translation() = -rotation().transpose() * translation(); return res; } MatrixType inverseForce() const { MatrixType res; - res.template topLeftCorner<3, 3>() = rotation().transpose(); - res.template topRightCorner<3, 3>() = translation().cross33() * rotation().transpose(); + res.template topLeftCorner<3, 3>() = rotation(); + res.template topRightCorner<3, 3>() = translation().cross33() * rotation(); res.template bottomLeftCorner<3, 3>().setZero(); - res.template bottomRightCorner<3, 3>() = rotation().transpose(); + res.template bottomRightCorner<3, 3>() = rotation(); return res; } MatrixType inverseMotion() const { MatrixType res; - res.template topLeftCorner<3, 3>() = rotation().transpose(); + res.template topLeftCorner<3, 3>() = rotation(); res.template topRightCorner<3, 3>().setZero(); - res.template bottomLeftCorner<3, 3>() = translation().cross33() * rotation().transpose(); - res.template bottomRightCorner<3, 3>() = rotation().transpose(); + res.template bottomLeftCorner<3, 3>() = translation().cross33() * rotation(); + res.template bottomRightCorner<3, 3>() = rotation(); return res; } + template + bool isApprox(const PlueckerTransform& other, const typename ::Eigen::NumTraits::Real& prec = ::Eigen::NumTraits::dummy_precision()) const + { + return rotation().isApprox(other.rotation(), prec) && translation().isApprox(other.translation(), prec); + } + MatrixType matrixForce() const { MatrixType res; - res.template topLeftCorner<3, 3>() = rotation(); - res.template topRightCorner<3, 3>() = -rotation() * translation().cross33(); + res.template topLeftCorner<3, 3>() = rotation().transpose(); + res.template topRightCorner<3, 3>() = -rotation().transpose() * translation().cross33(); res.template bottomLeftCorner<3, 3>().setZero(); - res.template bottomRightCorner<3, 3>() = rotation(); + res.template bottomRightCorner<3, 3>() = rotation().transpose(); return res; } MatrixType matrixMotion() const { MatrixType res; - res.template topLeftCorner<3, 3>() = rotation(); + res.template topLeftCorner<3, 3>() = rotation().transpose(); res.template topRightCorner<3, 3>().setZero(); - res.template bottomLeftCorner<3, 3>() = -rotation() * translation().cross33(); - res.template bottomRightCorner<3, 3>() = rotation(); + res.template bottomLeftCorner<3, 3>() = -rotation().transpose() * translation().cross33(); + res.template bottomRightCorner<3, 3>() = rotation().transpose(); return res; } + template + PlueckerTransform& operator=(const ::Eigen::Transform& other) + { + rotation() = other.linear(); + translation() = other.translation(); + return *this; + } + template ForceVector operator*(const ForceVector& other) const; template MotionVector operator*(const MotionVector& other) const; - PlueckerTransform operator*(const PlueckerTransform& other) const + template + PlueckerTransform operator*(const PlueckerTransform& other) const { PlueckerTransform res; res.rotation() = rotation() * other.rotation(); - res.translation() = other.translation() + other.rotation().transpose() * translation(); + res.translation() = rotation() * other.translation() + translation(); return res; } @@ -178,7 +200,7 @@ namespace rl { TransformType res; res.linear() = rotation(); - res.translation() = -rotation() * translation(); + res.translation() = translation(); return res; } diff --git a/src/rl/math/spatial/PlueckerTransform.hxx b/src/rl/math/spatial/PlueckerTransform.hxx index 920897de..7ff88832 100644 --- a/src/rl/math/spatial/PlueckerTransform.hxx +++ b/src/rl/math/spatial/PlueckerTransform.hxx @@ -40,8 +40,8 @@ namespace rl PlueckerTransform::operator*(const ForceVector& other) const { ForceVector res; - res.force() = rotation() * other.force(); - res.moment() = rotation() * (other.moment() - translation().cross(other.force())); + res.moment() = rotation().transpose() * (other.moment() - translation().cross(other.force())); + res.force() = rotation().transpose() * other.force(); return res; } @@ -52,8 +52,8 @@ namespace rl PlueckerTransform::operator*(const MotionVector& other) const { MotionVector res; - res.linear() = rotation() * (other.linear() - translation().cross(other.angular())); - res.angular() = rotation() * other.angular(); + res.angular() = rotation().transpose() * other.angular(); + res.linear() = rotation().transpose() * (other.linear() - translation().cross(other.angular())); return res; } @@ -64,8 +64,10 @@ namespace rl PlueckerTransform::operator*(const RigidBodyInertia& other) const { RigidBodyInertia res; - res.cog() = rotation() * (other.cog() - other.mass() * translation()); - res.inertia() = rotation() * (other.inertia() + translation().cross(other.cog()).cross33() + (other.cog() - other.mass() * translation()).cross(translation()).cross33()) * rotation().transpose(); + ::Eigen::Matrix px = translation().cross33(); + ::Eigen::Matrix c_m_p = other.cog() - other.mass() * translation(); + res.cog() = rotation().transpose() * c_m_p; + res.inertia() = rotation().transpose() * (other.inertia() + px * other.cog().cross33() + c_m_p.cross33() * px) * rotation(); res.mass() = other.mass(); return res; } @@ -77,9 +79,11 @@ namespace rl PlueckerTransform::operator*(const ArticulatedBodyInertia& other) const { ArticulatedBodyInertia res; - res.cog() = rotation() * (other.cog() - translation().cross33() * other.mass()) * rotation().transpose(); - res.inertia() = rotation() * (other.inertia() - translation().cross33() * other.cog().transpose() + (other.cog() - translation().cross33() * other.mass()) * translation().cross33()) * rotation().transpose(); - res.mass() = rotation() * other.mass() * rotation().transpose(); + ::Eigen::Matrix px = translation().cross33(); + ::Eigen::Matrix c_px_m = other.cog() - px * other.mass(); + res.cog() = rotation().transpose() * c_px_m * rotation(); + res.inertia() = rotation().transpose() * (other.inertia() - px * other.cog().transpose() + c_px_m * px) * rotation(); + res.mass() = rotation().transpose() * other.mass() * rotation(); return res; } @@ -90,8 +94,8 @@ namespace rl PlueckerTransform::operator/(const ForceVector& other) const { ForceVector res; - res.force() = rotation().transpose() * other.force(); - res.moment() = rotation().transpose() * other.moment() + translation().cross(rotation().transpose() * other.force()); + res.moment() = rotation() * other.moment() + translation().cross(rotation() * other.force()); + res.force() = rotation() * other.force(); return res; } @@ -102,8 +106,8 @@ namespace rl PlueckerTransform::operator/(const MotionVector& other) const { MotionVector res; - res.linear() = rotation().transpose() * other.linear() + translation().cross(rotation().transpose() * other.angular()); - res.angular() = rotation().transpose() * other.angular(); + res.angular() = rotation() * other.angular(); + res.linear() = rotation() * other.linear() + translation().cross(rotation() * other.angular()); return res; } @@ -114,8 +118,11 @@ namespace rl PlueckerTransform::operator/(const RigidBodyInertia& other) const { RigidBodyInertia res; - res.cog() = rotation().transpose() * other.cog() + other.mass() * translation(); - res.inertia() = rotation().transpose() * other.inertia() * rotation() - translation().cross(rotation().transpose() * other.cog()).cross33() - (rotation().transpose() * other.cog() + other.mass() * translation()).cross(translation()).cross33(); + ::Eigen::Matrix px = translation().cross33(); + ::Eigen::Matrix R_c = rotation() * other.cog(); + ::Eigen::Matrix R_c_m_p = R_c + other.mass() * translation(); + res.cog() = R_c_m_p; + res.inertia() = rotation() * other.inertia() * rotation().transpose() - px * R_c.cross33() - R_c_m_p.cross33() * px; res.mass() = other.mass(); return res; } @@ -127,11 +134,13 @@ namespace rl PlueckerTransform::operator/(const ArticulatedBodyInertia& other) const { ArticulatedBodyInertia res; - typename ArticulatedBodyInertia::CenterOfGravityType cog = rotation().transpose() * other.cog() * rotation(); - typename ArticulatedBodyInertia::MassType mass = rotation().transpose() * other.mass() * rotation(); - res.cog() = cog + translation().cross33() * mass; - res.inertia() = rotation().transpose() * other.inertia() * rotation() + translation().cross33() * cog.transpose() - (cog + translation().cross33() * mass) * translation().cross33(); - res.mass() = mass; + typename ArticulatedBodyInertia::CenterOfGravityType c = rotation() * other.cog() * rotation().transpose(); + typename ArticulatedBodyInertia::MassType m = rotation() * other.mass() * rotation().transpose(); + ::Eigen::Matrix px = translation().cross33(); + ::Eigen::Matrix c_px_m = c + px * m; + res.cog() = c_px_m; + res.inertia() = rotation() * other.inertia() * rotation().transpose() + px * c.transpose() - c_px_m * px; + res.mass() = m; return res; } } diff --git a/src/rl/math/spatial/RigidBodyInertia.h b/src/rl/math/spatial/RigidBodyInertia.h index 742cdb37..696751de 100644 --- a/src/rl/math/spatial/RigidBodyInertia.h +++ b/src/rl/math/spatial/RigidBodyInertia.h @@ -100,6 +100,12 @@ namespace rl return inertiaData; } + template + bool isApprox(const RigidBodyInertia& other, const typename ::Eigen::NumTraits::Real& prec = ::Eigen::NumTraits::dummy_precision()) const + { + return cog().isApprox(other.cog(), prec) && inertia().isApprox(other.inertia(), prec) && ::Eigen::internal::isApprox(mass(), other.mass(), prec); + } + MassType& mass() { return massData; @@ -129,7 +135,8 @@ namespace rl return *this; } - RigidBodyInertia operator+(const RigidBodyInertia& other) const + template + RigidBodyInertia operator+(const RigidBodyInertia& other) const { RigidBodyInertia res; res.cog() = cog() + other.cog(); @@ -138,7 +145,8 @@ namespace rl return res; } - RigidBodyInertia operator-(const RigidBodyInertia& other) const + template + RigidBodyInertia operator-(const RigidBodyInertia& other) const { RigidBodyInertia res; res.cog() = cog() - other.cog(); diff --git a/src/rl/mdl/Cylindrical.cpp b/src/rl/mdl/Cylindrical.cpp index e76a2c88..764d2ed5 100644 --- a/src/rl/mdl/Cylindrical.cpp +++ b/src/rl/mdl/Cylindrical.cpp @@ -58,7 +58,7 @@ namespace rl { this->q = q; this->t = ::rl::math::AngleAxis(this->q(0) + this->offset(0), this->S.block<3, 1>(0, 0)); - this->x.rotation() = this->t.linear().transpose(); + this->x.rotation() = this->t.linear(); this->t.translation() = this->S.block<3, 1>(3, 1) * (this->q(1) + this->offset(1)); this->x.translation() = this->t.translation(); } diff --git a/src/rl/mdl/Helical.cpp b/src/rl/mdl/Helical.cpp index 7b888648..07cd2259 100644 --- a/src/rl/mdl/Helical.cpp +++ b/src/rl/mdl/Helical.cpp @@ -68,7 +68,7 @@ namespace rl { this->q = q; this->t = ::rl::math::AngleAxis(this->q(0), this->S.block<3, 1>(0, 0)); - this->x.rotation() = this->t.linear().transpose(); + this->x.rotation() = this->t.linear(); this->t.translation() = this->S.block<3, 1>(3, 0) * this->h * (this->q(0) + this->offset(0)); this->x.translation() = this->t.translation(); } diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index e0334ddb..1b3c919d 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -137,11 +137,9 @@ namespace rl // tau - S^T * p^A this->u = this->tau - this->S.transpose() * this->out->pA.matrix(); // I^A - U * D^-1 * U^T - ::rl::math::ArticulatedBodyInertia ia; - ia = this->out->iA.matrix() - this->U * this->D.inverse() * this->U.transpose(); + ::rl::math::ArticulatedBodyInertia ia(this->out->iA - ::rl::math::ArticulatedBodyInertia(this->U * this->D.inverse() * this->U.transpose())); // p^A + I^a * c + U * D^-1 * u - ::rl::math::ForceVector pa; - pa = this->out->pA + ia * this->out->c + this->U.matrix() * this->D.inverse() * this->u; + ::rl::math::ForceVector pa(this->out->pA + ia * this->out->c + ::rl::math::ForceVector(this->U * this->D.inverse() * this->u)); // I^A + X^* * I^a * X this->in->iA = this->in->iA + this->x / ia; // p^A + X^* * p^a @@ -152,8 +150,7 @@ namespace rl Joint::forwardDynamics3() { // X * a + c - ::rl::math::MotionVector a; - a = this->x * this->in->a + this->out->c; + ::rl::math::MotionVector a(this->x * this->in->a + this->out->c); // D^-1 * (u - U^T * a') this->qdd = this->D.inverse() * (this->u - this->U.transpose() * a.matrix()); // S * qdd diff --git a/src/rl/mdl/Revolute.cpp b/src/rl/mdl/Revolute.cpp index 48449d20..fdfe11f8 100644 --- a/src/rl/mdl/Revolute.cpp +++ b/src/rl/mdl/Revolute.cpp @@ -123,7 +123,7 @@ namespace rl { this->q = q; this->t = ::rl::math::AngleAxis(this->q(0) + this->offset(0), this->S.block<3, 1>(0, 0)); - this->x.rotation() = this->t.linear().transpose(); + this->x.rotation() = this->t.linear(); } ::rl::math::Real diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index ce4697a2..496101f7 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -118,7 +118,7 @@ namespace rl { this->q = q; this->t = ::Eigen::Map(this->q.data()); - this->x.rotation() = this->t.linear().transpose(); + this->x.rotation() = this->t.linear(); } void diff --git a/src/rl/mdl/Transform.cpp b/src/rl/mdl/Transform.cpp index 0817768a..65d91c36 100644 --- a/src/rl/mdl/Transform.cpp +++ b/src/rl/mdl/Transform.cpp @@ -67,8 +67,7 @@ namespace rl this->in->iA = this->in->iA + this->x / this->out->iA; // p^A + I^a * c - ::rl::math::ForceVector pa; - pa = this->out->pA + this->out->iA * this->out->c; // TODO + ::rl::math::ForceVector pa(this->out->pA + this->out->iA * this->out->c); // p^A + X^* * p^a this->in->pA = this->in->pA + this->x / pa; @@ -85,7 +84,7 @@ namespace rl Transform::forwardPosition() { this->out->t = this->in->t * this->t; - this->out->x = this->x * this->in->x; + this->out->x = this->out->t; } void diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index eb9be204..8a60aa08 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -312,8 +312,7 @@ namespace rl f->t.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); f->t.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); - f->x.rotation() = f->t.linear().transpose(); - f->x.translation() = f->t.translation(); + f->x = f->t; transform = f; } diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index bf523ae9..fdf8f712 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -2,6 +2,7 @@ if(BUILD_RL_MATH) add_subdirectory(rlCircularTest) add_subdirectory(rlMathDeltaTest) add_subdirectory(rlNearestNeighborsTest) + add_subdirectory(rlSpatialTest) add_subdirectory(rlSplineTest) endif() diff --git a/tests/rlSpatialTest/CMakeLists.txt b/tests/rlSpatialTest/CMakeLists.txt new file mode 100644 index 00000000..da808b35 --- /dev/null +++ b/tests/rlSpatialTest/CMakeLists.txt @@ -0,0 +1,14 @@ +add_executable( + rlSpatialTest + rlSpatialTest.cpp +) + +target_link_libraries( + rlSpatialTest + math +) + +add_test( + rlSpatialTest + ${CMAKE_CURRENT_BINARY_DIR}/rlSpatialTest +) diff --git a/tests/rlSpatialTest/rlSpatialTest.cpp b/tests/rlSpatialTest/rlSpatialTest.cpp new file mode 100644 index 00000000..b2134b03 --- /dev/null +++ b/tests/rlSpatialTest/rlSpatialTest.cpp @@ -0,0 +1,872 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include +#include + +void +testArticulatedBodyInertia() +{ + rl::math::ArticulatedBodyInertia abi1; + abi1.cog().setRandom(); + abi1.inertia().setRandom(); + abi1.mass() = rl::math::Vector3::Random().asDiagonal(); + + rl::math::ArticulatedBodyInertia abi2; + abi2.cog().setRandom(); + abi2.inertia().setRandom(); + abi2.mass() = rl::math::Vector3::Random().asDiagonal(); + + rl::math::ArticulatedBodyInertia abi3 = abi1 + abi2; + rl::math::ArticulatedBodyInertia abi4 = abi3 - abi2; + + if (!abi4.matrix().isApprox(abi1.matrix())) + { + std::cerr << "abi1 + abi2 - abi2 != abi1" << std::endl; + std::cerr << "abi1 + abi2 - abi2 = " << std::endl << abi4.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::ArticulatedBodyInertia abi1_2 = abi1 * 2; + rl::math::ArticulatedBodyInertia abi1_abi1 = abi1 + abi1; + rl::math::ArticulatedBodyInertia abi1_2_05 = abi1_2 * 0.5; + + if (!abi1_2.matrix().isApprox(abi1_abi1.matrix())) + { + std::cerr << "abi1 * 2 != abi1 + abi1" << std::endl; + std::cerr << "abi1 * 2 = " << std::endl << abi1_2.matrix() << std::endl; + std::cerr << "abi1 + abi1 = " << std::endl << abi1_abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!abi1_2_05.matrix().isApprox(abi1.matrix())) + { + std::cerr << "abi1 * 2 * 0.5 != abi1" << std::endl; + std::cerr << "abi1 * 2 * 0.5 = " << std::endl << abi1_2.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::PlueckerTransform pt1; + pt1.rotation() = rl::math::Quaternion::UnitRandom().toRotationMatrix(); + pt1.translation().setRandom(); + + rl::math::ArticulatedBodyInertia abi5 = pt1 * abi1; + rl::math::ArticulatedBodyInertia abi6 = pt1 / abi5; + + if (!abi6.matrix().isApprox(abi1.matrix())) + { + std::cerr << "inv(pt1) * pt1 * abi1 != abi1" << std::endl; + std::cerr << "inv(pt1) * pt1 * abi1 = " << std::endl << abi6.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m1 = pt1.matrixForce() * abi1.matrix() * pt1.inverseMotion(); + + if (!abi5.matrix().isApprox(m1)) + { + std::cerr << "pt1 * abi1 != matrixForce(pt1) * abi1 * inverseMotion(pt1)" << std::endl; + std::cerr << "pt1 * abi1 = " << std::endl << abi5.matrix() << std::endl; + std::cerr << "matrixForce(pt1) * abi1 * inverseMotion(pt1) = " << std::endl << m1 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m2 = pt1.matrixMotion().transpose() * m1 * pt1.matrixMotion(); + + if (!abi1.matrix().isApprox(m2)) + { + std::cerr << "abi1 != matrixMotion(pt1)^T * abi5 * matrixMotion(pt1)" << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + std::cerr << "matrixMotion(pt1)^T * abi5 * matrixMotion(pt1) = " << std::endl << m2 << std::endl; + exit(EXIT_FAILURE); + } +} + +void +testEuclideanCrossProduct() +{ + rl::math::Vector3 a; + a.setRandom(); + + rl::math::Matrix33 m1a = a.cross33(); + rl::math::Matrix33 m1b = -a.cross33().transpose(); + + if (!m1a.isApprox(m1b)) + { + std::cerr << "ax != -ax^T" << std::endl; + std::cerr << "ax = " << std::endl << m1a << std::endl; + std::cerr << "-ax^T = " << std::endl << m1b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector3 b; + b.setRandom(); + + rl::math::Matrix33 m2a = (a + b).cross33(); + rl::math::Matrix33 m2b = a.cross33() + b.cross33(); + + if (!m2a.isApprox(m2b)) + { + std::cerr << "(a + b)x != ax + bx" << std::endl; + std::cerr << "(a + b)x = " << std::endl << m2a << std::endl; + std::cerr << "ax + bx = " << std::endl << m2b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Rotation r = rl::math::Quaternion::UnitRandom().toRotationMatrix(); + + rl::math::Matrix33 m3a = (r * a).cross33(); + rl::math::Matrix33 m3b = r * a.cross33() * r.transpose(); + + if (!m3a.isApprox(m3b)) + { + std::cerr << "(R * a)x != R ax R^T" << std::endl; + std::cerr << "(R * a)x = " << std::endl << m3a << std::endl; + std::cerr << "R ax R^T = " << std::endl << m3b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector3 v4a = a.cross33() * b; + rl::math::Vector3 v4b = -b.cross33() * a; + + if (!v4a.isApprox(v4b)) + { + std::cerr << "(ax) b != -(bx) a" << std::endl; + std::cerr << "(ax) b = " << std::endl << v4a << std::endl; + std::cerr << "-(bx) a = " << std::endl << v4b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector3 v5a = a.cross(b).transpose(); + rl::math::Vector3 v5b = a.transpose() * b.cross33(); + + if (!v5a.isApprox(v5b)) + { + std::cerr << "(a x b)^T != a^T bx" << std::endl; + std::cerr << "(a x b)^T = " << std::endl << v5a << std::endl; + std::cerr << "a^T bx = " << std::endl << v5b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix33 m6a = a.cross(b).cross33(); + rl::math::Matrix33 m6b = a.cross33() * b.cross33() - b.cross33() * a.cross33(); + + if (!m6a.isApprox(m6b)) + { + std::cerr << "(a x b)x != ax bx - bx ax" << std::endl; + std::cerr << "(a x b)x = " << std::endl << m6a << std::endl; + std::cerr << "ax bx - bx ax = " << std::endl << m6b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix33 m7a = a.cross(b).cross33(); + rl::math::Matrix33 m7b = b * a.transpose() - a * b.transpose(); + + if (!m7a.isApprox(m7b)) + { + std::cerr << "(a x b)x != b a^T - a b^T" << std::endl; + std::cerr << "(a x b)x = " << std::endl << m7a << std::endl; + std::cerr << "b a^T - a b^T = " << std::endl << m7b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix33 m8a = a.cross33() * b.cross33(); + rl::math::Matrix33 m8b = b * a.transpose() - a.dot(b) * rl::math::Matrix33::Identity(); + + if (!m8a.isApprox(m8b)) + { + std::cerr << "ax bx != b a^T - (a * b) I" << std::endl; + std::cerr << "ax bx = " << std::endl << m8a << std::endl; + std::cerr << "b a^T - (a * b) I = " << std::endl << m8b << std::endl; + exit(EXIT_FAILURE); + } +} + +void +testForceVector() +{ + rl::math::Vector6 v0; + v0.setRandom(); + + rl::math::ForceVector fv0; + fv0.moment() << v0.head<3>(); + fv0.force() << v0.tail<3>(); + + if (!fv0.matrix().isApprox(v0)) + { + std::cerr << "fv0.matrix() != v0" << std::endl; + std::cerr << "fv0 = " << fv0.matrix().transpose() << std::endl; + std::cerr << "v0 = " << v0.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v1; + v1.setRandom(); + + rl::math::ForceVector fv1(v1); + + if (!fv1.matrix().isApprox(v1)) + { + std::cerr << "fv1(v1).matrix() != v1" << std::endl; + std::cerr << "fv1(v1) = " << fv1.matrix().transpose() << std::endl; + std::cerr << "v1 = " << v1.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v2; + v2.setRandom(); + + rl::math::ForceVector fv2 = v2; + + if (!fv2.matrix().isApprox(v2)) + { + std::cerr << "(fv2 = v2).matrix() != v2" << std::endl; + std::cerr << "(fv2 = v2) = " << fv2.matrix().transpose() << std::endl; + std::cerr << "v2 = " << v2.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v3 = v1 + v2; + rl::math::ForceVector fv3 = fv1 + fv2; + + if (!fv3.matrix().isApprox(v3)) + { + std::cerr << "fv1 + fv2 != v1 + v2" << std::endl; + std::cerr << "fv1 + fv2 = " << fv3.matrix().transpose() << std::endl; + std::cerr << "v1 + v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v4 = v1 - v2; + rl::math::ForceVector fv4 = fv1 - fv2; + + if (!fv4.matrix().isApprox(v4)) + { + std::cerr << "fv1 - fv2 != v1 - v2" << std::endl; + std::cerr << "fv1 - fv2 = " << fv4.matrix().transpose() << std::endl; + std::cerr << "v1 - v2 = " << v4.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v5 = v1 * 1.23f; + rl::math::ForceVector fv5 = fv1 * 1.23f; + + if (!fv5.matrix().isApprox(v5)) + { + std::cerr << "fv1 * 1.23 != v1 * 1.23" << std::endl; + std::cerr << "fv1 * 1.23 = " << fv5.matrix().transpose() << std::endl; + std::cerr << "v1 * 1.23 = " << v5.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v6 = v1 / 1.23f; + rl::math::ForceVector fv6 = fv1 / 1.23f; + + if (!fv6.matrix().isApprox(v6)) + { + std::cerr << "fv1 / 1.23 != v1 / 1.23" << std::endl; + std::cerr << "v1 * 1.23 = " << fv6.matrix().transpose() << std::endl; + std::cerr << "v1 / 1.23 = " << v6.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::ForceVector fv7 = v1; + + if (!fv7.matrix().isApprox(v1)) + { + std::cerr << "fv7 != v1" << std::endl; + std::cerr << "fv7 = " << fv7.matrix().transpose() << std::endl; + std::cerr << "v1 = " << v1.transpose() << std::endl; + exit(EXIT_FAILURE); + } +} + +void +testMotionVector() +{ + rl::math::Vector6 v0; + v0.setRandom(); + + rl::math::MotionVector mv0; + mv0.angular() << v0.head<3>(); + mv0.linear() << v0.tail<3>(); + + if (!mv0.matrix().isApprox(v0)) + { + std::cerr << "mv0.matrix() != v0" << std::endl; + std::cerr << "mv0 = " << mv0.matrix().transpose() << std::endl; + std::cerr << "v0 = " << v0.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v1; + v1.setRandom(); + + rl::math::MotionVector mv1(v1); + + if (!mv1.matrix().isApprox(v1)) + { + std::cerr << "mv1(v1).matrix() != v1" << std::endl; + std::cerr << "mv1(v1) = " << mv1.matrix().transpose() << std::endl; + std::cerr << "v1 = " << v1.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v2; + v2.setRandom(); + + rl::math::MotionVector mv2 = v2; + + if (!mv2.matrix().isApprox(v2)) + { + std::cerr << "(mv2 = v2).matrix() != v2" << std::endl; + std::cerr << "(mv2 = v2) = " << mv2.matrix().transpose() << std::endl; + std::cerr << "v2 = " << v2.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v3 = v1 + v2; + rl::math::MotionVector mv3 = mv1 + mv2; + + if (!mv3.matrix().isApprox(v3)) + { + std::cerr << "mv1 + mv2 != v1 + v2" << std::endl; + std::cerr << "mv1 + mv2 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "v1 + v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v4 = v1 - v2; + rl::math::MotionVector mv4 = mv1 - mv2; + + if (!mv4.matrix().isApprox(v4)) + { + std::cerr << "mv1 - mv2 != v1 - v2" << std::endl; + std::cerr << "mv1 - mv2 = " << mv4.matrix().transpose() << std::endl; + std::cerr << "v1 - v2 = " << v4.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v5 = v1 * 1.23f; + rl::math::MotionVector mv5 = mv1 * 1.23f; + + if (!mv5.matrix().isApprox(v5)) + { + std::cerr << "mv1 * 1.23 != v1 * 1.23" << std::endl; + std::cerr << "mv1 * 1.23 = " << mv5.matrix().transpose() << std::endl; + std::cerr << "v1 * 1.23 = " << v5.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v6 = v1 / 1.23f; + rl::math::MotionVector mv6 = mv1 / 1.23f; + + if (!mv6.matrix().isApprox(v6)) + { + std::cerr << "mv1 / 1.23 != v1 / 1.23" << std::endl; + std::cerr << "v1 * 1.23 = " << mv6.matrix().transpose() << std::endl; + std::cerr << "v1 / 1.23 = " << v6.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::MotionVector mv7 = v1; + + if (!mv7.matrix().isApprox(v1)) + { + std::cerr << "mv7 != v1" << std::endl; + std::cerr << "mv7 = " << mv7.matrix().transpose() << std::endl; + std::cerr << "v1 = " << v1.transpose() << std::endl; + exit(EXIT_FAILURE); + } +} + +void +testPlueckerTransform() +{ + rl::math::Transform t0; + t0 = rl::math::Quaternion::UnitRandom(); + t0.translation().setRandom(); + + rl::math::PlueckerTransform pt0; + pt0.rotation() = t0.linear(); + pt0.translation() = t0.translation(); + + if (!pt0.rotation().isApprox(t0.linear()) || !pt0.translation().isApprox(t0.translation())) + { + std::cerr << "pt0 != t0" << std::endl; + std::cerr << "pt0.rotation = " << std::endl << pt0.rotation() << std::endl; + std::cerr << "pt0.translation = " << pt0.translation().transpose() << std::endl; + std::cerr << "t0.linear = " << std::endl << t0.linear() << std::endl; + std::cerr << "t0.translation = " << t0.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Transform t1; + t1 = rl::math::Quaternion::UnitRandom(); + t1.translation().setRandom(); + + rl::math::PlueckerTransform pt1(t1); + + if (!pt1.rotation().isApprox(t1.linear()) || !pt1.translation().isApprox(t1.translation())) + { + std::cerr << "pt1(t1) != t1" << std::endl; + std::cerr << "pt1(t1).rotation = " << std::endl << pt1.rotation() << std::endl; + std::cerr << "pt1(t1).translation = " << pt1.translation().transpose() << std::endl; + std::cerr << "t1.linear = " << std::endl << t1.linear() << std::endl; + std::cerr << "t1.translation = " << t1.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Transform t2; + t2 = rl::math::Quaternion::UnitRandom(); + t2.translation().setRandom(); + + rl::math::PlueckerTransform pt2 = t2; + + if (!pt2.rotation().isApprox(t2.linear()) || !pt2.translation().isApprox(t2.translation())) + { + std::cerr << "(pt2 = t2) != t2" << std::endl; + std::cerr << "(pt2 = t2).rotation = " << std::endl << pt2.rotation() << std::endl; + std::cerr << "(pt2 = t2).translation = " << pt2.translation().transpose() << std::endl; + std::cerr << "t2.linear = " << std::endl << t2.linear() << std::endl; + std::cerr << "t2.translation = " << t2.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Transform t3 = t1 * t2; + rl::math::PlueckerTransform pt3 = pt1 * pt2; + + if (!pt3.rotation().isApprox(t3.linear()) || !pt3.translation().isApprox(t3.translation())) + { + std::cerr << "pt1 * pt2 != t1 * t2" << std::endl; + std::cerr << "(pt1 * pt2).rotation = " << std::endl << pt3.rotation() << std::endl; + std::cerr << "(pt1 * pt2).translation = " << pt3.translation().transpose() << std::endl; + std::cerr << "(t1 * t2).linear = " << std::endl << t3.linear() << std::endl; + std::cerr << "(t1 * t2).translation = " << t3.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Transform t4 = t1.inverse() * t3; + rl::math::PlueckerTransform pt4 = pt1.inverse() * pt3; + + if (!pt4.rotation().isApprox(pt2.rotation()) || !pt4.translation().isApprox(pt2.translation())) + { + std::cerr << "inv(pt1) * pt1 * pt2 != pt2" << std::endl; + std::cerr << "(inv(pt1) * pt1 * pt2).rotation = " << std::endl << pt4.rotation() << std::endl; + std::cerr << "(inv(pt1) * pt1 * pt2).translation = " << pt4.translation().transpose() << std::endl; + std::cerr << "pt2.rotation = " << std::endl << pt2.rotation().matrix() << std::endl; + std::cerr << "pt2.translation = " << pt2.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!pt4.rotation().isApprox(t4.linear()) || !pt4.translation().isApprox(t4.translation())) + { + std::cerr << "inv(pt1) * pt3 != inv(t1) * t3" << std::endl; + std::cerr << "(inv(pt1) * pt3).rotation = " << std::endl << pt4.rotation() << std::endl; + std::cerr << "(inv(pt1) * pt3).translation = " << pt4.translation().transpose() << std::endl; + std::cerr << "(inv(t1) * t3).linear = " << std::endl << t4.linear() << std::endl; + std::cerr << "(inv(t1) * t3).translation = " << t4.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::PlueckerTransform pt5; + pt5.setIdentity(); + rl::math::PlueckerTransform pt6 = pt1.inverse() * pt1; + + if (!pt5.rotation().isApprox(pt6.rotation()) || !pt5.translation().isMuchSmallerThan(pt6.translation())) + { + std::cerr << "I != inv(pt1) * pt1" << std::endl; + std::cerr << "I.rotation = " << std::endl << pt5.rotation().matrix() << std::endl; + std::cerr << "I.translation = " << pt5.translation().transpose() << std::endl; + std::cerr << "(inv(pt1) * pt1).rotation = " << std::endl << pt6.rotation() << std::endl; + std::cerr << "(inv(pt1) * pt1).translation = " << pt6.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m1a = pt1.matrixMotion().inverse(); + rl::math::Matrix66 m1b = pt1.inverseMotion(); + + if (!m1a.matrix().isApprox(m1b)) + { + std::cerr << "matrixMotion(pt1)^-1 != inverseMotion(pt1)" << std::endl; + std::cerr << "matrixMotion(pt1)^-1 = " << std::endl << m1a << std::endl; + std::cerr << "inverseMotion(pt1) = " << std::endl << m1b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m2a = pt1.matrixForce().inverse(); + rl::math::Matrix66 m2b = pt1.inverseForce(); + + if (!m2a.matrix().isApprox(m2b)) + { + std::cerr << "matrixForce(pt1)^-1 != inverseForce(pt1)" << std::endl; + std::cerr << "matrixForce(pt1)^-1 = " << std::endl << m2a << std::endl; + std::cerr << "inverseForce(pt1) = " << std::endl << m2b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m3a = pt1.matrixForce(); + rl::math::Matrix66 m3b = pt1.matrixMotion().inverse().transpose(); + + if (!m3a.matrix().isApprox(m3b)) + { + std::cerr << "matrixForce(pt1) != matrixMotion(pt1)^-T" << std::endl; + std::cerr << "matrixForce(pt1) = " << std::endl << m3a << std::endl; + std::cerr << "matrixMotion(pt1)^-T = " << std::endl << m3b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v1; + v1.setRandom(); + + { + rl::math::MotionVector mv1; + mv1.angular() << v1.head<3>(); + mv1.linear() << v1.tail<3>(); + + rl::math::Vector6 v2 = pt1.matrixMotion() * v1; + rl::math::MotionVector mv2 = pt1 * mv1; + + if (!mv2.matrix().isApprox(v2)) + { + std::cerr << "pt1 * mv1 != matrixMotion(pt1) * v1" << std::endl; + std::cerr << "pt1 * mv1 = " << mv2.matrix().transpose() << std::endl; + std::cerr << "matrixMotion(pt1) * v1 = " << v2.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v3 = pt1.inverseMotion() * v2; + rl::math::MotionVector mv3 = pt1 / mv2; + + if (!mv3.matrix().isApprox(v3)) + { + std::cerr << "inv(pt1) / mv2 != inverseMotion(pt1) * v2" << std::endl; + std::cerr << "inv(pt1) / mv2 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "inverseMotion(pt1) * v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!mv3.matrix().isApprox(mv1.matrix())) + { + std::cerr << "pt1.inverse() * pt1 * mv1 != mv1" << std::endl; + std::cerr << "pt1.inverse() * pt1 * mv1 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::MotionVector mv4 = pt1.inverse() * mv2; + + if (!mv4.matrix().isApprox(mv1.matrix())) + { + std::cerr << "pt1.inverse() * pt1 * mv1 != mv1" << std::endl; + std::cerr << "pt1.inverse() * pt1 * mv1 = " << mv4.matrix().transpose() << std::endl; + std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + } + + { + rl::math::ForceVector fv1; + fv1.moment() << v1.head<3>(); + fv1.force() << v1.tail<3>(); + + rl::math::Vector6 v2 = pt1.matrixForce() * v1; + rl::math::ForceVector fv2 = pt1 * fv1; + + if (!fv2.matrix().isApprox(v2)) + { + std::cerr << "pt1 * fv1 != matrixForce(pt1) * v1" << std::endl; + std::cerr << "pt1 * fv1 = " << fv2.matrix().transpose() << std::endl; + std::cerr << "matrixForce(pt1) * v1 = " << v2.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v3 = pt1.inverseForce() * v2; + rl::math::ForceVector fv3 = pt1 / fv2; + + if (!fv3.matrix().isApprox(v3)) + { + std::cerr << "inv(pt1) / fv2 != inverseForce(pt1) * v2" << std::endl; + std::cerr << "inv(pt1) / fv2 = " << fv3.matrix().transpose() << std::endl; + std::cerr << "inverseForce(pt1) * v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!fv3.matrix().isApprox(fv1.matrix())) + { + std::cerr << "pt1.inverse() * pt1 * fv1 != fv1" << std::endl; + std::cerr << "pt1.inverse() * pt1 * fv1 = " << fv3.matrix().transpose() << std::endl; + std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::ForceVector fv4 = pt1.inverse() * fv2; + + if (!fv4.matrix().isApprox(fv1.matrix())) + { + std::cerr << "pt1.inverse() * pt1 * fv1 != fv1" << std::endl; + std::cerr << "pt1.inverse() * pt1 * fv1 = " << fv4.matrix().transpose() << std::endl; + std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + } +} + +void +testRigidBodyInertia() +{ + rl::math::RigidBodyInertia rbi1; + rbi1.cog().setRandom(); + rbi1.inertia().setRandom(); + rbi1.mass() = 10; + + rl::math::RigidBodyInertia rbi2; + rbi2.cog().setRandom(); + rbi2.inertia().setRandom(); + rbi2.mass() = 20; + + rl::math::RigidBodyInertia rbi3 = rbi1 + rbi2; + rl::math::RigidBodyInertia rbi4 = rbi3 - rbi2; + + if (!rbi4.matrix().isApprox(rbi1.matrix())) + { + std::cerr << "rbi1 + rbi2 - rbi2 != rbi1" << std::endl; + std::cerr << "rbi1 + rbi2 - rbi2 = " << std::endl << rbi4.matrix() << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::RigidBodyInertia rbi1_2 = rbi1 * 2; + rl::math::RigidBodyInertia rbi1_rbi1 = rbi1 + rbi1; + rl::math::RigidBodyInertia rbi1_2_05 = rbi1_2 * 0.5; + + if (!rbi1_2.matrix().isApprox(rbi1_rbi1.matrix())) + { + std::cerr << "rbi1 * 2 != rbi1 + rbi1" << std::endl; + std::cerr << "rbi1 * 2 = " << std::endl << rbi1_2.matrix() << std::endl; + std::cerr << "rbi1 + rbi1 = " << std::endl << rbi1_rbi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!rbi1_2_05.matrix().isApprox(rbi1.matrix())) + { + std::cerr << "rbi1 * 2 * 0.5 != rbi1" << std::endl; + std::cerr << "rbi1 * 2 * 0.5 = " << std::endl << rbi1_2_05.matrix() << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::PlueckerTransform pt1; + pt1.rotation() = rl::math::Quaternion::UnitRandom().toRotationMatrix(); + pt1.translation().setRandom(); + + rl::math::RigidBodyInertia rbi5 = pt1 * rbi1; + rl::math::RigidBodyInertia rbi6 = pt1 / rbi5; + + if (!rbi6.matrix().isApprox(rbi1.matrix())) + { + std::cerr << "inv(pt1) * pt1 * rbi1 != rbi1" << std::endl; + std::cerr << "inv(pt1) * pt1 * rbi1 = " << std::endl << rbi6.matrix() << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m1 = pt1.matrixForce() * rbi1.matrix() * pt1.inverseMotion(); + + if (!rbi5.matrix().isApprox(m1)) + { + std::cerr << "pt1 * rbi1 != matrixForce(pt1) * rbi1 * inverseMotion(pt1)" << std::endl; + std::cerr << "pt1 * rbi1 = " << std::endl << rbi5.matrix() << std::endl; + std::cerr << "matrixForce(pt1) * rbi1 * inverseMotion(pt1) = " << std::endl << m1 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m2 = pt1.matrixMotion().transpose() * m1 * pt1.matrixMotion(); + + if (!rbi1.matrix().isApprox(m2)) + { + std::cerr << "rbi1 != matrixMotion(pt1)^T * rbi5 * matrixMotion(pt1)" << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + std::cerr << "matrixMotion(pt1)^T * rbi5 * matrixMotion(pt1) = " << std::endl << m2 << std::endl; + exit(EXIT_FAILURE); + } +} + +void +testSpatialCrossProduct() +{ + rl::math::Vector6 v1; + v1.setRandom(); + + rl::math::Vector6 v2; + v2.setRandom(); + + rl::math::MotionVector mv1; + mv1.angular() << v1.head<3>(); + mv1.linear() << v1.tail<3>(); + + rl::math::MotionVector mv2; + mv2.angular() << v2.head<3>(); + mv2.linear() << v2.tail<3>(); + + rl::math::Vector6 v3 = mv1.cross66Motion() * v2; + rl::math::MotionVector mv3 = mv1.cross(mv2); + + if (!mv3.matrix().isApprox(v3)) + { + std::cerr << "mv1 x mv2 != crossMotion(mv1) x v2" << std::endl; + std::cerr << "mv1 x mv2 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "crossMotion(mv1) x v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::MotionVector mv4 = -mv2.cross(mv1); + + if (!mv4.matrix().isApprox(mv3.matrix())) + { + std::cerr << "mv1 x mv2 != -mv2 x mv1" << std::endl; + std::cerr << "mv1 x mv2 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "-mv2 x mv1 = " << mv4.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::ForceVector fv2; + fv2.moment() << v2.head<3>(); + fv2.force() << v2.tail<3>(); + + rl::math::Vector6 v5 = mv1.cross66Force() * v2; + rl::math::ForceVector fv5 = mv1.cross(fv2); + + if (!fv5.matrix().isApprox(v5)) + { + std::cerr << "mv1 x fv2 != crossForce(mv1) x v2" << std::endl; + std::cerr << "mv1 x fv2 = " << fv5.matrix().transpose() << std::endl; + std::cerr << "crossForce(mv1) x v2 = " << v5.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 mv1CrossForce = -mv1.cross66Motion().transpose(); + + if (!mv1CrossForce.matrix().isApprox(mv1.cross66Force())) + { + std::cerr << "crossForce(mv1) != -crossMotion(mv1)^T" << std::endl; + std::cerr << "crossForce(mv1) = " << std::endl << mv1CrossForce << std::endl; + std::cerr << "-crossMotion(mv1)^T = " << std::endl << mv1.cross66Force() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 cross1 = (mv1 + mv2).cross66Motion(); + rl::math::Matrix66 cross2 = mv1.cross66Motion() + mv2.cross66Motion(); + + if (!cross1.matrix().isApprox(cross2)) + { + std::cerr << "crossMotion(mv1 + mv2) != crossMotion(mv1) + crossMotion(mv2)" << std::endl; + std::cerr << "crossMotion(mv1 + mv2) = " << std::endl << cross1 << std::endl; + std::cerr << "crossMotion(mv1) + crossMotion(mv2) = " << std::endl << cross2 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 cross3 = (mv1 + mv2).cross66Force(); + rl::math::Matrix66 cross4 = mv1.cross66Force() + mv2.cross66Force(); + + if (!cross3.matrix().isApprox(cross4)) + { + std::cerr << "crossForce(mv1 + mv2) != crossForce(mv1) + crossForce(mv2)" << std::endl; + std::cerr << "crossForce(mv1 + mv2) = " << std::endl << cross3 << std::endl; + std::cerr << "crossForce(mv1) + crossForce(mv2) = " << std::endl << cross4 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::PlueckerTransform pt; + pt.rotation() = rl::math::Quaternion::UnitRandom().toRotationMatrix(); + pt.translation().setRandom(); + + rl::math::Matrix66 m1 = (pt * mv1).cross66Motion(); + rl::math::Matrix66 m2 = pt.matrixMotion() * mv1.cross66Motion() * pt.inverse().matrixMotion(); + + if (!m1.matrix().isApprox(m2)) + { + std::cerr << "crossMotion(pt * mv1) != pt * crossMotion(mv1) * pt^-1" << std::endl; + std::cerr << "crossMotion(pt * mv1) = " << std::endl << m1 << std::endl; + std::cerr << "pt * crossMotion(mv1) * pt^-1 = " << std::endl << m2 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m3 = (pt * mv1).cross66Force(); + rl::math::Matrix66 m4 = pt.matrixForce() * mv1.cross66Force() * pt.inverse().matrixForce(); + + if (!m3.matrix().isApprox(m4)) + { + std::cerr << "crossForce(pt * mv1) != pt * crossForce(mv1) * pt^-1" << std::endl; + std::cerr << "crossForce(pt * mv1) = " << std::endl << m3 << std::endl; + std::cerr << "pt * crossForce(mv1) * pt^-1 = " << std::endl << m4 << std::endl; + exit(EXIT_FAILURE); + } +} + +void +testSpatialDotProduct() +{ + rl::math::MotionVector mv1; + mv1.angular().setRandom(); + mv1.linear().setRandom(); + + rl::math::ForceVector fv2; + fv2.moment().setRandom(); + fv2.force().setRandom(); + + rl::math::Real dot1 = mv1.angular().dot(fv2.moment()) + mv1.linear().dot(fv2.force()); + rl::math::Real dot2 = mv1.dot(fv2); + + if (!Eigen::internal::isApprox(dot2, dot1)) + { + std::cerr << "mv1 * fv2 != mv1.angular * fv2.moment + mv1.linear * fv2.force" << std::endl; + std::cerr << "mv1 * fv2 = " << dot2 << std::endl; + std::cerr << "mv1.angular * fv2.moment + mv1.linear * fv2.force = " << dot1 << std::endl; + exit(EXIT_FAILURE); + } +} + +int +main(int argc, char** argv) +{ + testEuclideanCrossProduct(); + testMotionVector(); + testForceVector(); + testSpatialCrossProduct(); + testSpatialDotProduct(); + testPlueckerTransform(); + testRigidBodyInertia(); + testArticulatedBodyInertia(); + return EXIT_SUCCESS; +} From 16ebeef7ef09ee8bb8ebc5df56d3181880f39b77 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 17:47:34 +0200 Subject: [PATCH 076/546] Fix shadowed template parameter --- src/rl/math/spatial/PlueckerTransform.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rl/math/spatial/PlueckerTransform.h b/src/rl/math/spatial/PlueckerTransform.h index 7f140201..c631b1e2 100644 --- a/src/rl/math/spatial/PlueckerTransform.h +++ b/src/rl/math/spatial/PlueckerTransform.h @@ -74,8 +74,8 @@ namespace rl { } - template - PlueckerTransform(const ::Eigen::Transform& other) : + template + PlueckerTransform(const ::Eigen::Transform& other) : rotationData(other.linear()), translationData(other.translation()) { @@ -139,8 +139,8 @@ namespace rl return res; } - template - PlueckerTransform& operator=(const ::Eigen::Transform& other) + template + PlueckerTransform& operator=(const ::Eigen::Transform& other) { rotation() = other.linear(); translation() = other.translation(); From 85db57908546241040ab5fad0193b6c161e76342 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 19:18:41 +0200 Subject: [PATCH 077/546] Add static Identity and Zero functions to spatial classes --- src/rl/math/spatial/ArticulatedBodyInertia.h | 14 ++++++++++++++ src/rl/math/spatial/ForceVector.h | 7 +++++++ src/rl/math/spatial/MotionVector.h | 7 +++++++ src/rl/math/spatial/PlueckerTransform.h | 7 +++++++ src/rl/math/spatial/RigidBodyInertia.h | 14 ++++++++++++++ 5 files changed, 49 insertions(+) diff --git a/src/rl/math/spatial/ArticulatedBodyInertia.h b/src/rl/math/spatial/ArticulatedBodyInertia.h index ae6195bf..255ac11d 100644 --- a/src/rl/math/spatial/ArticulatedBodyInertia.h +++ b/src/rl/math/spatial/ArticulatedBodyInertia.h @@ -80,6 +80,20 @@ namespace rl { } + static ArticulatedBodyInertia Identity() + { + ArticulatedBodyInertia res; + res.setIdentity(); + return res; + } + + static ArticulatedBodyInertia Zero() + { + ArticulatedBodyInertia res; + res.setZero(); + return res; + } + CenterOfGravityType& cog() { return centerOfGravityData; diff --git a/src/rl/math/spatial/ForceVector.h b/src/rl/math/spatial/ForceVector.h index 46232ec1..78451a1d 100644 --- a/src/rl/math/spatial/ForceVector.h +++ b/src/rl/math/spatial/ForceVector.h @@ -75,6 +75,13 @@ namespace rl { } + static ForceVector Zero() + { + ForceVector res; + res.setZero(); + return res; + } + template Scalar dot(const MotionVector& other) const; diff --git a/src/rl/math/spatial/MotionVector.h b/src/rl/math/spatial/MotionVector.h index 710993ff..57e9e65e 100644 --- a/src/rl/math/spatial/MotionVector.h +++ b/src/rl/math/spatial/MotionVector.h @@ -76,6 +76,13 @@ namespace rl { } + static MotionVector Zero() + { + MotionVector res; + res.setZero(); + return res; + } + AngularType angular() { return data.template segment<3>(0); diff --git a/src/rl/math/spatial/PlueckerTransform.h b/src/rl/math/spatial/PlueckerTransform.h index c631b1e2..46e072be 100644 --- a/src/rl/math/spatial/PlueckerTransform.h +++ b/src/rl/math/spatial/PlueckerTransform.h @@ -85,6 +85,13 @@ namespace rl { } + static PlueckerTransform Identity() + { + PlueckerTransform res; + res.setIdentity(); + return res; + } + PlueckerTransform inverse() const { PlueckerTransform res; diff --git a/src/rl/math/spatial/RigidBodyInertia.h b/src/rl/math/spatial/RigidBodyInertia.h index 696751de..03f95be0 100644 --- a/src/rl/math/spatial/RigidBodyInertia.h +++ b/src/rl/math/spatial/RigidBodyInertia.h @@ -80,6 +80,20 @@ namespace rl { } + static RigidBodyInertia Identity() + { + RigidBodyInertia res; + res.setIdentity(); + return res; + } + + static RigidBodyInertia Zero() + { + RigidBodyInertia res; + res.setZero(); + return res; + } + CenterOfGravityType& cog() { return centerOfGravityData; From 51cb9846a9f9ff920e0084696dac856e99823f33 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 19:19:27 +0200 Subject: [PATCH 078/546] Add DiagonalMatrix typedef --- src/rl/math/Matrix.h | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/rl/math/Matrix.h b/src/rl/math/Matrix.h index 08349371..7cd8b9e7 100644 --- a/src/rl/math/Matrix.h +++ b/src/rl/math/Matrix.h @@ -112,6 +112,16 @@ namespace rl typedef ::Eigen::Ref MatrixRef; typedef ::Eigen::Ref ConstMatrixRef; + + typedef ::Eigen::DiagonalMatrix DiagonalMatrix; + + typedef ::Eigen::DiagonalMatrix DiagonalMatrix22; + + typedef ::Eigen::DiagonalMatrix DiagonalMatrix33; + + typedef ::Eigen::DiagonalMatrix DiagonalMatrix44; + + typedef ::Eigen::DiagonalMatrix DiagonalMatrix66; } } From 083562901aa55017b53adf97abcab098b6e95037 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 19:21:56 +0200 Subject: [PATCH 079/546] Add static GaussianRandom and UniformRandom functions to Quaternion --- src/rl/math/QuaternionBaseAddons.h | 47 ++++++++++++++++++++++++++---- 1 file changed, 41 insertions(+), 6 deletions(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index b8b297bb..cf629ce8 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -31,6 +31,33 @@ namespace Eigen { template class QuaternionBase { #endif +template +static Quaternion GaussianRandom(const QuaternionBase& mean, const MatrixBase& sigma) +{ + return GaussianRandom(Vector3::Random(), mean, sigma); +} + +template +static Quaternion GaussianRandom(const MatrixBase& rand, const QuaternionBase& mean, const MatrixBase& sigma) +{ + Quaternion q; + q.setFromGaussian(rand, mean, sigma); + return q; +} + +static Quaternion UniformRandom() +{ + return UniformRandom(Vector3::Random()); +} + +template +static Quaternion UniformRandom(const MatrixBase& rand) +{ + Quaternion q; + q.setFromUniform(rand); + return q; +} + template Vector3 angularVelocity(const QuaternionBase& qd) const @@ -71,9 +98,11 @@ exp() const return q; } +template Quaternion -firstDerivative(const Vector3& omega) const +firstDerivative(const MatrixBase& omega) const { + eigen_assert(3 == omega.size()); return (Quaternion(Scalar(0), omega.x(), omega.y(), omega.z()) * this->derived()) * Scalar(0.5); } @@ -146,10 +175,12 @@ pow(const Scalar& t) const return (this->derived().log() * Scalar(t)).exp(); } -template +template Quaternion -secondDerivative(const QuaternionBase& qd, const Vector3& omega, const Vector3& omegad) const +secondDerivative(const QuaternionBase& qd, const MatrixBase& omega, const MatrixBase& omegad) const { + eigen_assert(3 == omega.size()); + eigen_assert(3 == omegad.size()); return (Quaternion(Scalar(0), omegad.x(), omegad.y(), omegad.z()) * this->derived() + Quaternion(Scalar(0), omega.x(), omega.y(), omega.z()) * qd) * Scalar(0.5); } @@ -162,10 +193,12 @@ secondDerivative(const QuaternionBase& qd, const Vector3& omega, c * * http://characters.media.mit.edu/Theses/johnson_phd.pdf */ -template +template void -setFromGaussian(const Vector3& rand, const QuaternionBase& mean, const Vector3& sigma) +setFromGaussian(const MatrixBase& rand, const QuaternionBase& mean, const MatrixBase& sigma) { + eigen_assert(3 == rand.size()); + eigen_assert(3 == sigma.size()); eigen_assert(rand(0) >= Scalar(0)); eigen_assert(rand(0) <= Scalar(1)); eigen_assert(rand(1) >= Scalar(0)); @@ -189,13 +222,15 @@ setFromGaussian(const Vector3& rand, const QuaternionBase& mean, c * * https://doi.org/10.1109/ROBOT.2004.1308895 */ +template void -setFromUniform(const Vector3& rand) +setFromUniform(const MatrixBase& rand) { using ::std::cos; using ::std::sin; using ::std::sqrt; + eigen_assert(3 == rand.size()); eigen_assert(rand(0) >= Scalar(0)); eigen_assert(rand(0) <= Scalar(1)); eigen_assert(rand(1) >= Scalar(0)); From a41bf99aaebf59a43cb043a39ab920b7889ba74c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 19:22:23 +0200 Subject: [PATCH 080/546] Support older Eigen versions in rlSpatialTest --- tests/rlSpatialTest/rlSpatialTest.cpp | 38 ++++++++++----------------- 1 file changed, 14 insertions(+), 24 deletions(-) diff --git a/tests/rlSpatialTest/rlSpatialTest.cpp b/tests/rlSpatialTest/rlSpatialTest.cpp index b2134b03..7ef3e85e 100644 --- a/tests/rlSpatialTest/rlSpatialTest.cpp +++ b/tests/rlSpatialTest/rlSpatialTest.cpp @@ -38,12 +38,12 @@ testArticulatedBodyInertia() rl::math::ArticulatedBodyInertia abi1; abi1.cog().setRandom(); abi1.inertia().setRandom(); - abi1.mass() = rl::math::Vector3::Random().asDiagonal(); + abi1.mass() = rl::math::DiagonalMatrix33(rl::math::Vector3::Random()); rl::math::ArticulatedBodyInertia abi2; abi2.cog().setRandom(); abi2.inertia().setRandom(); - abi2.mass() = rl::math::Vector3::Random().asDiagonal(); + abi2.mass() = rl::math::DiagonalMatrix33(rl::math::Vector3::Random()); rl::math::ArticulatedBodyInertia abi3 = abi1 + abi2; rl::math::ArticulatedBodyInertia abi4 = abi3 - abi2; @@ -77,7 +77,7 @@ testArticulatedBodyInertia() } rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Quaternion::UnitRandom().toRotationMatrix(); + pt1.rotation() = rl::math::Rotation(rl::math::Quaternion::UniformRandom()); pt1.translation().setRandom(); rl::math::ArticulatedBodyInertia abi5 = pt1 * abi1; @@ -143,7 +143,7 @@ testEuclideanCrossProduct() exit(EXIT_FAILURE); } - rl::math::Rotation r = rl::math::Quaternion::UnitRandom().toRotationMatrix(); + rl::math::Rotation r = rl::math::Rotation(rl::math::Quaternion::UniformRandom()); rl::math::Matrix33 m3a = (r * a).cross33(); rl::math::Matrix33 m3b = r * a.cross33() * r.transpose(); @@ -414,7 +414,7 @@ void testPlueckerTransform() { rl::math::Transform t0; - t0 = rl::math::Quaternion::UnitRandom(); + t0 = rl::math::Quaternion::UniformRandom(); t0.translation().setRandom(); rl::math::PlueckerTransform pt0; @@ -432,7 +432,7 @@ testPlueckerTransform() } rl::math::Transform t1; - t1 = rl::math::Quaternion::UnitRandom(); + t1 = rl::math::Quaternion::UniformRandom(); t1.translation().setRandom(); rl::math::PlueckerTransform pt1(t1); @@ -448,7 +448,7 @@ testPlueckerTransform() } rl::math::Transform t2; - t2 = rl::math::Quaternion::UnitRandom(); + t2 = rl::math::Quaternion::UniformRandom(); t2.translation().setRandom(); rl::math::PlueckerTransform pt2 = t2; @@ -550,9 +550,7 @@ testPlueckerTransform() v1.setRandom(); { - rl::math::MotionVector mv1; - mv1.angular() << v1.head<3>(); - mv1.linear() << v1.tail<3>(); + rl::math::MotionVector mv1 = v1; rl::math::Vector6 v2 = pt1.matrixMotion() * v1; rl::math::MotionVector mv2 = pt1 * mv1; @@ -596,9 +594,7 @@ testPlueckerTransform() } { - rl::math::ForceVector fv1; - fv1.moment() << v1.head<3>(); - fv1.force() << v1.tail<3>(); + rl::math::ForceVector fv1 = v1; rl::math::Vector6 v2 = pt1.matrixForce() * v1; rl::math::ForceVector fv2 = pt1 * fv1; @@ -687,7 +683,7 @@ testRigidBodyInertia() } rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Quaternion::UnitRandom().toRotationMatrix(); + pt1.rotation() = rl::math::Rotation(rl::math::Quaternion::UniformRandom()); pt1.translation().setRandom(); rl::math::RigidBodyInertia rbi5 = pt1 * rbi1; @@ -731,13 +727,9 @@ testSpatialCrossProduct() rl::math::Vector6 v2; v2.setRandom(); - rl::math::MotionVector mv1; - mv1.angular() << v1.head<3>(); - mv1.linear() << v1.tail<3>(); + rl::math::MotionVector mv1 = v1; - rl::math::MotionVector mv2; - mv2.angular() << v2.head<3>(); - mv2.linear() << v2.tail<3>(); + rl::math::MotionVector mv2 = v2; rl::math::Vector6 v3 = mv1.cross66Motion() * v2; rl::math::MotionVector mv3 = mv1.cross(mv2); @@ -760,9 +752,7 @@ testSpatialCrossProduct() exit(EXIT_FAILURE); } - rl::math::ForceVector fv2; - fv2.moment() << v2.head<3>(); - fv2.force() << v2.tail<3>(); + rl::math::ForceVector fv2 = v2; rl::math::Vector6 v5 = mv1.cross66Force() * v2; rl::math::ForceVector fv5 = mv1.cross(fv2); @@ -808,7 +798,7 @@ testSpatialCrossProduct() } rl::math::PlueckerTransform pt; - pt.rotation() = rl::math::Quaternion::UnitRandom().toRotationMatrix(); + pt.rotation() = rl::math::Rotation(rl::math::Quaternion::UniformRandom()); pt.translation().setRandom(); rl::math::Matrix66 m1 = (pt * mv1).cross66Motion(); From 68eca9c16707647b07a4078e71066b5edca0b1ce Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 21:17:47 +0200 Subject: [PATCH 081/546] Optimize static Identity and Zero functions for spatial classes --- src/rl/math/spatial/ArticulatedBodyInertia.h | 23 +++++++++++++++----- src/rl/math/spatial/ForceVector.h | 4 +--- src/rl/math/spatial/MotionVector.h | 4 +--- src/rl/math/spatial/PlueckerTransform.h | 13 ++++++++--- src/rl/math/spatial/RigidBodyInertia.h | 23 +++++++++++++++----- 5 files changed, 46 insertions(+), 21 deletions(-) diff --git a/src/rl/math/spatial/ArticulatedBodyInertia.h b/src/rl/math/spatial/ArticulatedBodyInertia.h index 255ac11d..499732f2 100644 --- a/src/rl/math/spatial/ArticulatedBodyInertia.h +++ b/src/rl/math/spatial/ArticulatedBodyInertia.h @@ -68,6 +68,13 @@ namespace rl { } + ArticulatedBodyInertia(const CenterOfGravityType& centerOfGravity, const InertiaType& inertia, const MassType& mass) : + centerOfGravityData(centerOfGravity), + inertiaData(inertia), + massData(mass) + { + } + template ArticulatedBodyInertia(const ::Eigen::DenseBase& other) : centerOfGravityData(other.template topRightCorner<3, 3>()), @@ -82,16 +89,20 @@ namespace rl static ArticulatedBodyInertia Identity() { - ArticulatedBodyInertia res; - res.setIdentity(); - return res; + return ArticulatedBodyInertia( + CenterOfGravityType::Identity(), + InertiaType::Identity(), + MassType::Identity() + ); } static ArticulatedBodyInertia Zero() { - ArticulatedBodyInertia res; - res.setZero(); - return res; + return ArticulatedBodyInertia( + CenterOfGravityType::Zero(), + InertiaType::Zero(), + MassType::Zero() + ); } CenterOfGravityType& cog() diff --git a/src/rl/math/spatial/ForceVector.h b/src/rl/math/spatial/ForceVector.h index 78451a1d..a9b385ef 100644 --- a/src/rl/math/spatial/ForceVector.h +++ b/src/rl/math/spatial/ForceVector.h @@ -77,9 +77,7 @@ namespace rl static ForceVector Zero() { - ForceVector res; - res.setZero(); - return res; + return ForceVector(MatrixType::Zero()); } template diff --git a/src/rl/math/spatial/MotionVector.h b/src/rl/math/spatial/MotionVector.h index 57e9e65e..7db92aa2 100644 --- a/src/rl/math/spatial/MotionVector.h +++ b/src/rl/math/spatial/MotionVector.h @@ -78,9 +78,7 @@ namespace rl static MotionVector Zero() { - MotionVector res; - res.setZero(); - return res; + return MotionVector(MatrixType::Zero()); } AngularType angular() diff --git a/src/rl/math/spatial/PlueckerTransform.h b/src/rl/math/spatial/PlueckerTransform.h index 46e072be..83871579 100644 --- a/src/rl/math/spatial/PlueckerTransform.h +++ b/src/rl/math/spatial/PlueckerTransform.h @@ -74,6 +74,12 @@ namespace rl { } + PlueckerTransform(const RotationType& rotation, const TranslationType& translation) : + rotationData(rotation), + translationData(translation) + { + } + template PlueckerTransform(const ::Eigen::Transform& other) : rotationData(other.linear()), @@ -87,9 +93,10 @@ namespace rl static PlueckerTransform Identity() { - PlueckerTransform res; - res.setIdentity(); - return res; + return PlueckerTransform( + RotationType::Identity(), + TransformType::Zero() + ); } PlueckerTransform inverse() const diff --git a/src/rl/math/spatial/RigidBodyInertia.h b/src/rl/math/spatial/RigidBodyInertia.h index 03f95be0..534ec130 100644 --- a/src/rl/math/spatial/RigidBodyInertia.h +++ b/src/rl/math/spatial/RigidBodyInertia.h @@ -68,6 +68,13 @@ namespace rl { } + RigidBodyInertia(const CenterOfGravityType& centerOfGravity, const InertiaType& inertia, const MassType& mass) : + centerOfGravityData(centerOfGravity), + inertiaData(inertia), + massData(mass) + { + } + template RigidBodyInertia(const ::Eigen::DenseBase& other) : centerOfGravityData(other.template topRightCorner<3, 3>().cross3()), @@ -82,16 +89,20 @@ namespace rl static RigidBodyInertia Identity() { - RigidBodyInertia res; - res.setIdentity(); - return res; + return RigidBodyInertia( + CenterOfGravityType::Zero(), + InertiaType::Identity(), + 1 + ); } static RigidBodyInertia Zero() { - RigidBodyInertia res; - res.setZero(); - return res; + return RigidBodyInertia( + CenterOfGravityType::Zero(), + InertiaType::Zero(), + 0 + ); } CenterOfGravityType& cog() From b61880f49a0d3db4b9f2cc1e5561272c45a1c490 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 21:20:45 +0200 Subject: [PATCH 082/546] Remove Rotation typedef --- demos/rlRotationConverterDemo/MainWindow.cpp | 4 ++-- demos/rlRotationConverterDemo/MainWindow.h | 4 ++-- .../rlRotationConverterDemo/RotationMatrixModel.h | 2 +- src/rl/math/Rotation.h | 14 -------------- tests/rlSpatialTest/rlSpatialTest.cpp | 8 ++++---- 5 files changed, 9 insertions(+), 23 deletions(-) diff --git a/demos/rlRotationConverterDemo/MainWindow.cpp b/demos/rlRotationConverterDemo/MainWindow.cpp index 6e964127..b1d8a32d 100644 --- a/demos/rlRotationConverterDemo/MainWindow.cpp +++ b/demos/rlRotationConverterDemo/MainWindow.cpp @@ -57,7 +57,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputQuaternionGroupBox(new GroupBox(this)), inputQuaternionModel(new QuaternionModel(this)), inputQuaternionTableView(new TableView(this)), - inputRotationMatrix(rl::math::Rotation::Identity()), + inputRotationMatrix(rl::math::Matrix33::Identity()), inputRotationMatrixGroupBox(new GroupBox(this)), inputRotationMatrixModel(new RotationMatrixModel(this)), inputRotationMatrixTableView(new TableView(this)), @@ -70,7 +70,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputPrecision(8), outputQuaternion(rl::math::Quaternion::Identity()), outputQuaternionModel(new QuaternionModel(this)), - outputRotationMatrix(rl::math::Rotation::Identity()), + outputRotationMatrix(rl::math::Matrix33::Identity()), outputRotationMatrixModel(new RotationMatrixModel(this)), outputUnitRadians(false) { diff --git a/demos/rlRotationConverterDemo/MainWindow.h b/demos/rlRotationConverterDemo/MainWindow.h index 5ee6cebd..9e2c590f 100644 --- a/demos/rlRotationConverterDemo/MainWindow.h +++ b/demos/rlRotationConverterDemo/MainWindow.h @@ -121,7 +121,7 @@ public slots: TableView* inputQuaternionTableView; - rl::math::Rotation inputRotationMatrix; + rl::math::Matrix33 inputRotationMatrix; GroupBox* inputRotationMatrixGroupBox; @@ -147,7 +147,7 @@ public slots: QuaternionModel* outputQuaternionModel; - rl::math::Rotation outputRotationMatrix; + rl::math::Matrix33 outputRotationMatrix; RotationMatrixModel* outputRotationMatrixModel; diff --git a/demos/rlRotationConverterDemo/RotationMatrixModel.h b/demos/rlRotationConverterDemo/RotationMatrixModel.h index aee8c0aa..7bee1124 100644 --- a/demos/rlRotationConverterDemo/RotationMatrixModel.h +++ b/demos/rlRotationConverterDemo/RotationMatrixModel.h @@ -53,7 +53,7 @@ class RotationMatrixModel : public QAbstractTableModel bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); - rl::math::Rotation* rotation; + rl::math::Matrix33* rotation; protected: diff --git a/src/rl/math/Rotation.h b/src/rl/math/Rotation.h index 206debff..e3120246 100644 --- a/src/rl/math/Rotation.h +++ b/src/rl/math/Rotation.h @@ -39,20 +39,6 @@ namespace rl { namespace math { - typedef Matrix33 Rotation; - - typedef Matrix33Block RotationBlock; - - typedef Matrix33Column RotationColumn; - - typedef Matrix33Row RotationRow; - - typedef ConstMatrix33Block ConstRotationBlock; - - typedef ConstMatrix33Column ConstRotationColumn; - - typedef ConstMatrix33Row ConstRotationRow; - typedef ::Eigen::AngleAxis AngleAxis; } } diff --git a/tests/rlSpatialTest/rlSpatialTest.cpp b/tests/rlSpatialTest/rlSpatialTest.cpp index 7ef3e85e..b74fc157 100644 --- a/tests/rlSpatialTest/rlSpatialTest.cpp +++ b/tests/rlSpatialTest/rlSpatialTest.cpp @@ -77,7 +77,7 @@ testArticulatedBodyInertia() } rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Rotation(rl::math::Quaternion::UniformRandom()); + pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::UniformRandom()); pt1.translation().setRandom(); rl::math::ArticulatedBodyInertia abi5 = pt1 * abi1; @@ -143,7 +143,7 @@ testEuclideanCrossProduct() exit(EXIT_FAILURE); } - rl::math::Rotation r = rl::math::Rotation(rl::math::Quaternion::UniformRandom()); + rl::math::Matrix33 r = rl::math::Matrix33(rl::math::Quaternion::UniformRandom()); rl::math::Matrix33 m3a = (r * a).cross33(); rl::math::Matrix33 m3b = r * a.cross33() * r.transpose(); @@ -683,7 +683,7 @@ testRigidBodyInertia() } rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Rotation(rl::math::Quaternion::UniformRandom()); + pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::UniformRandom()); pt1.translation().setRandom(); rl::math::RigidBodyInertia rbi5 = pt1 * rbi1; @@ -798,7 +798,7 @@ testSpatialCrossProduct() } rl::math::PlueckerTransform pt; - pt.rotation() = rl::math::Rotation(rl::math::Quaternion::UniformRandom()); + pt.rotation() = rl::math::Matrix33(rl::math::Quaternion::UniformRandom()); pt.translation().setRandom(); rl::math::Matrix66 m1 = (pt * mv1).cross66Motion(); From ec4bd9a4e62e559fcebc147d925c668c9cb0d5f8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 21:21:43 +0200 Subject: [PATCH 083/546] Rename Quaternion UniformRandom and GaussianRandom functions --- demos/rlQuaternionDemo/rlQuaternionDemo.cpp | 6 +- src/rl/math/QuaternionBaseAddons.h | 167 +++++++++++--------- src/rl/mdl/Spherical.cpp | 8 +- src/rl/plan/Eet.cpp | 5 +- tests/rlSpatialTest/rlSpatialTest.cpp | 14 +- 5 files changed, 101 insertions(+), 99 deletions(-) diff --git a/demos/rlQuaternionDemo/rlQuaternionDemo.cpp b/demos/rlQuaternionDemo/rlQuaternionDemo.cpp index b6935547..d6116933 100644 --- a/demos/rlQuaternionDemo/rlQuaternionDemo.cpp +++ b/demos/rlQuaternionDemo/rlQuaternionDemo.cpp @@ -296,7 +296,6 @@ main(int argc, char** argv) rl::math::Vector3 point(0, 0, 1); std::function rand = std::bind(std::uniform_real_distribution(0.0, 1.0), std::mt19937(0)); - rl::math::Quaternion uniform; // splot "uniformQuaternions.dat" using 2:3:4 std::ofstream uniformQuaternions; @@ -304,7 +303,7 @@ main(int argc, char** argv) for (std::size_t i = 0; i < 10000; ++i) { - uniform.setFromUniform(rl::math::Vector3(rand(), rand(), rand())); + rl::math::Quaternion uniform = rl::math::Quaternion::Random(rl::math::Vector3(rand(), rand(), rand())); rl::math::Vector3 rotated = uniform._transformVector(point); uniformQuaternions << i << "\t" << rotated.transpose() << std::endl; } @@ -312,7 +311,6 @@ main(int argc, char** argv) uniformQuaternions.close(); std::function gauss = std::bind(std::normal_distribution(0.0, 1.0), std::mt19937(0)); - rl::math::Quaternion normal; // splot "normalQuaternions.dat" using 2:3:4 std::ofstream normalQuaternions; @@ -320,7 +318,7 @@ main(int argc, char** argv) for (std::size_t i = 0; i < 10000; ++i) { - normal.setFromGaussian(rl::math::Vector3(gauss(), gauss(), gauss()), rl::math::Quaternion::Identity(), rl::math::Vector3(0.25, 0.125, 0.0625)); + rl::math::Quaternion normal = rl::math::Quaternion::Random(rl::math::Vector3(gauss(), gauss(), gauss()), rl::math::Quaternion::Identity(), rl::math::Vector3(0.25, 0.125, 0.0625)); rl::math::Vector3 rotated = normal._transformVector(point); normalQuaternions << i << "\t" << rotated.transpose() << std::endl; } diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index cf629ce8..3675b0e1 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -31,31 +31,80 @@ namespace Eigen { template class QuaternionBase { #endif -template -static Quaternion GaussianRandom(const QuaternionBase& mean, const MatrixBase& sigma) +template +static Quaternion Random(const QuaternionBase& mean, const MatrixBase& sigma) { - return GaussianRandom(Vector3::Random(), mean, sigma); + return Random(Vector3::Random(), mean, sigma); } -template -static Quaternion GaussianRandom(const MatrixBase& rand, const QuaternionBase& mean, const MatrixBase& sigma) +/** + * QuTEM (Quaternion Tangent Ellipsoid at the Mean) sampling algorithm. + * + * Michael Patrick Johnson. Exploiting Quaternions to Support Expressive + * Interactive Character Motion. PhD Thesis, Massachusetts Institute of + * Technology, Cambridge, MA, USA, February 2003. + * + * http://characters.media.mit.edu/Theses/johnson_phd.pdf + */ +template +static Quaternion Random(const MatrixBase& rand, const QuaternionBase& mean, const MatrixBase& sigma) { - Quaternion q; - q.setFromGaussian(rand, mean, sigma); - return q; + eigen_assert(3 == rand.size()); + eigen_assert(3 == sigma.size()); + eigen_assert(rand(0) >= Scalar(0)); + eigen_assert(rand(0) <= Scalar(1)); + eigen_assert(rand(1) >= Scalar(0)); + eigen_assert(rand(1) <= Scalar(1)); + eigen_assert(rand(2) >= Scalar(0)); + eigen_assert(rand(2) <= Scalar(1)); + + Quaternion tmp; + tmp.w() = rand.norm(); + tmp.vec() = sigma.cwiseProduct(rand); + + return mean * tmp.exp(); } -static Quaternion UniformRandom() +static Quaternion Random() { - return UniformRandom(Vector3::Random()); + return Random(Vector3::Random()); } -template -static Quaternion UniformRandom(const MatrixBase& rand) +/** + * Generate uniformly-distributed random unit quaternions. + * + * James J. Kuffner. Effective Sampling and Distance Metrics for 3D Rigid Body + * Path Planning. Proceedings of the IEEE International Conference on Robotics + * and Automation, pages 3993-3998. New Orleans, LA, USA, April 2004. + * + * https://doi.org/10.1109/ROBOT.2004.1308895 + */ +template +static Quaternion Random(const MatrixBase& rand) { - Quaternion q; - q.setFromUniform(rand); - return q; + using ::std::cos; + using ::std::sin; + using ::std::sqrt; + + eigen_assert(3 == rand.size()); + eigen_assert(rand(0) >= Scalar(0)); + eigen_assert(rand(0) <= Scalar(1)); + eigen_assert(rand(1) >= Scalar(0)); + eigen_assert(rand(1) <= Scalar(1)); + eigen_assert(rand(2) >= Scalar(0)); + eigen_assert(rand(2) <= Scalar(1)); + + Scalar sigma1 = sqrt(Scalar(1) - rand(0)); + Scalar sigma2 = sqrt(rand(0)); + Scalar theta1 = Scalar(2 * M_PI) * rand(1); + Scalar theta2 = Scalar(2 * M_PI) * rand(2); + + return Quaternion( + cos(theta2) * sigma2, + sin(theta1) * sigma1, + cos(theta1) * sigma1, + sin(theta2) * sigma2 + ); } template @@ -98,9 +147,9 @@ exp() const return q; } -template +template Quaternion -firstDerivative(const MatrixBase& omega) const +firstDerivative(const MatrixBase& omega) const { eigen_assert(3 == omega.size()); return (Quaternion(Scalar(0), omega.x(), omega.y(), omega.z()) * this->derived()) * Scalar(0.5); @@ -175,78 +224,40 @@ pow(const Scalar& t) const return (this->derived().log() * Scalar(t)).exp(); } -template +template Quaternion -secondDerivative(const QuaternionBase& qd, const MatrixBase& omega, const MatrixBase& omegad) const +secondDerivative(const QuaternionBase& qd, const MatrixBase& omega, const MatrixBase& omegad) const { eigen_assert(3 == omega.size()); eigen_assert(3 == omegad.size()); return (Quaternion(Scalar(0), omegad.x(), omegad.y(), omegad.z()) * this->derived() + Quaternion(Scalar(0), omega.x(), omega.y(), omega.z()) * qd) * Scalar(0.5); } -/** - * QuTEM (Quaternion Tangent Ellipsoid at the Mean) sampling algorithm. - * - * Michael Patrick Johnson. Exploiting Quaternions to Support Expressive - * Interactive Character Motion. PhD Thesis, Massachusetts Institute of - * Technology, Cambridge, MA, USA, February 2003. - * - * http://characters.media.mit.edu/Theses/johnson_phd.pdf - */ -template -void -setFromGaussian(const MatrixBase& rand, const QuaternionBase& mean, const MatrixBase& sigma) +Derived& +setRandom() { - eigen_assert(3 == rand.size()); - eigen_assert(3 == sigma.size()); - eigen_assert(rand(0) >= Scalar(0)); - eigen_assert(rand(0) <= Scalar(1)); - eigen_assert(rand(1) >= Scalar(0)); - eigen_assert(rand(1) <= Scalar(1)); - eigen_assert(rand(2) >= Scalar(0)); - eigen_assert(rand(2) <= Scalar(1)); - - Quaternion tmp; - tmp.w() = rand.norm(); - tmp.vec() = sigma.cwiseProduct(rand); - - this->derived() = mean * tmp.exp(); + return this->derived() = Random(); } -/** - * Generate uniformly-distributed random unit quaternions. - * - * James J. Kuffner. Effective Sampling and Distance Metrics for 3D Rigid Body - * Path Planning. Proceedings of the IEEE International Conference on Robotics - * and Automation, pages 3993-3998. New Orleans, LA, USA, April 2004. - * - * https://doi.org/10.1109/ROBOT.2004.1308895 - */ -template -void -setFromUniform(const MatrixBase& rand) +template +Derived& +setRandom(const MatrixBase& rand) { - using ::std::cos; - using ::std::sin; - using ::std::sqrt; - - eigen_assert(3 == rand.size()); - eigen_assert(rand(0) >= Scalar(0)); - eigen_assert(rand(0) <= Scalar(1)); - eigen_assert(rand(1) >= Scalar(0)); - eigen_assert(rand(1) <= Scalar(1)); - eigen_assert(rand(2) >= Scalar(0)); - eigen_assert(rand(2) <= Scalar(1)); - - Scalar sigma1 = sqrt(Scalar(1) - rand(0)); - Scalar sigma2 = sqrt(rand(0)); - Scalar theta1 = Scalar(2 * M_PI) * rand(1); - Scalar theta2 = Scalar(2 * M_PI) * rand(2); - - this->derived().x() = sin(theta1) * sigma1; - this->derived().y() = cos(theta1) * sigma1; - this->derived().z() = sin(theta2) * sigma2; - this->derived().w() = cos(theta2) * sigma2; + return this->derived() = Random(rand); +} + +template +Derived& +setRandom(const QuaternionBase& mean, const MatrixBase& sigma) +{ + return this->derived() = Random(mean, sigma); +} + +template +Derived& +setRandom(const MatrixBase& rand, const QuaternionBase& mean, const MatrixBase& sigma) +{ + return this->derived() = Random(rand, mean, sigma); } template diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 496101f7..0662c2ee 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -77,17 +77,13 @@ namespace rl ::rl::math::Vector Spherical::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma) const { - ::rl::math::Quaternion quaternion; - quaternion.setFromGaussian(rand, ::Eigen::Map< const ::rl::math::Quaternion>(mean.data()), sigma); - return quaternion.coeffs(); + return ::rl::math::Quaternion::Random(rand, ::Eigen::Map< const ::rl::math::Quaternion>(mean.data()), sigma).coeffs(); } ::rl::math::Vector Spherical::generatePositionUniform(const ::rl::math::ConstVectorRef& rand) const { - ::rl::math::Quaternion quaternion; - quaternion.setFromUniform(rand); - return quaternion.coeffs(); + return ::rl::math::Quaternion::Random(rand).coeffs(); } void diff --git a/src/rl/plan/Eet.cpp b/src/rl/plan/Eet.cpp index 15378e9b..4bbf7bee 100644 --- a/src/rl/plan/Eet.cpp +++ b/src/rl/plan/Eet.cpp @@ -403,8 +403,6 @@ namespace rl ::rl::math::Transform chosen; chosen.setIdentity(); - ::rl::math::Quaternion quaternion; - this->model->setPosition(*this->goal); this->model->updateFrames(); ::rl::math::Transform goal = this->model->forwardPosition(); @@ -439,8 +437,7 @@ namespace rl // uniform sampling for orientation - quaternion.setFromUniform(::rl::math::Vector3(this->rand(), this->rand(), this->rand())); - chosen.linear() = quaternion.toRotationMatrix(); + chosen.linear() = ::rl::math::Matrix33(::rl::math::Quaternion::Random(::rl::math::Vector3(this->rand(), this->rand(), this->rand()))); nearest = this->nearest(this->tree[0], chosen); // nearest vertex in tree diff --git a/tests/rlSpatialTest/rlSpatialTest.cpp b/tests/rlSpatialTest/rlSpatialTest.cpp index b74fc157..9d32dc6b 100644 --- a/tests/rlSpatialTest/rlSpatialTest.cpp +++ b/tests/rlSpatialTest/rlSpatialTest.cpp @@ -77,7 +77,7 @@ testArticulatedBodyInertia() } rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::UniformRandom()); + pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); pt1.translation().setRandom(); rl::math::ArticulatedBodyInertia abi5 = pt1 * abi1; @@ -143,7 +143,7 @@ testEuclideanCrossProduct() exit(EXIT_FAILURE); } - rl::math::Matrix33 r = rl::math::Matrix33(rl::math::Quaternion::UniformRandom()); + rl::math::Matrix33 r = rl::math::Matrix33(rl::math::Quaternion::Random()); rl::math::Matrix33 m3a = (r * a).cross33(); rl::math::Matrix33 m3b = r * a.cross33() * r.transpose(); @@ -414,7 +414,7 @@ void testPlueckerTransform() { rl::math::Transform t0; - t0 = rl::math::Quaternion::UniformRandom(); + t0 = rl::math::Quaternion::Random(); t0.translation().setRandom(); rl::math::PlueckerTransform pt0; @@ -432,7 +432,7 @@ testPlueckerTransform() } rl::math::Transform t1; - t1 = rl::math::Quaternion::UniformRandom(); + t1 = rl::math::Quaternion::Random(); t1.translation().setRandom(); rl::math::PlueckerTransform pt1(t1); @@ -448,7 +448,7 @@ testPlueckerTransform() } rl::math::Transform t2; - t2 = rl::math::Quaternion::UniformRandom(); + t2 = rl::math::Quaternion::Random(); t2.translation().setRandom(); rl::math::PlueckerTransform pt2 = t2; @@ -683,7 +683,7 @@ testRigidBodyInertia() } rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::UniformRandom()); + pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); pt1.translation().setRandom(); rl::math::RigidBodyInertia rbi5 = pt1 * rbi1; @@ -798,7 +798,7 @@ testSpatialCrossProduct() } rl::math::PlueckerTransform pt; - pt.rotation() = rl::math::Matrix33(rl::math::Quaternion::UniformRandom()); + pt.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); pt.translation().setRandom(); rl::math::Matrix66 m1 = (pt * mv1).cross66Motion(); From d23dc9b460a128c33fa2b0dd41fd9ec201a6b09b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 21:41:00 +0200 Subject: [PATCH 084/546] Remove rlSpatialDemo --- demos/CMakeLists.txt | 1 - demos/rlSpatialDemo/CMakeLists.txt | 9 - demos/rlSpatialDemo/rlSpatialDemo.cpp | 306 -------------------------- 3 files changed, 316 deletions(-) delete mode 100644 demos/rlSpatialDemo/CMakeLists.txt delete mode 100644 demos/rlSpatialDemo/rlSpatialDemo.cpp diff --git a/demos/CMakeLists.txt b/demos/CMakeLists.txt index bf194a6c..c51ef1c5 100644 --- a/demos/CMakeLists.txt +++ b/demos/CMakeLists.txt @@ -7,7 +7,6 @@ if(BUILD_RL_MATH) add_subdirectory(rlQuaternionDemo) add_subdirectory(rlPolynomialRootsDemo) add_subdirectory(rlRotationConverterDemo) - add_subdirectory(rlSpatialDemo) add_subdirectory(rlTrapezoidalVelocityDemo) endif() diff --git a/demos/rlSpatialDemo/CMakeLists.txt b/demos/rlSpatialDemo/CMakeLists.txt deleted file mode 100644 index 32c866c2..00000000 --- a/demos/rlSpatialDemo/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -add_executable( - rlSpatialDemo - rlSpatialDemo.cpp -) - -target_link_libraries( - rlSpatialDemo - math -) diff --git a/demos/rlSpatialDemo/rlSpatialDemo.cpp b/demos/rlSpatialDemo/rlSpatialDemo.cpp deleted file mode 100644 index aab73b36..00000000 --- a/demos/rlSpatialDemo/rlSpatialDemo.cpp +++ /dev/null @@ -1,306 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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. -// - -#define EIGEN_MATRIXBASE_PLUGIN - -#include -#include - -int -main(int argc, char** argv) -{ - { - rl::math::MotionVector v1; - v1.angular() << 0, 1, 2; - v1.linear() << 3, 4, 5; - std::cout << "v1 = " << v1.matrix().transpose() << std::endl; - v1 = v1.matrix(); - std::cout << "v1 = " << v1.matrix().transpose() << std::endl; - - rl::math::MotionVector v2; - v2.angular() << 0, 1, 2; - v2.linear() << 3, 4, 5; - std::cout << "v2 = " << v2.matrix().transpose() << std::endl; - - rl::math::MotionVector v3; - v3 = v1 + v2; - std::cout << "v3 = " << v3.matrix().transpose() << std::endl; - v3 = v1 + v2 + v1; - std::cout << "v3 = " << v3.matrix().transpose() << std::endl; - v3 = v1 - v2; - std::cout << "v3 = " << v3.matrix().transpose() << std::endl; - v3 = v1 - v2 - v1; - std::cout << "v3 = " << v3.matrix().transpose() << std::endl; - - v3 = v1.cross(v2); - std::cout << "v3 = " << v3.matrix().transpose() << std::endl; - } - - std::cout << std::endl; - - { - rl::math::ForceVector f1; - f1.moment() << 0, 1, 2; - f1.force() << 3, 4, 5; - std::cout << "f1 = " << f1.matrix().transpose() << std::endl; - f1 = f1.matrix(); - std::cout << "f1 = " << f1.matrix().transpose() << std::endl; - - rl::math::ForceVector f2; - f2.moment() << 0, 1, 2; - f2.force() << 3, 4, 5; - std::cout << "f2 = " << f2.matrix().transpose() << std::endl; - - rl::math::ForceVector f3; - f3 = f1 + f2; - std::cout << "f3 = " << f3.matrix().transpose() << std::endl; - f3 = f1 + f2 + f3; - std::cout << "f3 = " << f3.matrix().transpose() << std::endl; - f3 = f1 - f2; - std::cout << "f3 = " << f3.matrix().transpose() << std::endl; - f3 = f1 - f2 - f1; - std::cout << "f3 = " << f3.matrix().transpose() << std::endl; - - rl::math::MotionVector v1; - v1.angular() << 0, 1, 2; - v1.linear() << 3, 4, 5; - - f3 = v1.cross(f2); - std::cout << "f3 = " << f3.matrix().transpose() << std::endl; - - std::cout << v1.dot(f1) << std::endl; - std::cout << f1.dot(v1) << std::endl; - } - - std::cout << std::endl; - - { - rl::math::PlueckerTransform X1; - X1.rotation() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - X1.translation() << 0, 1, 2; - std::cout << "X1.rotation = " << std::endl << X1.rotation() << std::endl; - std::cout << "X1.translation = " << X1.translation().transpose() << std::endl; - std::cout << "X1.matrixMotion = " << std::endl << X1.matrixMotion() << std::endl; - std::cout << "X1.matrixForce = " << std::endl << X1.matrixForce() << std::endl; - std::cout << "X1.inverseMotion = " << std::endl << X1.inverseMotion() << std::endl; - std::cout << "X1.inverseForce = " << std::endl << X1.inverseForce() << std::endl; - std::cout << "X1.transform = " << std::endl << X1.transform().matrix() << std::endl; - - rl::math::PlueckerTransform X2; - X2.rotation() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - X2.translation() << 0, 1, 2; - std::cout << "X2.rotation = " << std::endl << X2.rotation() << std::endl; - std::cout << "X2.translation = " << X2.translation().transpose() << std::endl; - - rl::math::PlueckerTransform X3; - X3 = X1 * X2; - std::cout << "X3.rotation = " << std::endl << X3.rotation() << std::endl; - std::cout << "X3.translation = " << X3.translation().transpose() << std::endl; - - rl::math::MotionVector v1; - v1.angular() << 0, 1, 2; - v1.linear() << 3, 4, 5; - std::cout << "v1 = " << v1.matrix().transpose() << std::endl; - - rl::math::MotionVector v2; - v2 = X1 * v1; - std::cout << "v2 = " << v2.matrix().transpose() << std::endl; - rl::math::MotionVector::MatrixType v2vector; - v2vector = X1.matrixMotion() * v1.matrix(); - std::cout << "v2vector = " << v2vector.transpose() << std::endl; - v2 = X1 / v1; - std::cout << "v2 = " << v2.matrix().transpose() << std::endl; - v2vector = X1.inverseMotion() * v1.matrix(); - std::cout << "v2vector = " << v2vector.transpose() << std::endl; - - rl::math::ForceVector f1; - f1.moment() << 0, 1, 2; - f1.force() << 3, 4, 5; - std::cout << "f1 = " << f1.matrix().transpose() << std::endl; - - rl::math::ForceVector f2; - f2 = X1 * f1; - std::cout << "f2 = " << f2.matrix().transpose() << std::endl; - rl::math::ForceVector::MatrixType f2vector; - f2vector = X1.matrixForce() * f1.matrix(); - std::cout << "f2vector = " << f2vector.transpose() << std::endl; - f2 = X1 / f1; - std::cout << "f2 = " << f2.matrix().transpose() << std::endl; - f2vector = X1.inverseForce() * f1.matrix(); - std::cout << "f2vector = " << f2vector.transpose() << std::endl; - } - - std::cout << std::endl; - - { - rl::math::PlueckerTransform X1; - X1.rotation() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - X1.translation() << 0, 1, 2; - std::cout << "X1.rotation = " << std::endl << X1.rotation() << std::endl; - std::cout << "X1.translation = " << X1.translation().transpose() << std::endl; - - rl::math::RigidBodyInertia I1; - I1.cog() << 0, 1, 2; - I1.inertia() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - I1.mass() = 1; - std::cout << "I1.cog = " << I1.cog().transpose() << std::endl; - std::cout << "I1.inertia = " << std::endl << I1.inertia() << std::endl; - std::cout << "I1.mass = " << I1.mass() << std::endl; - std::cout << "I1.matrix = " << std::endl << I1.matrix() << std::endl; - I1 = I1.matrix(); - std::cout << "I1.matrix = " << std::endl << I1.matrix() << std::endl; - - rl::math::RigidBodyInertia I2; - I2.cog() << 0, 1, 2; - I2.inertia() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - I2.mass() = 1; - - rl::math::RigidBodyInertia I3; - I3 = I1 + I2; - std::cout << "I3.cog = " << I3.cog().transpose() << std::endl; - std::cout << "I3.inertia = " << std::endl << I3.inertia() << std::endl; - std::cout << "I3.mass = " << I3.mass() << std::endl; - I3 = I1 - I2; - std::cout << "I3.cog = " << I3.cog().transpose() << std::endl; - std::cout << "I3.inertia = " << std::endl << I3.inertia() << std::endl; - std::cout << "I3.mass = " << I3.mass() << std::endl; - I3 = I1 * 2; - std::cout << "I3.cog = " << I3.cog().transpose() << std::endl; - std::cout << "I3.inertia = " << std::endl << I3.inertia() << std::endl; - std::cout << "I3.mass = " << I3.mass() << std::endl; - I3 = I1 / 2; - std::cout << "I3.cog = " << I3.cog().transpose() << std::endl; - std::cout << "I3.inertia = " << std::endl << I3.inertia() << std::endl; - std::cout << "I3.mass = " << I3.mass() << std::endl; - - I2 = X1 * I1; - std::cout << "I2.cog = " << I2.cog().transpose() << std::endl; - std::cout << "I2.inertia = " << std::endl << I2.inertia() << std::endl; - std::cout << "I2.mass = " << I2.mass() << std::endl; - std::cout << "I2.matrix = " << std::endl << I2.matrix() << std::endl; - rl::math::RigidBodyInertia::MatrixType I2matrix; - I2matrix = X1.matrixForce() * I1.matrix() * X1.inverseMotion(); - std::cout << "I2matrix = " << std::endl << I2matrix << std::endl; - - I2 = X1 / I1; - std::cout << "I2.cog = " << I2.cog().transpose() << std::endl; - std::cout << "I2.inertia = " << std::endl << I2.inertia() << std::endl; - std::cout << "I2.mass = " << I2.mass() << std::endl; - std::cout << "I2.matrix = " << std::endl << I2.matrix() << std::endl; - I2matrix = X1.inverseForce() * I1.matrix() * X1.matrixMotion(); - std::cout << "I2matrix = " << std::endl << I2matrix << std::endl; - - rl::math::MotionVector v1; - v1.angular() << 0, 1, 2; - v1.linear() << 3, 4, 5; - std::cout << "v1 = " << v1.matrix().transpose() << std::endl; - - rl::math::ForceVector f1; - f1 = I1 * v1; - std::cout << "f1 = " << f1.matrix().transpose() << std::endl; - } - - std::cout << std::endl; - - { - rl::math::PlueckerTransform X1; - X1.rotation() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - X1.translation() << 0, 1, 2; - std::cout << "X1.rotation = " << std::endl << X1.rotation() << std::endl; - std::cout << "X1.translation = " << X1.translation().transpose() << std::endl; - - rl::math::ArticulatedBodyInertia IA1; - IA1.cog() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - IA1.inertia() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - IA1.mass() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - std::cout << "IA1.cog = " << std::endl << IA1.cog() << std::endl; - std::cout << "IA1.inertia = " << std::endl << IA1.inertia() << std::endl; - std::cout << "IA1.mass = " << std::endl << IA1.mass() << std::endl; - std::cout << "IA1.matrix = " << std::endl << IA1.matrix() << std::endl; - IA1 = IA1.matrix(); - std::cout << "IA1.matrix = " << std::endl << IA1.matrix() << std::endl; - - rl::math::RigidBodyInertia I1; - I1.cog() << 0, 1, 2; - I1.inertia() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - I1.mass() = 1; - IA1 = I1; - std::cout << "IA1.cog = " << std::endl << IA1.cog() << std::endl; - std::cout << "IA1.inertia = " << std::endl << IA1.inertia() << std::endl; - std::cout << "IA1.mass = " << std::endl << IA1.mass() << std::endl; - - rl::math::ArticulatedBodyInertia IA2; - IA2.cog() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - IA2.inertia() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - IA2.mass() << 0, 1, 2, 3, 4, 5, 6, 7, 8; - - rl::math::ArticulatedBodyInertia IA3; - IA3 = IA1 + IA2; - std::cout << "IA3.cog = " << std::endl << IA3.cog() << std::endl; - std::cout << "IA3.inertia = " << std::endl << IA3.inertia() << std::endl; - std::cout << "IA3.mass = " << std::endl << IA3.mass() << std::endl; - IA3 = IA1 - IA2; - std::cout << "IA3.cog = " << std::endl << IA3.cog() << std::endl; - std::cout << "IA3.inertia = " << std::endl << IA3.inertia() << std::endl; - std::cout << "IA3.mass = " << std::endl << IA3.mass() << std::endl; - IA3 = IA1 * 2; - std::cout << "IA3.cog = " << std::endl << IA3.cog() << std::endl; - std::cout << "IA3.inertia = " << std::endl << IA3.inertia() << std::endl; - std::cout << "IA3.mass = " << std::endl << IA3.mass() << std::endl; - IA3 = IA1 / 2; - std::cout << "IA3.cog = " << std::endl << IA3.cog() << std::endl; - std::cout << "IA3.inertia = " << std::endl << IA3.inertia() << std::endl; - std::cout << "IA3.mass = " << std::endl << IA3.mass() << std::endl; - - IA2 = X1 * IA1; - std::cout << "IA2.cog = " << std::endl << IA2.cog() << std::endl; - std::cout << "IA2.inertia = " << std::endl << IA2.inertia() << std::endl; - std::cout << "IA2.mass = " << std::endl << IA2.mass() << std::endl; - std::cout << "IA2.matrix = " << std::endl << IA2.matrix() << std::endl; - rl::math::ArticulatedBodyInertia::MatrixType IA2matrix; - IA2matrix = X1.matrixForce() * IA1.matrix() * X1.inverseMotion(); - std::cout << "IA2matrix = " << std::endl << IA2matrix << std::endl; - - IA2 = X1 / IA1; - std::cout << "IA2.cog = " << std::endl << IA2.cog() << std::endl; - std::cout << "IA2.inertia = " << std::endl << IA2.inertia() << std::endl; - std::cout << "IA2.mass = " << std::endl << IA2.mass() << std::endl; - std::cout << "IA2.matrix = " << std::endl << IA2.matrix() << std::endl; - IA2matrix = X1.inverseForce() * IA1.matrix() * X1.matrixMotion(); - std::cout << "IA2matrix = " << std::endl << IA2matrix << std::endl; - - rl::math::MotionVector v1; - v1.angular() << 0, 1, 2; - v1.linear() << 3, 4, 5; - std::cout << "v1 = " << v1.matrix().transpose() << std::endl; - - rl::math::ForceVector f1; - f1 = IA1 * v1; - std::cout << "f1 = " << f1.matrix().transpose() << std::endl; - } - - return EXIT_SUCCESS; -} From a147023a04ba9dfe6a739e26eb71eb4aa6539c26 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 21:57:55 +0200 Subject: [PATCH 085/546] Fix Quaternion::Random --- src/rl/math/QuaternionBaseAddons.h | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 3675b0e1..13af7b95 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -34,7 +34,15 @@ namespace Eigen { template class QuaternionBase { template static Quaternion Random(const QuaternionBase& mean, const MatrixBase& sigma) { - return Random(Vector3::Random(), mean, sigma); + return Random( + Vector3( + internal::random(0, 1), + internal::random(0, 1), + internal::random(0, 1) + ), + mean, + sigma + ); } /** @@ -67,7 +75,13 @@ static Quaternion Random(const MatrixBase& rand, const Qu static Quaternion Random() { - return Random(Vector3::Random()); + return Random( + Vector3( + internal::random(0, 1), + internal::random(0, 1), + internal::random(0, 1) + ) + ); } /** From 38835afc9d0b807d900950c396e98bd4e288a5f7 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 21:58:13 +0200 Subject: [PATCH 086/546] Split rlSpatialTest into separate files --- tests/rlSpatialTest/CMakeLists.txt | 27 +- .../rlEuclideanCrossProductTest.cpp | 133 +++ .../rlSpatialArticulatedBodyInertiaTest.cpp | 114 +++ .../rlSpatialCrossProductTest.cpp | 140 +++ .../rlSpatialTest/rlSpatialDotProductTest.cpp | 53 ++ .../rlSpatialForceVectorTest.cpp | 130 +++ .../rlSpatialMotionVectorTest.cpp | 130 +++ .../rlSpatialPlueckerTransformTest.cpp | 262 ++++++ .../rlSpatialRigidBodyInertiaTest.cpp | 114 +++ tests/rlSpatialTest/rlSpatialTest.cpp | 862 ------------------ 10 files changed, 1091 insertions(+), 874 deletions(-) create mode 100644 tests/rlSpatialTest/rlEuclideanCrossProductTest.cpp create mode 100644 tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp create mode 100644 tests/rlSpatialTest/rlSpatialCrossProductTest.cpp create mode 100644 tests/rlSpatialTest/rlSpatialDotProductTest.cpp create mode 100644 tests/rlSpatialTest/rlSpatialForceVectorTest.cpp create mode 100644 tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp create mode 100644 tests/rlSpatialTest/rlSpatialPlueckerTransformTest.cpp create mode 100644 tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp delete mode 100644 tests/rlSpatialTest/rlSpatialTest.cpp diff --git a/tests/rlSpatialTest/CMakeLists.txt b/tests/rlSpatialTest/CMakeLists.txt index da808b35..27eea0c2 100644 --- a/tests/rlSpatialTest/CMakeLists.txt +++ b/tests/rlSpatialTest/CMakeLists.txt @@ -1,14 +1,17 @@ -add_executable( - rlSpatialTest - rlSpatialTest.cpp +set( + TESTS + rlEuclideanCrossProductTest + rlSpatialArticulatedBodyInertiaTest + rlSpatialCrossProductTest + rlSpatialDotProductTest + rlSpatialForceVectorTest + rlSpatialMotionVectorTest + rlSpatialPlueckerTransformTest + rlSpatialRigidBodyInertiaTest ) -target_link_libraries( - rlSpatialTest - math -) - -add_test( - rlSpatialTest - ${CMAKE_CURRENT_BINARY_DIR}/rlSpatialTest -) +foreach(TEST ${TESTS}) + add_executable(${TEST} ${TEST}.cpp) + target_link_libraries(${TEST} math) + add_test(${TEST} ${CMAKE_CURRENT_BINARY_DIR}/${TEST}) +endforeach() diff --git a/tests/rlSpatialTest/rlEuclideanCrossProductTest.cpp b/tests/rlSpatialTest/rlEuclideanCrossProductTest.cpp new file mode 100644 index 00000000..76298d52 --- /dev/null +++ b/tests/rlSpatialTest/rlEuclideanCrossProductTest.cpp @@ -0,0 +1,133 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include + +int +main(int argc, char** argv) +{ + rl::math::Vector3 a; + a.setRandom(); + + rl::math::Matrix33 m1a = a.cross33(); + rl::math::Matrix33 m1b = -a.cross33().transpose(); + + if (!m1a.isApprox(m1b)) + { + std::cerr << "ax != -ax^T" << std::endl; + std::cerr << "ax = " << std::endl << m1a << std::endl; + std::cerr << "-ax^T = " << std::endl << m1b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector3 b; + b.setRandom(); + + rl::math::Matrix33 m2a = (a + b).cross33(); + rl::math::Matrix33 m2b = a.cross33() + b.cross33(); + + if (!m2a.isApprox(m2b)) + { + std::cerr << "(a + b)x != ax + bx" << std::endl; + std::cerr << "(a + b)x = " << std::endl << m2a << std::endl; + std::cerr << "ax + bx = " << std::endl << m2b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix33 r = rl::math::Matrix33(rl::math::Quaternion::Random()); + + rl::math::Matrix33 m3a = (r * a).cross33(); + rl::math::Matrix33 m3b = r * a.cross33() * r.transpose(); + + if (!m3a.isApprox(m3b)) + { + std::cerr << "(R * a)x != R ax R^T" << std::endl; + std::cerr << "(R * a)x = " << std::endl << m3a << std::endl; + std::cerr << "R ax R^T = " << std::endl << m3b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector3 v4a = a.cross33() * b; + rl::math::Vector3 v4b = -b.cross33() * a; + + if (!v4a.isApprox(v4b)) + { + std::cerr << "(ax) b != -(bx) a" << std::endl; + std::cerr << "(ax) b = " << std::endl << v4a << std::endl; + std::cerr << "-(bx) a = " << std::endl << v4b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector3 v5a = a.cross(b).transpose(); + rl::math::Vector3 v5b = a.transpose() * b.cross33(); + + if (!v5a.isApprox(v5b)) + { + std::cerr << "(a x b)^T != a^T bx" << std::endl; + std::cerr << "(a x b)^T = " << std::endl << v5a << std::endl; + std::cerr << "a^T bx = " << std::endl << v5b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix33 m6a = a.cross(b).cross33(); + rl::math::Matrix33 m6b = a.cross33() * b.cross33() - b.cross33() * a.cross33(); + + if (!m6a.isApprox(m6b)) + { + std::cerr << "(a x b)x != ax bx - bx ax" << std::endl; + std::cerr << "(a x b)x = " << std::endl << m6a << std::endl; + std::cerr << "ax bx - bx ax = " << std::endl << m6b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix33 m7a = a.cross(b).cross33(); + rl::math::Matrix33 m7b = b * a.transpose() - a * b.transpose(); + + if (!m7a.isApprox(m7b)) + { + std::cerr << "(a x b)x != b a^T - a b^T" << std::endl; + std::cerr << "(a x b)x = " << std::endl << m7a << std::endl; + std::cerr << "b a^T - a b^T = " << std::endl << m7b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix33 m8a = a.cross33() * b.cross33(); + rl::math::Matrix33 m8b = b * a.transpose() - a.dot(b) * rl::math::Matrix33::Identity(); + + if (!m8a.isApprox(m8b)) + { + std::cerr << "ax bx != b a^T - (a * b) I" << std::endl; + std::cerr << "ax bx = " << std::endl << m8a << std::endl; + std::cerr << "b a^T - (a * b) I = " << std::endl << m8b << std::endl; + exit(EXIT_FAILURE); + } + + return EXIT_SUCCESS; +} diff --git a/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp b/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp new file mode 100644 index 00000000..3ed325a8 --- /dev/null +++ b/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp @@ -0,0 +1,114 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include + +int +main(int argc, char** argv) +{ + rl::math::ArticulatedBodyInertia abi1; + abi1.cog().setRandom(); + abi1.inertia().setRandom(); + abi1.mass() = rl::math::DiagonalMatrix33(rl::math::Vector3::Random()); + + rl::math::ArticulatedBodyInertia abi2; + abi2.cog().setRandom(); + abi2.inertia().setRandom(); + abi2.mass() = rl::math::DiagonalMatrix33(rl::math::Vector3::Random()); + + rl::math::ArticulatedBodyInertia abi3 = abi1 + abi2; + rl::math::ArticulatedBodyInertia abi4 = abi3 - abi2; + + if (!abi4.matrix().isApprox(abi1.matrix())) + { + std::cerr << "abi1 + abi2 - abi2 != abi1" << std::endl; + std::cerr << "abi1 + abi2 - abi2 = " << std::endl << abi4.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::ArticulatedBodyInertia abi1_2 = abi1 * 2; + rl::math::ArticulatedBodyInertia abi1_abi1 = abi1 + abi1; + rl::math::ArticulatedBodyInertia abi1_2_05 = abi1_2 * 0.5; + + if (!abi1_2.matrix().isApprox(abi1_abi1.matrix())) + { + std::cerr << "abi1 * 2 != abi1 + abi1" << std::endl; + std::cerr << "abi1 * 2 = " << std::endl << abi1_2.matrix() << std::endl; + std::cerr << "abi1 + abi1 = " << std::endl << abi1_abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!abi1_2_05.matrix().isApprox(abi1.matrix())) + { + std::cerr << "abi1 * 2 * 0.5 != abi1" << std::endl; + std::cerr << "abi1 * 2 * 0.5 = " << std::endl << abi1_2.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::PlueckerTransform pt1; + pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); + pt1.translation().setRandom(); + + rl::math::ArticulatedBodyInertia abi5 = pt1 * abi1; + rl::math::ArticulatedBodyInertia abi6 = pt1 / abi5; + + if (!abi6.matrix().isApprox(abi1.matrix())) + { + std::cerr << "inv(pt1) * pt1 * abi1 != abi1" << std::endl; + std::cerr << "inv(pt1) * pt1 * abi1 = " << std::endl << abi6.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m1 = pt1.matrixForce() * abi1.matrix() * pt1.inverseMotion(); + + if (!abi5.matrix().isApprox(m1)) + { + std::cerr << "pt1 * abi1 != matrixForce(pt1) * abi1 * inverseMotion(pt1)" << std::endl; + std::cerr << "pt1 * abi1 = " << std::endl << abi5.matrix() << std::endl; + std::cerr << "matrixForce(pt1) * abi1 * inverseMotion(pt1) = " << std::endl << m1 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m2 = pt1.matrixMotion().transpose() * m1 * pt1.matrixMotion(); + + if (!abi1.matrix().isApprox(m2)) + { + std::cerr << "abi1 != matrixMotion(pt1)^T * abi5 * matrixMotion(pt1)" << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + std::cerr << "matrixMotion(pt1)^T * abi5 * matrixMotion(pt1) = " << std::endl << m2 << std::endl; + exit(EXIT_FAILURE); + } + + return EXIT_SUCCESS; +} diff --git a/tests/rlSpatialTest/rlSpatialCrossProductTest.cpp b/tests/rlSpatialTest/rlSpatialCrossProductTest.cpp new file mode 100644 index 00000000..d7ef0740 --- /dev/null +++ b/tests/rlSpatialTest/rlSpatialCrossProductTest.cpp @@ -0,0 +1,140 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include + +int +main(int argc, char** argv) +{ + rl::math::Vector6 v1; + v1.setRandom(); + + rl::math::Vector6 v2; + v2.setRandom(); + + rl::math::MotionVector mv1 = v1; + + rl::math::MotionVector mv2 = v2; + + rl::math::Vector6 v3 = mv1.cross66Motion() * v2; + rl::math::MotionVector mv3 = mv1.cross(mv2); + + if (!mv3.matrix().isApprox(v3)) + { + std::cerr << "mv1 x mv2 != crossMotion(mv1) x v2" << std::endl; + std::cerr << "mv1 x mv2 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "crossMotion(mv1) x v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::MotionVector mv4 = -mv2.cross(mv1); + + if (!mv4.matrix().isApprox(mv3.matrix())) + { + std::cerr << "mv1 x mv2 != -mv2 x mv1" << std::endl; + std::cerr << "mv1 x mv2 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "-mv2 x mv1 = " << mv4.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::ForceVector fv2 = v2; + + rl::math::Vector6 v5 = mv1.cross66Force() * v2; + rl::math::ForceVector fv5 = mv1.cross(fv2); + + if (!fv5.matrix().isApprox(v5)) + { + std::cerr << "mv1 x fv2 != crossForce(mv1) x v2" << std::endl; + std::cerr << "mv1 x fv2 = " << fv5.matrix().transpose() << std::endl; + std::cerr << "crossForce(mv1) x v2 = " << v5.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 mv1CrossForce = -mv1.cross66Motion().transpose(); + + if (!mv1CrossForce.matrix().isApprox(mv1.cross66Force())) + { + std::cerr << "crossForce(mv1) != -crossMotion(mv1)^T" << std::endl; + std::cerr << "crossForce(mv1) = " << std::endl << mv1CrossForce << std::endl; + std::cerr << "-crossMotion(mv1)^T = " << std::endl << mv1.cross66Force() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 cross1 = (mv1 + mv2).cross66Motion(); + rl::math::Matrix66 cross2 = mv1.cross66Motion() + mv2.cross66Motion(); + + if (!cross1.matrix().isApprox(cross2)) + { + std::cerr << "crossMotion(mv1 + mv2) != crossMotion(mv1) + crossMotion(mv2)" << std::endl; + std::cerr << "crossMotion(mv1 + mv2) = " << std::endl << cross1 << std::endl; + std::cerr << "crossMotion(mv1) + crossMotion(mv2) = " << std::endl << cross2 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 cross3 = (mv1 + mv2).cross66Force(); + rl::math::Matrix66 cross4 = mv1.cross66Force() + mv2.cross66Force(); + + if (!cross3.matrix().isApprox(cross4)) + { + std::cerr << "crossForce(mv1 + mv2) != crossForce(mv1) + crossForce(mv2)" << std::endl; + std::cerr << "crossForce(mv1 + mv2) = " << std::endl << cross3 << std::endl; + std::cerr << "crossForce(mv1) + crossForce(mv2) = " << std::endl << cross4 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::PlueckerTransform pt; + pt.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); + pt.translation().setRandom(); + + rl::math::Matrix66 m1 = (pt * mv1).cross66Motion(); + rl::math::Matrix66 m2 = pt.matrixMotion() * mv1.cross66Motion() * pt.inverse().matrixMotion(); + + if (!m1.matrix().isApprox(m2)) + { + std::cerr << "crossMotion(pt * mv1) != pt * crossMotion(mv1) * pt^-1" << std::endl; + std::cerr << "crossMotion(pt * mv1) = " << std::endl << m1 << std::endl; + std::cerr << "pt * crossMotion(mv1) * pt^-1 = " << std::endl << m2 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m3 = (pt * mv1).cross66Force(); + rl::math::Matrix66 m4 = pt.matrixForce() * mv1.cross66Force() * pt.inverse().matrixForce(); + + if (!m3.matrix().isApprox(m4)) + { + std::cerr << "crossForce(pt * mv1) != pt * crossForce(mv1) * pt^-1" << std::endl; + std::cerr << "crossForce(pt * mv1) = " << std::endl << m3 << std::endl; + std::cerr << "pt * crossForce(mv1) * pt^-1 = " << std::endl << m4 << std::endl; + exit(EXIT_FAILURE); + } + + return EXIT_SUCCESS; +} diff --git a/tests/rlSpatialTest/rlSpatialDotProductTest.cpp b/tests/rlSpatialTest/rlSpatialDotProductTest.cpp new file mode 100644 index 00000000..221d4389 --- /dev/null +++ b/tests/rlSpatialTest/rlSpatialDotProductTest.cpp @@ -0,0 +1,53 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 + +int +main(int argc, char** argv) +{ + rl::math::MotionVector mv1; + mv1.angular().setRandom(); + mv1.linear().setRandom(); + + rl::math::ForceVector fv2; + fv2.moment().setRandom(); + fv2.force().setRandom(); + + rl::math::Real dot1 = mv1.angular().dot(fv2.moment()) + mv1.linear().dot(fv2.force()); + rl::math::Real dot2 = mv1.dot(fv2); + + if (!Eigen::internal::isApprox(dot2, dot1)) + { + std::cerr << "mv1 * fv2 != mv1.angular * fv2.moment + mv1.linear * fv2.force" << std::endl; + std::cerr << "mv1 * fv2 = " << dot2 << std::endl; + std::cerr << "mv1.angular * fv2.moment + mv1.linear * fv2.force = " << dot1 << std::endl; + exit(EXIT_FAILURE); + } + + return EXIT_SUCCESS; +} diff --git a/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp b/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp new file mode 100644 index 00000000..79bef654 --- /dev/null +++ b/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp @@ -0,0 +1,130 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 + +int +main(int argc, char** argv) +{ + rl::math::Vector6 v0; + v0.setRandom(); + + rl::math::ForceVector fv0; + fv0.moment() << v0.head<3>(); + fv0.force() << v0.tail<3>(); + + if (!fv0.matrix().isApprox(v0)) + { + std::cerr << "fv0.matrix() != v0" << std::endl; + std::cerr << "fv0 = " << fv0.matrix().transpose() << std::endl; + std::cerr << "v0 = " << v0.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v1; + v1.setRandom(); + + rl::math::ForceVector fv1(v1); + + if (!fv1.matrix().isApprox(v1)) + { + std::cerr << "fv1(v1).matrix() != v1" << std::endl; + std::cerr << "fv1(v1) = " << fv1.matrix().transpose() << std::endl; + std::cerr << "v1 = " << v1.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v2; + v2.setRandom(); + + rl::math::ForceVector fv2 = v2; + + if (!fv2.matrix().isApprox(v2)) + { + std::cerr << "(fv2 = v2).matrix() != v2" << std::endl; + std::cerr << "(fv2 = v2) = " << fv2.matrix().transpose() << std::endl; + std::cerr << "v2 = " << v2.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v3 = v1 + v2; + rl::math::ForceVector fv3 = fv1 + fv2; + + if (!fv3.matrix().isApprox(v3)) + { + std::cerr << "fv1 + fv2 != v1 + v2" << std::endl; + std::cerr << "fv1 + fv2 = " << fv3.matrix().transpose() << std::endl; + std::cerr << "v1 + v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v4 = v1 - v2; + rl::math::ForceVector fv4 = fv1 - fv2; + + if (!fv4.matrix().isApprox(v4)) + { + std::cerr << "fv1 - fv2 != v1 - v2" << std::endl; + std::cerr << "fv1 - fv2 = " << fv4.matrix().transpose() << std::endl; + std::cerr << "v1 - v2 = " << v4.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v5 = v1 * 1.23f; + rl::math::ForceVector fv5 = fv1 * 1.23f; + + if (!fv5.matrix().isApprox(v5)) + { + std::cerr << "fv1 * 1.23 != v1 * 1.23" << std::endl; + std::cerr << "fv1 * 1.23 = " << fv5.matrix().transpose() << std::endl; + std::cerr << "v1 * 1.23 = " << v5.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v6 = v1 / 1.23f; + rl::math::ForceVector fv6 = fv1 / 1.23f; + + if (!fv6.matrix().isApprox(v6)) + { + std::cerr << "fv1 / 1.23 != v1 / 1.23" << std::endl; + std::cerr << "v1 * 1.23 = " << fv6.matrix().transpose() << std::endl; + std::cerr << "v1 / 1.23 = " << v6.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::ForceVector fv7 = v1; + + if (!fv7.matrix().isApprox(v1)) + { + std::cerr << "fv7 != v1" << std::endl; + std::cerr << "fv7 = " << fv7.matrix().transpose() << std::endl; + std::cerr << "v1 = " << v1.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + return EXIT_SUCCESS; +} diff --git a/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp b/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp new file mode 100644 index 00000000..e684d8e5 --- /dev/null +++ b/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp @@ -0,0 +1,130 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 + +int +main(int argc, char** argv) +{ + rl::math::Vector6 v0; + v0.setRandom(); + + rl::math::MotionVector mv0; + mv0.angular() << v0.head<3>(); + mv0.linear() << v0.tail<3>(); + + if (!mv0.matrix().isApprox(v0)) + { + std::cerr << "mv0.matrix() != v0" << std::endl; + std::cerr << "mv0 = " << mv0.matrix().transpose() << std::endl; + std::cerr << "v0 = " << v0.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v1; + v1.setRandom(); + + rl::math::MotionVector mv1(v1); + + if (!mv1.matrix().isApprox(v1)) + { + std::cerr << "mv1(v1).matrix() != v1" << std::endl; + std::cerr << "mv1(v1) = " << mv1.matrix().transpose() << std::endl; + std::cerr << "v1 = " << v1.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v2; + v2.setRandom(); + + rl::math::MotionVector mv2 = v2; + + if (!mv2.matrix().isApprox(v2)) + { + std::cerr << "(mv2 = v2).matrix() != v2" << std::endl; + std::cerr << "(mv2 = v2) = " << mv2.matrix().transpose() << std::endl; + std::cerr << "v2 = " << v2.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v3 = v1 + v2; + rl::math::MotionVector mv3 = mv1 + mv2; + + if (!mv3.matrix().isApprox(v3)) + { + std::cerr << "mv1 + mv2 != v1 + v2" << std::endl; + std::cerr << "mv1 + mv2 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "v1 + v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v4 = v1 - v2; + rl::math::MotionVector mv4 = mv1 - mv2; + + if (!mv4.matrix().isApprox(v4)) + { + std::cerr << "mv1 - mv2 != v1 - v2" << std::endl; + std::cerr << "mv1 - mv2 = " << mv4.matrix().transpose() << std::endl; + std::cerr << "v1 - v2 = " << v4.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v5 = v1 * 1.23f; + rl::math::MotionVector mv5 = mv1 * 1.23f; + + if (!mv5.matrix().isApprox(v5)) + { + std::cerr << "mv1 * 1.23 != v1 * 1.23" << std::endl; + std::cerr << "mv1 * 1.23 = " << mv5.matrix().transpose() << std::endl; + std::cerr << "v1 * 1.23 = " << v5.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v6 = v1 / 1.23f; + rl::math::MotionVector mv6 = mv1 / 1.23f; + + if (!mv6.matrix().isApprox(v6)) + { + std::cerr << "mv1 / 1.23 != v1 / 1.23" << std::endl; + std::cerr << "v1 * 1.23 = " << mv6.matrix().transpose() << std::endl; + std::cerr << "v1 / 1.23 = " << v6.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::MotionVector mv7 = v1; + + if (!mv7.matrix().isApprox(v1)) + { + std::cerr << "mv7 != v1" << std::endl; + std::cerr << "mv7 = " << mv7.matrix().transpose() << std::endl; + std::cerr << "v1 = " << v1.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + return EXIT_SUCCESS; +} diff --git a/tests/rlSpatialTest/rlSpatialPlueckerTransformTest.cpp b/tests/rlSpatialTest/rlSpatialPlueckerTransformTest.cpp new file mode 100644 index 00000000..f8fb4bf6 --- /dev/null +++ b/tests/rlSpatialTest/rlSpatialPlueckerTransformTest.cpp @@ -0,0 +1,262 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include + +int +main(int argc, char** argv) +{ + rl::math::Transform t0; + t0 = rl::math::Quaternion::Random(); + t0.translation().setRandom(); + + rl::math::PlueckerTransform pt0; + pt0.rotation() = t0.linear(); + pt0.translation() = t0.translation(); + + if (!pt0.rotation().isApprox(t0.linear()) || !pt0.translation().isApprox(t0.translation())) + { + std::cerr << "pt0 != t0" << std::endl; + std::cerr << "pt0.rotation = " << std::endl << pt0.rotation() << std::endl; + std::cerr << "pt0.translation = " << pt0.translation().transpose() << std::endl; + std::cerr << "t0.linear = " << std::endl << t0.linear() << std::endl; + std::cerr << "t0.translation = " << t0.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Transform t1; + t1 = rl::math::Quaternion::Random(); + t1.translation().setRandom(); + + rl::math::PlueckerTransform pt1(t1); + + if (!pt1.rotation().isApprox(t1.linear()) || !pt1.translation().isApprox(t1.translation())) + { + std::cerr << "pt1(t1) != t1" << std::endl; + std::cerr << "pt1(t1).rotation = " << std::endl << pt1.rotation() << std::endl; + std::cerr << "pt1(t1).translation = " << pt1.translation().transpose() << std::endl; + std::cerr << "t1.linear = " << std::endl << t1.linear() << std::endl; + std::cerr << "t1.translation = " << t1.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Transform t2; + t2 = rl::math::Quaternion::Random(); + t2.translation().setRandom(); + + rl::math::PlueckerTransform pt2 = t2; + + if (!pt2.rotation().isApprox(t2.linear()) || !pt2.translation().isApprox(t2.translation())) + { + std::cerr << "(pt2 = t2) != t2" << std::endl; + std::cerr << "(pt2 = t2).rotation = " << std::endl << pt2.rotation() << std::endl; + std::cerr << "(pt2 = t2).translation = " << pt2.translation().transpose() << std::endl; + std::cerr << "t2.linear = " << std::endl << t2.linear() << std::endl; + std::cerr << "t2.translation = " << t2.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Transform t3 = t1 * t2; + rl::math::PlueckerTransform pt3 = pt1 * pt2; + + if (!pt3.rotation().isApprox(t3.linear()) || !pt3.translation().isApprox(t3.translation())) + { + std::cerr << "pt1 * pt2 != t1 * t2" << std::endl; + std::cerr << "(pt1 * pt2).rotation = " << std::endl << pt3.rotation() << std::endl; + std::cerr << "(pt1 * pt2).translation = " << pt3.translation().transpose() << std::endl; + std::cerr << "(t1 * t2).linear = " << std::endl << t3.linear() << std::endl; + std::cerr << "(t1 * t2).translation = " << t3.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Transform t4 = t1.inverse() * t3; + rl::math::PlueckerTransform pt4 = pt1.inverse() * pt3; + + if (!pt4.rotation().isApprox(pt2.rotation()) || !pt4.translation().isApprox(pt2.translation())) + { + std::cerr << "inv(pt1) * pt1 * pt2 != pt2" << std::endl; + std::cerr << "(inv(pt1) * pt1 * pt2).rotation = " << std::endl << pt4.rotation() << std::endl; + std::cerr << "(inv(pt1) * pt1 * pt2).translation = " << pt4.translation().transpose() << std::endl; + std::cerr << "pt2.rotation = " << std::endl << pt2.rotation().matrix() << std::endl; + std::cerr << "pt2.translation = " << pt2.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!pt4.rotation().isApprox(t4.linear()) || !pt4.translation().isApprox(t4.translation())) + { + std::cerr << "inv(pt1) * pt3 != inv(t1) * t3" << std::endl; + std::cerr << "(inv(pt1) * pt3).rotation = " << std::endl << pt4.rotation() << std::endl; + std::cerr << "(inv(pt1) * pt3).translation = " << pt4.translation().transpose() << std::endl; + std::cerr << "(inv(t1) * t3).linear = " << std::endl << t4.linear() << std::endl; + std::cerr << "(inv(t1) * t3).translation = " << t4.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::PlueckerTransform pt5; + pt5.setIdentity(); + rl::math::PlueckerTransform pt6 = pt1.inverse() * pt1; + + if (!pt5.rotation().isApprox(pt6.rotation()) || !pt5.translation().isMuchSmallerThan(pt6.translation())) + { + std::cerr << "I != inv(pt1) * pt1" << std::endl; + std::cerr << "I.rotation = " << std::endl << pt5.rotation().matrix() << std::endl; + std::cerr << "I.translation = " << pt5.translation().transpose() << std::endl; + std::cerr << "(inv(pt1) * pt1).rotation = " << std::endl << pt6.rotation() << std::endl; + std::cerr << "(inv(pt1) * pt1).translation = " << pt6.translation().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m1a = pt1.matrixMotion().inverse(); + rl::math::Matrix66 m1b = pt1.inverseMotion(); + + if (!m1a.matrix().isApprox(m1b)) + { + std::cerr << "matrixMotion(pt1)^-1 != inverseMotion(pt1)" << std::endl; + std::cerr << "matrixMotion(pt1)^-1 = " << std::endl << m1a << std::endl; + std::cerr << "inverseMotion(pt1) = " << std::endl << m1b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m2a = pt1.matrixForce().inverse(); + rl::math::Matrix66 m2b = pt1.inverseForce(); + + if (!m2a.matrix().isApprox(m2b)) + { + std::cerr << "matrixForce(pt1)^-1 != inverseForce(pt1)" << std::endl; + std::cerr << "matrixForce(pt1)^-1 = " << std::endl << m2a << std::endl; + std::cerr << "inverseForce(pt1) = " << std::endl << m2b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m3a = pt1.matrixForce(); + rl::math::Matrix66 m3b = pt1.matrixMotion().inverse().transpose(); + + if (!m3a.matrix().isApprox(m3b)) + { + std::cerr << "matrixForce(pt1) != matrixMotion(pt1)^-T" << std::endl; + std::cerr << "matrixForce(pt1) = " << std::endl << m3a << std::endl; + std::cerr << "matrixMotion(pt1)^-T = " << std::endl << m3b << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v1; + v1.setRandom(); + + { + rl::math::MotionVector mv1 = v1; + + rl::math::Vector6 v2 = pt1.matrixMotion() * v1; + rl::math::MotionVector mv2 = pt1 * mv1; + + if (!mv2.matrix().isApprox(v2)) + { + std::cerr << "pt1 * mv1 != matrixMotion(pt1) * v1" << std::endl; + std::cerr << "pt1 * mv1 = " << mv2.matrix().transpose() << std::endl; + std::cerr << "matrixMotion(pt1) * v1 = " << v2.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v3 = pt1.inverseMotion() * v2; + rl::math::MotionVector mv3 = pt1 / mv2; + + if (!mv3.matrix().isApprox(v3)) + { + std::cerr << "inv(pt1) / mv2 != inverseMotion(pt1) * v2" << std::endl; + std::cerr << "inv(pt1) / mv2 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "inverseMotion(pt1) * v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!mv3.matrix().isApprox(mv1.matrix())) + { + std::cerr << "pt1.inverse() * pt1 * mv1 != mv1" << std::endl; + std::cerr << "pt1.inverse() * pt1 * mv1 = " << mv3.matrix().transpose() << std::endl; + std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::MotionVector mv4 = pt1.inverse() * mv2; + + if (!mv4.matrix().isApprox(mv1.matrix())) + { + std::cerr << "pt1.inverse() * pt1 * mv1 != mv1" << std::endl; + std::cerr << "pt1.inverse() * pt1 * mv1 = " << mv4.matrix().transpose() << std::endl; + std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + } + + { + rl::math::ForceVector fv1 = v1; + + rl::math::Vector6 v2 = pt1.matrixForce() * v1; + rl::math::ForceVector fv2 = pt1 * fv1; + + if (!fv2.matrix().isApprox(v2)) + { + std::cerr << "pt1 * fv1 != matrixForce(pt1) * v1" << std::endl; + std::cerr << "pt1 * fv1 = " << fv2.matrix().transpose() << std::endl; + std::cerr << "matrixForce(pt1) * v1 = " << v2.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Vector6 v3 = pt1.inverseForce() * v2; + rl::math::ForceVector fv3 = pt1 / fv2; + + if (!fv3.matrix().isApprox(v3)) + { + std::cerr << "inv(pt1) / fv2 != inverseForce(pt1) * v2" << std::endl; + std::cerr << "inv(pt1) / fv2 = " << fv3.matrix().transpose() << std::endl; + std::cerr << "inverseForce(pt1) * v2 = " << v3.transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!fv3.matrix().isApprox(fv1.matrix())) + { + std::cerr << "pt1.inverse() * pt1 * fv1 != fv1" << std::endl; + std::cerr << "pt1.inverse() * pt1 * fv1 = " << fv3.matrix().transpose() << std::endl; + std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::ForceVector fv4 = pt1.inverse() * fv2; + + if (!fv4.matrix().isApprox(fv1.matrix())) + { + std::cerr << "pt1.inverse() * pt1 * fv1 != fv1" << std::endl; + std::cerr << "pt1.inverse() * pt1 * fv1 = " << fv4.matrix().transpose() << std::endl; + std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + } + + return EXIT_SUCCESS; +} diff --git a/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp b/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp new file mode 100644 index 00000000..ba7f25b3 --- /dev/null +++ b/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp @@ -0,0 +1,114 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include + +int +main(int argc, char** argv) +{ + rl::math::RigidBodyInertia rbi1; + rbi1.cog().setRandom(); + rbi1.inertia().setRandom(); + rbi1.mass() = 10; + + rl::math::RigidBodyInertia rbi2; + rbi2.cog().setRandom(); + rbi2.inertia().setRandom(); + rbi2.mass() = 20; + + rl::math::RigidBodyInertia rbi3 = rbi1 + rbi2; + rl::math::RigidBodyInertia rbi4 = rbi3 - rbi2; + + if (!rbi4.matrix().isApprox(rbi1.matrix())) + { + std::cerr << "rbi1 + rbi2 - rbi2 != rbi1" << std::endl; + std::cerr << "rbi1 + rbi2 - rbi2 = " << std::endl << rbi4.matrix() << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::RigidBodyInertia rbi1_2 = rbi1 * 2; + rl::math::RigidBodyInertia rbi1_rbi1 = rbi1 + rbi1; + rl::math::RigidBodyInertia rbi1_2_05 = rbi1_2 * 0.5; + + if (!rbi1_2.matrix().isApprox(rbi1_rbi1.matrix())) + { + std::cerr << "rbi1 * 2 != rbi1 + rbi1" << std::endl; + std::cerr << "rbi1 * 2 = " << std::endl << rbi1_2.matrix() << std::endl; + std::cerr << "rbi1 + rbi1 = " << std::endl << rbi1_rbi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!rbi1_2_05.matrix().isApprox(rbi1.matrix())) + { + std::cerr << "rbi1 * 2 * 0.5 != rbi1" << std::endl; + std::cerr << "rbi1 * 2 * 0.5 = " << std::endl << rbi1_2_05.matrix() << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::PlueckerTransform pt1; + pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); + pt1.translation().setRandom(); + + rl::math::RigidBodyInertia rbi5 = pt1 * rbi1; + rl::math::RigidBodyInertia rbi6 = pt1 / rbi5; + + if (!rbi6.matrix().isApprox(rbi1.matrix())) + { + std::cerr << "inv(pt1) * pt1 * rbi1 != rbi1" << std::endl; + std::cerr << "inv(pt1) * pt1 * rbi1 = " << std::endl << rbi6.matrix() << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m1 = pt1.matrixForce() * rbi1.matrix() * pt1.inverseMotion(); + + if (!rbi5.matrix().isApprox(m1)) + { + std::cerr << "pt1 * rbi1 != matrixForce(pt1) * rbi1 * inverseMotion(pt1)" << std::endl; + std::cerr << "pt1 * rbi1 = " << std::endl << rbi5.matrix() << std::endl; + std::cerr << "matrixForce(pt1) * rbi1 * inverseMotion(pt1) = " << std::endl << m1 << std::endl; + exit(EXIT_FAILURE); + } + + rl::math::Matrix66 m2 = pt1.matrixMotion().transpose() * m1 * pt1.matrixMotion(); + + if (!rbi1.matrix().isApprox(m2)) + { + std::cerr << "rbi1 != matrixMotion(pt1)^T * rbi5 * matrixMotion(pt1)" << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + std::cerr << "matrixMotion(pt1)^T * rbi5 * matrixMotion(pt1) = " << std::endl << m2 << std::endl; + exit(EXIT_FAILURE); + } + + return EXIT_SUCCESS; +} diff --git a/tests/rlSpatialTest/rlSpatialTest.cpp b/tests/rlSpatialTest/rlSpatialTest.cpp deleted file mode 100644 index 9d32dc6b..00000000 --- a/tests/rlSpatialTest/rlSpatialTest.cpp +++ /dev/null @@ -1,862 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 -#include -#include -#include -#include - -void -testArticulatedBodyInertia() -{ - rl::math::ArticulatedBodyInertia abi1; - abi1.cog().setRandom(); - abi1.inertia().setRandom(); - abi1.mass() = rl::math::DiagonalMatrix33(rl::math::Vector3::Random()); - - rl::math::ArticulatedBodyInertia abi2; - abi2.cog().setRandom(); - abi2.inertia().setRandom(); - abi2.mass() = rl::math::DiagonalMatrix33(rl::math::Vector3::Random()); - - rl::math::ArticulatedBodyInertia abi3 = abi1 + abi2; - rl::math::ArticulatedBodyInertia abi4 = abi3 - abi2; - - if (!abi4.matrix().isApprox(abi1.matrix())) - { - std::cerr << "abi1 + abi2 - abi2 != abi1" << std::endl; - std::cerr << "abi1 + abi2 - abi2 = " << std::endl << abi4.matrix() << std::endl; - std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::ArticulatedBodyInertia abi1_2 = abi1 * 2; - rl::math::ArticulatedBodyInertia abi1_abi1 = abi1 + abi1; - rl::math::ArticulatedBodyInertia abi1_2_05 = abi1_2 * 0.5; - - if (!abi1_2.matrix().isApprox(abi1_abi1.matrix())) - { - std::cerr << "abi1 * 2 != abi1 + abi1" << std::endl; - std::cerr << "abi1 * 2 = " << std::endl << abi1_2.matrix() << std::endl; - std::cerr << "abi1 + abi1 = " << std::endl << abi1_abi1.matrix() << std::endl; - exit(EXIT_FAILURE); - } - - if (!abi1_2_05.matrix().isApprox(abi1.matrix())) - { - std::cerr << "abi1 * 2 * 0.5 != abi1" << std::endl; - std::cerr << "abi1 * 2 * 0.5 = " << std::endl << abi1_2.matrix() << std::endl; - std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); - pt1.translation().setRandom(); - - rl::math::ArticulatedBodyInertia abi5 = pt1 * abi1; - rl::math::ArticulatedBodyInertia abi6 = pt1 / abi5; - - if (!abi6.matrix().isApprox(abi1.matrix())) - { - std::cerr << "inv(pt1) * pt1 * abi1 != abi1" << std::endl; - std::cerr << "inv(pt1) * pt1 * abi1 = " << std::endl << abi6.matrix() << std::endl; - std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 m1 = pt1.matrixForce() * abi1.matrix() * pt1.inverseMotion(); - - if (!abi5.matrix().isApprox(m1)) - { - std::cerr << "pt1 * abi1 != matrixForce(pt1) * abi1 * inverseMotion(pt1)" << std::endl; - std::cerr << "pt1 * abi1 = " << std::endl << abi5.matrix() << std::endl; - std::cerr << "matrixForce(pt1) * abi1 * inverseMotion(pt1) = " << std::endl << m1 << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 m2 = pt1.matrixMotion().transpose() * m1 * pt1.matrixMotion(); - - if (!abi1.matrix().isApprox(m2)) - { - std::cerr << "abi1 != matrixMotion(pt1)^T * abi5 * matrixMotion(pt1)" << std::endl; - std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; - std::cerr << "matrixMotion(pt1)^T * abi5 * matrixMotion(pt1) = " << std::endl << m2 << std::endl; - exit(EXIT_FAILURE); - } -} - -void -testEuclideanCrossProduct() -{ - rl::math::Vector3 a; - a.setRandom(); - - rl::math::Matrix33 m1a = a.cross33(); - rl::math::Matrix33 m1b = -a.cross33().transpose(); - - if (!m1a.isApprox(m1b)) - { - std::cerr << "ax != -ax^T" << std::endl; - std::cerr << "ax = " << std::endl << m1a << std::endl; - std::cerr << "-ax^T = " << std::endl << m1b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector3 b; - b.setRandom(); - - rl::math::Matrix33 m2a = (a + b).cross33(); - rl::math::Matrix33 m2b = a.cross33() + b.cross33(); - - if (!m2a.isApprox(m2b)) - { - std::cerr << "(a + b)x != ax + bx" << std::endl; - std::cerr << "(a + b)x = " << std::endl << m2a << std::endl; - std::cerr << "ax + bx = " << std::endl << m2b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix33 r = rl::math::Matrix33(rl::math::Quaternion::Random()); - - rl::math::Matrix33 m3a = (r * a).cross33(); - rl::math::Matrix33 m3b = r * a.cross33() * r.transpose(); - - if (!m3a.isApprox(m3b)) - { - std::cerr << "(R * a)x != R ax R^T" << std::endl; - std::cerr << "(R * a)x = " << std::endl << m3a << std::endl; - std::cerr << "R ax R^T = " << std::endl << m3b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector3 v4a = a.cross33() * b; - rl::math::Vector3 v4b = -b.cross33() * a; - - if (!v4a.isApprox(v4b)) - { - std::cerr << "(ax) b != -(bx) a" << std::endl; - std::cerr << "(ax) b = " << std::endl << v4a << std::endl; - std::cerr << "-(bx) a = " << std::endl << v4b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector3 v5a = a.cross(b).transpose(); - rl::math::Vector3 v5b = a.transpose() * b.cross33(); - - if (!v5a.isApprox(v5b)) - { - std::cerr << "(a x b)^T != a^T bx" << std::endl; - std::cerr << "(a x b)^T = " << std::endl << v5a << std::endl; - std::cerr << "a^T bx = " << std::endl << v5b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix33 m6a = a.cross(b).cross33(); - rl::math::Matrix33 m6b = a.cross33() * b.cross33() - b.cross33() * a.cross33(); - - if (!m6a.isApprox(m6b)) - { - std::cerr << "(a x b)x != ax bx - bx ax" << std::endl; - std::cerr << "(a x b)x = " << std::endl << m6a << std::endl; - std::cerr << "ax bx - bx ax = " << std::endl << m6b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix33 m7a = a.cross(b).cross33(); - rl::math::Matrix33 m7b = b * a.transpose() - a * b.transpose(); - - if (!m7a.isApprox(m7b)) - { - std::cerr << "(a x b)x != b a^T - a b^T" << std::endl; - std::cerr << "(a x b)x = " << std::endl << m7a << std::endl; - std::cerr << "b a^T - a b^T = " << std::endl << m7b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix33 m8a = a.cross33() * b.cross33(); - rl::math::Matrix33 m8b = b * a.transpose() - a.dot(b) * rl::math::Matrix33::Identity(); - - if (!m8a.isApprox(m8b)) - { - std::cerr << "ax bx != b a^T - (a * b) I" << std::endl; - std::cerr << "ax bx = " << std::endl << m8a << std::endl; - std::cerr << "b a^T - (a * b) I = " << std::endl << m8b << std::endl; - exit(EXIT_FAILURE); - } -} - -void -testForceVector() -{ - rl::math::Vector6 v0; - v0.setRandom(); - - rl::math::ForceVector fv0; - fv0.moment() << v0.head<3>(); - fv0.force() << v0.tail<3>(); - - if (!fv0.matrix().isApprox(v0)) - { - std::cerr << "fv0.matrix() != v0" << std::endl; - std::cerr << "fv0 = " << fv0.matrix().transpose() << std::endl; - std::cerr << "v0 = " << v0.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v1; - v1.setRandom(); - - rl::math::ForceVector fv1(v1); - - if (!fv1.matrix().isApprox(v1)) - { - std::cerr << "fv1(v1).matrix() != v1" << std::endl; - std::cerr << "fv1(v1) = " << fv1.matrix().transpose() << std::endl; - std::cerr << "v1 = " << v1.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v2; - v2.setRandom(); - - rl::math::ForceVector fv2 = v2; - - if (!fv2.matrix().isApprox(v2)) - { - std::cerr << "(fv2 = v2).matrix() != v2" << std::endl; - std::cerr << "(fv2 = v2) = " << fv2.matrix().transpose() << std::endl; - std::cerr << "v2 = " << v2.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v3 = v1 + v2; - rl::math::ForceVector fv3 = fv1 + fv2; - - if (!fv3.matrix().isApprox(v3)) - { - std::cerr << "fv1 + fv2 != v1 + v2" << std::endl; - std::cerr << "fv1 + fv2 = " << fv3.matrix().transpose() << std::endl; - std::cerr << "v1 + v2 = " << v3.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v4 = v1 - v2; - rl::math::ForceVector fv4 = fv1 - fv2; - - if (!fv4.matrix().isApprox(v4)) - { - std::cerr << "fv1 - fv2 != v1 - v2" << std::endl; - std::cerr << "fv1 - fv2 = " << fv4.matrix().transpose() << std::endl; - std::cerr << "v1 - v2 = " << v4.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v5 = v1 * 1.23f; - rl::math::ForceVector fv5 = fv1 * 1.23f; - - if (!fv5.matrix().isApprox(v5)) - { - std::cerr << "fv1 * 1.23 != v1 * 1.23" << std::endl; - std::cerr << "fv1 * 1.23 = " << fv5.matrix().transpose() << std::endl; - std::cerr << "v1 * 1.23 = " << v5.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v6 = v1 / 1.23f; - rl::math::ForceVector fv6 = fv1 / 1.23f; - - if (!fv6.matrix().isApprox(v6)) - { - std::cerr << "fv1 / 1.23 != v1 / 1.23" << std::endl; - std::cerr << "v1 * 1.23 = " << fv6.matrix().transpose() << std::endl; - std::cerr << "v1 / 1.23 = " << v6.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::ForceVector fv7 = v1; - - if (!fv7.matrix().isApprox(v1)) - { - std::cerr << "fv7 != v1" << std::endl; - std::cerr << "fv7 = " << fv7.matrix().transpose() << std::endl; - std::cerr << "v1 = " << v1.transpose() << std::endl; - exit(EXIT_FAILURE); - } -} - -void -testMotionVector() -{ - rl::math::Vector6 v0; - v0.setRandom(); - - rl::math::MotionVector mv0; - mv0.angular() << v0.head<3>(); - mv0.linear() << v0.tail<3>(); - - if (!mv0.matrix().isApprox(v0)) - { - std::cerr << "mv0.matrix() != v0" << std::endl; - std::cerr << "mv0 = " << mv0.matrix().transpose() << std::endl; - std::cerr << "v0 = " << v0.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v1; - v1.setRandom(); - - rl::math::MotionVector mv1(v1); - - if (!mv1.matrix().isApprox(v1)) - { - std::cerr << "mv1(v1).matrix() != v1" << std::endl; - std::cerr << "mv1(v1) = " << mv1.matrix().transpose() << std::endl; - std::cerr << "v1 = " << v1.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v2; - v2.setRandom(); - - rl::math::MotionVector mv2 = v2; - - if (!mv2.matrix().isApprox(v2)) - { - std::cerr << "(mv2 = v2).matrix() != v2" << std::endl; - std::cerr << "(mv2 = v2) = " << mv2.matrix().transpose() << std::endl; - std::cerr << "v2 = " << v2.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v3 = v1 + v2; - rl::math::MotionVector mv3 = mv1 + mv2; - - if (!mv3.matrix().isApprox(v3)) - { - std::cerr << "mv1 + mv2 != v1 + v2" << std::endl; - std::cerr << "mv1 + mv2 = " << mv3.matrix().transpose() << std::endl; - std::cerr << "v1 + v2 = " << v3.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v4 = v1 - v2; - rl::math::MotionVector mv4 = mv1 - mv2; - - if (!mv4.matrix().isApprox(v4)) - { - std::cerr << "mv1 - mv2 != v1 - v2" << std::endl; - std::cerr << "mv1 - mv2 = " << mv4.matrix().transpose() << std::endl; - std::cerr << "v1 - v2 = " << v4.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v5 = v1 * 1.23f; - rl::math::MotionVector mv5 = mv1 * 1.23f; - - if (!mv5.matrix().isApprox(v5)) - { - std::cerr << "mv1 * 1.23 != v1 * 1.23" << std::endl; - std::cerr << "mv1 * 1.23 = " << mv5.matrix().transpose() << std::endl; - std::cerr << "v1 * 1.23 = " << v5.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v6 = v1 / 1.23f; - rl::math::MotionVector mv6 = mv1 / 1.23f; - - if (!mv6.matrix().isApprox(v6)) - { - std::cerr << "mv1 / 1.23 != v1 / 1.23" << std::endl; - std::cerr << "v1 * 1.23 = " << mv6.matrix().transpose() << std::endl; - std::cerr << "v1 / 1.23 = " << v6.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::MotionVector mv7 = v1; - - if (!mv7.matrix().isApprox(v1)) - { - std::cerr << "mv7 != v1" << std::endl; - std::cerr << "mv7 = " << mv7.matrix().transpose() << std::endl; - std::cerr << "v1 = " << v1.transpose() << std::endl; - exit(EXIT_FAILURE); - } -} - -void -testPlueckerTransform() -{ - rl::math::Transform t0; - t0 = rl::math::Quaternion::Random(); - t0.translation().setRandom(); - - rl::math::PlueckerTransform pt0; - pt0.rotation() = t0.linear(); - pt0.translation() = t0.translation(); - - if (!pt0.rotation().isApprox(t0.linear()) || !pt0.translation().isApprox(t0.translation())) - { - std::cerr << "pt0 != t0" << std::endl; - std::cerr << "pt0.rotation = " << std::endl << pt0.rotation() << std::endl; - std::cerr << "pt0.translation = " << pt0.translation().transpose() << std::endl; - std::cerr << "t0.linear = " << std::endl << t0.linear() << std::endl; - std::cerr << "t0.translation = " << t0.translation().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Transform t1; - t1 = rl::math::Quaternion::Random(); - t1.translation().setRandom(); - - rl::math::PlueckerTransform pt1(t1); - - if (!pt1.rotation().isApprox(t1.linear()) || !pt1.translation().isApprox(t1.translation())) - { - std::cerr << "pt1(t1) != t1" << std::endl; - std::cerr << "pt1(t1).rotation = " << std::endl << pt1.rotation() << std::endl; - std::cerr << "pt1(t1).translation = " << pt1.translation().transpose() << std::endl; - std::cerr << "t1.linear = " << std::endl << t1.linear() << std::endl; - std::cerr << "t1.translation = " << t1.translation().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Transform t2; - t2 = rl::math::Quaternion::Random(); - t2.translation().setRandom(); - - rl::math::PlueckerTransform pt2 = t2; - - if (!pt2.rotation().isApprox(t2.linear()) || !pt2.translation().isApprox(t2.translation())) - { - std::cerr << "(pt2 = t2) != t2" << std::endl; - std::cerr << "(pt2 = t2).rotation = " << std::endl << pt2.rotation() << std::endl; - std::cerr << "(pt2 = t2).translation = " << pt2.translation().transpose() << std::endl; - std::cerr << "t2.linear = " << std::endl << t2.linear() << std::endl; - std::cerr << "t2.translation = " << t2.translation().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Transform t3 = t1 * t2; - rl::math::PlueckerTransform pt3 = pt1 * pt2; - - if (!pt3.rotation().isApprox(t3.linear()) || !pt3.translation().isApprox(t3.translation())) - { - std::cerr << "pt1 * pt2 != t1 * t2" << std::endl; - std::cerr << "(pt1 * pt2).rotation = " << std::endl << pt3.rotation() << std::endl; - std::cerr << "(pt1 * pt2).translation = " << pt3.translation().transpose() << std::endl; - std::cerr << "(t1 * t2).linear = " << std::endl << t3.linear() << std::endl; - std::cerr << "(t1 * t2).translation = " << t3.translation().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Transform t4 = t1.inverse() * t3; - rl::math::PlueckerTransform pt4 = pt1.inverse() * pt3; - - if (!pt4.rotation().isApprox(pt2.rotation()) || !pt4.translation().isApprox(pt2.translation())) - { - std::cerr << "inv(pt1) * pt1 * pt2 != pt2" << std::endl; - std::cerr << "(inv(pt1) * pt1 * pt2).rotation = " << std::endl << pt4.rotation() << std::endl; - std::cerr << "(inv(pt1) * pt1 * pt2).translation = " << pt4.translation().transpose() << std::endl; - std::cerr << "pt2.rotation = " << std::endl << pt2.rotation().matrix() << std::endl; - std::cerr << "pt2.translation = " << pt2.translation().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - if (!pt4.rotation().isApprox(t4.linear()) || !pt4.translation().isApprox(t4.translation())) - { - std::cerr << "inv(pt1) * pt3 != inv(t1) * t3" << std::endl; - std::cerr << "(inv(pt1) * pt3).rotation = " << std::endl << pt4.rotation() << std::endl; - std::cerr << "(inv(pt1) * pt3).translation = " << pt4.translation().transpose() << std::endl; - std::cerr << "(inv(t1) * t3).linear = " << std::endl << t4.linear() << std::endl; - std::cerr << "(inv(t1) * t3).translation = " << t4.translation().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::PlueckerTransform pt5; - pt5.setIdentity(); - rl::math::PlueckerTransform pt6 = pt1.inverse() * pt1; - - if (!pt5.rotation().isApprox(pt6.rotation()) || !pt5.translation().isMuchSmallerThan(pt6.translation())) - { - std::cerr << "I != inv(pt1) * pt1" << std::endl; - std::cerr << "I.rotation = " << std::endl << pt5.rotation().matrix() << std::endl; - std::cerr << "I.translation = " << pt5.translation().transpose() << std::endl; - std::cerr << "(inv(pt1) * pt1).rotation = " << std::endl << pt6.rotation() << std::endl; - std::cerr << "(inv(pt1) * pt1).translation = " << pt6.translation().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 m1a = pt1.matrixMotion().inverse(); - rl::math::Matrix66 m1b = pt1.inverseMotion(); - - if (!m1a.matrix().isApprox(m1b)) - { - std::cerr << "matrixMotion(pt1)^-1 != inverseMotion(pt1)" << std::endl; - std::cerr << "matrixMotion(pt1)^-1 = " << std::endl << m1a << std::endl; - std::cerr << "inverseMotion(pt1) = " << std::endl << m1b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 m2a = pt1.matrixForce().inverse(); - rl::math::Matrix66 m2b = pt1.inverseForce(); - - if (!m2a.matrix().isApprox(m2b)) - { - std::cerr << "matrixForce(pt1)^-1 != inverseForce(pt1)" << std::endl; - std::cerr << "matrixForce(pt1)^-1 = " << std::endl << m2a << std::endl; - std::cerr << "inverseForce(pt1) = " << std::endl << m2b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 m3a = pt1.matrixForce(); - rl::math::Matrix66 m3b = pt1.matrixMotion().inverse().transpose(); - - if (!m3a.matrix().isApprox(m3b)) - { - std::cerr << "matrixForce(pt1) != matrixMotion(pt1)^-T" << std::endl; - std::cerr << "matrixForce(pt1) = " << std::endl << m3a << std::endl; - std::cerr << "matrixMotion(pt1)^-T = " << std::endl << m3b << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v1; - v1.setRandom(); - - { - rl::math::MotionVector mv1 = v1; - - rl::math::Vector6 v2 = pt1.matrixMotion() * v1; - rl::math::MotionVector mv2 = pt1 * mv1; - - if (!mv2.matrix().isApprox(v2)) - { - std::cerr << "pt1 * mv1 != matrixMotion(pt1) * v1" << std::endl; - std::cerr << "pt1 * mv1 = " << mv2.matrix().transpose() << std::endl; - std::cerr << "matrixMotion(pt1) * v1 = " << v2.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v3 = pt1.inverseMotion() * v2; - rl::math::MotionVector mv3 = pt1 / mv2; - - if (!mv3.matrix().isApprox(v3)) - { - std::cerr << "inv(pt1) / mv2 != inverseMotion(pt1) * v2" << std::endl; - std::cerr << "inv(pt1) / mv2 = " << mv3.matrix().transpose() << std::endl; - std::cerr << "inverseMotion(pt1) * v2 = " << v3.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - if (!mv3.matrix().isApprox(mv1.matrix())) - { - std::cerr << "pt1.inverse() * pt1 * mv1 != mv1" << std::endl; - std::cerr << "pt1.inverse() * pt1 * mv1 = " << mv3.matrix().transpose() << std::endl; - std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::MotionVector mv4 = pt1.inverse() * mv2; - - if (!mv4.matrix().isApprox(mv1.matrix())) - { - std::cerr << "pt1.inverse() * pt1 * mv1 != mv1" << std::endl; - std::cerr << "pt1.inverse() * pt1 * mv1 = " << mv4.matrix().transpose() << std::endl; - std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; - exit(EXIT_FAILURE); - } - } - - { - rl::math::ForceVector fv1 = v1; - - rl::math::Vector6 v2 = pt1.matrixForce() * v1; - rl::math::ForceVector fv2 = pt1 * fv1; - - if (!fv2.matrix().isApprox(v2)) - { - std::cerr << "pt1 * fv1 != matrixForce(pt1) * v1" << std::endl; - std::cerr << "pt1 * fv1 = " << fv2.matrix().transpose() << std::endl; - std::cerr << "matrixForce(pt1) * v1 = " << v2.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Vector6 v3 = pt1.inverseForce() * v2; - rl::math::ForceVector fv3 = pt1 / fv2; - - if (!fv3.matrix().isApprox(v3)) - { - std::cerr << "inv(pt1) / fv2 != inverseForce(pt1) * v2" << std::endl; - std::cerr << "inv(pt1) / fv2 = " << fv3.matrix().transpose() << std::endl; - std::cerr << "inverseForce(pt1) * v2 = " << v3.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - if (!fv3.matrix().isApprox(fv1.matrix())) - { - std::cerr << "pt1.inverse() * pt1 * fv1 != fv1" << std::endl; - std::cerr << "pt1.inverse() * pt1 * fv1 = " << fv3.matrix().transpose() << std::endl; - std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::ForceVector fv4 = pt1.inverse() * fv2; - - if (!fv4.matrix().isApprox(fv1.matrix())) - { - std::cerr << "pt1.inverse() * pt1 * fv1 != fv1" << std::endl; - std::cerr << "pt1.inverse() * pt1 * fv1 = " << fv4.matrix().transpose() << std::endl; - std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; - exit(EXIT_FAILURE); - } - } -} - -void -testRigidBodyInertia() -{ - rl::math::RigidBodyInertia rbi1; - rbi1.cog().setRandom(); - rbi1.inertia().setRandom(); - rbi1.mass() = 10; - - rl::math::RigidBodyInertia rbi2; - rbi2.cog().setRandom(); - rbi2.inertia().setRandom(); - rbi2.mass() = 20; - - rl::math::RigidBodyInertia rbi3 = rbi1 + rbi2; - rl::math::RigidBodyInertia rbi4 = rbi3 - rbi2; - - if (!rbi4.matrix().isApprox(rbi1.matrix())) - { - std::cerr << "rbi1 + rbi2 - rbi2 != rbi1" << std::endl; - std::cerr << "rbi1 + rbi2 - rbi2 = " << std::endl << rbi4.matrix() << std::endl; - std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::RigidBodyInertia rbi1_2 = rbi1 * 2; - rl::math::RigidBodyInertia rbi1_rbi1 = rbi1 + rbi1; - rl::math::RigidBodyInertia rbi1_2_05 = rbi1_2 * 0.5; - - if (!rbi1_2.matrix().isApprox(rbi1_rbi1.matrix())) - { - std::cerr << "rbi1 * 2 != rbi1 + rbi1" << std::endl; - std::cerr << "rbi1 * 2 = " << std::endl << rbi1_2.matrix() << std::endl; - std::cerr << "rbi1 + rbi1 = " << std::endl << rbi1_rbi1.matrix() << std::endl; - exit(EXIT_FAILURE); - } - - if (!rbi1_2_05.matrix().isApprox(rbi1.matrix())) - { - std::cerr << "rbi1 * 2 * 0.5 != rbi1" << std::endl; - std::cerr << "rbi1 * 2 * 0.5 = " << std::endl << rbi1_2_05.matrix() << std::endl; - std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); - pt1.translation().setRandom(); - - rl::math::RigidBodyInertia rbi5 = pt1 * rbi1; - rl::math::RigidBodyInertia rbi6 = pt1 / rbi5; - - if (!rbi6.matrix().isApprox(rbi1.matrix())) - { - std::cerr << "inv(pt1) * pt1 * rbi1 != rbi1" << std::endl; - std::cerr << "inv(pt1) * pt1 * rbi1 = " << std::endl << rbi6.matrix() << std::endl; - std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 m1 = pt1.matrixForce() * rbi1.matrix() * pt1.inverseMotion(); - - if (!rbi5.matrix().isApprox(m1)) - { - std::cerr << "pt1 * rbi1 != matrixForce(pt1) * rbi1 * inverseMotion(pt1)" << std::endl; - std::cerr << "pt1 * rbi1 = " << std::endl << rbi5.matrix() << std::endl; - std::cerr << "matrixForce(pt1) * rbi1 * inverseMotion(pt1) = " << std::endl << m1 << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 m2 = pt1.matrixMotion().transpose() * m1 * pt1.matrixMotion(); - - if (!rbi1.matrix().isApprox(m2)) - { - std::cerr << "rbi1 != matrixMotion(pt1)^T * rbi5 * matrixMotion(pt1)" << std::endl; - std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; - std::cerr << "matrixMotion(pt1)^T * rbi5 * matrixMotion(pt1) = " << std::endl << m2 << std::endl; - exit(EXIT_FAILURE); - } -} - -void -testSpatialCrossProduct() -{ - rl::math::Vector6 v1; - v1.setRandom(); - - rl::math::Vector6 v2; - v2.setRandom(); - - rl::math::MotionVector mv1 = v1; - - rl::math::MotionVector mv2 = v2; - - rl::math::Vector6 v3 = mv1.cross66Motion() * v2; - rl::math::MotionVector mv3 = mv1.cross(mv2); - - if (!mv3.matrix().isApprox(v3)) - { - std::cerr << "mv1 x mv2 != crossMotion(mv1) x v2" << std::endl; - std::cerr << "mv1 x mv2 = " << mv3.matrix().transpose() << std::endl; - std::cerr << "crossMotion(mv1) x v2 = " << v3.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::MotionVector mv4 = -mv2.cross(mv1); - - if (!mv4.matrix().isApprox(mv3.matrix())) - { - std::cerr << "mv1 x mv2 != -mv2 x mv1" << std::endl; - std::cerr << "mv1 x mv2 = " << mv3.matrix().transpose() << std::endl; - std::cerr << "-mv2 x mv1 = " << mv4.matrix().transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::ForceVector fv2 = v2; - - rl::math::Vector6 v5 = mv1.cross66Force() * v2; - rl::math::ForceVector fv5 = mv1.cross(fv2); - - if (!fv5.matrix().isApprox(v5)) - { - std::cerr << "mv1 x fv2 != crossForce(mv1) x v2" << std::endl; - std::cerr << "mv1 x fv2 = " << fv5.matrix().transpose() << std::endl; - std::cerr << "crossForce(mv1) x v2 = " << v5.transpose() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 mv1CrossForce = -mv1.cross66Motion().transpose(); - - if (!mv1CrossForce.matrix().isApprox(mv1.cross66Force())) - { - std::cerr << "crossForce(mv1) != -crossMotion(mv1)^T" << std::endl; - std::cerr << "crossForce(mv1) = " << std::endl << mv1CrossForce << std::endl; - std::cerr << "-crossMotion(mv1)^T = " << std::endl << mv1.cross66Force() << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 cross1 = (mv1 + mv2).cross66Motion(); - rl::math::Matrix66 cross2 = mv1.cross66Motion() + mv2.cross66Motion(); - - if (!cross1.matrix().isApprox(cross2)) - { - std::cerr << "crossMotion(mv1 + mv2) != crossMotion(mv1) + crossMotion(mv2)" << std::endl; - std::cerr << "crossMotion(mv1 + mv2) = " << std::endl << cross1 << std::endl; - std::cerr << "crossMotion(mv1) + crossMotion(mv2) = " << std::endl << cross2 << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 cross3 = (mv1 + mv2).cross66Force(); - rl::math::Matrix66 cross4 = mv1.cross66Force() + mv2.cross66Force(); - - if (!cross3.matrix().isApprox(cross4)) - { - std::cerr << "crossForce(mv1 + mv2) != crossForce(mv1) + crossForce(mv2)" << std::endl; - std::cerr << "crossForce(mv1 + mv2) = " << std::endl << cross3 << std::endl; - std::cerr << "crossForce(mv1) + crossForce(mv2) = " << std::endl << cross4 << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::PlueckerTransform pt; - pt.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); - pt.translation().setRandom(); - - rl::math::Matrix66 m1 = (pt * mv1).cross66Motion(); - rl::math::Matrix66 m2 = pt.matrixMotion() * mv1.cross66Motion() * pt.inverse().matrixMotion(); - - if (!m1.matrix().isApprox(m2)) - { - std::cerr << "crossMotion(pt * mv1) != pt * crossMotion(mv1) * pt^-1" << std::endl; - std::cerr << "crossMotion(pt * mv1) = " << std::endl << m1 << std::endl; - std::cerr << "pt * crossMotion(mv1) * pt^-1 = " << std::endl << m2 << std::endl; - exit(EXIT_FAILURE); - } - - rl::math::Matrix66 m3 = (pt * mv1).cross66Force(); - rl::math::Matrix66 m4 = pt.matrixForce() * mv1.cross66Force() * pt.inverse().matrixForce(); - - if (!m3.matrix().isApprox(m4)) - { - std::cerr << "crossForce(pt * mv1) != pt * crossForce(mv1) * pt^-1" << std::endl; - std::cerr << "crossForce(pt * mv1) = " << std::endl << m3 << std::endl; - std::cerr << "pt * crossForce(mv1) * pt^-1 = " << std::endl << m4 << std::endl; - exit(EXIT_FAILURE); - } -} - -void -testSpatialDotProduct() -{ - rl::math::MotionVector mv1; - mv1.angular().setRandom(); - mv1.linear().setRandom(); - - rl::math::ForceVector fv2; - fv2.moment().setRandom(); - fv2.force().setRandom(); - - rl::math::Real dot1 = mv1.angular().dot(fv2.moment()) + mv1.linear().dot(fv2.force()); - rl::math::Real dot2 = mv1.dot(fv2); - - if (!Eigen::internal::isApprox(dot2, dot1)) - { - std::cerr << "mv1 * fv2 != mv1.angular * fv2.moment + mv1.linear * fv2.force" << std::endl; - std::cerr << "mv1 * fv2 = " << dot2 << std::endl; - std::cerr << "mv1.angular * fv2.moment + mv1.linear * fv2.force = " << dot1 << std::endl; - exit(EXIT_FAILURE); - } -} - -int -main(int argc, char** argv) -{ - testEuclideanCrossProduct(); - testMotionVector(); - testForceVector(); - testSpatialCrossProduct(); - testSpatialDotProduct(); - testPlueckerTransform(); - testRigidBodyInertia(); - testArticulatedBodyInertia(); - return EXIT_SUCCESS; -} From fa6a9e5ddc5e4cc156216978f070237a42e50d6c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 Apr 2018 23:19:30 +0200 Subject: [PATCH 087/546] Update UrdfFactory to new spatial definition --- src/rl/mdl/UrdfFactory.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 5d37ae81..765b6ce0 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -226,8 +226,7 @@ ::std::cout << "\tchild: " << child->getName() << ::std::endl; ::std::cout << "\torigin.translation: " << fixed->t.translation().transpose() << ::std::endl; ::std::cout << "\torigin.rotation: " << fixed->t.rotation().eulerAngles(2, 1, 0).reverse().transpose() * ::rl::math::RAD2DEG << ::std::endl; - fixed->x.rotation() = fixed->t.linear().transpose(); - fixed->x.translation() = fixed->t.translation(); + fixed->x = fixed->t; // joint From a1c8bcc7b2cf3230f86dae4070faf75585de3d86 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 24 Apr 2018 00:10:59 +0200 Subject: [PATCH 088/546] Update PlueckerTransform to use Transform --- src/rl/math/spatial/PlueckerTransform.h | 106 ++++++++---------- src/rl/math/spatial/PlueckerTransform.hxx | 36 +++--- src/rl/mdl/Cylindrical.cpp | 6 +- src/rl/mdl/Frame.cpp | 2 - src/rl/mdl/Frame.h | 2 - src/rl/mdl/Helical.cpp | 9 +- src/rl/mdl/Model.cpp | 12 +- src/rl/mdl/Prismatic.cpp | 3 +- src/rl/mdl/Revolute.cpp | 3 +- src/rl/mdl/Spherical.cpp | 3 +- src/rl/mdl/Transform.cpp | 5 +- src/rl/mdl/Transform.h | 2 - src/rl/mdl/UrdfFactory.cpp | 16 ++- src/rl/mdl/XmlFactory.cpp | 22 ++-- src/rl/plan/Eet.cpp | 2 +- .../rlEuclideanCrossProductTest.cpp | 2 +- .../rlSpatialArticulatedBodyInertiaTest.cpp | 2 +- .../rlSpatialCrossProductTest.cpp | 2 +- .../rlSpatialPlueckerTransformTest.cpp | 40 +++---- .../rlSpatialRigidBodyInertiaTest.cpp | 2 +- 20 files changed, 123 insertions(+), 154 deletions(-) diff --git a/src/rl/math/spatial/PlueckerTransform.h b/src/rl/math/spatial/PlueckerTransform.h index 83871579..49f9c307 100644 --- a/src/rl/math/spatial/PlueckerTransform.h +++ b/src/rl/math/spatial/PlueckerTransform.h @@ -60,30 +60,25 @@ namespace rl typedef ::Eigen::Matrix MatrixType; - typedef ::Eigen::Matrix RotationType; + typedef ::Eigen::Transform TransformType; - typedef const RotationType ConstRotationType; + typedef const TransformType ConstTransformType; - typedef ::Eigen::Transform TransformType; + typedef typename TransformType::LinearPart LinearPart; - typedef ::Eigen::Matrix TranslationType; + typedef typename TransformType::ConstLinearPart ConstLinearPart; - typedef const TranslationType ConstTranslationType; + typedef typename TransformType::TranslationPart TranslationPart; - PlueckerTransform() - { - } + typedef typename TransformType::ConstTranslationPart ConstTranslationPart; - PlueckerTransform(const RotationType& rotation, const TranslationType& translation) : - rotationData(rotation), - translationData(translation) + PlueckerTransform() { } template PlueckerTransform(const ::Eigen::Transform& other) : - rotationData(other.linear()), - translationData(other.translation()) + data(other) { } @@ -93,74 +88,73 @@ namespace rl static PlueckerTransform Identity() { - return PlueckerTransform( - RotationType::Identity(), - TransformType::Zero() - ); + return PlueckerTransform(TransformType::Identity()); } PlueckerTransform inverse() const { - PlueckerTransform res; - res.rotation() = rotation().transpose(); - res.translation() = -rotation().transpose() * translation(); - return res; + return PlueckerTransform(data.inverse()); } MatrixType inverseForce() const { MatrixType res; - res.template topLeftCorner<3, 3>() = rotation(); - res.template topRightCorner<3, 3>() = translation().cross33() * rotation(); + res.template topLeftCorner<3, 3>() = linear(); + res.template topRightCorner<3, 3>() = translation().cross33() * linear(); res.template bottomLeftCorner<3, 3>().setZero(); - res.template bottomRightCorner<3, 3>() = rotation(); + res.template bottomRightCorner<3, 3>() = linear(); return res; } MatrixType inverseMotion() const { MatrixType res; - res.template topLeftCorner<3, 3>() = rotation(); + res.template topLeftCorner<3, 3>() = linear(); res.template topRightCorner<3, 3>().setZero(); - res.template bottomLeftCorner<3, 3>() = translation().cross33() * rotation(); - res.template bottomRightCorner<3, 3>() = rotation(); + res.template bottomLeftCorner<3, 3>() = translation().cross33() * linear(); + res.template bottomRightCorner<3, 3>() = linear(); return res; } template bool isApprox(const PlueckerTransform& other, const typename ::Eigen::NumTraits::Real& prec = ::Eigen::NumTraits::dummy_precision()) const { - return rotation().isApprox(other.rotation(), prec) && translation().isApprox(other.translation(), prec); + return data.isApprox(other.data, prec); } MatrixType matrixForce() const { MatrixType res; - res.template topLeftCorner<3, 3>() = rotation().transpose(); - res.template topRightCorner<3, 3>() = -rotation().transpose() * translation().cross33(); + res.template topLeftCorner<3, 3>() = linear().transpose(); + res.template topRightCorner<3, 3>() = -linear().transpose() * translation().cross33(); res.template bottomLeftCorner<3, 3>().setZero(); - res.template bottomRightCorner<3, 3>() = rotation().transpose(); + res.template bottomRightCorner<3, 3>() = linear().transpose(); return res; } MatrixType matrixMotion() const { MatrixType res; - res.template topLeftCorner<3, 3>() = rotation().transpose(); + res.template topLeftCorner<3, 3>() = linear().transpose(); res.template topRightCorner<3, 3>().setZero(); - res.template bottomLeftCorner<3, 3>() = -rotation().transpose() * translation().cross33(); - res.template bottomRightCorner<3, 3>() = rotation().transpose(); + res.template bottomLeftCorner<3, 3>() = -linear().transpose() * translation().cross33(); + res.template bottomRightCorner<3, 3>() = linear().transpose(); return res; } template PlueckerTransform& operator=(const ::Eigen::Transform& other) { - rotation() = other.linear(); - translation() = other.translation(); + data = other; return *this; } + template + ::Eigen::Transform operator*(const ::Eigen::Transform& other) const + { + return data * other; + } + template ForceVector operator*(const ForceVector& other) const; @@ -170,10 +164,7 @@ namespace rl template PlueckerTransform operator*(const PlueckerTransform& other) const { - PlueckerTransform res; - res.rotation() = rotation() * other.rotation(); - res.translation() = rotation() * other.translation() + translation(); - return res; + return PlueckerTransform(data * other.data); } template @@ -194,46 +185,45 @@ namespace rl template ArticulatedBodyInertia operator/(const ArticulatedBodyInertia& other) const; - RotationType& rotation() + LinearPart linear() { - return rotationData; + return data.linear(); } - ConstRotationType& rotation() const + ConstLinearPart linear() const { - return rotationData; + return data.linear(); } void setIdentity() { - rotation().setIdentity(); - translation().setZero(); + data.setIdentity(); } - TransformType transform() const + TransformType& transform() { - TransformType res; - res.linear() = rotation(); - res.translation() = translation(); - return res; + return data; } - TranslationType& translation() + ConstTransformType transform() const { - return translationData; + return data; } - ConstTranslationType& translation() const + TranslationPart translation() { - return translationData; + return data.translation(); + } + + ConstTranslationPart translation() const + { + return data.translation(); } protected: private: - RotationType rotationData; - - TranslationType translationData; + TransformType data; }; } } diff --git a/src/rl/math/spatial/PlueckerTransform.hxx b/src/rl/math/spatial/PlueckerTransform.hxx index 7ff88832..23060425 100644 --- a/src/rl/math/spatial/PlueckerTransform.hxx +++ b/src/rl/math/spatial/PlueckerTransform.hxx @@ -40,8 +40,8 @@ namespace rl PlueckerTransform::operator*(const ForceVector& other) const { ForceVector res; - res.moment() = rotation().transpose() * (other.moment() - translation().cross(other.force())); - res.force() = rotation().transpose() * other.force(); + res.moment() = linear().transpose() * (other.moment() - translation().cross(other.force())); + res.force() = linear().transpose() * other.force(); return res; } @@ -52,8 +52,8 @@ namespace rl PlueckerTransform::operator*(const MotionVector& other) const { MotionVector res; - res.angular() = rotation().transpose() * other.angular(); - res.linear() = rotation().transpose() * (other.linear() - translation().cross(other.angular())); + res.angular() = linear().transpose() * other.angular(); + res.linear() = linear().transpose() * (other.linear() - translation().cross(other.angular())); return res; } @@ -66,8 +66,8 @@ namespace rl RigidBodyInertia res; ::Eigen::Matrix px = translation().cross33(); ::Eigen::Matrix c_m_p = other.cog() - other.mass() * translation(); - res.cog() = rotation().transpose() * c_m_p; - res.inertia() = rotation().transpose() * (other.inertia() + px * other.cog().cross33() + c_m_p.cross33() * px) * rotation(); + res.cog() = linear().transpose() * c_m_p; + res.inertia() = linear().transpose() * (other.inertia() + px * other.cog().cross33() + c_m_p.cross33() * px) * linear(); res.mass() = other.mass(); return res; } @@ -81,9 +81,9 @@ namespace rl ArticulatedBodyInertia res; ::Eigen::Matrix px = translation().cross33(); ::Eigen::Matrix c_px_m = other.cog() - px * other.mass(); - res.cog() = rotation().transpose() * c_px_m * rotation(); - res.inertia() = rotation().transpose() * (other.inertia() - px * other.cog().transpose() + c_px_m * px) * rotation(); - res.mass() = rotation().transpose() * other.mass() * rotation(); + res.cog() = linear().transpose() * c_px_m * linear(); + res.inertia() = linear().transpose() * (other.inertia() - px * other.cog().transpose() + c_px_m * px) * linear(); + res.mass() = linear().transpose() * other.mass() * linear(); return res; } @@ -94,8 +94,8 @@ namespace rl PlueckerTransform::operator/(const ForceVector& other) const { ForceVector res; - res.moment() = rotation() * other.moment() + translation().cross(rotation() * other.force()); - res.force() = rotation() * other.force(); + res.moment() = linear() * other.moment() + translation().cross(linear() * other.force()); + res.force() = linear() * other.force(); return res; } @@ -106,8 +106,8 @@ namespace rl PlueckerTransform::operator/(const MotionVector& other) const { MotionVector res; - res.angular() = rotation() * other.angular(); - res.linear() = rotation() * other.linear() + translation().cross(rotation() * other.angular()); + res.angular() = linear() * other.angular(); + res.linear() = linear() * other.linear() + translation().cross(linear() * other.angular()); return res; } @@ -119,10 +119,10 @@ namespace rl { RigidBodyInertia res; ::Eigen::Matrix px = translation().cross33(); - ::Eigen::Matrix R_c = rotation() * other.cog(); + ::Eigen::Matrix R_c = linear() * other.cog(); ::Eigen::Matrix R_c_m_p = R_c + other.mass() * translation(); res.cog() = R_c_m_p; - res.inertia() = rotation() * other.inertia() * rotation().transpose() - px * R_c.cross33() - R_c_m_p.cross33() * px; + res.inertia() = linear() * other.inertia() * linear().transpose() - px * R_c.cross33() - R_c_m_p.cross33() * px; res.mass() = other.mass(); return res; } @@ -134,12 +134,12 @@ namespace rl PlueckerTransform::operator/(const ArticulatedBodyInertia& other) const { ArticulatedBodyInertia res; - typename ArticulatedBodyInertia::CenterOfGravityType c = rotation() * other.cog() * rotation().transpose(); - typename ArticulatedBodyInertia::MassType m = rotation() * other.mass() * rotation().transpose(); + typename ArticulatedBodyInertia::CenterOfGravityType c = linear() * other.cog() * linear().transpose(); + typename ArticulatedBodyInertia::MassType m = linear() * other.mass() * linear().transpose(); ::Eigen::Matrix px = translation().cross33(); ::Eigen::Matrix c_px_m = c + px * m; res.cog() = c_px_m; - res.inertia() = rotation() * other.inertia() * rotation().transpose() + px * c.transpose() - c_px_m * px; + res.inertia() = linear() * other.inertia() * linear().transpose() + px * c.transpose() - c_px_m * px; res.mass() = m; return res; } diff --git a/src/rl/mdl/Cylindrical.cpp b/src/rl/mdl/Cylindrical.cpp index 764d2ed5..d9ed682a 100644 --- a/src/rl/mdl/Cylindrical.cpp +++ b/src/rl/mdl/Cylindrical.cpp @@ -57,10 +57,8 @@ namespace rl Cylindrical::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; - this->t = ::rl::math::AngleAxis(this->q(0) + this->offset(0), this->S.block<3, 1>(0, 0)); - this->x.rotation() = this->t.linear(); - this->t.translation() = this->S.block<3, 1>(3, 1) * (this->q(1) + this->offset(1)); - this->x.translation() = this->t.translation(); + this->x.linear() = ::rl::math::AngleAxis(this->q(0) + this->offset(0), this->S.block<3, 1>(0, 0)).toRotationMatrix(); + this->x.translation() = this->S.block<3, 1>(3, 1) * (this->q(1) + this->offset(1)); } } } diff --git a/src/rl/mdl/Frame.cpp b/src/rl/mdl/Frame.cpp index 6dcd3547..d80b8f7b 100644 --- a/src/rl/mdl/Frame.cpp +++ b/src/rl/mdl/Frame.cpp @@ -38,7 +38,6 @@ namespace rl i(), iA(), pA(), - t(), v(), x(), descriptor() @@ -49,7 +48,6 @@ namespace rl this->i.setIdentity(); // TODO this->iA.setIdentity(); // TODO this->pA.setZero(); // TODO - this->t.setIdentity(); // TODO this->v.setZero(); // TODO this->x.setIdentity(); // TODO } diff --git a/src/rl/mdl/Frame.h b/src/rl/mdl/Frame.h index 40039078..0786e0b5 100644 --- a/src/rl/mdl/Frame.h +++ b/src/rl/mdl/Frame.h @@ -90,8 +90,6 @@ namespace rl ::rl::math::ForceVector pA; - ::rl::math::Transform t; - ::rl::math::MotionVector v; ::rl::math::PlueckerTransform x; diff --git a/src/rl/mdl/Helical.cpp b/src/rl/mdl/Helical.cpp index 07cd2259..2d659ef0 100644 --- a/src/rl/mdl/Helical.cpp +++ b/src/rl/mdl/Helical.cpp @@ -59,18 +59,15 @@ namespace rl Helical::setPitch(const ::rl::math::Real& h) { this->h = h; - this->t.translation() = this->S.block<3, 1>(3, 0) * this->h * (this->q(0) + this->offset(0)); - this->x.translation() = this->t.translation(); + this->x.translation() = this->S.block<3, 1>(3, 0) * this->h * (this->q(0) + this->offset(0)); } void Helical::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; - this->t = ::rl::math::AngleAxis(this->q(0), this->S.block<3, 1>(0, 0)); - this->x.rotation() = this->t.linear(); - this->t.translation() = this->S.block<3, 1>(3, 0) * this->h * (this->q(0) + this->offset(0)); - this->x.translation() = this->t.translation(); + this->x.linear() = ::rl::math::AngleAxis(this->q(0), this->S.block<3, 1>(0, 0)).toRotationMatrix(); + this->x.translation() = this->S.block<3, 1>(3, 0) * this->h * (this->q(0) + this->offset(0)); } } } diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 7effe35d..db70ca03 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -213,7 +213,7 @@ namespace rl { assert(i < this->getBodies()); - return this->bodies[i]->t; + return this->bodies[i]->x.transform(); } const ::rl::math::Matrix& @@ -287,7 +287,7 @@ namespace rl { assert(i < this->getOperationalDof()); - return this->tree[this->leaves[i]]->t; + return this->tree[this->leaves[i]]->x.transform(); } const ::rl::math::MotionVector& @@ -589,7 +589,7 @@ namespace rl { assert(i < this->tools.size()); - return this->tree[this->tools[i]]->t; + return this->tree[this->tools[i]]->x.transform(); } const ::rl::math::Transform& @@ -597,7 +597,7 @@ namespace rl { assert(i < this->tools.size()); - return this->tree[this->tools[i]]->t; + return this->tree[this->tools[i]]->x.transform(); } void @@ -671,13 +671,13 @@ namespace rl ::rl::math::Transform& Model::world() { - return this->tree[this->root]->t; + return this->tree[this->root]->x.transform(); } const ::rl::math::Transform& Model::world() const { - return this->tree[this->root]->t; + return this->tree[this->root]->x.transform(); } } } diff --git a/src/rl/mdl/Prismatic.cpp b/src/rl/mdl/Prismatic.cpp index 3b5a9269..6e0dd461 100644 --- a/src/rl/mdl/Prismatic.cpp +++ b/src/rl/mdl/Prismatic.cpp @@ -49,8 +49,7 @@ namespace rl Prismatic::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; - this->t.translation() = this->S.block<3, 1>(3, 0) * (this->q(0) + this->offset(0)); - this->x.translation() = this->t.translation(); + this->x.translation() = this->S.block<3, 1>(3, 0) * (this->q(0) + this->offset(0)); } } } diff --git a/src/rl/mdl/Revolute.cpp b/src/rl/mdl/Revolute.cpp index fdfe11f8..fc9a5200 100644 --- a/src/rl/mdl/Revolute.cpp +++ b/src/rl/mdl/Revolute.cpp @@ -122,8 +122,7 @@ namespace rl Revolute::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; - this->t = ::rl::math::AngleAxis(this->q(0) + this->offset(0), this->S.block<3, 1>(0, 0)); - this->x.rotation() = this->t.linear(); + this->x.linear() = ::rl::math::AngleAxis(this->q(0) + this->offset(0), this->S.block<3, 1>(0, 0)).toRotationMatrix(); } ::rl::math::Real diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 0662c2ee..4bdceef3 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -113,8 +113,7 @@ namespace rl Spherical::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; - this->t = ::Eigen::Map(this->q.data()); - this->x.rotation() = this->t.linear(); + this->x.linear() = ::Eigen::Map(this->q.data()).toRotationMatrix(); } void diff --git a/src/rl/mdl/Transform.cpp b/src/rl/mdl/Transform.cpp index 65d91c36..46d88d25 100644 --- a/src/rl/mdl/Transform.cpp +++ b/src/rl/mdl/Transform.cpp @@ -35,11 +35,9 @@ namespace rl Element(), in(nullptr), out(nullptr), - t(), x(), descriptor() { - this->t.setIdentity(); // TODO this->x.setIdentity(); // TODO } @@ -83,8 +81,7 @@ namespace rl void Transform::forwardPosition() { - this->out->t = this->in->t * this->t; - this->out->x = this->out->t; + this->out->x = this->in->x * this->x; } void diff --git a/src/rl/mdl/Transform.h b/src/rl/mdl/Transform.h index 07b35011..04f12e29 100644 --- a/src/rl/mdl/Transform.h +++ b/src/rl/mdl/Transform.h @@ -83,8 +83,6 @@ namespace rl Frame* out; - ::rl::math::Transform t; - ::rl::math::PlueckerTransform x; protected: diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 765b6ce0..2ac8c215 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -201,7 +201,7 @@ ::std::cout << "\tchild: " << child->getName() << ::std::endl; ::std::string tmp = path.eval("string(origin/@rpy)").getValue< ::std::string>(); ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); - fixed->t = ::rl::math::AngleAxis( + fixed->x.linear() = ::rl::math::AngleAxis( ::boost::lexical_cast< ::rl::math::Real>(rpy[2]), ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( @@ -210,7 +210,7 @@ ::std::cout << "\tchild: " << child->getName() << ::std::endl; ) * ::rl::math::AngleAxis( ::boost::lexical_cast< ::rl::math::Real>(rpy[0]), ::rl::math::Vector3::UnitX() - ); + ).toRotationMatrix(); } if (path.eval("count(origin/@xyz) > 0").getValue()) @@ -219,14 +219,12 @@ ::std::cout << "\tchild: " << child->getName() << ::std::endl; ::std::string tmp = path.eval("string(origin/@xyz)").getValue< ::std::string>(); ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); - fixed->t.translation().x() = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); - fixed->t.translation().y() = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); - fixed->t.translation().z() = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); + fixed->x.translation().x() = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); + fixed->x.translation().y() = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); + fixed->x.translation().z() = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); } -::std::cout << "\torigin.translation: " << fixed->t.translation().transpose() << ::std::endl; -::std::cout << "\torigin.rotation: " << fixed->t.rotation().eulerAngles(2, 1, 0).reverse().transpose() * ::rl::math::RAD2DEG << ::std::endl; - - fixed->x = fixed->t; +::std::cout << "\torigin.translation: " << fixed->x.translation().transpose() << ::std::endl; +::std::cout << "\torigin.rotation: " << fixed->x.linear().eulerAngles(2, 1, 0).reverse().transpose() * ::rl::math::RAD2DEG << ::std::endl; // joint diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index 8a60aa08..06d4fce7 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -153,7 +153,7 @@ namespace rl model->add(w); - w->t = ::rl::math::AngleAxis( + w->x.linear() = ::rl::math::AngleAxis( path.eval("number(rotation/z)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( @@ -162,11 +162,11 @@ namespace rl ) * ::rl::math::AngleAxis( path.eval("number(rotation/x)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX() - ); + ).toRotationMatrix(); - w->t.translation().x() = path.eval("number(translation/x)").getValue< ::rl::math::Real>(0); - w->t.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); - w->t.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); + w->x.translation().x() = path.eval("number(translation/x)").getValue< ::rl::math::Real>(0); + w->x.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); + w->x.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); w->setGravity( path.eval("number(g/x)").getValue< ::rl::math::Real>(0), @@ -297,7 +297,7 @@ namespace rl model->add(f, a, b); - f->t = ::rl::math::AngleAxis( + f->x.linear() = ::rl::math::AngleAxis( path.eval("number(rotation/z)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( @@ -306,13 +306,11 @@ namespace rl ) * ::rl::math::AngleAxis( path.eval("number(rotation/x)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX() - ); - - f->t.translation().x() = path.eval("number(translation/x)").getValue< ::rl::math::Real>(0); - f->t.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); - f->t.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); + ).toRotationMatrix(); - f->x = f->t; + f->x.translation().x() = path.eval("number(translation/x)").getValue< ::rl::math::Real>(0); + f->x.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); + f->x.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); transform = f; } diff --git a/src/rl/plan/Eet.cpp b/src/rl/plan/Eet.cpp index 4bbf7bee..6f9f2d36 100644 --- a/src/rl/plan/Eet.cpp +++ b/src/rl/plan/Eet.cpp @@ -437,7 +437,7 @@ namespace rl // uniform sampling for orientation - chosen.linear() = ::rl::math::Matrix33(::rl::math::Quaternion::Random(::rl::math::Vector3(this->rand(), this->rand(), this->rand()))); + chosen.linear() = ::rl::math::Quaternion::Random(::rl::math::Vector3(this->rand(), this->rand(), this->rand())).toRotationMatrix(); nearest = this->nearest(this->tree[0], chosen); // nearest vertex in tree diff --git a/tests/rlSpatialTest/rlEuclideanCrossProductTest.cpp b/tests/rlSpatialTest/rlEuclideanCrossProductTest.cpp index 76298d52..50c6a1a2 100644 --- a/tests/rlSpatialTest/rlEuclideanCrossProductTest.cpp +++ b/tests/rlSpatialTest/rlEuclideanCrossProductTest.cpp @@ -61,7 +61,7 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } - rl::math::Matrix33 r = rl::math::Matrix33(rl::math::Quaternion::Random()); + rl::math::Matrix33 r = rl::math::Quaternion::Random().toRotationMatrix(); rl::math::Matrix33 m3a = (r * a).cross33(); rl::math::Matrix33 m3b = r * a.cross33() * r.transpose(); diff --git a/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp b/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp index 3ed325a8..8a094f3c 100644 --- a/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp +++ b/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp @@ -76,7 +76,7 @@ main(int argc, char** argv) } rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); + pt1.linear() = rl::math::Quaternion::Random().toRotationMatrix(); pt1.translation().setRandom(); rl::math::ArticulatedBodyInertia abi5 = pt1 * abi1; diff --git a/tests/rlSpatialTest/rlSpatialCrossProductTest.cpp b/tests/rlSpatialTest/rlSpatialCrossProductTest.cpp index d7ef0740..a8cede53 100644 --- a/tests/rlSpatialTest/rlSpatialCrossProductTest.cpp +++ b/tests/rlSpatialTest/rlSpatialCrossProductTest.cpp @@ -111,7 +111,7 @@ main(int argc, char** argv) } rl::math::PlueckerTransform pt; - pt.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); + pt.linear() = rl::math::Quaternion::Random().toRotationMatrix(); pt.translation().setRandom(); rl::math::Matrix66 m1 = (pt * mv1).cross66Motion(); diff --git a/tests/rlSpatialTest/rlSpatialPlueckerTransformTest.cpp b/tests/rlSpatialTest/rlSpatialPlueckerTransformTest.cpp index f8fb4bf6..8546d1dc 100644 --- a/tests/rlSpatialTest/rlSpatialPlueckerTransformTest.cpp +++ b/tests/rlSpatialTest/rlSpatialPlueckerTransformTest.cpp @@ -35,17 +35,17 @@ int main(int argc, char** argv) { rl::math::Transform t0; - t0 = rl::math::Quaternion::Random(); + t0.linear() = rl::math::Quaternion::Random().toRotationMatrix(); t0.translation().setRandom(); rl::math::PlueckerTransform pt0; - pt0.rotation() = t0.linear(); + pt0.linear() = t0.linear(); pt0.translation() = t0.translation(); - if (!pt0.rotation().isApprox(t0.linear()) || !pt0.translation().isApprox(t0.translation())) + if (!pt0.linear().isApprox(t0.linear()) || !pt0.translation().isApprox(t0.translation())) { std::cerr << "pt0 != t0" << std::endl; - std::cerr << "pt0.rotation = " << std::endl << pt0.rotation() << std::endl; + std::cerr << "pt0.rotation = " << std::endl << pt0.linear() << std::endl; std::cerr << "pt0.translation = " << pt0.translation().transpose() << std::endl; std::cerr << "t0.linear = " << std::endl << t0.linear() << std::endl; std::cerr << "t0.translation = " << t0.translation().transpose() << std::endl; @@ -53,15 +53,15 @@ main(int argc, char** argv) } rl::math::Transform t1; - t1 = rl::math::Quaternion::Random(); + t1.linear() = rl::math::Quaternion::Random().toRotationMatrix(); t1.translation().setRandom(); rl::math::PlueckerTransform pt1(t1); - if (!pt1.rotation().isApprox(t1.linear()) || !pt1.translation().isApprox(t1.translation())) + if (!pt1.linear().isApprox(t1.linear()) || !pt1.translation().isApprox(t1.translation())) { std::cerr << "pt1(t1) != t1" << std::endl; - std::cerr << "pt1(t1).rotation = " << std::endl << pt1.rotation() << std::endl; + std::cerr << "pt1(t1).rotation = " << std::endl << pt1.linear() << std::endl; std::cerr << "pt1(t1).translation = " << pt1.translation().transpose() << std::endl; std::cerr << "t1.linear = " << std::endl << t1.linear() << std::endl; std::cerr << "t1.translation = " << t1.translation().transpose() << std::endl; @@ -69,15 +69,15 @@ main(int argc, char** argv) } rl::math::Transform t2; - t2 = rl::math::Quaternion::Random(); + t2.linear() = rl::math::Quaternion::Random().toRotationMatrix(); t2.translation().setRandom(); rl::math::PlueckerTransform pt2 = t2; - if (!pt2.rotation().isApprox(t2.linear()) || !pt2.translation().isApprox(t2.translation())) + if (!pt2.linear().isApprox(t2.linear()) || !pt2.translation().isApprox(t2.translation())) { std::cerr << "(pt2 = t2) != t2" << std::endl; - std::cerr << "(pt2 = t2).rotation = " << std::endl << pt2.rotation() << std::endl; + std::cerr << "(pt2 = t2).rotation = " << std::endl << pt2.linear() << std::endl; std::cerr << "(pt2 = t2).translation = " << pt2.translation().transpose() << std::endl; std::cerr << "t2.linear = " << std::endl << t2.linear() << std::endl; std::cerr << "t2.translation = " << t2.translation().transpose() << std::endl; @@ -87,10 +87,10 @@ main(int argc, char** argv) rl::math::Transform t3 = t1 * t2; rl::math::PlueckerTransform pt3 = pt1 * pt2; - if (!pt3.rotation().isApprox(t3.linear()) || !pt3.translation().isApprox(t3.translation())) + if (!pt3.linear().isApprox(t3.linear()) || !pt3.translation().isApprox(t3.translation())) { std::cerr << "pt1 * pt2 != t1 * t2" << std::endl; - std::cerr << "(pt1 * pt2).rotation = " << std::endl << pt3.rotation() << std::endl; + std::cerr << "(pt1 * pt2).rotation = " << std::endl << pt3.linear() << std::endl; std::cerr << "(pt1 * pt2).translation = " << pt3.translation().transpose() << std::endl; std::cerr << "(t1 * t2).linear = " << std::endl << t3.linear() << std::endl; std::cerr << "(t1 * t2).translation = " << t3.translation().transpose() << std::endl; @@ -100,20 +100,20 @@ main(int argc, char** argv) rl::math::Transform t4 = t1.inverse() * t3; rl::math::PlueckerTransform pt4 = pt1.inverse() * pt3; - if (!pt4.rotation().isApprox(pt2.rotation()) || !pt4.translation().isApprox(pt2.translation())) + if (!pt4.linear().isApprox(pt2.linear()) || !pt4.translation().isApprox(pt2.translation())) { std::cerr << "inv(pt1) * pt1 * pt2 != pt2" << std::endl; - std::cerr << "(inv(pt1) * pt1 * pt2).rotation = " << std::endl << pt4.rotation() << std::endl; + std::cerr << "(inv(pt1) * pt1 * pt2).rotation = " << std::endl << pt4.linear() << std::endl; std::cerr << "(inv(pt1) * pt1 * pt2).translation = " << pt4.translation().transpose() << std::endl; - std::cerr << "pt2.rotation = " << std::endl << pt2.rotation().matrix() << std::endl; + std::cerr << "pt2.rotation = " << std::endl << pt2.linear().matrix() << std::endl; std::cerr << "pt2.translation = " << pt2.translation().transpose() << std::endl; exit(EXIT_FAILURE); } - if (!pt4.rotation().isApprox(t4.linear()) || !pt4.translation().isApprox(t4.translation())) + if (!pt4.linear().isApprox(t4.linear()) || !pt4.translation().isApprox(t4.translation())) { std::cerr << "inv(pt1) * pt3 != inv(t1) * t3" << std::endl; - std::cerr << "(inv(pt1) * pt3).rotation = " << std::endl << pt4.rotation() << std::endl; + std::cerr << "(inv(pt1) * pt3).rotation = " << std::endl << pt4.linear() << std::endl; std::cerr << "(inv(pt1) * pt3).translation = " << pt4.translation().transpose() << std::endl; std::cerr << "(inv(t1) * t3).linear = " << std::endl << t4.linear() << std::endl; std::cerr << "(inv(t1) * t3).translation = " << t4.translation().transpose() << std::endl; @@ -124,12 +124,12 @@ main(int argc, char** argv) pt5.setIdentity(); rl::math::PlueckerTransform pt6 = pt1.inverse() * pt1; - if (!pt5.rotation().isApprox(pt6.rotation()) || !pt5.translation().isMuchSmallerThan(pt6.translation())) + if (!pt5.linear().isApprox(pt6.linear()) || !pt5.translation().isMuchSmallerThan(pt6.translation())) { std::cerr << "I != inv(pt1) * pt1" << std::endl; - std::cerr << "I.rotation = " << std::endl << pt5.rotation().matrix() << std::endl; + std::cerr << "I.rotation = " << std::endl << pt5.linear().matrix() << std::endl; std::cerr << "I.translation = " << pt5.translation().transpose() << std::endl; - std::cerr << "(inv(pt1) * pt1).rotation = " << std::endl << pt6.rotation() << std::endl; + std::cerr << "(inv(pt1) * pt1).rotation = " << std::endl << pt6.linear() << std::endl; std::cerr << "(inv(pt1) * pt1).translation = " << pt6.translation().transpose() << std::endl; exit(EXIT_FAILURE); } diff --git a/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp b/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp index ba7f25b3..9ab3d451 100644 --- a/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp +++ b/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp @@ -76,7 +76,7 @@ main(int argc, char** argv) } rl::math::PlueckerTransform pt1; - pt1.rotation() = rl::math::Matrix33(rl::math::Quaternion::Random()); + pt1.linear() = rl::math::Quaternion::Random().toRotationMatrix(); pt1.translation().setRandom(); rl::math::RigidBodyInertia rbi5 = pt1 * rbi1; From ec74fc03684bf784ea3093109d7ab2344ef6f620 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 25 Apr 2018 12:10:01 +0200 Subject: [PATCH 089/546] Minor fix --- src/rl/sg/ode/Body.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rl/sg/ode/Body.cpp b/src/rl/sg/ode/Body.cpp index 59dcabda..5de735c3 100644 --- a/src/rl/sg/ode/Body.cpp +++ b/src/rl/sg/ode/Body.cpp @@ -87,9 +87,9 @@ namespace rl { ::dBodySetPosition( this->body, - static_cast(frame(0, 3)), - static_cast(frame(1, 3)), - static_cast(frame(2, 3)) + static_cast< ::dReal>(frame(0, 3)), + static_cast< ::dReal>(frame(1, 3)), + static_cast< ::dReal>(frame(2, 3)) ); ::dMatrix3 rotation; From 0eed4718e172b488df09cd5f5e1f161bce286e7d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 25 Apr 2018 12:10:39 +0200 Subject: [PATCH 090/546] Update rl::sg::solid::Shape::update to use Eigen::ColMajor --- src/rl/sg/solid/Shape.cpp | 29 +++-------------------------- src/rl/sg/solid/Shape.h | 2 +- 2 files changed, 4 insertions(+), 27 deletions(-) diff --git a/src/rl/sg/solid/Shape.cpp b/src/rl/sg/solid/Shape.cpp index 6b05a53a..df0e4f9d 100644 --- a/src/rl/sg/solid/Shape.cpp +++ b/src/rl/sg/solid/Shape.cpp @@ -201,20 +201,9 @@ namespace rl void Shape::getTransform(::rl::math::Transform& transform) { - double m[16]; - - DT_GetMatrixd(this->object, m); - - for (::std::size_t i = 0; i < 4; ++i) - { - for (::std::size_t j = 0; j < 4; ++j) - { - this->frame(i, j) = static_cast< ::rl::math::Real>(m[i + j * 4]); - } - } - + DT_GetMatrixd(this->object, this->frame.data()); + this->transform = static_cast(this->getBody())->frame.inverse() * this->frame; - transform = this->transform; } @@ -237,20 +226,8 @@ namespace rl { this->frame = static_cast(this->getBody())->frame * this->transform; - double m[16]; - - for (::std::size_t i = 0; i < 4; ++i) - { - for (::std::size_t j = 0; j < 4; ++j) - { - m[i + j * 4] = static_cast(this->frame(i, j)); - } - } - - DT_SetMatrixd(this->object, m); - + DT_SetMatrixd(this->object, this->frame.data()); DT_GetBBox(this->object, this->min, this->max); - BP_SetBBox(this->proxy, this->min, this->max); } } diff --git a/src/rl/sg/solid/Shape.h b/src/rl/sg/solid/Shape.h index 1bc34cc5..a22a9d74 100644 --- a/src/rl/sg/solid/Shape.h +++ b/src/rl/sg/solid/Shape.h @@ -77,7 +77,7 @@ namespace rl DT_ShapeHandle create(const SoMFVec3f& point, const SoMFInt32& coordIndex); - ::rl::math::Transform frame; + ::Eigen::Transform< ::rl::math::Real, 3, ::Eigen::Affine, ::Eigen::ColMajor> frame; DT_Vector3 max; From 5db05dc601ace70df3e6cf5d2643cb4901b7c79c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 25 Apr 2018 17:30:41 +0200 Subject: [PATCH 091/546] Optimize rl::mdl interfaces based on profiler --- src/rl/mdl/Joint.cpp | 16 ++++------------ src/rl/mdl/Joint.h | 4 ++-- src/rl/mdl/Metric.cpp | 20 ++++---------------- src/rl/mdl/Model.cpp | 10 +++++++--- src/rl/mdl/Spherical.cpp | 12 ++++++------ src/rl/mdl/Spherical.h | 4 ++-- 6 files changed, 25 insertions(+), 41 deletions(-) diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index 1b3c919d..522d3557 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -166,32 +166,24 @@ namespace rl this->out->v = this->x * this->in->v + this->v; } - ::rl::math::Vector - Joint::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma) const + void + Joint::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const { - ::rl::math::Vector q(this->getDofPosition()); - for (::std::size_t i = 0; i < this->getDofPosition(); ++i) { q(i) = mean(i) + rand(i) * sigma(i); } this->clip(q); - - return q; } - ::rl::math::Vector - Joint::generatePositionUniform(const ::rl::math::ConstVectorRef& rand) const + void + Joint::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const { - ::rl::math::Vector q(this->getDofPosition()); - for (::std::size_t i = 0; i < this->getDofPosition(); ++i) { q(i) = this->min(i) + rand(i) * (this->max(i) - this->min(i)); } - - return q; } const ::rl::math::Vector& diff --git a/src/rl/mdl/Joint.h b/src/rl/mdl/Joint.h index 9ca65e5b..079243a0 100644 --- a/src/rl/mdl/Joint.h +++ b/src/rl/mdl/Joint.h @@ -57,9 +57,9 @@ namespace rl void forwardVelocity(); - virtual ::rl::math::Vector generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma) const; + virtual void generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const; - virtual ::rl::math::Vector generatePositionUniform(const ::rl::math::ConstVectorRef& rand) const; + virtual void generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const; const ::rl::math::Vector& getAcceleration() const; diff --git a/src/rl/mdl/Metric.cpp b/src/rl/mdl/Metric.cpp index c9716379..c3b6933c 100644 --- a/src/rl/mdl/Metric.cpp +++ b/src/rl/mdl/Metric.cpp @@ -47,9 +47,7 @@ namespace rl for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { - ::rl::math::VectorBlock qi = q.segment(j, this->joints[i]->getDofPosition()); - this->joints[i]->clip(qi); - q.segment(j, this->joints[i]->getDofPosition()) = qi; + this->joints[i]->clip(q.segment(j, this->joints[i]->getDofPosition())); } } @@ -89,16 +87,12 @@ namespace rl for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { - ::rl::math::VectorBlock qi = q.segment(j, this->joints[i]->getDofPosition()); - this->joints[i]->interpolate( q1.segment(j, this->joints[i]->getDofPosition()), q2.segment(j, this->joints[i]->getDofPosition()), alpha, - qi + q.segment(j, this->joints[i]->getDofPosition()) ); - - q.segment(j, this->joints[i]->getDofPosition()) = qi; } } @@ -131,9 +125,7 @@ namespace rl for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { - ::rl::math::VectorBlock qi = q.segment(j, this->joints[i]->getDofPosition()); - this->joints[i]->normalize(qi); - q.segment(j, this->joints[i]->getDofPosition()) = qi; + this->joints[i]->normalize(q.segment(j, this->joints[i]->getDofPosition())); } } @@ -146,15 +138,11 @@ namespace rl for (::std::size_t i = 0, j = 0, k = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), k += this->joints[i]->getDof(), ++i) { - ::rl::math::VectorBlock q2i = q2.segment(j, this->joints[i]->getDofPosition()); - this->joints[i]->step( q1.segment(j, this->joints[i]->getDofPosition()), qdot.segment(k, this->joints[i]->getDof()), - q2i + q2.segment(j, this->joints[i]->getDofPosition()) ); - - q2.segment(j, this->joints[i]->getDofPosition()) = q2i; } } diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index db70ca03..c8006509 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -119,10 +119,11 @@ namespace rl for (::std::size_t i = 0, j = 0, k = 0; i < this->joints.size(); k += this->joints[i]->getDof(), j += this->joints[i]->getDofPosition(), ++i) { - q.segment(j, this->joints[i]->getDofPosition()) = this->joints[i]->generatePositionGaussian( + this->joints[i]->generatePositionGaussian( rand.segment(k, this->joints[i]->getDof()), mean.segment(j, this->joints[i]->getDofPosition()), - sigma.segment(k, this->joints[i]->getDof()) + sigma.segment(k, this->joints[i]->getDof()), + q.segment(j, this->joints[i]->getDofPosition()) ); } @@ -136,7 +137,10 @@ namespace rl for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { - q.segment(j, this->joints[i]->getDofPosition()) = this->joints[i]->generatePositionUniform(rand.segment(j, this->joints[i]->getDofPosition())); + this->joints[i]->generatePositionUniform( + rand.segment(j, this->joints[i]->getDofPosition()), + q.segment(j, this->joints[i]->getDofPosition()) + ); } return q; diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 4bdceef3..51ddf042 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -74,16 +74,16 @@ namespace rl return quaternion1.angularDistance(quaternion2); } - ::rl::math::Vector - Spherical::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma) const + void + Spherical::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const { - return ::rl::math::Quaternion::Random(rand, ::Eigen::Map< const ::rl::math::Quaternion>(mean.data()), sigma).coeffs(); + q = ::rl::math::Quaternion::Random(rand, ::Eigen::Map< const ::rl::math::Quaternion>(mean.data()), sigma).coeffs(); } - ::rl::math::Vector - Spherical::generatePositionUniform(const ::rl::math::ConstVectorRef& rand) const + void + Spherical::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const { - return ::rl::math::Quaternion::Random(rand).coeffs(); + q = ::rl::math::Quaternion::Random(rand).coeffs(); } void diff --git a/src/rl/mdl/Spherical.h b/src/rl/mdl/Spherical.h index 440164ed..d085f2d9 100644 --- a/src/rl/mdl/Spherical.h +++ b/src/rl/mdl/Spherical.h @@ -44,9 +44,9 @@ namespace rl ::rl::math::Real distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; - ::rl::math::Vector generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma) const; + void generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const; - ::rl::math::Vector generatePositionUniform(const ::rl::math::ConstVectorRef& rand) const; + void generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const; void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; From aea57c87b57a35f249ba54a1627e92fdc93d4c10 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 25 Apr 2018 18:26:36 +0200 Subject: [PATCH 092/546] Add rl::mdl::Spherical::isValid --- src/rl/mdl/Spherical.cpp | 6 ++++++ src/rl/mdl/Spherical.h | 2 ++ 2 files changed, 8 insertions(+) diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 51ddf042..84bc1f4a 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -94,6 +94,12 @@ namespace rl q = quaternion1.slerp(alpha, quaternion2).coeffs(); } + bool + Spherical::isValid(const ::rl::math::ConstVectorRef& q) const + { + return ::Eigen::internal::isApprox(q.norm(), static_cast< ::rl::math::Real>(1), 1.0e-3f); + } + void Spherical::normalize(::rl::math::VectorRef q) const { diff --git a/src/rl/mdl/Spherical.h b/src/rl/mdl/Spherical.h index d085f2d9..189ed35c 100644 --- a/src/rl/mdl/Spherical.h +++ b/src/rl/mdl/Spherical.h @@ -50,6 +50,8 @@ namespace rl void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; + bool isValid(const ::rl::math::ConstVectorRef& q) const; + void normalize(::rl::math::VectorRef q) const; void setPosition(const ::rl::math::ConstVectorRef& q); From 9f08f4792362111b901b0706a3dccde3e1aa64a1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 25 Apr 2018 18:29:22 +0200 Subject: [PATCH 093/546] Add quaternion min/max values --- src/rl/mdl/Spherical.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 84bc1f4a..37fb49ca 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -35,6 +35,8 @@ namespace rl Spherical::Spherical() : Joint(4, 3) { + this->max.setConstant(1); // TODO + this->min.setConstant(-1); // TODO this->qUnits(0) = ::rl::math::UNIT_NONE; // TODO this->qUnits(1) = ::rl::math::UNIT_NONE; // TODO this->qUnits(2) = ::rl::math::UNIT_NONE; // TODO From 9fe14c4f8eba312a7a7da6d3a8f299ecfbfe696d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 27 Apr 2018 21:26:03 +0200 Subject: [PATCH 094/546] Add 6-DOF joint --- src/rl/mdl/CMakeLists.txt | 2 + src/rl/mdl/Joint.cpp | 8 +- src/rl/mdl/SixDof.cpp | 150 ++++++++++++++++++++++++++++++++++++++ src/rl/mdl/SixDof.h | 71 ++++++++++++++++++ src/rl/mdl/XmlFactory.cpp | 24 +++++- 5 files changed, 250 insertions(+), 5 deletions(-) create mode 100644 src/rl/mdl/SixDof.cpp create mode 100644 src/rl/mdl/SixDof.h diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 6b9a21e6..fdaf0fef 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -21,6 +21,7 @@ set( Model.h Prismatic.h Revolute.h + SixDof.h Spherical.h Transform.h UrdfFactory.h @@ -48,6 +49,7 @@ set( Model.cpp Prismatic.cpp Revolute.cpp + SixDof.cpp Spherical.cpp Transform.cpp UrdfFactory.cpp diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index 522d3557..7ea3f7c6 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -79,7 +79,7 @@ namespace rl void Joint::clip(::rl::math::VectorRef q) const { - for (::std::size_t i = 0; i < this->getDofPosition(); ++i) + for (::std::size_t i = 0; i < q.size(); ++i) { if (this->wraparound(i)) { @@ -169,7 +169,7 @@ namespace rl void Joint::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const { - for (::std::size_t i = 0; i < this->getDofPosition(); ++i) + for (::std::size_t i = 0; i < q.size(); ++i) { q(i) = mean(i) + rand(i) * sigma(i); } @@ -180,7 +180,7 @@ namespace rl void Joint::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const { - for (::std::size_t i = 0; i < this->getDofPosition(); ++i) + for (::std::size_t i = 0; i < q.size(); ++i) { q(i) = this->min(i) + rand(i) * (this->max(i) - this->min(i)); } @@ -289,7 +289,7 @@ namespace rl bool Joint::isValid(const ::rl::math::ConstVectorRef& q) const { - for (::std::size_t i = 0; i < this->getDofPosition(); ++i) + for (::std::size_t i = 0; i < q.size(); ++i) { if (q(i) < this->min(i) || q(i) > this->max(i)) { diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp new file mode 100644 index 00000000..834e1e3b --- /dev/null +++ b/src/rl/mdl/SixDof.cpp @@ -0,0 +1,150 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "SixDof.h" + +namespace rl +{ + namespace mdl + { + SixDof::SixDof() : + Joint(7, 6) + { + this->max.tail(4).setConstant(1); // TODO + this->min.tail(4).setConstant(-1); // TODO + this->qUnits(0) = ::rl::math::UNIT_METER; + this->qUnits(1) = ::rl::math::UNIT_METER; + this->qUnits(2) = ::rl::math::UNIT_METER; + this->qUnits(3) = ::rl::math::UNIT_NONE; // TODO + this->qUnits(4) = ::rl::math::UNIT_NONE; // TODO + this->qUnits(5) = ::rl::math::UNIT_NONE; // TODO + this->qUnits(6) = ::rl::math::UNIT_NONE; // TODO + this->qdUnits(0) = ::rl::math::UNIT_METER_PER_SECOND; + this->qdUnits(1) = ::rl::math::UNIT_METER_PER_SECOND; + this->qdUnits(2) = ::rl::math::UNIT_METER_PER_SECOND; + this->qdUnits(3) = ::rl::math::UNIT_RADIAN_PER_SECOND; + this->qdUnits(4) = ::rl::math::UNIT_RADIAN_PER_SECOND; + this->qdUnits(5) = ::rl::math::UNIT_RADIAN_PER_SECOND; + this->qddUnits(0) = ::rl::math::UNIT_METER_PER_SECOND_SQUARED; + this->qddUnits(1) = ::rl::math::UNIT_METER_PER_SECOND_SQUARED; + this->qddUnits(2) = ::rl::math::UNIT_METER_PER_SECOND_SQUARED; + this->qddUnits(3) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; + this->qddUnits(4) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; + this->qddUnits(5) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; + this->S.setIdentity(); + this->speedUnits(0) = ::rl::math::UNIT_METER_PER_SECOND; + this->speedUnits(1) = ::rl::math::UNIT_METER_PER_SECOND; + this->speedUnits(2) = ::rl::math::UNIT_METER_PER_SECOND; + this->speedUnits(3) = ::rl::math::UNIT_RADIAN_PER_SECOND; + this->speedUnits(4) = ::rl::math::UNIT_RADIAN_PER_SECOND; + this->speedUnits(5) = ::rl::math::UNIT_RADIAN_PER_SECOND; + this->tauUnits(0) = ::rl::math::UNIT_NEWTON; + this->tauUnits(1) = ::rl::math::UNIT_NEWTON; + this->tauUnits(2) = ::rl::math::UNIT_NEWTON; + this->tauUnits(3) = ::rl::math::UNIT_NEWTON_METER; + this->tauUnits(4) = ::rl::math::UNIT_NEWTON_METER; + this->tauUnits(5) = ::rl::math::UNIT_NEWTON_METER; + } + + SixDof::~SixDof() + { + } + + void + SixDof::clip(::rl::math::VectorRef q) const + { + Joint::clip(q.head(3)); + ::Eigen::Map< ::rl::math::Quaternion>(q.tail(4).data()).normalize(); + } + + ::rl::math::Real + SixDof::distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const + { + ::Eigen::Map quaternion1(q1.tail(4).data()); + ::Eigen::Map quaternion2(q2.tail(4).data()); + return ::std::sqrt(::std::pow(Joint::distance(q1.head(3), q2.head(3)), 2) + ::std::pow(quaternion1.angularDistance(quaternion2), 2)); + } + + void + SixDof::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const + { + Joint::generatePositionGaussian(rand.head(3), mean.head(3), sigma.head(3), q.head(3)); + q.tail(4) = ::rl::math::Quaternion::Random(rand.tail(4), ::Eigen::Map< const ::rl::math::Quaternion>(mean.tail(4).data()), sigma.tail(4)).coeffs(); + } + + void + SixDof::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const + { + Joint::generatePositionUniform(rand.head(3), q.head(3)); + q.tail(4) = ::rl::math::Quaternion::Random(rand.tail(4)).coeffs(); + } + + void + SixDof::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const + { + Joint::interpolate(q1.head(3), q2.head(3), alpha, q.head(3)); + ::Eigen::Map quaternion1(q1.tail(4).data()); + ::Eigen::Map quaternion2(q2.tail(4).data()); + q.tail(4) = quaternion1.slerp(alpha, quaternion2).coeffs(); + } + + bool + SixDof::isValid(const ::rl::math::ConstVectorRef& q) const + { + return Joint::isValid(q.head(3)) && ::Eigen::internal::isApprox(q.tail(4).norm(), static_cast< ::rl::math::Real>(1), 1.0e-3f); + } + + void + SixDof::normalize(::rl::math::VectorRef q) const + { + ::Eigen::Map< ::rl::math::Quaternion>(q.tail(4).data()).normalize(); + } + + void + SixDof::setPosition(const ::rl::math::ConstVectorRef& q) + { + this->q = q; + this->x.translation() = this->q.head(3) + this->offset.head(3); + this->x.linear() = ::Eigen::Map(this->q.tail(4).data()).toRotationMatrix(); + } + + void + SixDof::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const + { + Joint::step(q1.head(3), qdot.head(3), q2.head(3)); + ::Eigen::Map quaternion1(q1.tail(4).data()); + q2.tail(4) = (quaternion1 * quaternion1.firstDerivative(qdot)).coeffs(); + } + + ::rl::math::Real + SixDof::transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const + { + return ::std::pow(this->distance(q1, q2), 2); + } + } +} diff --git a/src/rl/mdl/SixDof.h b/src/rl/mdl/SixDof.h new file mode 100644 index 00000000..5b19bbdd --- /dev/null +++ b/src/rl/mdl/SixDof.h @@ -0,0 +1,71 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MDL_SIXDOF_H +#define RL_MDL_SIXDOF_H + +#include "Joint.h" + +namespace rl +{ + namespace mdl + { + class SixDof : public Joint + { + public: + SixDof(); + + virtual ~SixDof(); + + void clip(::rl::math::VectorRef q) const; + + ::rl::math::Real distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; + + void generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const; + + void generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const; + + void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; + + bool isValid(const ::rl::math::ConstVectorRef& q) const; + + void normalize(::rl::math::VectorRef q) const; + + void setPosition(const ::rl::math::ConstVectorRef& q); + + void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const; + + ::rl::math::Real transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; + + protected: + + private: + + }; + } +} + +#endif // RL_MDL_SIXDOF_H diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index 06d4fce7..d4d7e493 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -48,6 +48,7 @@ #include "Model.h" #include "Prismatic.h" #include "Revolute.h" +#include "SixDof.h" #include "Spherical.h" #include "World.h" #include "XmlFactory.h" @@ -235,7 +236,7 @@ namespace rl // transforms - ::rl::xml::NodeSet transforms = path.eval("cylindrical|fixed|helical|prismatic|revolute|spherical").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet transforms = path.eval("cylindrical|fixed|helical|prismatic|revolute|sixDof|spherical").getValue< ::rl::xml::NodeSet>(); for (int j = 0; j < transforms.size(); ++j) { @@ -379,6 +380,27 @@ namespace rl transform = r; } + else if ("sixDof" == transforms[j].getName()) + { + SixDof* s = new SixDof(); + + model->add(s, a, b); + + s->max(0) = path.eval("number(max[1])").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); + s->max(1) = path.eval("number(max[2])").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); + s->max(2) = path.eval("number(max[3])").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); + s->min(0) = path.eval("number(min[1])").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); + s->min(1) = path.eval("number(min[2])").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); + s->min(2) = path.eval("number(min[3])").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); + s->offset(0) = path.eval("number(offset[1])").getValue< ::rl::math::Real>(0); + s->offset(1) = path.eval("number(offset[2])").getValue< ::rl::math::Real>(0); + s->offset(2) = path.eval("number(offset[3])").getValue< ::rl::math::Real>(0); + s->speed(0) = path.eval("number(speed[1])").getValue< ::rl::math::Real>(0); + s->speed(1) = path.eval("number(speed[2])").getValue< ::rl::math::Real>(0); + s->speed(2) = path.eval("number(speed[3])").getValue< ::rl::math::Real>(0); + + transform = s; + } else if ("spherical" == transforms[j].getName()) { Spherical* s = new Spherical(); From 27fe3c4d39c825795f1cab35cb7c26e9486f2de8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 27 Apr 2018 23:09:40 +0200 Subject: [PATCH 095/546] Use fixed-size block expressions in SixDof and fix Model::generatePositionUniform --- src/rl/mdl/Model.cpp | 4 ++-- src/rl/mdl/SixDof.cpp | 44 +++++++++++++++++++++---------------------- 2 files changed, 24 insertions(+), 24 deletions(-) diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index c8006509..58dce433 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -135,10 +135,10 @@ namespace rl { ::rl::math::Vector q(this->getDofPosition()); - for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) + for (::std::size_t i = 0, j = 0, k = 0; i < this->joints.size(); k += this->joints[i]->getDof(), j += this->joints[i]->getDofPosition(), ++i) { this->joints[i]->generatePositionUniform( - rand.segment(j, this->joints[i]->getDofPosition()), + rand.segment(k, this->joints[i]->getDof()), q.segment(j, this->joints[i]->getDofPosition()) ); } diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index 834e1e3b..cb52fc28 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -35,8 +35,8 @@ namespace rl SixDof::SixDof() : Joint(7, 6) { - this->max.tail(4).setConstant(1); // TODO - this->min.tail(4).setConstant(-1); // TODO + this->max.tail<4>().setConstant(1); // TODO + this->min.tail<4>().setConstant(-1); // TODO this->qUnits(0) = ::rl::math::UNIT_METER; this->qUnits(1) = ::rl::math::UNIT_METER; this->qUnits(2) = ::rl::math::UNIT_METER; @@ -78,67 +78,67 @@ namespace rl void SixDof::clip(::rl::math::VectorRef q) const { - Joint::clip(q.head(3)); - ::Eigen::Map< ::rl::math::Quaternion>(q.tail(4).data()).normalize(); + Joint::clip(q.head<3>()); + ::Eigen::Map< ::rl::math::Quaternion>(q.tail<4>().data()).normalize(); } ::rl::math::Real SixDof::distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const { - ::Eigen::Map quaternion1(q1.tail(4).data()); - ::Eigen::Map quaternion2(q2.tail(4).data()); - return ::std::sqrt(::std::pow(Joint::distance(q1.head(3), q2.head(3)), 2) + ::std::pow(quaternion1.angularDistance(quaternion2), 2)); + ::Eigen::Map quaternion1(q1.tail<4>().data()); + ::Eigen::Map quaternion2(q2.tail<4>().data()); + return ::std::sqrt(::std::pow(Joint::distance(q1.head<3>(), q2.head<3>()), 2) + ::std::pow(quaternion1.angularDistance(quaternion2), 2)); } void SixDof::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const { - Joint::generatePositionGaussian(rand.head(3), mean.head(3), sigma.head(3), q.head(3)); - q.tail(4) = ::rl::math::Quaternion::Random(rand.tail(4), ::Eigen::Map< const ::rl::math::Quaternion>(mean.tail(4).data()), sigma.tail(4)).coeffs(); + Joint::generatePositionGaussian(rand.head<3>(), mean.head<3>(), sigma.head<3>(), q.head<3>()); + q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>(), ::Eigen::Map< const ::rl::math::Quaternion>(mean.tail<4>().data()), sigma.tail<3>()).coeffs(); } void SixDof::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const { - Joint::generatePositionUniform(rand.head(3), q.head(3)); - q.tail(4) = ::rl::math::Quaternion::Random(rand.tail(4)).coeffs(); + Joint::generatePositionUniform(rand.head<3>(), q.head<3>()); + q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>()).coeffs(); } void SixDof::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { - Joint::interpolate(q1.head(3), q2.head(3), alpha, q.head(3)); - ::Eigen::Map quaternion1(q1.tail(4).data()); - ::Eigen::Map quaternion2(q2.tail(4).data()); - q.tail(4) = quaternion1.slerp(alpha, quaternion2).coeffs(); + Joint::interpolate(q1.head<3>(), q2.head<3>(), alpha, q.head<3>()); + ::Eigen::Map quaternion1(q1.tail<4>().data()); + ::Eigen::Map quaternion2(q2.tail<4>().data()); + q.tail<4>() = quaternion1.slerp(alpha, quaternion2).coeffs(); } bool SixDof::isValid(const ::rl::math::ConstVectorRef& q) const { - return Joint::isValid(q.head(3)) && ::Eigen::internal::isApprox(q.tail(4).norm(), static_cast< ::rl::math::Real>(1), 1.0e-3f); + return Joint::isValid(q.head<3>()) && ::Eigen::internal::isApprox(q.tail<4>().norm(), static_cast< ::rl::math::Real>(1), 1.0e-3f); } void SixDof::normalize(::rl::math::VectorRef q) const { - ::Eigen::Map< ::rl::math::Quaternion>(q.tail(4).data()).normalize(); + ::Eigen::Map< ::rl::math::Quaternion>(q.tail<4>().data()).normalize(); } void SixDof::setPosition(const ::rl::math::ConstVectorRef& q) { this->q = q; - this->x.translation() = this->q.head(3) + this->offset.head(3); - this->x.linear() = ::Eigen::Map(this->q.tail(4).data()).toRotationMatrix(); + this->x.translation() = this->q.head<3>() + this->offset.head<3>(); + this->x.linear() = ::Eigen::Map(this->q.tail<4>().data()).toRotationMatrix(); } void SixDof::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const { - Joint::step(q1.head(3), qdot.head(3), q2.head(3)); - ::Eigen::Map quaternion1(q1.tail(4).data()); - q2.tail(4) = (quaternion1 * quaternion1.firstDerivative(qdot)).coeffs(); + Joint::step(q1.head<3>(), qdot.head<3>(), q2.head<3>()); + ::Eigen::Map quaternion1(q1.tail<4>().data()); + q2.tail<4>() = (quaternion1 * quaternion1.firstDerivative(qdot.tail<3>())).coeffs(); } ::rl::math::Real From 6a3ba7b933fed68933229647618a32cfd90d63ca Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 28 Apr 2018 21:51:33 +0200 Subject: [PATCH 096/546] Avoid using Joint functions in SixDof --- src/rl/mdl/SixDof.cpp | 69 ++++++++++++++++++++++++++++++++++++------- 1 file changed, 59 insertions(+), 10 deletions(-) diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index cb52fc28..e9c506c9 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -78,36 +78,62 @@ namespace rl void SixDof::clip(::rl::math::VectorRef q) const { - Joint::clip(q.head<3>()); + for (::std::size_t i = 0; i < 3; ++i) + { + if (q(i) > this->max(i)) + { + q(i) = this->max(i); + } + else if (q(i) < this->min(i)) + { + q(i) = this->min(i); + } + } + ::Eigen::Map< ::rl::math::Quaternion>(q.tail<4>().data()).normalize(); } ::rl::math::Real SixDof::distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const { - ::Eigen::Map quaternion1(q1.tail<4>().data()); - ::Eigen::Map quaternion2(q2.tail<4>().data()); - return ::std::sqrt(::std::pow(Joint::distance(q1.head<3>(), q2.head<3>()), 2) + ::std::pow(quaternion1.angularDistance(quaternion2), 2)); + return ::std::sqrt(this->transformedDistance(q1, q2)); } void SixDof::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const { - Joint::generatePositionGaussian(rand.head<3>(), mean.head<3>(), sigma.head<3>(), q.head<3>()); + for (::std::size_t i = 0; i < 3; ++i) + { + q(i) = mean(i) + rand(i) * sigma(i); + + if (q(i) > this->max(i)) + { + q(i) = this->max(i); + } + else if (q(i) < this->min(i)) + { + q(i) = this->min(i); + } + } + q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>(), ::Eigen::Map< const ::rl::math::Quaternion>(mean.tail<4>().data()), sigma.tail<3>()).coeffs(); } void SixDof::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const { - Joint::generatePositionUniform(rand.head<3>(), q.head<3>()); + for (::std::size_t i = 0; i < 3; ++i) + { + q(i) = this->min(i) + rand(i) * (this->max(i) - this->min(i)); + } + q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>()).coeffs(); } void SixDof::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { - Joint::interpolate(q1.head<3>(), q2.head<3>(), alpha, q.head<3>()); + q.head<3>() = (1.0f - alpha) * q1.head<3>() + alpha * q2.head<3>(); ::Eigen::Map quaternion1(q1.tail<4>().data()); ::Eigen::Map quaternion2(q2.tail<4>().data()); q.tail<4>() = quaternion1.slerp(alpha, quaternion2).coeffs(); @@ -116,7 +142,15 @@ namespace rl bool SixDof::isValid(const ::rl::math::ConstVectorRef& q) const { - return Joint::isValid(q.head<3>()) && ::Eigen::internal::isApprox(q.tail<4>().norm(), static_cast< ::rl::math::Real>(1), 1.0e-3f); + for (::std::size_t i = 0; i < 3; ++i) + { + if (q(i) < this->min(i) || q(i) > this->max(i)) + { + return false; + } + } + + return ::Eigen::internal::isApprox(q.tail<4>().norm(), static_cast< ::rl::math::Real>(1), 1.0e-3f); } void @@ -136,7 +170,20 @@ namespace rl void SixDof::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const { - Joint::step(q1.head<3>(), qdot.head<3>(), q2.head<3>()); + q2.head<3>() = q1.head<3>() + qdot.head<3>(); + + for (::std::size_t i = 0; i < 3; ++i) + { + if (q2(i) > this->max(i)) + { + q2(i) = this->max(i); + } + else if (q2(i) < this->min(i)) + { + q2(i) = this->min(i); + } + } + ::Eigen::Map quaternion1(q1.tail<4>().data()); q2.tail<4>() = (quaternion1 * quaternion1.firstDerivative(qdot.tail<3>())).coeffs(); } @@ -144,7 +191,9 @@ namespace rl ::rl::math::Real SixDof::transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const { - return ::std::pow(this->distance(q1, q2), 2); + ::Eigen::Map quaternion1(q1.tail<4>().data()); + ::Eigen::Map quaternion2(q2.tail<4>().data()); + return (q2.head<3>() - q1.head<3>()).squaredNorm() + ::std::pow(quaternion1.angularDistance(quaternion2), 2); } } } From 52e81a8eaa0af7ca2d95dfce9bf2366ea6eba262 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 16:51:29 +0200 Subject: [PATCH 097/546] Rename clip and add clamp in preparation of std::clamp --- src/rl/kin/Kinematics.cpp | 14 +++++--------- src/rl/kin/Kinematics.h | 4 ++-- src/rl/math/Real.h | 14 ++++++++++++++ src/rl/mdl/Joint.cpp | 14 +++++--------- src/rl/mdl/Joint.h | 2 +- src/rl/mdl/Metric.cpp | 4 ++-- src/rl/mdl/Metric.h | 2 +- src/rl/mdl/SixDof.cpp | 30 ++++-------------------------- src/rl/mdl/SixDof.h | 2 +- src/rl/mdl/Spherical.cpp | 2 +- src/rl/mdl/Spherical.h | 2 +- src/rl/plan/BridgeSampler.cpp | 2 +- src/rl/plan/Model.cpp | 6 +++--- src/rl/plan/Model.h | 2 +- 14 files changed, 42 insertions(+), 58 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 144a8bbf..4f583f47 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -89,7 +89,7 @@ namespace rl } void - Kinematics::clip(::rl::math::Vector& q) const + Kinematics::clamp(::rl::math::Vector& q) const { for (::std::size_t i = 0; i < this->getDof(); ++i) { @@ -107,13 +107,9 @@ namespace rl q(i) += range; } } - else if (q(i) > this->joints[i]->max) - { - q(i) = this->joints[i]->max; - } - else if (q(i) < this->joints[i]->min) + else { - q(i) = this->joints[i]->min; + q(i) = ::rl::math::clamp(q(i), this->joints[i]->min, this->joints[i]->max); } } } @@ -511,7 +507,7 @@ namespace rl q(i) = mean(i) + rand(i) * sigma(i); } - this->clip(q); + this->clamp(q); return q; } @@ -890,7 +886,7 @@ namespace rl q2(i) = q1(i) + qdot(i); } - this->clip(q2); + this->clamp(q2); } ::rl::math::Transform& diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 4290df41..91dddf8e 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -63,11 +63,11 @@ namespace rl bool areColliding(const ::std::size_t& i, const ::std::size_t& j) const; /** - * Clip specified configuration to be within joint limits. + * Clamp specified configuration to be within joint limits. * * @param[out] q \f$\vec{q}\f$ */ - virtual void clip(::rl::math::Vector& q) const; + virtual void clamp(::rl::math::Vector& q) const; virtual Kinematics* clone() const; diff --git a/src/rl/math/Real.h b/src/rl/math/Real.h index 41490bd4..3f7b5c37 100644 --- a/src/rl/math/Real.h +++ b/src/rl/math/Real.h @@ -27,6 +27,7 @@ #ifndef RL_MATH_REAL_H #define RL_MATH_REAL_H +#include #include /** @@ -54,6 +55,19 @@ namespace rl } } + template + inline const T& clamp(const T& v, const T& lo, const T& hi) + { + return clamp(v, lo, hi, ::std::less<>()); + } + + template + inline const T& clamp(const T& v, const T& lo, const T& hi, Compare comp) + { + assert(!comp(hi, lo)); + return comp(v, lo) ? lo : comp(hi, v) ? hi : v; + } + template inline T sign(const T& arg) { diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index 7ea3f7c6..12fc8dbb 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -77,7 +77,7 @@ namespace rl } void - Joint::clip(::rl::math::VectorRef q) const + Joint::clamp(::rl::math::VectorRef q) const { for (::std::size_t i = 0; i < q.size(); ++i) { @@ -95,13 +95,9 @@ namespace rl q(i) += range; } } - else if (q(i) > this->max(i)) + else { - q(i) = this->max(i); - } - else if (q(i) < this->min(i)) - { - q(i) = this->min(i); + q(i) = ::rl::math::clamp(q(i), this->min(i), this->max(i)); } } } @@ -174,7 +170,7 @@ namespace rl q(i) = mean(i) + rand(i) * sigma(i); } - this->clip(q); + this->clamp(q); } void @@ -333,7 +329,7 @@ namespace rl Joint::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const { q2 = q1 + qdot; - this->clip(q2); + this->clamp(q2); } ::rl::math::Real diff --git a/src/rl/mdl/Joint.h b/src/rl/mdl/Joint.h index 079243a0..2970bd74 100644 --- a/src/rl/mdl/Joint.h +++ b/src/rl/mdl/Joint.h @@ -43,7 +43,7 @@ namespace rl virtual ~Joint(); - virtual void clip(::rl::math::VectorRef q) const; + virtual void clamp(::rl::math::VectorRef q) const; virtual ::rl::math::Real distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; diff --git a/src/rl/mdl/Metric.cpp b/src/rl/mdl/Metric.cpp index c3b6933c..2e8958eb 100644 --- a/src/rl/mdl/Metric.cpp +++ b/src/rl/mdl/Metric.cpp @@ -41,13 +41,13 @@ namespace rl } void - Metric::clip(::rl::math::Vector& q) const + Metric::clamp(::rl::math::Vector& q) const { assert(q.size() == this->getDofPosition()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { - this->joints[i]->clip(q.segment(j, this->joints[i]->getDofPosition())); + this->joints[i]->clamp(q.segment(j, this->joints[i]->getDofPosition())); } } diff --git a/src/rl/mdl/Metric.h b/src/rl/mdl/Metric.h index c21f6e3f..4371a7f9 100644 --- a/src/rl/mdl/Metric.h +++ b/src/rl/mdl/Metric.h @@ -40,7 +40,7 @@ namespace rl virtual ~Metric(); - void clip(::rl::math::Vector& q) const; + void clamp(::rl::math::Vector& q) const; Model* clone() const; diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index e9c506c9..6527551a 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -76,18 +76,11 @@ namespace rl } void - SixDof::clip(::rl::math::VectorRef q) const + SixDof::clamp(::rl::math::VectorRef q) const { for (::std::size_t i = 0; i < 3; ++i) { - if (q(i) > this->max(i)) - { - q(i) = this->max(i); - } - else if (q(i) < this->min(i)) - { - q(i) = this->min(i); - } + q(i) = ::rl::math::clamp(q(i), this->min(i), this->max(i)); } ::Eigen::Map< ::rl::math::Quaternion>(q.tail<4>().data()).normalize(); @@ -105,15 +98,7 @@ namespace rl for (::std::size_t i = 0; i < 3; ++i) { q(i) = mean(i) + rand(i) * sigma(i); - - if (q(i) > this->max(i)) - { - q(i) = this->max(i); - } - else if (q(i) < this->min(i)) - { - q(i) = this->min(i); - } + q(i) = ::rl::math::clamp(q(i), this->min(i), this->max(i)); } q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>(), ::Eigen::Map< const ::rl::math::Quaternion>(mean.tail<4>().data()), sigma.tail<3>()).coeffs(); @@ -174,14 +159,7 @@ namespace rl for (::std::size_t i = 0; i < 3; ++i) { - if (q2(i) > this->max(i)) - { - q2(i) = this->max(i); - } - else if (q2(i) < this->min(i)) - { - q2(i) = this->min(i); - } + q2(i) = ::rl::math::clamp(q2(i), this->min(i), this->max(i)); } ::Eigen::Map quaternion1(q1.tail<4>().data()); diff --git a/src/rl/mdl/SixDof.h b/src/rl/mdl/SixDof.h index 5b19bbdd..465f0e60 100644 --- a/src/rl/mdl/SixDof.h +++ b/src/rl/mdl/SixDof.h @@ -40,7 +40,7 @@ namespace rl virtual ~SixDof(); - void clip(::rl::math::VectorRef q) const; + void clamp(::rl::math::VectorRef q) const; ::rl::math::Real distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 37fb49ca..1752e12d 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -63,7 +63,7 @@ namespace rl } void - Spherical::clip(::rl::math::VectorRef q) const + Spherical::clamp(::rl::math::VectorRef q) const { ::Eigen::Map< ::rl::math::Quaternion>(q.data()).normalize(); } diff --git a/src/rl/mdl/Spherical.h b/src/rl/mdl/Spherical.h index 189ed35c..98bff28a 100644 --- a/src/rl/mdl/Spherical.h +++ b/src/rl/mdl/Spherical.h @@ -40,7 +40,7 @@ namespace rl virtual ~Spherical(); - void clip(::rl::math::VectorRef q) const; + void clamp(::rl::math::VectorRef q) const; ::rl::math::Real distance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; diff --git a/src/rl/plan/BridgeSampler.cpp b/src/rl/plan/BridgeSampler.cpp index 41d3de73..7812b510 100644 --- a/src/rl/plan/BridgeSampler.cpp +++ b/src/rl/plan/BridgeSampler.cpp @@ -67,7 +67,7 @@ namespace rl q3(i) = this->gauss() * (*this->sigma)(i) + q2(i); } - this->model->clip(q3); + this->model->clamp(q3); if (this->model->isColliding()) { diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index d65ada6e..63cf22b0 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -58,15 +58,15 @@ namespace rl } void - Model::clip(::rl::math::Vector& q) const + Model::clamp(::rl::math::Vector& q) const { if (nullptr != this->kin) { - this->kin->clip(q); + this->kin->clamp(q); } else { - this->mdl->clip(q); + this->mdl->clamp(q); } } diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 1685a324..8cc5b9d2 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -47,7 +47,7 @@ namespace rl virtual bool areColliding(const ::std::size_t& i, const ::std::size_t& j) const; - virtual void clip(::rl::math::Vector& q) const; + virtual void clamp(::rl::math::Vector& q) const; virtual ::rl::math::Real distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const; From a74a2013f24633d2e3583afa62354247205c733d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 17:16:44 +0200 Subject: [PATCH 098/546] Use Model::generatePositionGaussian in BridgeSampler --- src/rl/plan/BridgeSampler.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rl/plan/BridgeSampler.cpp b/src/rl/plan/BridgeSampler.cpp index 7812b510..4a18d9ca 100644 --- a/src/rl/plan/BridgeSampler.cpp +++ b/src/rl/plan/BridgeSampler.cpp @@ -51,7 +51,7 @@ namespace rl else { ::rl::math::Vector q(this->model->getDof()); - ::rl::math::Vector q3(this->model->getDof()); + ::rl::math::Vector gauss(this->model->getDof()); while (true) { @@ -64,10 +64,10 @@ namespace rl { for (::std::size_t i = 0; i < this->model->getDof(); ++i) { - q3(i) = this->gauss() * (*this->sigma)(i) + q2(i); + gauss(i) = this->gauss(); } - this->model->clamp(q3); + ::rl::math::Vector q3 = this->model->generatePositionGaussian(gauss, q2, *this->sigma); if (this->model->isColliding()) { From 77ca1a1cba4d334251b598aebe546d5ed1f75e5a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 17:17:19 +0200 Subject: [PATCH 099/546] Update GaussianSampler --- src/rl/plan/GaussianSampler.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/src/rl/plan/GaussianSampler.cpp b/src/rl/plan/GaussianSampler.cpp index 7d1131b3..f8147e6d 100644 --- a/src/rl/plan/GaussianSampler.cpp +++ b/src/rl/plan/GaussianSampler.cpp @@ -54,20 +54,18 @@ namespace rl ::rl::math::Vector GaussianSampler::generateCollisionFree() { - ::rl::math::Vector q2(this->model->getDof()); + ::rl::math::Vector gauss(this->model->getDof()); while (true) { ::rl::math::Vector q = this->generate(); - ::rl::math::Vector gauss(this->model->getDof()); - for (::std::size_t i = 0; i < this->model->getDof(); ++i) { gauss(i) = this->gauss(); } - q2 = this->model->generatePositionGaussian(gauss, q, *this->sigma); + ::rl::math::Vector q2 = this->model->generatePositionGaussian(gauss, q, *this->sigma); this->model->setPosition(q); this->model->updateFrames(); @@ -89,8 +87,7 @@ namespace rl if (!this->model->isColliding()) { - q = q2; - return q; + return q2; } } } From 9174a1ed43da0c604d8afa51f8b303c90bb746f2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 20:29:14 +0200 Subject: [PATCH 100/546] Add RandomOnCircle and RandomOnSphere functions --- src/rl/math/MatrixBaseAddons.h | 95 ++++++++++++++++++++++++++++++++++ 1 file changed, 95 insertions(+) diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index abfb4543..e8786a3c 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -31,6 +31,75 @@ namespace Eigen { template class MatrixBase { #endif +Matrix +static RandomOnCircle() +{ + return RandomOnCircle(internal::random(0, 1)); +} + +/** + * Generate random point on unit circle. + * + * http://mathworld.wolfram.com/CirclePointPicking.html + */ +Matrix +static RandomOnCircle(const Scalar& rand) +{ + using ::std::cos; + using ::std::sin; + + eigen_assert(rand >= Scalar(0)); + eigen_assert(rand <= Scalar(1)); + + Scalar theta = Scalar(2 * M_PI) * rand; + + Matrix res; + res.x() = cos(theta); + res.y() = sin(theta); + return res; +} + +Matrix +static RandomOnSphere() +{ + return RandomOnSphere( + Vector2( + internal::random(0, 1), + internal::random(0, 1) + ) + ); +} + +/** + * Generate random point on unit sphere. + * + * http://mathworld.wolfram.com/SpherePointPicking.html + */ +template +Matrix +static RandomOnSphere(const DenseBase& rand) +{ + using ::std::cos; + using ::std::pow; + using ::std::sin; + using ::std::sqrt; + + eigen_assert(2 == rand.size()); + eigen_assert(rand(0) >= Scalar(0)); + eigen_assert(rand(0) <= Scalar(1)); + eigen_assert(rand(1) >= Scalar(0)); + eigen_assert(rand(1) <= Scalar(1)); + + Scalar theta = Scalar(2 * M_PI) * rand(0); + Scalar z = Scalar(2) * rand(1) - Scalar(1); + + Matrix res; + res.x() = sqrt(1 - pow(z, 2)) * cos(theta); + res.y() = sqrt(1 - pow(z, 2)) * sin(theta); + res.z() = z; + return res; +} + Matrix cross3() const { @@ -59,6 +128,32 @@ cross33() const return res; } +Derived& +setRandomOnCircle() +{ + return this->derived() = RandomOnCircle(); +} + +template +Derived& +setRandomOnCircle(const Scalar& rand) +{ + return this->derived() = RandomOnCircle(rand); +} + +Derived& +setRandomOnSphere() +{ + return this->derived() = RandomOnSphere(); +} + +template +Derived& +setRandomOnSphere(const DenseBase& rand) +{ + return this->derived() = RandomOnSphere(rand); +} + Matrix voigt6() const { From bc5d5dafdef52c33be85037db1866db2a545c9fd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 20:32:20 +0200 Subject: [PATCH 101/546] Use Vector3::RandomOnSphere instead of boost::uniform_on_sphere in WorkspaceSphereExplorer --- src/rl/plan/WorkspaceSphereExplorer.cpp | 20 ++++++++++---------- src/rl/plan/WorkspaceSphereExplorer.h | 8 +++++--- 2 files changed, 15 insertions(+), 13 deletions(-) diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index 0bcac165..4d239bc8 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -49,10 +49,8 @@ namespace rl end(nullptr), graph(), queue(), - rand( - ::std::mt19937(::std::random_device()()), - ::boost::uniform_on_sphere< ::rl::math::Real>(3) - ) + randDistribution(0, 1), + randEngine(::std::random_device()()) { } @@ -165,13 +163,9 @@ namespace rl //for (::std::size_t i = 0; i < this->samples; ++i) // TODO { WorkspaceSphere sphere; - sphere.parent = vertex; - - ::boost::uniform_on_sphere< ::rl::math::Real>::result_type sample = this->rand(); - sphere.center = ::std::make_shared< ::rl::math::Vector3>( - top.radius * ::Eigen::Map< ::rl::math::Vector3>(sample.data()) + *top.center + top.radius * ::rl::math::Vector3::RandomOnSphere(::rl::math::Vector2(this->rand(), this->rand())) + *top.center ); if ((*this->start - *sphere.center).norm() <= this->range) @@ -275,6 +269,12 @@ namespace rl return false; } + ::std::uniform_real_distribution< ::rl::math::Real>::result_type + WorkspaceSphereExplorer::rand() + { + return this->randDistribution(this->randEngine); + } + void WorkspaceSphereExplorer::reset() { @@ -287,7 +287,7 @@ namespace rl void WorkspaceSphereExplorer::seed(const ::std::mt19937::result_type& value) { - this->rand.engine().seed(value); + this->randEngine.seed(value); } } } diff --git a/src/rl/plan/WorkspaceSphereExplorer.h b/src/rl/plan/WorkspaceSphereExplorer.h index 16413f23..6ecb068f 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.h +++ b/src/rl/plan/WorkspaceSphereExplorer.h @@ -31,8 +31,6 @@ #include #include #include -#include -#include #include #include "WorkspaceSphere.h" @@ -126,6 +124,8 @@ namespace rl bool isCovered(const Vertex& parent, const ::rl::math::Vector3& point) const; + ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + Vertex begin; Vertex end; @@ -134,7 +134,9 @@ namespace rl ::std::multiset queue; - ::boost::variate_generator< ::std::mt19937, ::boost::uniform_on_sphere< ::rl::math::Real>> rand; + ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + + ::std::mt19937 randEngine; private: From b8f3dec7cafab6935a633ef3e360ce5716bcb562 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 20:34:44 +0200 Subject: [PATCH 102/546] Minor fix --- src/rl/plan/WorkspaceSphereExplorer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index 4d239bc8..c004e72f 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -163,10 +163,10 @@ namespace rl //for (::std::size_t i = 0; i < this->samples; ++i) // TODO { WorkspaceSphere sphere; - sphere.parent = vertex; sphere.center = ::std::make_shared< ::rl::math::Vector3>( top.radius * ::rl::math::Vector3::RandomOnSphere(::rl::math::Vector2(this->rand(), this->rand())) + *top.center ); + sphere.parent = vertex; if ((*this->start - *sphere.center).norm() <= this->range) { From ae23abb87c60e8f2afad79c3eae142a069d3dd3a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 21:09:57 +0200 Subject: [PATCH 103/546] Move functions in Real.h into separate header --- src/rl/kin/Kinematics.cpp | 1 + src/rl/math/CMakeLists.txt | 1 + src/rl/math/LowPass.h | 2 + src/rl/math/Real.h | 46 --------------------- src/rl/math/algorithm.h | 83 ++++++++++++++++++++++++++++++++++++++ src/rl/mdl/Joint.cpp | 2 + src/rl/mdl/SixDof.cpp | 1 + 7 files changed, 90 insertions(+), 46 deletions(-) create mode 100644 src/rl/math/algorithm.h diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 4f583f47..a66cb4f2 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -25,6 +25,7 @@ // #include +#include #include #include #include diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index f5784728..58f4db84 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(Eigen3 REQUIRED) set( BASE_HDRS + algorithm.h Array.h Circular.h CircularVector2.h diff --git a/src/rl/math/LowPass.h b/src/rl/math/LowPass.h index ee48adcd..f874b95e 100644 --- a/src/rl/math/LowPass.h +++ b/src/rl/math/LowPass.h @@ -27,6 +27,8 @@ #ifndef RL_MATH_LOWPASS_H #define RL_MATH_LOWPASS_H +#include + #include "Real.h" namespace rl diff --git a/src/rl/math/Real.h b/src/rl/math/Real.h index 3f7b5c37..a1d4cf64 100644 --- a/src/rl/math/Real.h +++ b/src/rl/math/Real.h @@ -27,9 +27,6 @@ #ifndef RL_MATH_REAL_H #define RL_MATH_REAL_H -#include -#include - /** * Robotics Library. */ @@ -41,49 +38,6 @@ namespace rl namespace math { typedef double Real; - - template - inline T cbrt(const T& arg) - { - if (arg < 0) - { - return -::std::pow(-arg, static_cast(1.0 / 3.0)); - } - else - { - return ::std::pow(arg, static_cast(1.0 / 3.0)); - } - } - - template - inline const T& clamp(const T& v, const T& lo, const T& hi) - { - return clamp(v, lo, hi, ::std::less<>()); - } - - template - inline const T& clamp(const T& v, const T& lo, const T& hi, Compare comp) - { - assert(!comp(hi, lo)); - return comp(v, lo) ? lo : comp(hi, v) ? hi : v; - } - - template - inline T sign(const T& arg) - { - if (arg > 0) - { - return 1; - } - else if (arg < 0) - { - return -1; - } - else - { - return 0; - } - } } } diff --git a/src/rl/math/algorithm.h b/src/rl/math/algorithm.h new file mode 100644 index 00000000..c35f568d --- /dev/null +++ b/src/rl/math/algorithm.h @@ -0,0 +1,83 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MATH_ALGORITHM_H +#define RL_MATH_ALGORITHM_H + +#include +#include +#include + +namespace rl +{ + namespace math + { + template + inline T cbrt(const T& arg) + { + if (arg < 0) + { + return -::std::pow(-arg, static_cast(1.0 / 3.0)); + } + else + { + return ::std::pow(arg, static_cast(1.0 / 3.0)); + } + } + + template + inline const T& clamp(const T& v, const T& lo, const T& hi, Compare comp) + { + assert(!comp(hi, lo)); + return comp(v, lo) ? lo : comp(hi, v) ? hi : v; + } + + template + inline const T& clamp(const T& v, const T& lo, const T& hi) + { + return clamp(v, lo, hi, ::std::less()); + } + + template + inline T sign(const T& arg) + { + if (arg > 0) + { + return 1; + } + else if (arg < 0) + { + return -1; + } + else + { + return 0; + } + } + } +} + +#endif // RL_MATH_ALGORITHM_H diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index 12fc8dbb..a2eab545 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -24,6 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include + #include "Frame.h" #include "Joint.h" diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index 6527551a..d51e4738 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -24,6 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include #include #include "SixDof.h" From d06242e356bcddcf41f659362903cc99fbbaf291 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 21:31:34 +0200 Subject: [PATCH 104/546] Move coordinate conversion functions to MatrixBaseAddons.h --- src/rl/math/MatrixBaseAddons.h | 64 ++++++++++++++++++++++++++++++++++ src/rl/math/Unit.h | 26 -------------- 2 files changed, 64 insertions(+), 26 deletions(-) diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index e8786a3c..c750ea42 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -31,6 +31,53 @@ namespace Eigen { template class MatrixBase { #endif +template +Matrix +static CartesianFromPolar(const MatrixBase& polar) +{ + using ::std::cos; + using ::std::sin; + + eigen_assert(2 == polar.size()); + + Matrix cartesian; + cartesian.x() = polar.x() * cos(polar.y()); + cartesian.y() = polar.x() * sin(polar.y()); + return cartesian; +} + +template +Matrix +static CartesianFromSpherical(const MatrixBase& spherical) +{ + using ::std::cos; + using ::std::sin; + + eigen_assert(3 == spherical.size()); + + Matrix cartesian; + cartesian.x() = spherical.x() * sin(spherical.y()) * cos(spherical.z()); + cartesian.y() = spherical.x() * sin(spherical.y()) * sin(spherical.z()); + cartesian.z() = spherical.x() * cos(spherical.y()); + return cartesian; +} + +template +Matrix +static PolarFromCartesian(const MatrixBase& cartesian) +{ + using ::std::atan2; + using ::std::pow; + using ::std::sqrt; + + eigen_assert(2 == cartesian.size()); + + Matrix polar; + polar.x() = sqrt(pow(cartesian.x(), 2) + pow(cartesian.y(), 2)); + polar.y() = atan2(cartesian.y(), cartesian.x()); + return polar; +} + Matrix static RandomOnCircle() { @@ -100,6 +147,23 @@ static RandomOnSphere(const DenseBase& rand) return res; } +template +Matrix +static SphericalFromCartesian(const MatrixBase& cartesian) +{ + using ::std::atan2; + using ::std::pow; + using ::std::sqrt; + + eigen_assert(3 == cartesian.size()); + + Matrix spherical; + spherical.x() = sqrt(pow(cartesian.x(), 2) + pow(cartesian.y(), 2) + pow(cartesian.z(), 2)); + spherical.y() = atan2(sqrt(pow(cartesian.x(), 2) + pow(cartesian.y(), 2)), cartesian.z()); + spherical.z() = atan2(cartesian.y(), cartesian.x()); + return spherical; +} + Matrix cross3() const { diff --git a/src/rl/math/Unit.h b/src/rl/math/Unit.h index 89f779a5..160cc5a7 100644 --- a/src/rl/math/Unit.h +++ b/src/rl/math/Unit.h @@ -212,32 +212,6 @@ namespace rl static const Real UNIT2MILLI = 1.0e+3f; static const Real UNIT2NANO = 1.0e+9f; - - inline void cartesianToPolar(const Real& x, const Real& y, Real& r, Real& theta) - { - r = ::std::sqrt(::std::pow(x, 2) + ::std::pow(y, 2)); - theta = ::std::atan2(y, x); - } - - inline void cartesianToSpherical(const Real& x, const Real& y, const Real& z, Real& rho, Real& psi, Real& theta) - { - rho = ::std::sqrt(::std::pow(x, 2) + ::std::pow(y, 2) + ::std::pow(z, 2)); - psi = ::std::atan2(::std::sqrt(::std::pow(x, 2) + ::std::pow(y, 2)), z); - theta = ::std::atan2(y, x); - } - - inline void polarToCartesian(const Real& r, const Real& theta, Real& x, Real& y) - { - x = r * ::std::cos(theta); - y = r * ::std::sin(theta); - } - - inline void sphericalToCartesian(const Real& rho, const Real& psi, const Real& theta, Real& x, Real& y, Real& z) - { - x = rho * ::std::sin(psi) * ::std::cos(theta); - y = rho * ::std::sin(psi) * ::std::sin(theta); - z = rho * ::std::cos(psi); - } } } From 82316ec38e4996a81b3a4324bda21f04bb414e8f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Apr 2018 22:08:12 +0200 Subject: [PATCH 105/546] Adjust rlEetTestSolid vertex and edge count due to RandomOnSphere --- tests/rlEetTest/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index 86f9b771..3ba8f64c 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -71,7 +71,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) solid ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml - 281 280 + 292 291 2 1 1 0 0 0 9 11 1 0 0 -90 ) From 80897448b43d0a96d699a97307db472c4c6d52f6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 1 May 2018 01:54:34 +0200 Subject: [PATCH 106/546] Adjust rlEetTest vertex and edge count due to RandomOnSphere --- tests/rlEetTest/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index 3ba8f64c..4c9f9257 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -58,7 +58,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) pqp ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml - 238 237 + 239 238 2 1 1 0 0 0 9 11 1 0 0 -90 ) @@ -71,7 +71,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) solid ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml - 292 291 + 306 305 2 1 1 0 0 0 9 11 1 0 0 -90 ) From b1ca83208dc9d6ee6e3b660403ee419dbb12b868 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 1 May 2018 01:54:46 +0200 Subject: [PATCH 107/546] Update static constructors in MatrixBaseAddons.h --- src/rl/math/MatrixBaseAddons.h | 73 +++++++++++++++++++++------------- 1 file changed, 46 insertions(+), 27 deletions(-) diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index c750ea42..bef3cbd6 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -38,12 +38,14 @@ static CartesianFromPolar(const MatrixBase& polar) using ::std::cos; using ::std::sin; + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 2) + eigen_assert(2 == polar.size()); - Matrix cartesian; - cartesian.x() = polar.x() * cos(polar.y()); - cartesian.y() = polar.x() * sin(polar.y()); - return cartesian; + return Matrix( + polar.x() * cos(polar.y()), + polar.x() * sin(polar.y()) + ); } template @@ -53,13 +55,17 @@ static CartesianFromSpherical(const MatrixBase& spherical) using ::std::cos; using ::std::sin; + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 3) + eigen_assert(3 == spherical.size()); - Matrix cartesian; - cartesian.x() = spherical.x() * sin(spherical.y()) * cos(spherical.z()); - cartesian.y() = spherical.x() * sin(spherical.y()) * sin(spherical.z()); - cartesian.z() = spherical.x() * cos(spherical.y()); - return cartesian; + Scalar sin_y = sin(spherical.y()); + + return Matrix( + spherical.x() * sin_y * cos(spherical.z()), + spherical.x() * sin_y * sin(spherical.z()), + spherical.x() * cos(spherical.y()) + ); } template @@ -70,12 +76,14 @@ static PolarFromCartesian(const MatrixBase& cartesian) using ::std::pow; using ::std::sqrt; + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 2) + eigen_assert(2 == cartesian.size()); - Matrix polar; - polar.x() = sqrt(pow(cartesian.x(), 2) + pow(cartesian.y(), 2)); - polar.y() = atan2(cartesian.y(), cartesian.x()); - return polar; + return Matrix( + sqrt(pow(cartesian.x(), 2) + pow(cartesian.y(), 2)), + atan2(cartesian.y(), cartesian.x()) + ); } Matrix @@ -95,15 +103,17 @@ static RandomOnCircle(const Scalar& rand) using ::std::cos; using ::std::sin; + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 2) + eigen_assert(rand >= Scalar(0)); eigen_assert(rand <= Scalar(1)); Scalar theta = Scalar(2 * M_PI) * rand; - Matrix res; - res.x() = cos(theta); - res.y() = sin(theta); - return res; + return Matrix( + cos(theta), + sin(theta) + ); } Matrix @@ -131,6 +141,8 @@ static RandomOnSphere(const DenseBase& rand) using ::std::sin; using ::std::sqrt; + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 3) + eigen_assert(2 == rand.size()); eigen_assert(rand(0) >= Scalar(0)); eigen_assert(rand(0) <= Scalar(1)); @@ -139,12 +151,13 @@ static RandomOnSphere(const DenseBase& rand) Scalar theta = Scalar(2 * M_PI) * rand(0); Scalar z = Scalar(2) * rand(1) - Scalar(1); + Scalar sqrt_1_z_2 = sqrt(1 - pow(z, 2)); - Matrix res; - res.x() = sqrt(1 - pow(z, 2)) * cos(theta); - res.y() = sqrt(1 - pow(z, 2)) * sin(theta); - res.z() = z; - return res; + return Matrix( + sqrt_1_z_2 * cos(theta), + sqrt_1_z_2 * sin(theta), + z + ); } template @@ -155,13 +168,19 @@ static SphericalFromCartesian(const MatrixBase& cartesian) using ::std::pow; using ::std::sqrt; + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 3) + eigen_assert(3 == cartesian.size()); - Matrix spherical; - spherical.x() = sqrt(pow(cartesian.x(), 2) + pow(cartesian.y(), 2) + pow(cartesian.z(), 2)); - spherical.y() = atan2(sqrt(pow(cartesian.x(), 2) + pow(cartesian.y(), 2)), cartesian.z()); - spherical.z() = atan2(cartesian.y(), cartesian.x()); - return spherical; + Scalar x_2 = pow(cartesian.x(), 2); + Scalar y_2 = pow(cartesian.y(), 2); + Scalar z_2 = pow(cartesian.z(), 2); + + return Matrix( + sqrt(x_2 + y_2 + z_2), + atan2(sqrt(x_2 + y_2), cartesian.z()), + atan2(cartesian.y(), cartesian.x()) + ); } Matrix From a8ad4a600684d58610020e5079a0af4d6003d3e1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 1 May 2018 15:06:56 +0200 Subject: [PATCH 108/546] Update static coordinate conversion constructors --- src/rl/math/MatrixBaseAddons.h | 90 +++++++++++++++++++++++++++------- 1 file changed, 71 insertions(+), 19 deletions(-) diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index bef3cbd6..761d9f7f 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -34,43 +34,86 @@ namespace Eigen { template class MatrixBase { template Matrix static CartesianFromPolar(const MatrixBase& polar) +{ + eigen_assert(2 == polar.size()); + return CartesianFromPolar(polar(0), polar(1)); +} + +/** + * Convert polar coordinates into Cartesian coordinates. + * + * http://mathworld.wolfram.com/PolarCoordinates.html + * + * @param[in] r Radial distance from the origin + * @param[in] theta Counterclockwise angle from the x-axis + */ +Matrix +static CartesianFromPolar(const Scalar& r, const Scalar& theta) { using ::std::cos; using ::std::sin; EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 2) - eigen_assert(2 == polar.size()); + eigen_assert(r >= Scalar(0)); return Matrix( - polar.x() * cos(polar.y()), - polar.x() * sin(polar.y()) + r * cos(theta), + r * sin(theta) ); } template Matrix static CartesianFromSpherical(const MatrixBase& spherical) +{ + eigen_assert(3 == spherical.size()); + return CartesianFromSpherical(spherical(0), spherical(1), spherical(2)); +} + +/** + * Convert spherical coordinates into Cartesian coordinates. + * + * http://mathworld.wolfram.com/SphericalCoordinates.html + * + * @param[in] r Radial distance from the origin + * @param[in] theta Azimuthal angle in the xy-plane from the x-axis + * @param[in] phi Polar angle (also known as the zenith angle and colatitude) from the positive z-axis + */ +Matrix +static CartesianFromSpherical(const Scalar& r, const Scalar& theta, const Scalar& phi) { using ::std::cos; using ::std::sin; EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 3) - eigen_assert(3 == spherical.size()); + eigen_assert(r >= Scalar(0)); - Scalar sin_y = sin(spherical.y()); + Scalar sin_phi = sin(phi); return Matrix( - spherical.x() * sin_y * cos(spherical.z()), - spherical.x() * sin_y * sin(spherical.z()), - spherical.x() * cos(spherical.y()) + r * cos(theta) * sin_phi, + r * sin(theta) * sin_phi, + r * cos(phi) ); } template Matrix static PolarFromCartesian(const MatrixBase& cartesian) +{ + eigen_assert(2 == cartesian.size()); + return PolarFromCartesian(cartesian.x(), cartesian.y()); +} + +/** + * Convert Cartesian coordinates into polar coordinates. + * + * http://mathworld.wolfram.com/PolarCoordinates.html + */ +Matrix +static PolarFromCartesian(const Scalar& x, const Scalar& y) { using ::std::atan2; using ::std::pow; @@ -78,11 +121,9 @@ static PolarFromCartesian(const MatrixBase& cartesian) EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 2) - eigen_assert(2 == cartesian.size()); - return Matrix( - sqrt(pow(cartesian.x(), 2) + pow(cartesian.y(), 2)), - atan2(cartesian.y(), cartesian.x()) + sqrt(pow(x, 2) + pow(y, 2)), + atan2(y, x) ); } @@ -163,6 +204,19 @@ static RandomOnSphere(const DenseBase& rand) template Matrix static SphericalFromCartesian(const MatrixBase& cartesian) +{ + eigen_assert(3 == cartesian.size()); + return SphericalFromCartesian(cartesian.x(), cartesian.y(), cartesian.z()); +} + +/** + * Convert Cartesian coordinates into spherical coordinates. + * + * http://mathworld.wolfram.com/SphericalCoordinates.html + */ +template +Matrix +static SphericalFromCartesian(const Scalar& x, const Scalar& y, const Scalar& z) { using ::std::atan2; using ::std::pow; @@ -170,16 +224,14 @@ static SphericalFromCartesian(const MatrixBase& cartesian) EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived, 3) - eigen_assert(3 == cartesian.size()); - - Scalar x_2 = pow(cartesian.x(), 2); - Scalar y_2 = pow(cartesian.y(), 2); - Scalar z_2 = pow(cartesian.z(), 2); + Scalar x_2 = pow(x, 2); + Scalar y_2 = pow(y, 2); + Scalar z_2 = pow(z, 2); return Matrix( sqrt(x_2 + y_2 + z_2), - atan2(sqrt(x_2 + y_2), cartesian.z()), - atan2(cartesian.y(), cartesian.x()) + atan2(sqrt(x_2 + y_2), z), + atan2(y, x) ); } From 930d893aea8910cc3e8888e80f886b72a3d884ff Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 1 May 2018 16:34:23 +0200 Subject: [PATCH 109/546] Update variable name for Quaternion Gaussian sampling --- src/rl/math/QuaternionBaseAddons.h | 45 ++++++++---------------------- 1 file changed, 12 insertions(+), 33 deletions(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 13af7b95..8f76f109 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -31,20 +31,6 @@ namespace Eigen { template class QuaternionBase { #endif -template -static Quaternion Random(const QuaternionBase& mean, const MatrixBase& sigma) -{ - return Random( - Vector3( - internal::random(0, 1), - internal::random(0, 1), - internal::random(0, 1) - ), - mean, - sigma - ); -} - /** * QuTEM (Quaternion Tangent Ellipsoid at the Mean) sampling algorithm. * @@ -55,20 +41,20 @@ static Quaternion Random(const QuaternionBase& mean, cons * http://characters.media.mit.edu/Theses/johnson_phd.pdf */ template -static Quaternion Random(const MatrixBase& rand, const QuaternionBase& mean, const MatrixBase& sigma) +static Quaternion Random(const MatrixBase& gauss, const QuaternionBase& mean, const MatrixBase& sigma) { - eigen_assert(3 == rand.size()); + eigen_assert(3 == gauss.size()); eigen_assert(3 == sigma.size()); - eigen_assert(rand(0) >= Scalar(0)); - eigen_assert(rand(0) <= Scalar(1)); - eigen_assert(rand(1) >= Scalar(0)); - eigen_assert(rand(1) <= Scalar(1)); - eigen_assert(rand(2) >= Scalar(0)); - eigen_assert(rand(2) <= Scalar(1)); + eigen_assert(gauss(0) >= Scalar(0)); + eigen_assert(gauss(0) <= Scalar(1)); + eigen_assert(gauss(1) >= Scalar(0)); + eigen_assert(gauss(1) <= Scalar(1)); + eigen_assert(gauss(2) >= Scalar(0)); + eigen_assert(gauss(2) <= Scalar(1)); Quaternion tmp; - tmp.w() = rand.norm(); - tmp.vec() = sigma.cwiseProduct(rand); + tmp.w() = gauss.norm(); + tmp.vec() = sigma.cwiseProduct(gauss); return mean * tmp.exp(); } @@ -260,18 +246,11 @@ setRandom(const MatrixBase& rand) return this->derived() = Random(rand); } -template -Derived& -setRandom(const QuaternionBase& mean, const MatrixBase& sigma) -{ - return this->derived() = Random(mean, sigma); -} - template Derived& -setRandom(const MatrixBase& rand, const QuaternionBase& mean, const MatrixBase& sigma) +setRandom(const MatrixBase& gauss, const QuaternionBase& mean, const MatrixBase& sigma) { - return this->derived() = Random(rand, mean, sigma); + return this->derived() = Random(gauss, mean, sigma); } template From 8def7ccdb878d8bcb4782a5066a27dfcbee9cbd4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 1 May 2018 16:35:06 +0200 Subject: [PATCH 110/546] Use Quaternion::Random(gauss, mean, sigma) in Eet --- src/rl/plan/Eet.cpp | 17 ++++++----------- 1 file changed, 6 insertions(+), 11 deletions(-) diff --git a/src/rl/plan/Eet.cpp b/src/rl/plan/Eet.cpp index 6f9f2d36..267ab438 100644 --- a/src/rl/plan/Eet.cpp +++ b/src/rl/plan/Eet.cpp @@ -443,18 +443,13 @@ namespace rl if (sigma < this->beta) // maintain orientation for small sigma { - // Gauss sampling for orientation + // Gauss sampling for orientation similar to nearest vertex - ::rl::math::Real x = this->gauss() * sigma * 180.0f * ::rl::math::DEG2RAD / this->beta; - ::rl::math::Real y = this->gauss() * sigma * 180.0f * ::rl::math::DEG2RAD / this->beta; - ::rl::math::Real z = this->gauss() * sigma * 180.0f * ::rl::math::DEG2RAD / this->beta; - - // orientation similar to nearest vertex - - chosen.linear() = (*get(this->tree[0], nearest.second)->t).linear() * - ::rl::math::AngleAxis(z, ::rl::math::Vector3::UnitZ()) * - ::rl::math::AngleAxis(y, ::rl::math::Vector3::UnitY()) * - ::rl::math::AngleAxis(x, ::rl::math::Vector3::UnitX()); + chosen.linear() = ::rl::math::Quaternion::Random( + ::rl::math::Vector3(this->gauss(), this->gauss(), this->gauss()), + ::rl::math::Quaternion((*get(this->tree[0], nearest.second)->t).linear()), + ::rl::math::Vector3::Constant(sigma / this->beta) + ).toRotationMatrix(); } } From 7af3afaf873e29624334e3a888001dc40f18c926 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 1 May 2018 18:03:16 +0200 Subject: [PATCH 111/546] Move Dynamic::eulerCauchy and Dynamic::rungeKuttaNystrom into separate classes --- demos/rlDynamics1Demo/rlDynamics1Demo.cpp | 4 +- src/rl/mdl/CMakeLists.txt | 6 ++ src/rl/mdl/Dynamic.cpp | 77 ---------------------- src/rl/mdl/Dynamic.h | 46 ------------- src/rl/mdl/EulerCauchyIntegrator.cpp | 38 +++++++++++ src/rl/mdl/EulerCauchyIntegrator.h | 44 +++++++++++++ src/rl/mdl/Integrator.cpp | 16 +++++ src/rl/mdl/Integrator.h | 33 ++++++++++ src/rl/mdl/RungeKuttaNystromIntegrator.cpp | 73 ++++++++++++++++++++ src/rl/mdl/RungeKuttaNystromIntegrator.h | 48 ++++++++++++++ 10 files changed, 261 insertions(+), 124 deletions(-) create mode 100644 src/rl/mdl/EulerCauchyIntegrator.cpp create mode 100644 src/rl/mdl/EulerCauchyIntegrator.h create mode 100644 src/rl/mdl/Integrator.cpp create mode 100644 src/rl/mdl/Integrator.h create mode 100644 src/rl/mdl/RungeKuttaNystromIntegrator.cpp create mode 100644 src/rl/mdl/RungeKuttaNystromIntegrator.h diff --git a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp index ef19a649..6df7d719 100644 --- a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp +++ b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp @@ -30,6 +30,7 @@ #include #include #include +#include #include int @@ -73,7 +74,8 @@ main(int argc, char** argv) dynamic->forwardDynamics(); std::cout << "qdd = " << dynamic->getAcceleration().transpose() << std::endl; - dynamic->rungeKuttaNystrom(1); + rl::mdl::RungeKuttaNystromIntegrator integrator(dynamic); + integrator.integrate(1); std::cout << "q = " << dynamic->getPosition().transpose() << std::endl; std::cout << "qd = " << dynamic->getVelocity().transpose() << std::endl; } diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index fdaf0fef..3160ce21 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -8,11 +8,13 @@ set( Cylindrical.h Dynamic.h Element.h + EulerCauchyIntegrator.h Exception.h Factory.h Fixed.h Frame.h Helical.h + Integrator.h InverseKinematics.h JacobianInverseKinematics.h Joint.h @@ -21,6 +23,7 @@ set( Model.h Prismatic.h Revolute.h + RungeKuttaNystromIntegrator.h SixDof.h Spherical.h Transform.h @@ -36,11 +39,13 @@ set( Cylindrical.cpp Dynamic.cpp Element.cpp + EulerCauchyIntegrator.cpp Exception.cpp Fixed.cpp Factory.cpp Frame.cpp Helical.cpp + Integrator.cpp InverseKinematics.cpp JacobianInverseKinematics.cpp Joint.cpp @@ -49,6 +54,7 @@ set( Model.cpp Prismatic.cpp Revolute.cpp + RungeKuttaNystromIntegrator.cpp SixDof.cpp Spherical.cpp Transform.cpp diff --git a/src/rl/mdl/Dynamic.cpp b/src/rl/mdl/Dynamic.cpp index dfcf292b..d790d933 100644 --- a/src/rl/mdl/Dynamic.cpp +++ b/src/rl/mdl/Dynamic.cpp @@ -185,27 +185,6 @@ namespace rl return new Dynamic(*this); } - void - Dynamic::eulerCauchy(const ::rl::math::Real& dt) - { - ::rl::math::Vector y = this->getPosition(); - ::rl::math::Vector dy = this->getVelocity(); - - this->forwardDynamics(); - - // f - ::rl::math::Vector f = this->getAcceleration(); - - // y_0 + dy_0 * dt - y += dt * dy; // TODO - // dy_0 + f * dt - dy += dt * f; // TODO - - this->setPosition(y); - this->setVelocity(dy); - this->setAcceleration(f); - } - void Dynamic::forwardDynamics() { @@ -290,62 +269,6 @@ namespace rl } } - void - Dynamic::rungeKuttaNystrom(const ::rl::math::Real& dt) - { - ::rl::math::Vector y0 = this->getPosition(); - ::rl::math::Vector dy0 = this->getVelocity(); - - this->forwardDynamics(); - - ::rl::math::Vector f = this->getAcceleration(); - - // k1 = dt / 2 * f - ::rl::math::Vector k1 = dt / 2 * f; - - // y_0 + dt / 2 * dy_0 + dt / 4 * k_1 - ::rl::math::Vector y = y0 + dt / 2 * dy0 + dt / 4 * k1; // TODO - // dy_0 + k1 - ::rl::math::Vector dy = dy0 + k1; - - this->setPosition(y); - this->setVelocity(dy); - this->forwardDynamics(); - - // k2 = dt / 2 * f - ::rl::math::Vector k2 = dt / 2 * this->getAcceleration(); - - // dy_0 + k_2 - dy = dy0 + k2; - - this->setVelocity(dy); - this->forwardDynamics(); - - // k3 = dt / 2 * f - ::rl::math::Vector k3 = dt / 2 * this->getAcceleration(); - - // y_0 + dt * dy_0 + dt * k_3 - y = y0 + dt * dy0 + dt * k3; // TODO - // dy_0 + 2 * k_3 - dy = dy0 + 2 * k3; - - this->setPosition(y); - this->setVelocity(dy); - this->forwardDynamics(); - - // k4 = dt / 2 * f - ::rl::math::Vector k4 = dt / 2 * this->getAcceleration(); - - // y_0 + dy_0 * dt + dt / 3 * (k_1 + k_2 + k_3) - y = y0 + dy0 * dt + dt / 3 * (k1 + k2 + k3); // TODO - // dy_0 + 1 / 3 * (k_1 + 2 * k_2 + 2 * k_3 + k_4) - dy = dy0 + 1.0f / 3.0f * (k1 + 2 * k2 + 2 * k3 + k4); // TODO - - this->setPosition(y); - this->setVelocity(dy); - this->setAcceleration(f); - } - void Dynamic::setWorldGravity(const ::rl::math::Real& x, const ::rl::math::Real& y, const ::rl::math::Real& z) { diff --git a/src/rl/mdl/Dynamic.h b/src/rl/mdl/Dynamic.h index b5c07e19..865d5ae2 100644 --- a/src/rl/mdl/Dynamic.h +++ b/src/rl/mdl/Dynamic.h @@ -148,27 +148,6 @@ namespace rl Model* clone() const; - /** - * Integration via Euler-Cauchy. - * - * \f[ \vec{q}_{i + 1} = \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} \f] - * \f[ \dot{\vec{q}}_{i + 1} = \dot{\vec{q}}_{i} + \Delta t \, f(t_{i}, \vec{q}_{i}, \dot{\vec{q}}_{i}) \f] - * \f[ \ddot{\vec{q}} = f(t, \vec{q}, \dot{\vec{q}}) \f] - * \f[ t_{i + 1} = t_{i} + \Delta t \f] - * - * @param[in] dt Integration time step \f$\Delta t\f$ - * - * @pre setPosition() - * @pre setVelocity() - * @pre setTorque() - * @post getPosition() - * @post getVelocity() - * @post getAcceleration() - * - * @see forwardDynamics - */ - void eulerCauchy(const ::rl::math::Real& dt); - /** * Forward dynamics via articulated-body algorithm. * @@ -253,31 +232,6 @@ namespace rl void inverseForce(); - /** - * Integration via Runge-Kutta-Nyström. - * - * \f[ \vec{q}_{i + 1} = \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} + \frac{\Delta t}{3} (\vec{k}_{1} + \vec{k}_{2} + \vec{k}_{3}) \f] - * \f[ \dot{\vec{q}}_{i + 1} = \dot{\vec{q}}_{i} + \frac{1}{3} (\vec{k}_{1} + 2 \vec{k}_{2} + 2 \vec{k}_{3} + \vec{k}_{4}) \f] - * \f[ \ddot{\vec{q}} = f(t, \vec{q}, \dot{\vec{q}}) \f] - * \f[ t_{i + 1} = t_{i} + \Delta t \f] - * \f[ \vec{k}_{1} = \frac{\Delta t}{2} \, f(t_{i}, \vec{q}_{i}, \dot{\vec{q}}_{i}) \f] - * \f[ \vec{k}_{2} = \frac{\Delta t}{2} \, f(t_{i} + \frac{\Delta t}{2}, \vec{q}_{i} + \frac{\Delta t}{2} \, \dot{\vec{q}}_{i} + \frac{\Delta t}{4} \, \vec{k}_{1}, \dot{\vec{q}}_{i} + \vec{k}_{1}) \f] - * \f[ \vec{k}_{3} = \frac{\Delta t}{2} \, f(t_{i} + \frac{\Delta t}{2}, \vec{q}_{i} + \frac{\Delta t}{2} \, \dot{\vec{q}}_{i} + \frac{\Delta t}{4} \, \vec{k}_{1}, \dot{\vec{q}}_{i} + \vec{k}_{2}) \f] - * \f[ \vec{k}_{4} = \frac{\Delta t}{2} \, f(t_{i} + \Delta t, \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} + \Delta t \, \vec{k}_{3}, \dot{\vec{q}}_{i} + 2 \vec{k}_{3}) \f] - * - * @param[in] dt Integration time step \f$\Delta t\f$ - * - * @pre setPosition() - * @pre setVelocity() - * @pre setTorque() - * @post getPosition() - * @post getVelocity() - * @post getAcceleration() - * - * @see forwardDynamics() - */ - void rungeKuttaNystrom(const ::rl::math::Real& dt); - void setWorldGravity(const ::rl::math::Real& x, const ::rl::math::Real& y, const ::rl::math::Real& z); void setWorldGravity(const ::rl::math::Vector& xyz); diff --git a/src/rl/mdl/EulerCauchyIntegrator.cpp b/src/rl/mdl/EulerCauchyIntegrator.cpp new file mode 100644 index 00000000..a88c91e6 --- /dev/null +++ b/src/rl/mdl/EulerCauchyIntegrator.cpp @@ -0,0 +1,38 @@ +#include "Dynamic.h" +#include "EulerCauchyIntegrator.h" + +namespace rl +{ + namespace mdl + { + EulerCauchyIntegrator::EulerCauchyIntegrator(Dynamic* dynamic) : + Integrator(dynamic) + { + } + + EulerCauchyIntegrator::~EulerCauchyIntegrator() + { + } + + void + EulerCauchyIntegrator::integrate(const ::rl::math::Real& dt) + { + ::rl::math::Vector y = this->dynamic->getPosition(); + ::rl::math::Vector dy = this->dynamic->getVelocity(); + + this->dynamic->forwardDynamics(); + + // f + ::rl::math::Vector f = this->dynamic->getAcceleration(); + + // y_0 + dy_0 * dt + y += dt * dy; + // dy_0 + f * dt + dy += dt * f; + + this->dynamic->setPosition(y); + this->dynamic->setVelocity(dy); + this->dynamic->setAcceleration(f); + } + } +} diff --git a/src/rl/mdl/EulerCauchyIntegrator.h b/src/rl/mdl/EulerCauchyIntegrator.h new file mode 100644 index 00000000..e2d518fb --- /dev/null +++ b/src/rl/mdl/EulerCauchyIntegrator.h @@ -0,0 +1,44 @@ +#ifndef RL_MDL_EULERCAUCHYINTEGRATOR_H +#define RL_MDL_EULERCAUCHYINTEGRATOR_H + +#include "Integrator.h" + +namespace rl +{ + namespace mdl + { + /** + * Integration via Euler-Cauchy. + * + * \f[ \vec{q}_{i + 1} = \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} \f] + * \f[ \dot{\vec{q}}_{i + 1} = \dot{\vec{q}}_{i} + \Delta t \, f(t_{i}, \vec{q}_{i}, \dot{\vec{q}}_{i}) \f] + * \f[ \ddot{\vec{q}} = f(t, \vec{q}, \dot{\vec{q}}) \f] + * \f[ t_{i + 1} = t_{i} + \Delta t \f] + * + * @pre Dynamic::setPosition() + * @pre Dynamic::setVelocity() + * @pre Dynamic::setTorque() + * @post Dynamic::getPosition() + * @post Dynamic::getVelocity() + * @post Dynamic::getAcceleration() + * + * @see Dynamic::forwardDynamics() + */ + class EulerCauchyIntegrator : public Integrator + { + public: + EulerCauchyIntegrator(Dynamic* dynamic); + + virtual ~EulerCauchyIntegrator(); + + void integrate(const ::rl::math::Real& dt); + + protected: + + private: + + }; + } +} + +#endif // RL_MDL_EULERCAUCHYINTEGRATOR_H diff --git a/src/rl/mdl/Integrator.cpp b/src/rl/mdl/Integrator.cpp new file mode 100644 index 00000000..2b6d4454 --- /dev/null +++ b/src/rl/mdl/Integrator.cpp @@ -0,0 +1,16 @@ +#include "Integrator.h" + +namespace rl +{ + namespace mdl + { + Integrator::Integrator(Dynamic* dynamic) : + dynamic(dynamic) + { + } + + Integrator::~Integrator() + { + } + } +} diff --git a/src/rl/mdl/Integrator.h b/src/rl/mdl/Integrator.h new file mode 100644 index 00000000..aa85938d --- /dev/null +++ b/src/rl/mdl/Integrator.h @@ -0,0 +1,33 @@ +#ifndef RL_MDL_INTEGRATOR_H +#define RL_MDL_INTEGRATOR_H + +#include + +namespace rl +{ + namespace mdl + { + class Dynamic; + + class Integrator + { + public: + Integrator(Dynamic* dynamic); + + virtual ~Integrator(); + + /** + * @param[in] dt Integration time step \f$\Delta t\f$ + */ + virtual void integrate(const ::rl::math::Real& dt) = 0; + + protected: + Dynamic* dynamic; + + private: + + }; + } +} + +#endif // RL_MDL_INTEGRATOR_H diff --git a/src/rl/mdl/RungeKuttaNystromIntegrator.cpp b/src/rl/mdl/RungeKuttaNystromIntegrator.cpp new file mode 100644 index 00000000..fa165848 --- /dev/null +++ b/src/rl/mdl/RungeKuttaNystromIntegrator.cpp @@ -0,0 +1,73 @@ +#include "Dynamic.h" +#include "RungeKuttaNystromIntegrator.h" + +namespace rl +{ + namespace mdl + { + RungeKuttaNystromIntegrator::RungeKuttaNystromIntegrator(Dynamic* dynamic) : + Integrator(dynamic) + { + } + + RungeKuttaNystromIntegrator::~RungeKuttaNystromIntegrator() + { + } + + void + RungeKuttaNystromIntegrator::integrate(const ::rl::math::Real& dt) + { + ::rl::math::Vector y0 = this->dynamic->getPosition(); + ::rl::math::Vector dy0 = this->dynamic->getVelocity(); + + this->dynamic->forwardDynamics(); + + ::rl::math::Vector f = this->dynamic->getAcceleration(); + + // k1 = dt / 2 * f + ::rl::math::Vector k1 = dt / 2 * f; + + // y_0 + dt / 2 * dy_0 + dt / 4 * k_1 + ::rl::math::Vector y = y0 + dt / 2 * dy0 + dt / 4 * k1; + // dy_0 + k1 + ::rl::math::Vector dy = dy0 + k1; + + this->dynamic->setPosition(y); + this->dynamic->setVelocity(dy); + this->dynamic->forwardDynamics(); + + // k2 = dt / 2 * f + ::rl::math::Vector k2 = dt / 2 * this->dynamic->getAcceleration(); + + // dy_0 + k_2 + dy = dy0 + k2; + + this->dynamic->setVelocity(dy); + this->dynamic->forwardDynamics(); + + // k3 = dt / 2 * f + ::rl::math::Vector k3 = dt / 2 * this->dynamic->getAcceleration(); + + // y_0 + dt * dy_0 + dt * k_3 + y = y0 + dt * dy0 + dt * k3; + // dy_0 + 2 * k_3 + dy = dy0 + 2 * k3; + + this->dynamic->setPosition(y); + this->dynamic->setVelocity(dy); + this->dynamic->forwardDynamics(); + + // k4 = dt / 2 * f + ::rl::math::Vector k4 = dt / 2 * this->dynamic->getAcceleration(); + + // y_0 + dy_0 * dt + dt / 3 * (k_1 + k_2 + k_3) + y = y0 + dy0 * dt + dt / 3 * (k1 + k2 + k3); + // dy_0 + 1 / 3 * (k_1 + 2 * k_2 + 2 * k_3 + k_4) + dy = dy0 + 1.0f / 3.0f * (k1 + 2 * k2 + 2 * k3 + k4); + + this->dynamic->setPosition(y); + this->dynamic->setVelocity(dy); + this->dynamic->setAcceleration(f); + } + } +} diff --git a/src/rl/mdl/RungeKuttaNystromIntegrator.h b/src/rl/mdl/RungeKuttaNystromIntegrator.h new file mode 100644 index 00000000..9d3f5ac1 --- /dev/null +++ b/src/rl/mdl/RungeKuttaNystromIntegrator.h @@ -0,0 +1,48 @@ +#ifndef RL_MDL_RUNGEKUTTANYSTROMINTEGRATOR_H +#define RL_MDL_RUNGEKUTTANYSTROMINTEGRATOR_H + +#include "Integrator.h" + +namespace rl +{ + namespace mdl + { + /** + * Integration via Runge-Kutta-Nyström. + * + * \f[ \vec{q}_{i + 1} = \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} + \frac{\Delta t}{3} (\vec{k}_{1} + \vec{k}_{2} + \vec{k}_{3}) \f] + * \f[ \dot{\vec{q}}_{i + 1} = \dot{\vec{q}}_{i} + \frac{1}{3} (\vec{k}_{1} + 2 \vec{k}_{2} + 2 \vec{k}_{3} + \vec{k}_{4}) \f] + * \f[ \ddot{\vec{q}} = f(t, \vec{q}, \dot{\vec{q}}) \f] + * \f[ t_{i + 1} = t_{i} + \Delta t \f] + * \f[ \vec{k}_{1} = \frac{\Delta t}{2} \, f(t_{i}, \vec{q}_{i}, \dot{\vec{q}}_{i}) \f] + * \f[ \vec{k}_{2} = \frac{\Delta t}{2} \, f(t_{i} + \frac{\Delta t}{2}, \vec{q}_{i} + \frac{\Delta t}{2} \, \dot{\vec{q}}_{i} + \frac{\Delta t}{4} \, \vec{k}_{1}, \dot{\vec{q}}_{i} + \vec{k}_{1}) \f] + * \f[ \vec{k}_{3} = \frac{\Delta t}{2} \, f(t_{i} + \frac{\Delta t}{2}, \vec{q}_{i} + \frac{\Delta t}{2} \, \dot{\vec{q}}_{i} + \frac{\Delta t}{4} \, \vec{k}_{1}, \dot{\vec{q}}_{i} + \vec{k}_{2}) \f] + * \f[ \vec{k}_{4} = \frac{\Delta t}{2} \, f(t_{i} + \Delta t, \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} + \Delta t \, \vec{k}_{3}, \dot{\vec{q}}_{i} + 2 \vec{k}_{3}) \f] + * + * @pre Dynamic::setPosition() + * @pre Dynamic::setVelocity() + * @pre Dynamic::setTorque() + * @post Dynamic::getPosition() + * @post Dynamic::getVelocity() + * @post Dynamic::getAcceleration() + * + * @see Dynamic::forwardDynamics() + */ + class RungeKuttaNystromIntegrator : public Integrator + { + public: + RungeKuttaNystromIntegrator(Dynamic* dynamic); + + virtual ~RungeKuttaNystromIntegrator(); + + void integrate(const ::rl::math::Real& dt); + + protected: + + private: + + }; + } +} + +#endif // RL_MDL_RUNGEKUTTANYSTROMINTEGRATOR_H From 6345fb7c3cafce58e7c298cbfa9ed2a6682f3668 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 13 May 2018 01:41:07 +0200 Subject: [PATCH 112/546] Add cubic spline interpolation --- .../rlInterpolatorDemo/rlInterpolatorDemo.cpp | 15 ++ src/rl/math/Spline.h | 136 +++++++++++++++++- .../rlSplineTest/rlPolynomialExtremaTest.cpp | 51 ++++++- tests/rlSplineTest/rlSplineTest.cpp | 28 ++++ 4 files changed, 228 insertions(+), 2 deletions(-) diff --git a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp index bc71a808..c5b6ab45 100644 --- a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp +++ b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp @@ -187,6 +187,10 @@ main(int argc, char** argv) y.push_back(3); y.push_back(3); y.push_back(-2); + rl::math::Spline f0 = rl::math::Spline::CubicFirst(x, y, 0, 0); + eval(f0); + rl::math::Spline f1 = rl::math::Spline::CubicNatural(x, y); + eval(f1); rl::math::Spline f2 = rl::math::Spline::LinearParabolic(x, y, 0.25f); eval(f2); rl::math::Spline f3 = rl::math::Spline::LinearQuartic(x, y, 0.25f); @@ -210,6 +214,17 @@ main(int argc, char** argv) y.push_back(rl::math::ArrayX::Constant(1, 3)); y.push_back(rl::math::ArrayX::Constant(1, 3)); y.push_back(rl::math::ArrayX::Constant(1, -2)); + rl::math::Spline f0 = rl::math::Spline::CubicFirst( + x, + y, + rl::math::ArrayX::Constant(1, 0), + rl::math::ArrayX::Constant(1, 0) + ); + eval(f0); + rl::math::Spline f1 = rl::math::Spline::CubicNatural(x, y); + eval(f1); + rl::math::Spline f2 = rl::math::Spline::LinearParabolic(x, y, 0.25f); + eval(f2); rl::math::Spline f3 = rl::math::Spline::LinearQuartic(x, y, 0.25f); eval(f3); rl::math::Spline f4 = rl::math::Spline::LinearSextic(x, y, 0.25f); diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 00934b44..542fa2d0 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -72,6 +72,140 @@ namespace rl { } + /** + * Generates a cubic spline that interpolates the supporting points + * y with start and end tangents yd0 and yd1. + * + * http://banach.millersville.edu/~bob/math375/CubicSpline/main.pdf + */ + template + static Spline CubicFirst(const Container1& x, const Container2& y, const T& yd0, const T& yd1) + { + assert(x.size() > 1); + assert(x.size() == y.size()); + assert(TypeTraits::size(y[0]) == TypeTraits::size(yd0)); + assert(TypeTraits::size(y[0]) == TypeTraits::size(yd1)); + + ::std::size_t n = y.size(); + ::std::size_t dim = TypeTraits::size(y[0]); + + const Container2& a = y; + Container1 h(n - 1); + + for (::std::size_t i = 0; i < n - 1; ++i) + { + h[i] = x[i + 1] - x[i]; + } + + Container1 mu(n - 1); + Container2 z(n); + + T alpha0 = 3 / h[0] * (a[1] - a[0]) - 3 * yd0; + Container1::value_type l0 = 2 * h[0]; + mu[0] = 0.5; + z[0] = alpha0 / l0; + + for (::std::size_t i = 1; i < n - 1; ++i) + { + T alpha = 3 / h[i] * (a[i + 1] - a[i]) - 3 / h[i - 1] * (a[i] - a[i - 1]); + Container1::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; + mu[i] = h[i] / l; + z[i] = (alpha - h[i - 1] * z[i - 1]) / l; + } + + T alpha1 = 3 * yd1 - 3 / h[n - 2] * (a[n - 1] - a[n - 2]); + Container1::value_type l1 = h[n - 2] * (2 - mu[n - 2]); + z[n - 1] = (alpha1 - h[n - 2] * z[n - 2]) / l1; + + Container2 c(n); + + c[n - 1] = z[n - 1]; + + for (::std::size_t i = n - 1; i-- > 0;) + { + c[i] = z[i] - mu[i] * c[i + 1]; + } + + Spline f; + + for (::std::size_t i = 0; i < n - 1; ++i) + { + Polynomial fi(3); + fi.coefficient(0) = a[i]; + fi.coefficient(1) = (a[i + 1] - a[i]) / h[i] - (h[i] * (c[i + 1] + 2 * c[i])) / 3; + fi.coefficient(2) = c[i]; + fi.coefficient(3) = (c[i + 1] - c[i]) / (3 * h[i]); + fi.upper() = h[i]; + f.push_back(fi); + } + + return f; + } + + /** + * Generates a cubic spline that interpolates the supporting points + * y, with a natural curvature of zero at the endpoints. + * + * http://banach.millersville.edu/~bob/math375/CubicSpline/main.pdf + */ + template + static Spline CubicNatural(const Container1& x, const Container2& y) + { + assert(x.size() > 1); + assert(x.size() == y.size()); + + ::std::size_t n = y.size(); + ::std::size_t dim = TypeTraits::size(y[0]); + + const Container2& a = y; + Container1 h(n - 1); + + for (::std::size_t i = 0; i < n - 1; ++i) + { + h[i] = x[i + 1] - x[i]; + } + + Container1 mu(n - 1); + Container2 z(n); + + mu[0] = 0; + z[0] = TypeTraits::Zero(dim); + + for (::std::size_t i = 1; i < n - 1; ++i) + { + T alpha = 3 / h[i] * (a[i + 1] - a[i]) - 3 / h[i - 1] * (a[i] - a[i - 1]); + Container1::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; + mu[i] = h[i] / l; + z[i] = (alpha - h[i - 1] * z[i - 1]) / l; + } + + z[n - 1] = TypeTraits::Zero(dim); + + Container2 c(n); + + c[n - 1] = TypeTraits::Zero(dim); + + for (::std::size_t i = n - 1; i-- > 0;) + { + c[i] = z[i] - mu[i] * c[i + 1]; + } + + Spline f; + + for (::std::size_t i = 0; i < n - 1; ++i) + { + Polynomial fi(3); + fi.coefficient(0) = a[i]; + fi.coefficient(1) = (a[i + 1] - a[i]) / h[i] - (h[i] * (c[i + 1] + 2 * c[i])) / 3; + fi.coefficient(2) = c[i]; + fi.coefficient(3) = (c[i + 1] - c[i]) / (3 * h[i]); + fi.upper() = h[i]; + f.push_back(fi); + } + + return f; + } + /** * Generates a piecewise spline with parabolic segments around the * given supporting points y and linear segments in between. @@ -551,7 +685,7 @@ namespace rl * A trapezoidal acceleration trajectory has up to seven segments of * constant jerk. Its velocity curve is double-S shaped. * - * see L. Biagiotti, C. Melchiorri (2008) "Trajectory Planning for Automatic + * L. Biagiotti, C. Melchiorri (2008) "Trajectory Planning for Automatic * Machines and Robots", pp. 90ff. */ static Spline TrapeziodalAccelerationAtRest(const T& q0, const T& q1, const T& vmax, const T& amax, const T& jmax) diff --git a/tests/rlSplineTest/rlPolynomialExtremaTest.cpp b/tests/rlSplineTest/rlPolynomialExtremaTest.cpp index bb9807c0..c927fb71 100644 --- a/tests/rlSplineTest/rlPolynomialExtremaTest.cpp +++ b/tests/rlSplineTest/rlPolynomialExtremaTest.cpp @@ -26,7 +26,7 @@ #include #include -#include +#include int main(int argc, char** argv) @@ -58,6 +58,55 @@ main(int argc, char** argv) } } + { + rl::math::Real factor = 1.23; + rl::math::Real eps = 1e-8; + + rl::math::ArrayX x(6); + x << 0, 1, 2, 3.5, 6, 7; + std::vector y(6, rl::math::ArrayX(2)); + y[0] << 0, 3; + y[1] << 1, 2; + y[2] << 2, -1; + y[3] << 3, 3; + y[4] << 3, 7; + y[5] << -2, -2; + + rl::math::Spline original = rl::math::Spline::CubicNatural(x, y); + rl::math::Spline scaled = original.scaledX(factor); + + // original and scaled spline segments should have the same maxima + + for (std::size_t i = 0; i < original.size(); ++i) + { + rl::math::ArrayX maxSpeedOriginal = original.at(i).derivative().getAbsoluteMaximum(); + rl::math::ArrayX maxSpeedScaled = scaled.at(i).derivative().getAbsoluteMaximum(); + + if ((maxSpeedOriginal - factor * maxSpeedScaled).matrix().norm() > eps) + { + std::cerr << "rlPolynomialExtremaTest: (maxSpeedOriginal - factor * maxSpeedScaled).norm() > eps" << std::endl; + return EXIT_FAILURE; + } + + rl::math::ArrayX maxAccOriginal = original.at(i).derivative().derivative().getAbsoluteMaximum(); + rl::math::ArrayX maxAccScaled = scaled.at(i).derivative().derivative().getAbsoluteMaximum(); + + if ((maxAccOriginal - factor * factor * maxAccScaled).matrix().norm() > eps) + { + std::cerr << "rlPolynomialExtremaTest: (maxAccOriginal - factor * factor * maxAccScaled).matrix().norm() > eps" << std::endl; + return EXIT_FAILURE; + } + +#if 0 + std::cout << "maxSpeedOriginal: " << maxSpeedOriginal.transpose() << std::endl; + std::cout << "maxSpeedScaled: " << maxSpeedScaled.transpose() << std::endl; + std::cout << "maxAccOriginal: " << maxAccOriginal.transpose() << std::endl; + std::cout << "maxAccScaled: " << maxAccScaled.transpose() << std::endl; +#endif + } + + } + std::cout << "rlPolynomialExtremaTest: Polynomial::getAbsoluteMaximum() is ok." << std::endl; return EXIT_SUCCESS; diff --git a/tests/rlSplineTest/rlSplineTest.cpp b/tests/rlSplineTest/rlSplineTest.cpp index 00653304..aaa27966 100644 --- a/tests/rlSplineTest/rlSplineTest.cpp +++ b/tests/rlSplineTest/rlSplineTest.cpp @@ -53,10 +53,24 @@ main(int argc, char** argv) y.push_back(-2); rl::math::Real yd0 = 0; rl::math::Real yd1 = 0; + rl::math::Spline s1 = rl::math::Spline::CubicFirst(x, y, yd0, yd1); + rl::math::Spline s2 = rl::math::Spline::CubicNatural(x, y); rl::math::Spline s3 = rl::math::Spline::LinearParabolic(x, y, 0.25); rl::math::Spline s4 = rl::math::Spline::LinearQuartic(x, y, 0.25); rl::math::Spline s5 = rl::math::Spline::LinearSextic(x, y, 0.25); + if (!s1.isContinuous(1)) + { + std::cerr << "CubicFirst should be 1-continuous." << std::endl; + return EXIT_FAILURE; + } + + if (!s2.isContinuous(1)) + { + std::cerr << "CubicNatural should be 1-continuous." << std::endl; + return EXIT_FAILURE; + } + if (!s3.isContinuous(1)) { std::cerr << "LinearParabolic should be 1-continuous." << std::endl; @@ -96,10 +110,24 @@ main(int argc, char** argv) yd0 << 0, 2; rl::math::ArrayX yd1(2); yd1 << 0, 3; + rl::math::Spline s1 = rl::math::Spline::CubicFirst(x, y, yd0, yd1); + rl::math::Spline s2 = rl::math::Spline::CubicNatural(x, y); rl::math::Spline s3 = rl::math::Spline::LinearParabolic(x, y, 0.25); rl::math::Spline s4 = rl::math::Spline::LinearQuartic(x, y, 0.25); rl::math::Spline s5 = rl::math::Spline::LinearSextic(x, y, 0.25); + if (!s1.isContinuous(1)) + { + std::cerr << "CubicFirst should be 1-continuous." << std::endl; + return EXIT_FAILURE; + } + + if (!s2.isContinuous(1)) + { + std::cerr << "CubicNatural should be 1-continuous." << std::endl; + return EXIT_FAILURE; + } + if (!s3.isContinuous(1)) { std::cerr << "LinearParabolic should be 1-continuous." << std::endl; From d301873c4bcce810b84f913d1803e4beb307160d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 13 May 2018 01:41:24 +0200 Subject: [PATCH 113/546] Correct spline test names --- tests/rlSplineTest/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/tests/rlSplineTest/CMakeLists.txt b/tests/rlSplineTest/CMakeLists.txt index d5a10283..f7269332 100644 --- a/tests/rlSplineTest/CMakeLists.txt +++ b/tests/rlSplineTest/CMakeLists.txt @@ -54,7 +54,7 @@ target_link_libraries( ) add_test( - rlSplineTestConstructCubicAndLinearQuartic + rlSplineTest ${CMAKE_CURRENT_BINARY_DIR}/rlSplineTest ) @@ -84,7 +84,7 @@ target_link_libraries( ) add_test( - rlSplineScaleTestLinearQuartic + rlSplineScaleTest ${CMAKE_CURRENT_BINARY_DIR}/rlSplineScaleTest ) From d2b5e78049cb59036679f7d88d4de4a044a9e9e5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 13 May 2018 01:50:02 +0200 Subject: [PATCH 114/546] Add missing typename keyword --- src/rl/math/Spline.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 542fa2d0..a940624a 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -101,20 +101,20 @@ namespace rl Container2 z(n); T alpha0 = 3 / h[0] * (a[1] - a[0]) - 3 * yd0; - Container1::value_type l0 = 2 * h[0]; + typename Container1::value_type l0 = 2 * h[0]; mu[0] = 0.5; z[0] = alpha0 / l0; for (::std::size_t i = 1; i < n - 1; ++i) { T alpha = 3 / h[i] * (a[i + 1] - a[i]) - 3 / h[i - 1] * (a[i] - a[i - 1]); - Container1::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; + typename Container1::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; mu[i] = h[i] / l; z[i] = (alpha - h[i - 1] * z[i - 1]) / l; } T alpha1 = 3 * yd1 - 3 / h[n - 2] * (a[n - 1] - a[n - 2]); - Container1::value_type l1 = h[n - 2] * (2 - mu[n - 2]); + typename Container1::value_type l1 = h[n - 2] * (2 - mu[n - 2]); z[n - 1] = (alpha1 - h[n - 2] * z[n - 2]) / l1; Container2 c(n); @@ -174,7 +174,7 @@ namespace rl for (::std::size_t i = 1; i < n - 1; ++i) { T alpha = 3 / h[i] * (a[i + 1] - a[i]) - 3 / h[i - 1] * (a[i] - a[i - 1]); - Container1::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; + typename Container1::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; mu[i] = h[i] / l; z[i] = (alpha - h[i - 1] * z[i - 1]) / l; } From 5aa524ce3a4ed42cc90b067e243bc0cdd3e3559b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 13 May 2018 02:02:53 +0200 Subject: [PATCH 115/546] Optimize cubic spline interpolation memory usage --- src/rl/math/Spline.h | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index a940624a..c94f02d4 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -117,9 +117,7 @@ namespace rl typename Container1::value_type l1 = h[n - 2] * (2 - mu[n - 2]); z[n - 1] = (alpha1 - h[n - 2] * z[n - 2]) / l1; - Container2 c(n); - - c[n - 1] = z[n - 1]; + Container2& c = z; for (::std::size_t i = n - 1; i-- > 0;) { @@ -181,9 +179,7 @@ namespace rl z[n - 1] = TypeTraits::Zero(dim); - Container2 c(n); - - c[n - 1] = TypeTraits::Zero(dim); + Container2& c = z; for (::std::size_t i = n - 1; i-- > 0;) { From c254e72411de0589d48d99a03818c97a81bf4fad Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 13 May 2018 17:41:50 +0200 Subject: [PATCH 116/546] Specialize TypeTraits for float/double, add value_type, and provide implementation for generic containers --- src/rl/math/TypeTraits.h | 149 +++++++++++++++++++++++++++++++++++++-- 1 file changed, 142 insertions(+), 7 deletions(-) diff --git a/src/rl/math/TypeTraits.h b/src/rl/math/TypeTraits.h index ec2e848a..7114545c 100644 --- a/src/rl/math/TypeTraits.h +++ b/src/rl/math/TypeTraits.h @@ -31,6 +31,8 @@ #define EIGEN_QUATERNIONBASE_PLUGIN #define EIGEN_TRANSFORM_PLUGIN +#include +#include #include #include @@ -42,37 +44,166 @@ namespace rl class TypeTraits { public: + typedef typename T::value_type value_type; + static T Constant(const ::std::size_t& i, const T& value) { - return value; + return T(i, value); } static T Zero(const ::std::size_t& i) { - return 0; + return T(i, 0); } static T abs(const T& t) { - return ::std::abs(t); + using ::std::abs; + using ::std::size; + using ::std::transform; + T res(size(t)); + transform(t.begin(), t.end(), res.begin(), static_cast(&abs)); + return res; } - static bool equal(const T& lhs, const T& rhs, const T& epsilon = ::Eigen::NumTraits::dummy_precision()) + static bool equal(const T& lhs, const T& rhs, const value_type& epsilon = ::Eigen::NumTraits::dummy_precision()) { - return ::std::abs(lhs - rhs) < epsilon; + using ::std::abs; + using ::std::begin; + using ::std::end; + using ::std::min; + + auto first1 = begin(lhs); + auto last1 = end(lhs); + auto first2 = begin(rhs); + + value_type norm = value_type(); + value_type norm1 = value_type(); + value_type norm2 = value_type(); + + while (first1 != last1) + { + value_type tmp = abs(*first1 - *first2); + norm += tmp * tmp; + value_type tmp1 = abs(*first1); + norm1 += tmp1 * tmp1; + value_type tmp2 = abs(*first2); + norm2 += tmp2 * tmp2; + ++first1; + ++first2; + } + + return norm <= epsilon * epsilon * min(norm1, norm2); } static T max_element(const T& t) { - return t; + using ::std::max_element; + return max_element(t.begin(), t.end()); } static T min_element(const T& t) { - return t; + using ::std::min_element; + return min_element(t.begin(), t.end()); } static ::std::size_t size(const T& t) + { + using ::std::size; + return size(t); + } + + protected: + + private: + + }; + + template<> + class TypeTraits + { + public: + typedef float value_type; + + static float Constant(const ::std::size_t& i, const float& value) + { + return value; + } + + static float Zero(const ::std::size_t& i) + { + return 0; + } + + static float abs(const float& t) + { + return ::std::abs(t); + } + + static bool equal(const float& lhs, const float& rhs, const float& epsilon = ::Eigen::NumTraits::dummy_precision()) + { + return ::Eigen::internal::isApprox(lhs, rhs, epsilon); + } + + static float max_element(const float& t) + { + return t; + } + + static float min_element(const float& t) + { + return t; + } + + static ::std::size_t size(const float& t) + { + return 1; + } + + protected: + + private: + + }; + + template<> + class TypeTraits + { + public: + typedef double value_type; + + static double Constant(const ::std::size_t& i, const double& value) + { + return value; + } + + static double Zero(const ::std::size_t& i) + { + return 0; + } + + static double abs(const double& t) + { + return ::std::abs(t); + } + + static bool equal(const double& lhs, const double& rhs, const double& epsilon = ::Eigen::NumTraits::dummy_precision()) + { + return ::Eigen::internal::isApprox(lhs, rhs, epsilon); + } + + static double max_element(const double& t) + { + return t; + } + + static double min_element(const double& t) + { + return t; + } + + static ::std::size_t size(const double& t) { return 1; } @@ -87,6 +218,8 @@ namespace rl class TypeTraits< ::Eigen::Array> { public: + typedef Scalar value_type; + static ::Eigen::Array Constant(const ::std::size_t& i, const Scalar& value) { return ::Eigen::Array::Constant(i, value); @@ -132,6 +265,8 @@ namespace rl class TypeTraits< ::Eigen::Matrix> { public: + typedef Scalar value_type; + static ::Eigen::Matrix Constant(const ::std::size_t& i, const Scalar& value) { return ::Eigen::Matrix::Constant(i, value); From dae0295942f7d2d52102893da141defeb8ba1437 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 13 May 2018 17:43:10 +0200 Subject: [PATCH 117/546] Use TypeTraits::value_type in Spline --- src/rl/math/Spline.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index c94f02d4..eb5ac8f9 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -101,20 +101,20 @@ namespace rl Container2 z(n); T alpha0 = 3 / h[0] * (a[1] - a[0]) - 3 * yd0; - typename Container1::value_type l0 = 2 * h[0]; + typename TypeTraits::value_type l0 = 2 * h[0]; mu[0] = 0.5; z[0] = alpha0 / l0; for (::std::size_t i = 1; i < n - 1; ++i) { T alpha = 3 / h[i] * (a[i + 1] - a[i]) - 3 / h[i - 1] * (a[i] - a[i - 1]); - typename Container1::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; + typename TypeTraits::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; mu[i] = h[i] / l; z[i] = (alpha - h[i - 1] * z[i - 1]) / l; } T alpha1 = 3 * yd1 - 3 / h[n - 2] * (a[n - 1] - a[n - 2]); - typename Container1::value_type l1 = h[n - 2] * (2 - mu[n - 2]); + typename TypeTraits::value_type l1 = h[n - 2] * (2 - mu[n - 2]); z[n - 1] = (alpha1 - h[n - 2] * z[n - 2]) / l1; Container2& c = z; @@ -172,7 +172,7 @@ namespace rl for (::std::size_t i = 1; i < n - 1; ++i) { T alpha = 3 / h[i] * (a[i + 1] - a[i]) - 3 / h[i - 1] * (a[i] - a[i - 1]); - typename Container1::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; + typename TypeTraits::value_type l = 2 * (x[i + 1] - x[i - 1]) - h[i - 1] * mu[i - 1]; mu[i] = h[i] / l; z[i] = (alpha - h[i - 1] * z[i - 1]) / l; } From 3f27cf4e4143b1e753c5f1a22f80b994dce713e6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 13 May 2018 17:43:26 +0200 Subject: [PATCH 118/546] Update Polynomial and Spline documentation --- src/rl/math/Polynomial.h | 5 ++- src/rl/math/Spline.h | 76 ++++++++++++++++++++++++++++++++++------ 2 files changed, 68 insertions(+), 13 deletions(-) diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index 734a4787..d9286815 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -51,10 +51,9 @@ namespace rl namespace math { /** - * A vector-valued polynomial function from Real -> T. + * A polynomial function. * - * A Polynomial is indefinitely often differentiable and can be evaluated - * efficiently. + * \f[ f(x) = c_0 + c_1 x + c_2 x^2 + \ldots + c_{n - 1} x^{n - 1} + c_n x^n \f] */ template class Polynomial : public Function diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index eb5ac8f9..1c0ceff4 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -38,13 +38,10 @@ namespace rl namespace math { /** - * A piecewise Function of Polynomial functions. + * A piecewise polynomial function. * - * A Spline is a function that consists of a list of polynomials, which - * may have different degrees. It is indefinitely often differentiable, - * and can be scaled algebraically. As all children of Function, its is - * mapping Real -> T, but a Spline is only defined in the interval - * [lower() upper()]. + * A Spline is a function consisting of a list of polynomials, which + * may have different degrees. * * @see Polynomial */ @@ -73,10 +70,41 @@ namespace rl } /** - * Generates a cubic spline that interpolates the supporting points - * y with start and end tangents yd0 and yd1. + * Generates a cubic spline that interpolates a set of data points + * with known first derivatives at the endpoints. + * + * A cubic spline interpolant \f$S\f$ for a function \f$f\f$ with a + * set of nodes \f$x_0 < x_1 < \cdots < x_n\f$ is a piecewise cubic polynomial + * \f$S_i\f$ on \f$[x_i, x_{i + 1}]\f$ for \f$i = 0, \ldots, n - 1\f$ + * and \f$x_i \leq x \leq x_{i + 1}\f$ with + * \f{align*}{ + * S_i(x) &= a_i + b_i (x - x_i) + c_i (x - x_i)^2 + d_i (x - x_i)^3 \, , \\ + * S_i'(x) &= b_i + 2 c_i (x - x_i) + 3 d_i (x - x_i)^2 \, , \\ + * S_i''(x) &= 2 c_i + 6 d_i (x - x_i) \, . + * \f} + * + * The spline matches the nodes and is continuous in the first and second + * derivatives as defined by the properties + * \f{align*}{ + * S(x_i) &= f(x_i) \, , \\ + * S_i(x_{i + 1}) &= S_{i + 1}(x_{i + 1}) \, , \\ + * S'_i(x_{i + 1}) &= S'_{i + 1}(x_{i + 1}) \, , \\ + * S''_i(x_{i + 1}) &= S''_{i + 1}(x_{i + 1}) \, . + * \f} + * + * In this variant, the boundary conditions are defined by the first + * derivatives + * \f{align*}{ + * S'(x_0) = f'(x_0) \, , \\ + * S'(x_n) = f'(x_n) \, . + * \f} * * http://banach.millersville.edu/~bob/math375/CubicSpline/main.pdf + * + * @param[in] x \f$x_0, \ldots, x_n\f$ + * @param[in] y \f$f(x_0), \ldots, f_(x_n)\f$ + * @param[in] yd0 \f$f'(x_0)\f$ + * @param[in] yd1 \f$f'(x_n)\f$ */ template static Spline CubicFirst(const Container1& x, const Container2& y, const T& yd0, const T& yd1) @@ -141,10 +169,38 @@ namespace rl } /** - * Generates a cubic spline that interpolates the supporting points - * y, with a natural curvature of zero at the endpoints. + * Generates a cubic spline that interpolates a set of data points + * with second derivatives at the endpoints set to zero. + * + * A cubic spline interpolant \f$S\f$ for a function \f$f\f$ with a + * set of nodes \f$x_0 < x_1 < \cdots < x_n\f$ is a piecewise cubic polynomial + * \f$S_i\f$ on \f$[x_i, x_{i + 1}]\f$ for \f$i = 0, \ldots, n - 1\f$ + * and \f$x_i \leq x \leq x_{i + 1}\f$ with + * \f{align*}{ + * S_i(x) &= a_i + b_i (x - x_i) + c_i (x - x_i)^2 + d_i (x - x_i)^3 \, , \\ + * S_i'(x) &= b_i + 2 c_i (x - x_i) + 3 d_i (x - x_i)^2 \, , \\ + * S_i''(x) &= 2 c_i + 6 d_i (x - x_i) \, . + * \f} + * + * The spline matches the nodes and is continuous in the first and second + * derivatives as defined by the properties + * \f{align*}{ + * S(x_i) &= f(x_i) \, , \\ + * S_i(x_{i + 1}) &= S_{i + 1}(x_{i + 1}) \, , \\ + * S'_i(x_{i + 1}) &= S'_{i + 1}(x_{i + 1}) \, , \\ + * S''_i(x_{i + 1}) &= S''_{i + 1}(x_{i + 1}) \, . + * \f} + * + * In this variant, the boundary conditions are defined by the second + * derivatives + * \f{align*}{ + * S''(x_0) = S''(x_n) = 0 \, . + * \f} * * http://banach.millersville.edu/~bob/math375/CubicSpline/main.pdf + * + * @param[in] x \f$x_0, \ldots, x_n\f$ + * @param[in] y \f$f(x_0), \ldots, f_(x_n)\f$ */ template static Spline CubicNatural(const Container1& x, const Container2& y) From cd1ed5713dcc4997782aa7a27946b8b07df33883 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 25 May 2018 13:25:21 +0200 Subject: [PATCH 119/546] Use step, distance, and interpolate in Jacobian IK --- src/rl/mdl/JacobianInverseKinematics.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index 30cf5e20..f37a8cd4 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -29,6 +29,7 @@ namespace rl double remaining = ::std::chrono::duration(this->duration).count(); ::rl::math::Vector q = this->kinematic->getPosition(); + ::rl::math::Vector q2(this->kinematic->getDofPosition()); ::rl::math::Vector dq(this->kinematic->getDofPosition()); ::rl::math::Vector dx(6 * this->kinematic->getOperationalDof()); @@ -36,9 +37,9 @@ namespace rl do { - ::rl::math::Real norm = 1; + ::rl::math::Real delta = 1; - for (::std::size_t i = 0; i < this->iterations && norm > this->epsilon; ++i) + for (::std::size_t i = 0; i < this->iterations && delta > this->epsilon; ++i) { this->kinematic->forwardPosition(); dx.setZero(); @@ -62,16 +63,15 @@ namespace rl dq = this->kinematic->getJacobianInverse() * dx; } - norm = dq.norm(); + this->kinematic->step(q, dq, q2); + delta = this->kinematic->distance(q, q2); - if (norm > this->delta) + if (delta > this->delta) { - dq *= this->delta / norm; - norm = dq.norm(); + this->kinematic->interpolate(q, q2, this->delta, q2); } - q += dq; - + q = q2; this->kinematic->setPosition(q); } From a5579b93a7c2259be60fd141ed48b16b617a31c2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 30 May 2018 17:14:39 +0200 Subject: [PATCH 120/546] Fix S matrix for 6-DOF joint --- src/rl/mdl/SixDof.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index d51e4738..7b4e2ee3 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -57,7 +57,10 @@ namespace rl this->qddUnits(3) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; this->qddUnits(4) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; this->qddUnits(5) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; - this->S.setIdentity(); + this->S.topLeftCorner<3, 3>().setZero(); + this->S.topRightCorner<3, 3>().setIdentity(); + this->S.bottomLeftCorner<3, 3>().setIdentity(); + this->S.bottomRightCorner<3, 3>().setZero(); this->speedUnits(0) = ::rl::math::UNIT_METER_PER_SECOND; this->speedUnits(1) = ::rl::math::UNIT_METER_PER_SECOND; this->speedUnits(2) = ::rl::math::UNIT_METER_PER_SECOND; From 58536860950f19806753f5f3b9381aa0a88a87c4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 31 May 2018 19:00:02 +0200 Subject: [PATCH 121/546] Check for zero quaternion in Joint::normalize() --- src/rl/mdl/SixDof.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index 7b4e2ee3..fea24d48 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -145,7 +145,16 @@ namespace rl void SixDof::normalize(::rl::math::VectorRef q) const { - ::Eigen::Map< ::rl::math::Quaternion>(q.tail<4>().data()).normalize(); + ::Eigen::Map< ::rl::math::Quaternion> quaternion(q.tail<4>().data()); + + if (quaternion.squaredNorm() > 0) + { + quaternion.normalize(); + } + else + { + quaternion.setIdentity(); + } } void From 4af433b74a903a5722271fb51b7cdd5940653a1c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 31 May 2018 19:00:24 +0200 Subject: [PATCH 122/546] Minor fix --- src/rl/mdl/SixDof.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index fea24d48..e75909fe 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -101,8 +101,7 @@ namespace rl { for (::std::size_t i = 0; i < 3; ++i) { - q(i) = mean(i) + rand(i) * sigma(i); - q(i) = ::rl::math::clamp(q(i), this->min(i), this->max(i)); + q(i) = ::rl::math::clamp(mean(i) + rand(i) * sigma(i), this->min(i), this->max(i)); } q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>(), ::Eigen::Map< const ::rl::math::Quaternion>(mean.tail<4>().data()), sigma.tail<3>()).coeffs(); From 4c00a016d896ccd28ae5be62f0ad98682a5cdf99 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 31 May 2018 20:53:30 +0200 Subject: [PATCH 123/546] Fix step function for SixDof joints --- src/rl/mdl/SixDof.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index e75909fe..d4755270 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -167,15 +167,14 @@ namespace rl void SixDof::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const { - q2.head<3>() = q1.head<3>() + qdot.head<3>(); + ::Eigen::Map quaternion1(q1.tail<4>().data()); + q2.head<3>() = q1.head<3>() + quaternion1._transformVector(::Eigen::Map(qdot.head<3>().data())); + q2.tail<4>() = (quaternion1 * ::rl::math::AngleAxis(qdot.tail<3>().norm(), qdot.tail<3>().normalized())).coeffs(); for (::std::size_t i = 0; i < 3; ++i) { q2(i) = ::rl::math::clamp(q2(i), this->min(i), this->max(i)); } - - ::Eigen::Map quaternion1(q1.tail<4>().data()); - q2.tail<4>() = (quaternion1 * quaternion1.firstDerivative(qdot.tail<3>())).coeffs(); } ::rl::math::Real From 0a006b3b802c4511d623743cb608282e04add99e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 31 May 2018 21:06:20 +0200 Subject: [PATCH 124/546] Rename step function parameter from qdot to dq --- src/rl/kin/Kinematics.cpp | 6 +++--- src/rl/kin/Kinematics.h | 2 +- src/rl/mdl/Joint.cpp | 4 ++-- src/rl/mdl/Joint.h | 2 +- src/rl/mdl/Metric.cpp | 6 +++--- src/rl/mdl/Metric.h | 2 +- src/rl/mdl/SixDof.cpp | 6 +++--- src/rl/mdl/SixDof.h | 2 +- src/rl/mdl/Spherical.cpp | 4 ++-- src/rl/mdl/Spherical.h | 2 +- src/rl/plan/Model.cpp | 6 +++--- src/rl/plan/Model.h | 2 +- 12 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index a66cb4f2..fc50a01c 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -876,15 +876,15 @@ namespace rl } void - Kinematics::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const + Kinematics::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& dq, ::rl::math::Vector& q2) const { assert(q1.size() == this->getDof()); - assert(qdot.size() == this->getDof()); + assert(dq.size() == this->getDof()); assert(q2.size() == this->getDof()); for (::std::size_t i = 0; i < this->getDof(); ++i) { - q2(i) = q1(i) + qdot(i); + q2(i) = q1(i) + dq(i); } this->clamp(q2); diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 91dddf8e..a1da3b32 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -263,7 +263,7 @@ namespace rl */ void setPosition(const ::rl::math::Vector& q); - virtual void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const; + virtual void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& dq, ::rl::math::Vector& q2) const; ::rl::math::Transform& tool(const ::std::size_t& i = 0); diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index a2eab545..b248b3bd 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -328,9 +328,9 @@ namespace rl } void - Joint::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const + Joint::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& dq, ::rl::math::VectorRef q2) const { - q2 = q1 + qdot; + q2 = q1 + dq; this->clamp(q2); } diff --git a/src/rl/mdl/Joint.h b/src/rl/mdl/Joint.h index 2970bd74..aba80306 100644 --- a/src/rl/mdl/Joint.h +++ b/src/rl/mdl/Joint.h @@ -105,7 +105,7 @@ namespace rl void setVelocity(const ::rl::math::ConstVectorRef& qd); - virtual void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const; + virtual void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& dq, ::rl::math::VectorRef q2) const; virtual ::rl::math::Real transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; diff --git a/src/rl/mdl/Metric.cpp b/src/rl/mdl/Metric.cpp index 2e8958eb..fc91e792 100644 --- a/src/rl/mdl/Metric.cpp +++ b/src/rl/mdl/Metric.cpp @@ -130,17 +130,17 @@ namespace rl } void - Metric::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const + Metric::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& dq, ::rl::math::Vector& q2) const { assert(q1.size() == this->getDofPosition()); - assert(qdot.size() == this->getDof()); + assert(dq.size() == this->getDof()); assert(q2.size() == this->getDofPosition()); for (::std::size_t i = 0, j = 0, k = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), k += this->joints[i]->getDof(), ++i) { this->joints[i]->step( q1.segment(j, this->joints[i]->getDofPosition()), - qdot.segment(k, this->joints[i]->getDof()), + dq.segment(k, this->joints[i]->getDof()), q2.segment(j, this->joints[i]->getDofPosition()) ); } diff --git a/src/rl/mdl/Metric.h b/src/rl/mdl/Metric.h index 4371a7f9..9c83eda2 100644 --- a/src/rl/mdl/Metric.h +++ b/src/rl/mdl/Metric.h @@ -54,7 +54,7 @@ namespace rl void normalize(::rl::math::Vector& q) const; - void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const; + void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& dq, ::rl::math::Vector& q2) const; ::rl::math::Real transformedDistance(const ::rl::math::Real& d) const; diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index d4755270..dd5ae813 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -165,11 +165,11 @@ namespace rl } void - SixDof::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const + SixDof::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& dq, ::rl::math::VectorRef q2) const { ::Eigen::Map quaternion1(q1.tail<4>().data()); - q2.head<3>() = q1.head<3>() + quaternion1._transformVector(::Eigen::Map(qdot.head<3>().data())); - q2.tail<4>() = (quaternion1 * ::rl::math::AngleAxis(qdot.tail<3>().norm(), qdot.tail<3>().normalized())).coeffs(); + q2.head<3>() = q1.head<3>() + quaternion1._transformVector(::Eigen::Map(dq.head<3>().data())); + q2.tail<4>() = (quaternion1 * ::rl::math::AngleAxis(dq.tail<3>().norm(), dq.tail<3>().normalized())).coeffs(); for (::std::size_t i = 0; i < 3; ++i) { diff --git a/src/rl/mdl/SixDof.h b/src/rl/mdl/SixDof.h index 465f0e60..963f8ba5 100644 --- a/src/rl/mdl/SixDof.h +++ b/src/rl/mdl/SixDof.h @@ -56,7 +56,7 @@ namespace rl void setPosition(const ::rl::math::ConstVectorRef& q); - void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const; + void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& dq, ::rl::math::VectorRef q2) const; ::rl::math::Real transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 1752e12d..282c3978 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -125,10 +125,10 @@ namespace rl } void - Spherical::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const + Spherical::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& dq, ::rl::math::VectorRef q2) const { ::Eigen::Map quaternion1(q1.data()); - q2 = (quaternion1 * ::rl::math::AngleAxis(qdot.norm(), qdot.normalized())).coeffs(); + q2 = (quaternion1 * ::rl::math::AngleAxis(dq.norm(), dq.normalized())).coeffs(); } ::rl::math::Real diff --git a/src/rl/mdl/Spherical.h b/src/rl/mdl/Spherical.h index 98bff28a..6058e144 100644 --- a/src/rl/mdl/Spherical.h +++ b/src/rl/mdl/Spherical.h @@ -56,7 +56,7 @@ namespace rl void setPosition(const ::rl::math::ConstVectorRef& q); - void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& qdot, ::rl::math::VectorRef q2) const; + void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& dq, ::rl::math::VectorRef q2) const; ::rl::math::Real transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index 63cf22b0..c179cf2f 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -434,15 +434,15 @@ namespace rl } void - Model::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const + Model::step(const ::rl::math::Vector& q1, const ::rl::math::Vector& dq, ::rl::math::Vector& q2) const { if (nullptr != this->kin) { - this->kin->step(q1, qdot, q2); + this->kin->step(q1, dq, q2); } else { - this->mdl->step(q1, qdot, q2); + this->mdl->step(q1, dq, q2); } } diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 8cc5b9d2..28ceec8e 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -107,7 +107,7 @@ namespace rl virtual void setPosition(const ::rl::math::Vector& q); - virtual void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& qdot, ::rl::math::Vector& q2) const; + virtual void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& dq, ::rl::math::Vector& q2) const; virtual ::rl::math::Real transformedDistance(const ::rl::math::Real& d) const; From 60ff8a6971756edae34d27ee2f3c4233f76787ee Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 5 Jun 2018 14:13:20 +0200 Subject: [PATCH 125/546] More verbose feedback in Planner::verify --- demos/rlPlanDemo/Thread.cpp | 1 - src/rl/plan/Planner.cpp | 20 ++++++++++++++++++++ 2 files changed, 20 insertions(+), 1 deletion(-) diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index 5b285c72..94e014a1 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -190,7 +190,6 @@ Thread::run() if (!MainWindow::instance()->planner->verify()) { - emit statusChanged("Invalid start or goal configuration."); return; } diff --git a/src/rl/plan/Planner.cpp b/src/rl/plan/Planner.cpp index ec6e1550..c6b8d7ff 100644 --- a/src/rl/plan/Planner.cpp +++ b/src/rl/plan/Planner.cpp @@ -51,11 +51,21 @@ namespace rl { if (!this->model->isValid(*this->start)) { + if (nullptr != this->viewer) + { + this->viewer->showMessage("Invalid start configuration."); + } + return false; } if (!this->model->isValid(*this->goal)) { + if (nullptr != this->viewer) + { + this->viewer->showMessage("Invalid goal configuration."); + } + return false; } @@ -64,6 +74,11 @@ namespace rl if (this->model->isColliding()) { + if (nullptr != this->viewer) + { + this->viewer->showMessage("Colliding start configuration in body " + ::std::to_string(this->model->getCollidingBody()) + "."); + } + return false; } @@ -72,6 +87,11 @@ namespace rl if (this->model->isColliding()) { + if (nullptr != this->viewer) + { + this->viewer->showMessage("Colliding goal configuration in body " + ::std::to_string(this->model->getCollidingBody()) + "."); + } + return false; } From 81a347a16409b47c95787856a37d954626aceb36 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 6 Jun 2018 22:45:45 +0200 Subject: [PATCH 126/546] Fix alphabetical order in rl::mdl::Model --- src/rl/mdl/Model.cpp | 24 ++++++++++++------------ src/rl/mdl/Model.h | 8 ++++---- 2 files changed, 16 insertions(+), 16 deletions(-) diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 58dce433..77c1ac2b 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -367,52 +367,52 @@ namespace rl } ::rl::math::Vector - Model::getTorque() const + Model::getSpeed() const { - ::rl::math::Vector tau(this->getDof()); + ::rl::math::Vector speed(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { - tau.segment(j, this->joints[i]->getDof()) = this->joints[i]->getTorque(); + speed.segment(j, this->joints[i]->getDof()) = this->joints[i]->getSpeed(); } - return tau; + return speed; } ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> - Model::getTorqueUnits() const + Model::getSpeedUnits() const { ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { - units.segment(j, this->joints[i]->getDof()) = this->joints[i]->getTorqueUnits(); + units.segment(j, this->joints[i]->getDof()) = this->joints[i]->getSpeedUnits(); } return units; } ::rl::math::Vector - Model::getSpeed() const + Model::getTorque() const { - ::rl::math::Vector speed(this->getDof()); + ::rl::math::Vector tau(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { - speed.segment(j, this->joints[i]->getDof()) = this->joints[i]->getSpeed(); + tau.segment(j, this->joints[i]->getDof()) = this->joints[i]->getTorque(); } - return speed; + return tau; } ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> - Model::getSpeedUnits() const + Model::getTorqueUnits() const { ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { - units.segment(j, this->joints[i]->getDof()) = this->joints[i]->getSpeedUnits(); + units.segment(j, this->joints[i]->getDof()) = this->joints[i]->getTorqueUnits(); } return units; diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index df938868..5b1601f2 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -123,14 +123,14 @@ namespace rl ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getPositionUnits() const; - ::rl::math::Vector getTorque() const; - - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getTorqueUnits() const; - ::rl::math::Vector getSpeed() const; ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getSpeedUnits() const; + ::rl::math::Vector getTorque() const; + + ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getTorqueUnits() const; + ::rl::math::Vector getVelocity() const; ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getVelocityUnits() const; From c7873a947eaefa84d6dfe1c32247f179be1094dd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 6 Jun 2018 23:06:21 +0200 Subject: [PATCH 127/546] Add access to frames and transforms in rl::mdl::Model and rename getFrame() to getBodyFrame() --- demos/rlCoachMdl/ConfigurationModel.cpp | 4 +-- demos/rlCoachMdl/OperationalModel.cpp | 2 +- demos/rlSimulator/ConfigurationModel.cpp | 4 +-- demos/rlSimulator/OperationalModel.cpp | 2 +- src/rl/mdl/Model.cpp | 40 +++++++++++++++++++++-- src/rl/mdl/Model.h | 13 +++++++- src/rl/plan/Model.cpp | 4 +-- tests/rlCollisionTest/rlCollisionTest.cpp | 4 +-- 8 files changed, 59 insertions(+), 14 deletions(-) diff --git a/demos/rlCoachMdl/ConfigurationModel.cpp b/demos/rlCoachMdl/ConfigurationModel.cpp index 2e32417b..41296bd7 100644 --- a/demos/rlCoachMdl/ConfigurationModel.cpp +++ b/demos/rlCoachMdl/ConfigurationModel.cpp @@ -196,7 +196,7 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int for (std::size_t i = 0; i < MainWindow::instance()->geometryModels[this->id]->getNumBodies(); ++i) { - MainWindow::instance()->geometryModels[this->id]->getBody(i)->setFrame(kinematic->getFrame(i)); + MainWindow::instance()->geometryModels[this->id]->getBody(i)->setFrame(kinematic->getBodyFrame(i)); } emit dataChanged(index, index); @@ -223,7 +223,7 @@ ConfigurationModel::setData(const rl::math::Vector& q) for (std::size_t i = 0; i < MainWindow::instance()->geometryModels[this->id]->getNumBodies(); ++i) { - MainWindow::instance()->geometryModels[this->id]->getBody(i)->setFrame(kinematic->getFrame(i)); + MainWindow::instance()->geometryModels[this->id]->getBody(i)->setFrame(kinematic->getBodyFrame(i)); } emit dataChanged(this->createIndex(0, 0), this->createIndex(this->rowCount(), this->columnCount())); diff --git a/demos/rlCoachMdl/OperationalModel.cpp b/demos/rlCoachMdl/OperationalModel.cpp index 4619f368..9f4d6f29 100644 --- a/demos/rlCoachMdl/OperationalModel.cpp +++ b/demos/rlCoachMdl/OperationalModel.cpp @@ -280,7 +280,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r for (std::size_t i = 0; i < MainWindow::instance()->geometryModels[this->id]->getNumBodies(); ++i) { - MainWindow::instance()->geometryModels[this->id]->getBody(i)->setFrame(kinematic->getFrame(i)); + MainWindow::instance()->geometryModels[this->id]->getBody(i)->setFrame(kinematic->getBodyFrame(i)); } emit dataChanged(this->createIndex(0, 0), this->createIndex(this->rowCount(), this->columnCount())); diff --git a/demos/rlSimulator/ConfigurationModel.cpp b/demos/rlSimulator/ConfigurationModel.cpp index d86b88da..5495e39f 100644 --- a/demos/rlSimulator/ConfigurationModel.cpp +++ b/demos/rlSimulator/ConfigurationModel.cpp @@ -126,7 +126,7 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int for (std::size_t i = 0; i < MainWindow::instance()->geometryModels->getNumBodies(); ++i) { - MainWindow::instance()->geometryModels->getBody(i)->setFrame(kinematic->getFrame(i)); + MainWindow::instance()->geometryModels->getBody(i)->setFrame(kinematic->getBodyFrame(i)); } } else if (dynamic_cast(this)) @@ -192,7 +192,7 @@ ConfigurationModel::setData(const rl::math::Vector& values) for (std::size_t i = 0; i < MainWindow::instance()->geometryModels->getNumBodies(); ++i) { - MainWindow::instance()->geometryModels->getBody(i)->setFrame(kinematic->getFrame(i)); + MainWindow::instance()->geometryModels->getBody(i)->setFrame(kinematic->getBodyFrame(i)); } } else if (dynamic_cast(this)) diff --git a/demos/rlSimulator/OperationalModel.cpp b/demos/rlSimulator/OperationalModel.cpp index 47694176..01b09464 100644 --- a/demos/rlSimulator/OperationalModel.cpp +++ b/demos/rlSimulator/OperationalModel.cpp @@ -235,7 +235,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r for (std::size_t i = 0; i < MainWindow::instance()->geometryModels->getNumBodies(); ++i) { - MainWindow::instance()->geometryModels->getBody(i)->setFrame(kinematic->getFrame(i)); + MainWindow::instance()->geometryModels->getBody(i)->setFrame(kinematic->getBodyFrame(i)); } emit dataChanged(this->createIndex(0, 0), this->createIndex(this->rowCount(), this->columnCount())); diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 77c1ac2b..8750d4e3 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -186,6 +186,14 @@ namespace rl return this->bodies[i]; } + const ::rl::math::Transform& + Model::getBodyFrame(const ::std::size_t& i) const + { + assert(i < this->getBodies()); + + return this->bodies[i]->x.transform(); + } + ::std::size_t Model::getDof() const { @@ -212,12 +220,18 @@ namespace rl return dof; } - const ::rl::math::Transform& + Frame* Model::getFrame(const ::std::size_t& i) const { - assert(i < this->getBodies()); + assert(i < this->frames.size()); - return this->bodies[i]->x.transform(); + return this->frames[i]; + } + + ::std::size_t + Model::getFrames() const + { + return this->frames.size(); } const ::rl::math::Matrix& @@ -418,6 +432,20 @@ namespace rl return units; } + Transform* + Model::getTransform(const ::std::size_t& i) const + { + assert(i < this->transforms.size()); + + return this->transforms[i]; + } + + ::std::size_t + Model::getTransforms() const + { + return this->transforms.size(); + } + ::rl::math::Vector Model::getVelocity() const { @@ -444,6 +472,12 @@ namespace rl return units; } + World* + Model::getWorld() const + { + return dynamic_cast(this->tree[this->root].get()); + } + bool Model::isColliding(const ::std::size_t& i) const { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 5b1601f2..5688ad9c 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -51,6 +51,7 @@ namespace rl class Body; class Compound; class Joint; + class World; class Model { @@ -81,11 +82,15 @@ namespace rl Body* getBody(const ::std::size_t& i) const; + const ::rl::math::Transform& getBodyFrame(const ::std::size_t& i) const; + ::std::size_t getDof() const; ::std::size_t getDofPosition() const; - const ::rl::math::Transform& getFrame(const ::std::size_t& i) const; + Frame* getFrame(const ::std::size_t& i) const; + + ::std::size_t getFrames() const; const ::rl::math::Matrix& getGammaPosition() const; @@ -123,6 +128,10 @@ namespace rl ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getPositionUnits() const; + Transform* getTransform(const ::std::size_t& i) const; + + ::std::size_t getTransforms() const; + ::rl::math::Vector getSpeed() const; ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getSpeedUnits() const; @@ -135,6 +144,8 @@ namespace rl ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getVelocityUnits() const; + World* getWorld() const; + bool isColliding(const ::std::size_t& i) const; void replace(Compound* compound, Transform* transform); diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index c179cf2f..c92dc5f1 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -208,7 +208,7 @@ namespace rl } else { - return this->mdl->getFrame(i); + return this->mdl->getBodyFrame(i); } } @@ -512,7 +512,7 @@ namespace rl { for (::std::size_t i = 0; i < this->model->getNumBodies(); ++i) { - this->model->getBody(i)->setFrame(this->mdl->getFrame(i)); + this->model->getBody(i)->setFrame(this->mdl->getBodyFrame(i)); } } } diff --git a/tests/rlCollisionTest/rlCollisionTest.cpp b/tests/rlCollisionTest/rlCollisionTest.cpp index d0b8ed11..974c0bab 100644 --- a/tests/rlCollisionTest/rlCollisionTest.cpp +++ b/tests/rlCollisionTest/rlCollisionTest.cpp @@ -151,7 +151,7 @@ main(int argc, char** argv) assert(scenes[i]->getModel(0)->getNumBodies() == kinematics->getBodies()); for (std::size_t b = 0; b < kinematics->getBodies(); ++b) { - scenes[i]->getModel(0)->getBody(b)->setFrame(kinematics->getFrame(b)); + scenes[i]->getModel(0)->getBody(b)->setFrame(kinematics->getBodyFrame(b)); } } @@ -185,7 +185,7 @@ main(int argc, char** argv) { for (std::size_t b = 0; b < kinematics->getBodies(); ++b) { - scenes[i]->getModel(0)->getBody(b)->setFrame(kinematics->getFrame(b)); + scenes[i]->getModel(0)->getBody(b)->setFrame(kinematics->getBodyFrame(b)); } results[i] = collides(scenes[i], kinematics); } From 8e6b7bc45c3f9e104e0fd78b1d19902a67e7b980 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 6 Jul 2018 18:47:28 +0200 Subject: [PATCH 128/546] Refactor rl::sg::Scene::load to rl::sg::XmlFactory::load --- demos/rlCoachKin/MainWindow.cpp | 4 +- demos/rlCoachMdl/MainWindow.cpp | 8 +- demos/rlCollisionDemo/MainWindow.cpp | 6 +- demos/rlPlanDemo/MainWindow.cpp | 14 +- demos/rlPrmDemo/rlPrmDemo.cpp | 4 +- demos/rlSimulator/MainWindow.cpp | 8 +- demos/rlViewDemo/rlViewDemo.cpp | 4 +- src/rl/sg/CMakeLists.txt | 4 + src/rl/sg/Factory.cpp | 41 +++ src/rl/sg/Factory.h | 55 ++++ src/rl/sg/Scene.cpp | 260 +-------------- src/rl/sg/Scene.h | 8 +- src/rl/sg/XmlFactory.cpp | 304 ++++++++++++++++++ src/rl/sg/XmlFactory.h | 57 ++++ src/rl/sg/bullet/Scene.cpp | 7 +- src/rl/sg/bullet/Scene.h | 2 + src/rl/sg/fcl/Scene.cpp | 7 +- src/rl/sg/fcl/Scene.h | 2 + src/rl/sg/pqp/Scene.cpp | 7 +- src/rl/sg/pqp/Scene.h | 2 + src/rl/sg/so/Scene.h | 2 + tests/rlCollisionTest/rlCollisionTest.cpp | 10 +- .../rlCollisionTest/rlSceneCollisionTest.cpp | 6 +- tests/rlEetTest/rlEetTest.cpp | 4 +- tests/rlPrmTest/rlPrmTest.cpp | 4 +- 25 files changed, 540 insertions(+), 290 deletions(-) create mode 100644 src/rl/sg/Factory.cpp create mode 100644 src/rl/sg/Factory.h create mode 100644 src/rl/sg/XmlFactory.cpp create mode 100644 src/rl/sg/XmlFactory.h diff --git a/demos/rlCoachKin/MainWindow.cpp b/demos/rlCoachKin/MainWindow.cpp index ae634b1d..a166821b 100644 --- a/demos/rlCoachKin/MainWindow.cpp +++ b/demos/rlCoachKin/MainWindow.cpp @@ -30,6 +30,7 @@ #include #include #include +#include #include "ConfigurationDelegate.h" #include "ConfigurationModel.h" @@ -70,7 +71,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QGLFormat::setDefaultFormat(format); this->scene = std::make_shared(); - this->scene->load(QApplication::arguments()[1].toStdString()); + rl::sg::XmlFactory geometryFactory; + geometryFactory.load(QApplication::arguments()[1].toStdString(), this->scene.get()); for (int i = 2; i < QApplication::arguments().size(); ++i) { diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index 97b2a848..1245bf20 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -32,6 +32,7 @@ #include #include #include +#include #include "ConfigurationDelegate.h" #include "ConfigurationModel.h" @@ -74,15 +75,16 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoGradientBackground::initClass(); this->scene = std::make_shared(); - this->scene->load(QApplication::arguments()[1].toStdString()); + rl::sg::XmlFactory geometryFactory; + geometryFactory.load(QApplication::arguments()[1].toStdString(), this->scene.get()); - rl::mdl::XmlFactory factory; + rl::mdl::XmlFactory kinematicFactory; for (int i = 2; i < QApplication::arguments().size(); ++i) { this->geometryModels.push_back(this->scene->getModel(i - 2)); std::shared_ptr kinematicModel; - kinematicModel.reset(factory.create(QApplication::arguments()[i].toStdString())); + kinematicModel.reset(kinematicFactory.create(QApplication::arguments()[i].toStdString())); this->kinematicModels.push_back(kinematicModel); } diff --git a/demos/rlCollisionDemo/MainWindow.cpp b/demos/rlCollisionDemo/MainWindow.cpp index ce1b8f01..f46716a9 100644 --- a/demos/rlCollisionDemo/MainWindow.cpp +++ b/demos/rlCollisionDemo/MainWindow.cpp @@ -42,6 +42,7 @@ #include #include #include +#include #ifdef RL_SG_BULLET #include @@ -198,8 +199,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->setWindowTitle(filename + " - " + this->engine.toUpper() + " - rlCollisionDemo"); - this->collisionScene->load(this->filename.toStdString()); - this->viewScene->load(this->filename.toStdString()); + rl::sg::XmlFactory factory; + factory.load(this->filename.toStdString(), this->collisionScene.get()); + factory.load(this->filename.toStdString(), this->viewScene.get()); this->viewer->viewAll(); diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index fedc64e0..dc369501 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -73,6 +73,7 @@ #include #include #include +#include #include #include #include @@ -936,8 +937,11 @@ MainWindow::load(const QString& filename) } #endif // RL_SG_SOLID + rl::mdl::XmlFactory modelFactory; + rl::sg::XmlFactory sceneFactory; + rl::xml::NodeSet modelScene = path.eval("(/rl/plan|/rlplan)//model/scene").getValue(); - this->scene->load(modelScene[0].getUri(modelScene[0].getProperty("href"))); + sceneFactory.load(modelScene[0].getUri(modelScene[0].getProperty("href")), this->scene.get()); this->sceneModel = this->scene->getModel( path.eval("number((/rl/plan|/rlplan)//model/model)").getValue() ); @@ -945,8 +949,7 @@ MainWindow::load(const QString& filename) if ("mdl" == path.eval("string((/rl/plan|/rlplan)//model/kinematics/@type)").getValue()) { rl::xml::NodeSet mdl = path.eval("(/rl/plan|/rlplan)//model/kinematics").getValue(); - rl::mdl::XmlFactory factory; - this->mdl.reset(dynamic_cast(factory.create( + this->mdl.reset(dynamic_cast(modelFactory.create( mdl[0].getUri(mdl[0].getProperty("href")) ))); @@ -1029,7 +1032,7 @@ MainWindow::load(const QString& filename) this->scene2 = std::make_shared(); rl::xml::NodeSet viewerScene = path.eval("(/rl/plan|/rlplan)//viewer/model/scene").getValue(); - this->scene2->load(viewerScene[0].getUri(viewerScene[0].getProperty("href"))); + sceneFactory.load(viewerScene[0].getUri(viewerScene[0].getProperty("href")), this->scene2.get()); this->sceneModel2 = static_cast(this->scene2->getModel( path.eval("number((/rl/plan|/rlplan)//viewer/model/model)").getValue() )); @@ -1037,8 +1040,7 @@ MainWindow::load(const QString& filename) if ("mdl" == path.eval("string((/rl/plan|/rlplan)//viewer/model/kinematics/@type)").getValue()) { rl::xml::NodeSet mdl2 = path.eval("(/rl/plan|/rlplan)//viewer/model/kinematics").getValue(); - rl::mdl::XmlFactory factory; - this->mdl2.reset(dynamic_cast(factory.create( + this->mdl2.reset(dynamic_cast(modelFactory.create( mdl2[0].getUri(mdl2[0].getProperty("href")) ))); diff --git a/demos/rlPrmDemo/rlPrmDemo.cpp b/demos/rlPrmDemo/rlPrmDemo.cpp index 8cf33c56..9257da07 100644 --- a/demos/rlPrmDemo/rlPrmDemo.cpp +++ b/demos/rlPrmDemo/rlPrmDemo.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include #include @@ -50,8 +51,9 @@ main(int argc, char** argv) try { + rl::sg::XmlFactory factory; rl::sg::solid::Scene scene; - scene.load(argv[1]); + factory.load(argv[1], &scene); std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[2])); diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index 8777ed23..6ceef391 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -44,6 +44,7 @@ #include #include #include +#include #include "ConfigurationDelegate.h" #include "ConfigurationModel.h" @@ -112,12 +113,13 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoGradientBackground::initClass(); this->scene = std::make_shared(); - this->scene->load(QApplication::arguments()[1].toStdString()); + rl::sg::XmlFactory geometryFactory; + geometryFactory.load(QApplication::arguments()[1].toStdString(), this->scene.get()); - rl::mdl::XmlFactory factory; + rl::mdl::XmlFactory kinematicFactory; this->geometryModels = this->scene->getModel(0); - this->kinematicModels.reset(factory.create(QApplication::arguments()[2].toStdString())); + this->kinematicModels.reset(kinematicFactory.create(QApplication::arguments()[2].toStdString())); this->simulationResetQ = rl::math::Vector::Zero(kinematicModels->getDof()); this->simulationResetQd = rl::math::Vector::Zero(kinematicModels->getDof()); this->simulationResetQdd = rl::math::Vector::Zero(kinematicModels->getDof()); diff --git a/demos/rlViewDemo/rlViewDemo.cpp b/demos/rlViewDemo/rlViewDemo.cpp index 0d190ebb..8738ff01 100644 --- a/demos/rlViewDemo/rlViewDemo.cpp +++ b/demos/rlViewDemo/rlViewDemo.cpp @@ -32,6 +32,7 @@ #include #include #include +#include #include int @@ -55,11 +56,12 @@ main(int argc, char** argv) filename = argv[1]; } + rl::sg::XmlFactory factory; rl::sg::so::Scene scene; if (!filename.isEmpty()) { - scene.load(filename.toStdString()); + factory.load(filename.toStdString(), &scene); } SoQtExaminerViewer viewer(widget, nullptr, true, SoQtFullViewer::BUILD_POPUP); diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index f0fb0ad5..a00c7002 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -12,11 +12,13 @@ set( DepthScene.h DistanceScene.h Exception.h + Factory.h Model.h RaycastScene.h Scene.h Shape.h SimpleScene.h + XmlFactory.h ) list(APPEND HDRS ${BASE_HDRS}) @@ -26,11 +28,13 @@ set( DepthScene.cpp DistanceScene.cpp Exception.cpp + Factory.cpp Model.cpp RaycastScene.cpp Scene.cpp Shape.cpp SimpleScene.cpp + XmlFactory.cpp ) list(APPEND SRCS ${BASE_SRCS}) diff --git a/src/rl/sg/Factory.cpp b/src/rl/sg/Factory.cpp new file mode 100644 index 00000000..8a84d6b2 --- /dev/null +++ b/src/rl/sg/Factory.cpp @@ -0,0 +1,41 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Factory.h" + +namespace rl +{ + namespace sg + { + Factory::Factory() + { + } + + Factory::~Factory() + { + } + } +} diff --git a/src/rl/sg/Factory.h b/src/rl/sg/Factory.h new file mode 100644 index 00000000..0664967e --- /dev/null +++ b/src/rl/sg/Factory.h @@ -0,0 +1,55 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_SG_FACTORY_H +#define RL_SG_FACTORY_H + +#include + +namespace rl +{ + namespace sg + { + class Scene; + + class Factory + { + public: + Factory(); + + virtual ~Factory(); + + virtual void load(const ::std::string& filename, Scene* scene) = 0; + + protected: + + private: + + }; + } +} + +#endif // RL_SG_FACTORY_H diff --git a/src/rl/sg/Scene.cpp b/src/rl/sg/Scene.cpp index 6518a4c4..0e22d42e 100644 --- a/src/rl/sg/Scene.cpp +++ b/src/rl/sg/Scene.cpp @@ -25,36 +25,14 @@ // #include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "Body.h" -#include "Exception.h" -#include "Model.h" #include "Scene.h" -#include "Shape.h" namespace rl { namespace sg { Scene::Scene() : - isScalingSupported(true), models(), name() { @@ -100,215 +78,10 @@ namespace rl return this->models.size(); } - void - Scene::load(const ::std::string& filename, const bool& doBoundingBoxPoints, const bool& doPoints) + bool + Scene::isScalingSupported() const { - ::rl::xml::DomParser parser; - - ::rl::xml::Document document = parser.readFile(filename, "", XML_PARSE_NOENT | XML_PARSE_XINCLUDE); - document.substitute(XML_PARSE_NOENT | XML_PARSE_XINCLUDE); - - ::rl::xml::Path path(document); - - ::rl::xml::NodeSet scenes = path.eval("(/rl/sg|/rlsg)/scene").getValue< ::rl::xml::NodeSet>(); - - for (int i = 0; i < ::std::min(1, scenes.size()); ++i) - { - ::SoInput input; - - if (!input.openFile(scenes[i].getLocalPath(scenes[i].getProperty("href")).c_str() ,true)) - { - throw Exception("::rl::sg::Scene::load() - failed to open file"); - } - - ::SoVRMLGroup* root = SoDB::readAllVRML(&input); - - if (nullptr == root) - { - throw Exception("::rl::sg::Scene::load() - failed to read file"); - } - - ::SbViewportRegion viewportRegion; - - root->ref(); - - // model - - ::rl::xml::NodeSet models = ::rl::xml::Path(document, scenes[i]).eval("model").getValue< ::rl::xml::NodeSet>(); - - for (int j = 0; j < models.size(); ++j) - { - ::rl::xml::Path path(document, models[j]); - - ::SoSearchAction modelSearchAction; - modelSearchAction.setName(models[j].getProperty("name").c_str()); - modelSearchAction.apply(root); - - if (nullptr == modelSearchAction.getPath()) - { - continue; - } - - Model* model = this->create(); - - model->setName(models[j].getProperty("name")); - - // body - - ::rl::xml::NodeSet bodies = path.eval("body").getValue< ::rl::xml::NodeSet>(); - - for (int k = 0; k < bodies.size(); ++k) - { - ::SoSearchAction bodySearchAction; - bodySearchAction.setName(bodies[k].getProperty("name").c_str()); - bodySearchAction.apply(static_cast< ::SoFullPath*>(modelSearchAction.getPath())->getTail()); - - if (nullptr == bodySearchAction.getPath()) - { - continue; - } - - Body* body = model->create(); - - body->setName(bodies[k].getProperty("name")); - - ::SoSearchAction pathSearchAction; - pathSearchAction.setNode(static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()); - pathSearchAction.apply(root); - - ::SoGetMatrixAction bodyGetMatrixAction(viewportRegion); - bodyGetMatrixAction.apply(static_cast< ::SoFullPath*>(pathSearchAction.getPath())); - ::SbMatrix bodyMatrix = bodyGetMatrixAction.getMatrix(); - - if (!this->isScalingSupported) - { - ::SbVec3f bodyTranslation; - ::SbRotation bodyRotation; - ::SbVec3f bodyScaleFactor; - ::SbRotation bodyScaleOrientation; - ::SbVec3f bodyCenter; - bodyMatrix.getTransform(bodyTranslation, bodyRotation, bodyScaleFactor, bodyScaleOrientation, bodyCenter); - - for (int l = 0; l < 3; ++l) - { - if (::std::abs(bodyScaleFactor[l] - 1.0f) > 1.0e-6f) - { - throw Exception("::rl::sg::Scene::load() - bodyScaleFactor not supported"); - } - } - } - - ::rl::math::Transform frame; - - for (int m = 0; m < 4; ++m) - { - for (int n = 0; n < 4; ++n) - { - frame(m, n) = bodyMatrix[n][m]; - } - } - - body->setFrame(frame); - - if (static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()->isOfType(::SoVRMLTransform::getClassTypeId())) - { - ::SoVRMLTransform* bodyVrmlTransform = static_cast< ::SoVRMLTransform*>(static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()); - - for (int l = 0; l < 3; ++l) - { - body->center(l) = bodyVrmlTransform->center.getValue()[l]; - } - } - - ::SoPathList pathList; - - // shape - - ::SoSearchAction shapeSearchAction; - shapeSearchAction.setInterest(::SoSearchAction::ALL); - shapeSearchAction.setType(::SoVRMLShape::getClassTypeId()); - shapeSearchAction.apply(static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()); - - for (int l = 0; l < shapeSearchAction.getPaths().getLength(); ++l) - { - ::SoFullPath* path = static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l]); - - if (path->getLength() > 1) - { - path = static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l]->copy(1, static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l])->getLength() - 1)); - } - - pathList.append(path); - - ::SoGetMatrixAction shapeGetMatrixAction(viewportRegion); - shapeGetMatrixAction.apply(path); - ::SbMatrix shapeMatrix = shapeGetMatrixAction.getMatrix(); - - if (!this->isScalingSupported) - { - ::SbVec3f shapeTranslation; - ::SbRotation shapeRotation; - ::SbVec3f shapeScaleFactor; - ::SbRotation shapeScaleOrientation; - ::SbVec3f shapeCenter; - shapeMatrix.getTransform(shapeTranslation, shapeRotation, shapeScaleFactor, shapeScaleOrientation, shapeCenter); - - for (int m = 0; m < 3; ++m) - { - if (::std::abs(shapeScaleFactor[m] - 1.0f) > 1.0e-6f) - { - throw Exception("::rl::sg::Scene::load() - shapeScaleFactor not supported"); - } - } - } - - ::SoVRMLShape* shapeVrmlShape = static_cast< ::SoVRMLShape*>(static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l])->getTail()); - - Shape* shape = body->create(shapeVrmlShape); - - shape->setName(shapeVrmlShape->getName().getString()); - - ::rl::math::Transform transform; - - for (int m = 0; m < 4; ++m) - { - for (int n = 0; n < 4; ++n) - { - transform(m, n) = shapeMatrix[n][m]; - } - } - - shape->setTransform(transform); - } - - // bounding box - - if (doBoundingBoxPoints) - { - ::SoGetBoundingBoxAction getBoundingBoxAction(viewportRegion); - getBoundingBoxAction.apply(pathList); - ::SbBox3f boundingBox = getBoundingBoxAction.getBoundingBox(); - - for (int l = 0; l < 3; ++l) - { - body->max(l) = boundingBox.getMax()[l]; - body->min(l) = boundingBox.getMin()[l]; - } - } - - // convex hull - - if (doPoints) - { - ::SoCallbackAction callbackAction; - callbackAction.addTriangleCallback(::SoVRMLGeometry::getClassTypeId(), Scene::triangleCallback, &body->points); - callbackAction.apply(pathList); - } - } - } - - root->unref(); - } + return true; } void @@ -327,32 +100,5 @@ namespace rl { this->name = name; } - - void - Scene::triangleCallback(void* userData, SoCallbackAction* action, const SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const SoPrimitiveVertex* v3) - { - ::std::vector< ::rl::math::Vector3>* points = static_cast< ::std::vector< ::rl::math::Vector3>*>(userData); - - ::rl::math::Vector3 p1; - p1(0) = v1->getPoint()[0]; - p1(1) = v1->getPoint()[1]; - p1(2) = v1->getPoint()[2]; - - points->push_back(p1); - - ::rl::math::Vector3 p2; - p2(0) = v2->getPoint()[0]; - p2(1) = v2->getPoint()[1]; - p2(2) = v2->getPoint()[2]; - - points->push_back(p2); - - ::rl::math::Vector3 p3; - p3(0) = v3->getPoint()[0]; - p3(1) = v3->getPoint()[1]; - p3(2) = v3->getPoint()[2]; - - points->push_back(p3); - } } } diff --git a/src/rl/sg/Scene.h b/src/rl/sg/Scene.h index 518a079e..7a978a5d 100644 --- a/src/rl/sg/Scene.h +++ b/src/rl/sg/Scene.h @@ -29,8 +29,6 @@ #include #include -#include -#include namespace rl { @@ -64,20 +62,16 @@ namespace rl ::std::size_t getNumModels() const; - void load(const ::std::string& filename, const bool& doBoundingBoxPoints = false, const bool& doPoints = false); + virtual bool isScalingSupported() const; virtual void remove(Model* model); virtual void setName(const ::std::string& name); protected: - bool isScalingSupported; - ::std::vector models; private: - static void triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const ::SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3); - ::std::string name; }; } diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp new file mode 100644 index 00000000..04ff0334 --- /dev/null +++ b/src/rl/sg/XmlFactory.cpp @@ -0,0 +1,304 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "Body.h" +#include "Exception.h" +#include "Model.h" +#include "Scene.h" +#include "Shape.h" +#include "XmlFactory.h" + +namespace rl +{ + namespace sg + { + XmlFactory::XmlFactory() + { + } + + XmlFactory::~XmlFactory() + { + } + + void + XmlFactory::load(const ::std::string& filename, Scene* scene) + { + this->load(filename, scene, false, false); + } + + void + XmlFactory::load(const ::std::string& filename, Scene* scene, const bool& doBoundingBoxPoints, const bool& doPoints) + { + ::rl::xml::DomParser parser; + + ::rl::xml::Document document = parser.readFile(filename, "", XML_PARSE_NOENT | XML_PARSE_XINCLUDE); + document.substitute(XML_PARSE_NOENT | XML_PARSE_XINCLUDE); + + ::rl::xml::Path path(document); + + ::rl::xml::NodeSet scenes = path.eval("(/rl/sg|/rlsg)/scene").getValue< ::rl::xml::NodeSet>(); + + for (int i = 0; i < ::std::min(1, scenes.size()); ++i) + { + ::SoInput input; + + if (!input.openFile(scenes[i].getLocalPath(scenes[i].getProperty("href")).c_str() ,true)) + { + throw Exception("::rl::sg::XmlFactory::load() - failed to open file"); + } + + ::SoVRMLGroup* root = SoDB::readAllVRML(&input); + + if (nullptr == root) + { + throw Exception("::rl::sg::XmlFactory::load() - failed to read file"); + } + + ::SbViewportRegion viewportRegion; + + root->ref(); + + // model + + ::rl::xml::NodeSet models = ::rl::xml::Path(document, scenes[i]).eval("model").getValue< ::rl::xml::NodeSet>(); + + for (int j = 0; j < models.size(); ++j) + { + ::rl::xml::Path path(document, models[j]); + + ::SoSearchAction modelSearchAction; + modelSearchAction.setName(models[j].getProperty("name").c_str()); + modelSearchAction.apply(root); + + if (nullptr == modelSearchAction.getPath()) + { + continue; + } + + Model* model = scene->create(); + + model->setName(models[j].getProperty("name")); + + // body + + ::rl::xml::NodeSet bodies = path.eval("body").getValue< ::rl::xml::NodeSet>(); + + for (int k = 0; k < bodies.size(); ++k) + { + ::SoSearchAction bodySearchAction; + bodySearchAction.setName(bodies[k].getProperty("name").c_str()); + bodySearchAction.apply(static_cast< ::SoFullPath*>(modelSearchAction.getPath())->getTail()); + + if (nullptr == bodySearchAction.getPath()) + { + continue; + } + + Body* body = model->create(); + + body->setName(bodies[k].getProperty("name")); + + ::SoSearchAction pathSearchAction; + pathSearchAction.setNode(static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()); + pathSearchAction.apply(root); + + ::SoGetMatrixAction bodyGetMatrixAction(viewportRegion); + bodyGetMatrixAction.apply(static_cast< ::SoFullPath*>(pathSearchAction.getPath())); + ::SbMatrix bodyMatrix = bodyGetMatrixAction.getMatrix(); + + if (!scene->isScalingSupported()) + { + ::SbVec3f bodyTranslation; + ::SbRotation bodyRotation; + ::SbVec3f bodyScaleFactor; + ::SbRotation bodyScaleOrientation; + ::SbVec3f bodyCenter; + bodyMatrix.getTransform(bodyTranslation, bodyRotation, bodyScaleFactor, bodyScaleOrientation, bodyCenter); + + for (int l = 0; l < 3; ++l) + { + if (::std::abs(bodyScaleFactor[l] - 1.0f) > 1.0e-6f) + { + throw Exception("::rl::sg::XmlFactory::load() - bodyScaleFactor not supported"); + } + } + } + + ::rl::math::Transform frame; + + for (int m = 0; m < 4; ++m) + { + for (int n = 0; n < 4; ++n) + { + frame(m, n) = bodyMatrix[n][m]; + } + } + + body->setFrame(frame); + + if (static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()->isOfType(::SoVRMLTransform::getClassTypeId())) + { + ::SoVRMLTransform* bodyVrmlTransform = static_cast< ::SoVRMLTransform*>(static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()); + + for (int l = 0; l < 3; ++l) + { + body->center(l) = bodyVrmlTransform->center.getValue()[l]; + } + } + + ::SoPathList pathList; + + // shape + + ::SoSearchAction shapeSearchAction; + shapeSearchAction.setInterest(::SoSearchAction::ALL); + shapeSearchAction.setType(::SoVRMLShape::getClassTypeId()); + shapeSearchAction.apply(static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()); + + for (int l = 0; l < shapeSearchAction.getPaths().getLength(); ++l) + { + ::SoFullPath* path = static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l]); + + if (path->getLength() > 1) + { + path = static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l]->copy(1, static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l])->getLength() - 1)); + } + + pathList.append(path); + + ::SoGetMatrixAction shapeGetMatrixAction(viewportRegion); + shapeGetMatrixAction.apply(path); + ::SbMatrix shapeMatrix = shapeGetMatrixAction.getMatrix(); + + if (!scene->isScalingSupported()) + { + ::SbVec3f shapeTranslation; + ::SbRotation shapeRotation; + ::SbVec3f shapeScaleFactor; + ::SbRotation shapeScaleOrientation; + ::SbVec3f shapeCenter; + shapeMatrix.getTransform(shapeTranslation, shapeRotation, shapeScaleFactor, shapeScaleOrientation, shapeCenter); + + for (int m = 0; m < 3; ++m) + { + if (::std::abs(shapeScaleFactor[m] - 1.0f) > 1.0e-6f) + { + throw Exception("::rl::sg::XmlFactory::load() - shapeScaleFactor not supported"); + } + } + } + + ::SoVRMLShape* shapeVrmlShape = static_cast< ::SoVRMLShape*>(static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l])->getTail()); + + Shape* shape = body->create(shapeVrmlShape); + + shape->setName(shapeVrmlShape->getName().getString()); + + ::rl::math::Transform transform; + + for (int m = 0; m < 4; ++m) + { + for (int n = 0; n < 4; ++n) + { + transform(m, n) = shapeMatrix[n][m]; + } + } + + shape->setTransform(transform); + } + + // bounding box + + if (doBoundingBoxPoints) + { + ::SoGetBoundingBoxAction getBoundingBoxAction(viewportRegion); + getBoundingBoxAction.apply(pathList); + ::SbBox3f boundingBox = getBoundingBoxAction.getBoundingBox(); + + for (int l = 0; l < 3; ++l) + { + body->max(l) = boundingBox.getMax()[l]; + body->min(l) = boundingBox.getMin()[l]; + } + } + + // convex hull + + if (doPoints) + { + ::SoCallbackAction callbackAction; + callbackAction.addTriangleCallback(::SoVRMLGeometry::getClassTypeId(), XmlFactory::triangleCallback, &body->points); + callbackAction.apply(pathList); + } + } + } + + root->unref(); + } + } + + void + XmlFactory::triangleCallback(void* userData, SoCallbackAction* action, const SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const SoPrimitiveVertex* v3) + { + ::std::vector< ::rl::math::Vector3>* points = static_cast< ::std::vector< ::rl::math::Vector3>*>(userData); + + ::rl::math::Vector3 p1; + p1(0) = v1->getPoint()[0]; + p1(1) = v1->getPoint()[1]; + p1(2) = v1->getPoint()[2]; + + points->push_back(p1); + + ::rl::math::Vector3 p2; + p2(0) = v2->getPoint()[0]; + p2(1) = v2->getPoint()[1]; + p2(2) = v2->getPoint()[2]; + + points->push_back(p2); + + ::rl::math::Vector3 p3; + p3(0) = v3->getPoint()[0]; + p3(1) = v3->getPoint()[1]; + p3(2) = v3->getPoint()[2]; + + points->push_back(p3); + } + } +} diff --git a/src/rl/sg/XmlFactory.h b/src/rl/sg/XmlFactory.h new file mode 100644 index 00000000..ab71bd7c --- /dev/null +++ b/src/rl/sg/XmlFactory.h @@ -0,0 +1,57 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_SG_XMLFACTORY_H +#define RL_SG_XMLFACTORY_H + +#include + +#include "Factory.h" + +namespace rl +{ + namespace sg + { + class XmlFactory : public Factory + { + public: + XmlFactory(); + + virtual ~XmlFactory(); + + void load(const ::std::string& filename, Scene* scene); + + void load(const ::std::string& filename, Scene* scene, const bool& doBoundingBoxPoints, const bool& doPoints); + + protected: + + private: + static void triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const ::SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3); + }; + } +} + +#endif // RL_SG_XMLFACTORY_H diff --git a/src/rl/sg/bullet/Scene.cpp b/src/rl/sg/bullet/Scene.cpp index 73a336ce..281665dc 100644 --- a/src/rl/sg/bullet/Scene.cpp +++ b/src/rl/sg/bullet/Scene.cpp @@ -52,7 +52,6 @@ namespace rl dispatcher(&configuration), world(&dispatcher, &broadphase, &configuration) { - this->isScalingSupported = false; } Scene::~Scene() @@ -213,6 +212,12 @@ namespace rl return false; } + bool + Scene::isScalingSupported() const + { + return false; + } + ::rl::sg::Shape* Scene::raycast(const ::rl::math::Vector3& source, const ::rl::math::Vector3& target, ::rl::math::Real& distance) { diff --git a/src/rl/sg/bullet/Scene.h b/src/rl/sg/bullet/Scene.h index b790e3a0..8a7823c4 100644 --- a/src/rl/sg/bullet/Scene.h +++ b/src/rl/sg/bullet/Scene.h @@ -70,6 +70,8 @@ namespace rl bool isColliding(); + bool isScalingSupported() const; + ::rl::sg::Shape* raycast(const ::rl::math::Vector3& source, const ::rl::math::Vector3& target, ::rl::math::Real& distance); bool raycast(::rl::sg::Shape* shape, const ::rl::math::Vector3& source, const ::rl::math::Vector3& target, ::rl::math::Real& distance); diff --git a/src/rl/sg/fcl/Scene.cpp b/src/rl/sg/fcl/Scene.cpp index 5fad67d1..71d8cc76 100644 --- a/src/rl/sg/fcl/Scene.cpp +++ b/src/rl/sg/fcl/Scene.cpp @@ -48,7 +48,6 @@ namespace rl ::rl::sg::SimpleScene(), manager() { - this->isScalingSupported = false; this->manager.setup(); } @@ -318,6 +317,12 @@ namespace rl return collisionData.result.numContacts() > 0; } + bool + Scene::isScalingSupported() const + { + return false; + } + void Scene::remove(::rl::sg::Model* model) { diff --git a/src/rl/sg/fcl/Scene.h b/src/rl/sg/fcl/Scene.h index f9938903..60f465e3 100644 --- a/src/rl/sg/fcl/Scene.h +++ b/src/rl/sg/fcl/Scene.h @@ -77,6 +77,8 @@ namespace rl bool isColliding(); + bool isScalingSupported() const; + void remove(::rl::sg::Model* model); void removeCollisionObject(::fcl::CollisionObject* collisionObject); diff --git a/src/rl/sg/pqp/Scene.cpp b/src/rl/sg/pqp/Scene.cpp index fe210c94..7ec10b58 100644 --- a/src/rl/sg/pqp/Scene.cpp +++ b/src/rl/sg/pqp/Scene.cpp @@ -39,7 +39,6 @@ namespace rl ::rl::sg::DistanceScene(), ::rl::sg::SimpleScene() { - this->isScalingSupported = false; } Scene::~Scene() @@ -159,6 +158,12 @@ namespace rl return result.Distance(); } + + bool + Scene::isScalingSupported() const + { + return false; + } } } } diff --git a/src/rl/sg/pqp/Scene.h b/src/rl/sg/pqp/Scene.h index 71091389..8a6c52fc 100644 --- a/src/rl/sg/pqp/Scene.h +++ b/src/rl/sg/pqp/Scene.h @@ -61,6 +61,8 @@ namespace rl ::rl::math::Real distance(::rl::sg::Shape* shape, const ::rl::math::Vector3& point, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2); + bool isScalingSupported() const; + protected: private: diff --git a/src/rl/sg/so/Scene.h b/src/rl/sg/so/Scene.h index 6f91fcd8..7f5197c0 100644 --- a/src/rl/sg/so/Scene.h +++ b/src/rl/sg/so/Scene.h @@ -27,6 +27,8 @@ #ifndef RL_SG_SO_SCENE_H #define RL_SG_SO_SCENE_H +#include + #include "../Scene.h" namespace rl diff --git a/tests/rlCollisionTest/rlCollisionTest.cpp b/tests/rlCollisionTest/rlCollisionTest.cpp index 974c0bab..0223485c 100644 --- a/tests/rlCollisionTest/rlCollisionTest.cpp +++ b/tests/rlCollisionTest/rlCollisionTest.cpp @@ -35,6 +35,8 @@ #include #include #include +#include + #ifdef RL_SG_BULLET #include #endif // RL_SG_BULLET @@ -103,8 +105,8 @@ main(int argc, char** argv) return EXIT_FAILURE; } - rl::mdl::XmlFactory factory; - std::shared_ptr model(factory.create(argv[2])); + rl::mdl::XmlFactory modelFactory; + std::shared_ptr model(modelFactory.create(argv[2])); rl::mdl::Kinematic* kinematics = dynamic_cast(model.get()); std::size_t dof = kinematics->getDof(); @@ -144,10 +146,12 @@ main(int argc, char** argv) sceneNames.push_back("solid"); #endif // RL_SG_SOLID + rl::sg::XmlFactory sceneFactory; + for (std::size_t i = 0; i < scenes.size(); ++i) { std::cout << "Loading " << sceneNames[i] << " scene" << std::endl; - scenes[i]->load(argv[1]); + sceneFactory.load(argv[1], scenes[i]); assert(scenes[i]->getModel(0)->getNumBodies() == kinematics->getBodies()); for (std::size_t b = 0; b < kinematics->getBodies(); ++b) { diff --git a/tests/rlCollisionTest/rlSceneCollisionTest.cpp b/tests/rlCollisionTest/rlSceneCollisionTest.cpp index 35106236..bda31625 100644 --- a/tests/rlCollisionTest/rlSceneCollisionTest.cpp +++ b/tests/rlCollisionTest/rlSceneCollisionTest.cpp @@ -29,6 +29,8 @@ #include #include #include +#include + #ifdef RL_SG_BULLET #include #endif // RL_SG_BULLET @@ -80,10 +82,12 @@ main(int argc, char** argv) sceneNames.push_back("solid"); #endif // RL_SG_SOLID + rl::sg::XmlFactory factory; + for (std::size_t i = 0; i < scenes.size(); ++i) { std::cout << "Loading " << sceneNames[i] << " scene" << std::endl; - scenes[i]->load(argv[1]); + factory.load(argv[1], scenes[i]); } std::cout << "Loading done." << std::endl; diff --git a/tests/rlEetTest/rlEetTest.cpp b/tests/rlEetTest/rlEetTest.cpp index 9628e6c6..6e18e12f 100644 --- a/tests/rlEetTest/rlEetTest.cpp +++ b/tests/rlEetTest/rlEetTest.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #ifdef RL_SG_BULLET #include @@ -88,7 +89,8 @@ main(int argc, char** argv) } #endif // RL_SG_SOLID - scene->load(argv[2]); + rl::sg::XmlFactory factory; + factory.load(argv[2], scene.get()); std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[3])); diff --git a/tests/rlPrmTest/rlPrmTest.cpp b/tests/rlPrmTest/rlPrmTest.cpp index 10628ce5..153d6edc 100644 --- a/tests/rlPrmTest/rlPrmTest.cpp +++ b/tests/rlPrmTest/rlPrmTest.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #ifdef RL_SG_BULLET #include @@ -98,7 +99,8 @@ main(int argc, char** argv) } #endif // RL_SG_SOLID - scene->load(argv[2]); + rl::sg::XmlFactory factory; + factory.load(argv[2], scene.get()); std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[3])); From 81d4566dae0d4928d2365fa1d8f14cbee4c06a27 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 8 Jul 2018 19:29:30 +0200 Subject: [PATCH 129/546] Add URDF factory to rl::sg --- src/rl/mdl/UrdfFactory.cpp | 2 +- src/rl/sg/CMakeLists.txt | 2 + src/rl/sg/UrdfFactory.cpp | 251 +++++++++++++++++++++++++++++++++++++ src/rl/sg/UrdfFactory.h | 53 ++++++++ 4 files changed, 307 insertions(+), 1 deletion(-) create mode 100644 src/rl/sg/UrdfFactory.cpp create mode 100644 src/rl/sg/UrdfFactory.h diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 2ac8c215..277ce598 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -101,7 +101,7 @@ ::std::cout << model->getName() << ::std::endl; ::std::cout << "link: " << j << ::std::endl; ::rl::xml::Path path(document, links[j]); - if (path.eval("count(inertial) > 0").getValue()) + if (path.eval("count(collision|inertial|visual) > 0").getValue()) { Body* b = new Body(); diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index a00c7002..52f16031 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -18,6 +18,7 @@ set( Scene.h Shape.h SimpleScene.h + UrdfFactory.h XmlFactory.h ) list(APPEND HDRS ${BASE_HDRS}) @@ -34,6 +35,7 @@ set( Scene.cpp Shape.cpp SimpleScene.cpp + UrdfFactory.cpp XmlFactory.cpp ) list(APPEND SRCS ${BASE_SRCS}) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp new file mode 100644 index 00000000..cd171424 --- /dev/null +++ b/src/rl/sg/UrdfFactory.cpp @@ -0,0 +1,251 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 // TODO +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "Body.h" +#include "Exception.h" +#include "Model.h" +#include "Scene.h" +#include "Shape.h" +#include "SimpleScene.h" +#include "UrdfFactory.h" + +namespace rl +{ + namespace sg + { + UrdfFactory::UrdfFactory() + { + } + + UrdfFactory::~UrdfFactory() + { + } + + void + UrdfFactory::load(const ::std::string& filename, Scene* scene) + { + ::rl::xml::DomParser parser; + + ::rl::xml::Document document = parser.readFile(filename, "", XML_PARSE_NOENT); + document.substitute(XML_PARSE_NOENT); + + ::rl::xml::Path path(document); + + ::rl::xml::NodeSet robots = path.eval("/robot").getValue< ::rl::xml::NodeSet>(); + + if (robots.empty()) + { + throw Exception("URDF is missing robot node"); + } + + for (int i = 0; i < robots.size(); ++i) + { + ::rl::xml::Path path(document, robots[i]); + + Model* model = scene->create(); + + // name + + model->setName(path.eval("string(@name)").getValue< ::std::string>()); +::std::cout << model->getName() << ::std::endl; + + // links + + ::rl::xml::NodeSet links = path.eval("link").getValue< ::rl::xml::NodeSet>(); + + for (int j = 0; j < links.size(); ++j) + { +::std::cout << "link: " << j << ::std::endl; + ::rl::xml::Path path(document, links[j]); + + Body* body = model->create(); + + body->setName(path.eval("string(@name)").getValue< ::std::string>()); +::std::cout << "\tname: " << body->getName() << ::std::endl; + + if (SimpleScene* simple = dynamic_cast(scene)) + { + if (path.eval("count(collision) > 0").getValue()) + { + path.setNode(path.eval("collision").getValue< ::rl::xml::NodeSet>()[0]); + } + else if (path.eval("count(visual) > 0").getValue()) + { + path.setNode(path.eval("visual").getValue< ::rl::xml::NodeSet>()[0]); + } + else + { + continue; + } + } + else + { + if (path.eval("count(visual) > 0").getValue()) + { + path.setNode(path.eval("visual").getValue< ::rl::xml::NodeSet>()[0]); + } + else if (path.eval("count(collision) > 0").getValue()) + { + path.setNode(path.eval("collision").getValue< ::rl::xml::NodeSet>()[0]); + } + else + { + continue; + } + } + + SoVRMLShape* vrmlShape = new SoVRMLShape(); + + SoVRMLAppearance* vrmlAppearance = new SoVRMLAppearance(); + vrmlShape->appearance = vrmlAppearance; + + SoVRMLMaterial* vrmlMaterial = new SoVRMLMaterial(); + vrmlAppearance->material = vrmlMaterial; + + ::rl::xml::NodeSet shapes = path.eval("geometry/box|geometry/cylinder|geometry/sphere").getValue< ::rl::xml::NodeSet>(); + + for (int k = 0; k < shapes.size(); ++k) + { + if ("box" == shapes[k].getName()) + { + SoVRMLBox* box = new SoVRMLBox(); + + if (!shapes[k].getProperty("size").empty()) + { + ::std::vector< ::std::string> size; + ::std::string tmp = shapes[k].getProperty("size"); + ::boost::split(size, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); + + box->size.setValue( + ::boost::lexical_cast< ::rl::math::Real>(size[0]), + ::boost::lexical_cast< ::rl::math::Real>(size[1]), + ::boost::lexical_cast< ::rl::math::Real>(size[2]) + ); + } + + vrmlShape->geometry = box; +::std::cout << "\tbox: " << box->size.getValue()[0] << ", " << box->size.getValue()[1] << ", " << box->size.getValue()[2] << ::std::endl; + } + else if ("cylinder" == shapes[k].getName()) + { + SoVRMLCylinder* cylinder = new SoVRMLCylinder(); + + if (!shapes[k].getProperty("length").empty()) + { + cylinder->height.setValue( + ::boost::lexical_cast< ::rl::math::Real>(shapes[k].getProperty("length")) + ); + } + + if (!shapes[k].getProperty("radius").empty()) + { + cylinder->radius.setValue( + ::boost::lexical_cast< ::rl::math::Real>(shapes[k].getProperty("radius")) + ); + } + + vrmlShape->geometry = cylinder; +::std::cout << "\tcylinder: " << cylinder->height.getValue() << ", " << cylinder->radius.getValue() << ::std::endl; + } + else if ("sphere" == shapes[k].getName()) + { + SoVRMLSphere* sphere = new SoVRMLSphere(); + + if (!shapes[k].getProperty("radius").empty()) + { + sphere->radius.setValue( + ::boost::lexical_cast< ::rl::math::Real>(shapes[k].getProperty("radius")) + ); + } + + vrmlShape->geometry = sphere; +::std::cout << "\tsphere: " << sphere->radius.getValue() << ::std::endl; + } + } + + Shape* shape = body->create(vrmlShape); + + ::rl::math::Transform origin = ::rl::math::Transform::Identity(); + + if (path.eval("count(origin/@rpy) > 0").getValue()) + { + ::std::vector< ::std::string> rpy; + ::std::string tmp = path.eval("string(origin/@rpy)").getValue< ::std::string>(); + ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); + + origin.linear() = ::rl::math::AngleAxis( + ::boost::lexical_cast< ::rl::math::Real>(rpy[2]), + ::rl::math::Vector3::UnitZ() + ) * ::rl::math::AngleAxis( + ::boost::lexical_cast< ::rl::math::Real>(rpy[1]), + ::rl::math::Vector3::UnitY() + ) * ::rl::math::AngleAxis( + ::boost::lexical_cast< ::rl::math::Real>(rpy[0]), + ::rl::math::Vector3::UnitX() + ).toRotationMatrix(); + } + + if (vrmlShape->geometry.getValue()->isOfType(SoVRMLCylinder::getClassTypeId())) + { + origin *= ::rl::math::AngleAxis(90.0f * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX()); + } + + if (path.eval("count(origin/@xyz) > 0").getValue()) + { + ::std::vector< ::std::string> xyz; + ::std::string tmp = path.eval("string(origin/@xyz)").getValue< ::std::string>(); + ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); + + origin.translation().x() = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); + origin.translation().y() = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); + origin.translation().z() = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); + } + + shape->setTransform(origin); + } + } + } + } +} diff --git a/src/rl/sg/UrdfFactory.h b/src/rl/sg/UrdfFactory.h new file mode 100644 index 00000000..f546aa93 --- /dev/null +++ b/src/rl/sg/UrdfFactory.h @@ -0,0 +1,53 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_SG_URDFFACTORY_H +#define RL_SG_URDFFACTORY_H + +#include "Factory.h" + +namespace rl +{ + namespace sg + { + class UrdfFactory : public Factory + { + public: + UrdfFactory(); + + virtual ~UrdfFactory(); + + void load(const ::std::string& filename, Scene* scene); + + protected: + + private: + + }; + } +} + +#endif // RL_SG_URDFFACTORY_H From 10ee3abb1fbe516b9a836266299eae2102cfad9d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 8 Jul 2018 19:29:53 +0200 Subject: [PATCH 130/546] Add support for XmlFactory and UrdfFactory in rlCoachMdl --- demos/rlCoachMdl/MainWindow.cpp | 33 ++++++++++++++++++++++++++++----- 1 file changed, 28 insertions(+), 5 deletions(-) diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index 1245bf20..d8926372 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -31,7 +31,9 @@ #include #include #include +#include #include +#include #include #include "ConfigurationDelegate.h" @@ -74,17 +76,38 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoDB::init(); SoGradientBackground::initClass(); - this->scene = std::make_shared(); - rl::sg::XmlFactory geometryFactory; - geometryFactory.load(QApplication::arguments()[1].toStdString(), this->scene.get()); + std::shared_ptr geometryFactory; + std::string geometryFilename = QApplication::arguments()[1].toStdString(); - rl::mdl::XmlFactory kinematicFactory; + if ("urdf" == geometryFilename.substr(geometryFilename.length() - 4, 4)) + { + geometryFactory = std::make_shared(); + } + else + { + geometryFactory = std::make_shared(); + } + + this->scene = std::make_shared(); + geometryFactory->load(geometryFilename, this->scene.get()); for (int i = 2; i < QApplication::arguments().size(); ++i) { + std::shared_ptr kinematicFactory; + std::string kinematicFilename = QApplication::arguments()[i].toStdString(); + + if ("urdf" == kinematicFilename.substr(kinematicFilename.length() - 4, 4)) + { + kinematicFactory = std::make_shared(); + } + else + { + kinematicFactory = std::make_shared(); + } + this->geometryModels.push_back(this->scene->getModel(i - 2)); std::shared_ptr kinematicModel; - kinematicModel.reset(kinematicFactory.create(QApplication::arguments()[i].toStdString())); + kinematicModel.reset(kinematicFactory->create(kinematicFilename)); this->kinematicModels.push_back(kinematicModel); } From f6b9130c114009520cbcb317e589cf71c4a62374 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Jul 2018 00:13:13 +0200 Subject: [PATCH 131/546] Use unordered_map in rl::mdl::UrdfFactory --- src/rl/mdl/UrdfFactory.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 277ce598..bb23ca90 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -25,7 +25,7 @@ // #include // TODO -#include +#include #include #include #include @@ -94,7 +94,7 @@ ::std::cout << model->getName() << ::std::endl; ::rl::xml::NodeSet links = path.eval("link").getValue< ::rl::xml::NodeSet>(); - ::std::map< ::std::string, Frame*> name2frame; + ::std::unordered_map< ::std::string, Frame*> name2frame; for (int j = 0; j < links.size(); ++j) { @@ -165,7 +165,7 @@ ::std::cout << "\tname: " << f->getName() << ::std::endl; // joints - ::std::map< ::std::string, ::std::string> child2parent; + ::std::unordered_map< ::std::string, ::std::string> child2parent; ::rl::xml::NodeSet joints = path.eval("joint").getValue< ::rl::xml::NodeSet>(); @@ -329,7 +329,7 @@ ::std::cout << "\tname: " << r->getName() << ::std::endl; Frame* root = nullptr; - for (::std::map< ::std::string, Frame*>::const_iterator frame = name2frame.begin(); frame != name2frame.end(); ++frame) + for (::std::unordered_map< ::std::string, Frame*>::const_iterator frame = name2frame.begin(); frame != name2frame.end(); ++frame) { if (child2parent.end() == child2parent.find(frame->first)) { From 970a23f086acd24ea81a4056e6094dc413d7b371 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Jul 2018 00:13:56 +0200 Subject: [PATCH 132/546] Parse materials in rl::sg::UrdfFactory --- src/rl/sg/UrdfFactory.cpp | 74 ++++++++++++++++++++++++++++++++++++--- 1 file changed, 70 insertions(+), 4 deletions(-) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index cd171424..c9cf3047 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -25,6 +25,7 @@ // #include // TODO +#include #include #include #include @@ -91,6 +92,40 @@ namespace rl model->setName(path.eval("string(@name)").getValue< ::std::string>()); ::std::cout << model->getName() << ::std::endl; + // materials + + ::rl::xml::NodeSet materials = path.eval("material").getValue< ::rl::xml::NodeSet>(); + + ::std::unordered_map< ::std::string, SoVRMLMaterial*> name2material; + + for (int j = 0; j < materials.size(); ++j) + { +::std::cout << "material: " << j << ::std::endl; + ::rl::xml::Path path(document, materials[j]); + + if (path.eval("count(color/@rgba) > 0").getValue()) + { + ::std::vector< ::std::string> rgba; + ::std::string tmp = path.eval("string(color/@rgba)").getValue< ::std::string>(); + ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); +::std::cout << "\trgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; + + SoVRMLMaterial* vrmlMaterial = new SoVRMLMaterial(); + + vrmlMaterial->diffuseColor.setValue( + ::boost::lexical_cast< ::rl::math::Real>(rgba[0]), + ::boost::lexical_cast< ::rl::math::Real>(rgba[1]), + ::boost::lexical_cast< ::rl::math::Real>(rgba[2]) + ); + vrmlMaterial->transparency.setValue( + 1.0f - ::boost::lexical_cast< ::rl::math::Real>(rgba[3]) + ); + + name2material[path.eval("string(@name)").getValue< ::std::string>()] = vrmlMaterial; +::std::cout << "\tname: " << path.eval("string(@name)").getValue< ::std::string>() << ::std::endl; + } + } + // links ::rl::xml::NodeSet links = path.eval("link").getValue< ::rl::xml::NodeSet>(); @@ -141,8 +176,36 @@ ::std::cout << "\tname: " << body->getName() << ::std::endl; SoVRMLAppearance* vrmlAppearance = new SoVRMLAppearance(); vrmlShape->appearance = vrmlAppearance; - SoVRMLMaterial* vrmlMaterial = new SoVRMLMaterial(); - vrmlAppearance->material = vrmlMaterial; + if (path.eval("count(material/color/@rgba) > 0").getValue()) + { + ::std::vector< ::std::string> rgba; + ::std::string tmp = path.eval("string(material/color/@rgba)").getValue< ::std::string>(); + ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); +::std::cout << "\tmaterial rgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; + + SoVRMLMaterial* vrmlMaterial = new SoVRMLMaterial(); + + vrmlMaterial->diffuseColor.setValue( + ::boost::lexical_cast< ::rl::math::Real>(rgba[0]), + ::boost::lexical_cast< ::rl::math::Real>(rgba[1]), + ::boost::lexical_cast< ::rl::math::Real>(rgba[2]) + ); + vrmlMaterial->transparency.setValue( + 1.0f - ::boost::lexical_cast< ::rl::math::Real>(rgba[3]) + ); + + vrmlAppearance->material = vrmlMaterial; + } + else if (path.eval("count(material/@name) > 0").getValue()) + { +::std::cout << "\tmaterial name: " << path.eval("string(material/@name)").getValue< ::std::string>() << ::std::endl; + vrmlAppearance->material = name2material[path.eval("string(material/@name)").getValue< ::std::string>()]; + } + else + { + SoVRMLMaterial* vrmlMaterial = new SoVRMLMaterial(); + vrmlAppearance->material = vrmlMaterial; + } ::rl::xml::NodeSet shapes = path.eval("geometry/box|geometry/cylinder|geometry/sphere").getValue< ::rl::xml::NodeSet>(); @@ -166,7 +229,7 @@ ::std::cout << "\tname: " << body->getName() << ::std::endl; } vrmlShape->geometry = box; -::std::cout << "\tbox: " << box->size.getValue()[0] << ", " << box->size.getValue()[1] << ", " << box->size.getValue()[2] << ::std::endl; +::std::cout << "\tbox: " << box->size.getValue()[0] << " " << box->size.getValue()[1] << " " << box->size.getValue()[2] << ::std::endl; } else if ("cylinder" == shapes[k].getName()) { @@ -187,7 +250,7 @@ ::std::cout << "\tbox: " << box->size.getValue()[0] << ", " << box->size.getValu } vrmlShape->geometry = cylinder; -::std::cout << "\tcylinder: " << cylinder->height.getValue() << ", " << cylinder->radius.getValue() << ::std::endl; +::std::cout << "\tcylinder: " << cylinder->height.getValue() << " " << cylinder->radius.getValue() << ::std::endl; } else if ("sphere" == shapes[k].getName()) { @@ -214,6 +277,7 @@ ::std::cout << "\tsphere: " << sphere->radius.getValue() << ::std::endl; ::std::vector< ::std::string> rpy; ::std::string tmp = path.eval("string(origin/@rpy)").getValue< ::std::string>(); ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); +::std::cout << "\trpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << ::std::endl; origin.linear() = ::rl::math::AngleAxis( ::boost::lexical_cast< ::rl::math::Real>(rpy[2]), @@ -237,11 +301,13 @@ ::std::cout << "\tsphere: " << sphere->radius.getValue() << ::std::endl; ::std::vector< ::std::string> xyz; ::std::string tmp = path.eval("string(origin/@xyz)").getValue< ::std::string>(); ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); +::std::cout << "\txyz: " << xyz[0] << " " << xyz[1] << " " << xyz[2] << ::std::endl; origin.translation().x() = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); origin.translation().y() = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); origin.translation().z() = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); } +::std::cout << "\torigin:" << ::std::endl << origin.matrix() << ::std::endl; shape->setTransform(origin); } From 9bcf3e7eb05deeb7d998aa3a2d10891962003031 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Jul 2018 15:50:04 +0200 Subject: [PATCH 133/546] Parse continuous URDF joints --- src/rl/mdl/UrdfFactory.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index bb23ca90..5acc1479 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -282,7 +282,7 @@ ::std::cout << "\taxis: " << p->S(3, 0) << " " << p->S(4, 0) << " " << p->S(5, 0 p->setName(path.eval("string(@name)").getValue< ::std::string>()); ::std::cout << "\tname: " << p->getName() << ::std::endl; } - else if ("revolute" == type) + else if ("revolute" == type || "continuous" == type) { Revolute* r = new Revolute(); From ef7f71dc23179f5d89d06f3875fdda6d016d28f5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Jul 2018 15:50:32 +0200 Subject: [PATCH 134/546] Add support for STL meshes in rl::sg::UrdfFactory --- src/rl/sg/UrdfFactory.cpp | 147 ++++++++++++++++++++++++++------------ 1 file changed, 101 insertions(+), 46 deletions(-) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index c9cf3047..681f122c 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -27,11 +27,16 @@ #include // TODO #include #include -#include +#include +#include +#include +#include +#include #include #include #include #include +#include #include #include #include @@ -96,7 +101,7 @@ ::std::cout << model->getName() << ::std::endl; ::rl::xml::NodeSet materials = path.eval("material").getValue< ::rl::xml::NodeSet>(); - ::std::unordered_map< ::std::string, SoVRMLMaterial*> name2material; + ::std::unordered_map< ::std::string, ::SoVRMLMaterial*> name2material; for (int j = 0; j < materials.size(); ++j) { @@ -110,7 +115,7 @@ ::std::cout << "material: " << j << ::std::endl; ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\trgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; - SoVRMLMaterial* vrmlMaterial = new SoVRMLMaterial(); + ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); vrmlMaterial->diffuseColor.setValue( ::boost::lexical_cast< ::rl::math::Real>(rgba[0]), @@ -171,9 +176,10 @@ ::std::cout << "\tname: " << body->getName() << ::std::endl; } } - SoVRMLShape* vrmlShape = new SoVRMLShape(); + ::SoVRMLShape* vrmlShape = new ::SoVRMLShape(); + vrmlShape->ref(); - SoVRMLAppearance* vrmlAppearance = new SoVRMLAppearance(); + ::SoVRMLAppearance* vrmlAppearance = new ::SoVRMLAppearance(); vrmlShape->appearance = vrmlAppearance; if (path.eval("count(material/color/@rgba) > 0").getValue()) @@ -183,7 +189,7 @@ ::std::cout << "\tname: " << body->getName() << ::std::endl; ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\tmaterial rgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; - SoVRMLMaterial* vrmlMaterial = new SoVRMLMaterial(); + ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); vrmlMaterial->diffuseColor.setValue( ::boost::lexical_cast< ::rl::math::Real>(rgba[0]), @@ -203,17 +209,17 @@ ::std::cout << "\tmaterial name: " << path.eval("string(material/@name)").getVal } else { - SoVRMLMaterial* vrmlMaterial = new SoVRMLMaterial(); + ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); vrmlAppearance->material = vrmlMaterial; } - ::rl::xml::NodeSet shapes = path.eval("geometry/box|geometry/cylinder|geometry/sphere").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet shapes = path.eval("geometry/box|geometry/cylinder|geometry/mesh|geometry/sphere").getValue< ::rl::xml::NodeSet>(); for (int k = 0; k < shapes.size(); ++k) { if ("box" == shapes[k].getName()) { - SoVRMLBox* box = new SoVRMLBox(); + ::SoVRMLBox* box = new ::SoVRMLBox(); if (!shapes[k].getProperty("size").empty()) { @@ -233,7 +239,7 @@ ::std::cout << "\tbox: " << box->size.getValue()[0] << " " << box->size.getValue } else if ("cylinder" == shapes[k].getName()) { - SoVRMLCylinder* cylinder = new SoVRMLCylinder(); + ::SoVRMLCylinder* cylinder = new ::SoVRMLCylinder(); if (!shapes[k].getProperty("length").empty()) { @@ -252,9 +258,53 @@ ::std::cout << "\tbox: " << box->size.getValue()[0] << " " << box->size.getValue vrmlShape->geometry = cylinder; ::std::cout << "\tcylinder: " << cylinder->height.getValue() << " " << cylinder->radius.getValue() << ::std::endl; } + else if ("mesh" == shapes[k].getName()) + { + if (!shapes[k].getProperty("filename").empty()) + { + ::std::string filename = shapes[k].getLocalPath(shapes[k].getProperty("filename")); +::std::cout << "\tmesh: " << filename << ::std::endl; + + if (!boost::iequals("stl", filename.substr(filename.length() - 3, 3))) + { + throw Exception("Only STL meshes currently supported"); + } + + ::SoSTLFileKit* stlFileKit = new ::SoSTLFileKit(); + stlFileKit->ref(); + stlFileKit->readFile(filename.c_str()); + ::SoSeparator* stl = stlFileKit->convert(); + stl->ref(); + stlFileKit->unref(); + + ::SoToVRML2Action toVrml2Action; + toVrml2Action.apply(stl); + ::SoVRMLGroup* vrml2 = toVrml2Action.getVRML2SceneGraph(); + vrml2->ref(); + stl->unref(); + + ::SoSearchAction searchAction; + searchAction.setInterest(::SoSearchAction::ALL); + searchAction.setType(::SoVRMLShape::getClassTypeId()); + searchAction.apply(vrml2); + + for (int l = 0; l < searchAction.getPaths().getLength(); ++l) + { + vrmlShape->geometry = static_cast< ::SoVRMLShape*>(static_cast< ::SoFullPath*>(searchAction.getPaths()[l])->getTail())->geometry; + + if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLIndexedFaceSet::getClassTypeId())) + { + SoVRMLIndexedFaceSet* vrmlIndexedFaceSet = static_cast(vrmlShape->geometry.getValue()); + vrmlIndexedFaceSet->convex.setValue(false); + } + } + + vrml2->unref(); + } + } else if ("sphere" == shapes[k].getName()) { - SoVRMLSphere* sphere = new SoVRMLSphere(); + ::SoVRMLSphere* sphere = new ::SoVRMLSphere(); if (!shapes[k].getProperty("radius").empty()) { @@ -268,48 +318,53 @@ ::std::cout << "\tsphere: " << sphere->radius.getValue() << ::std::endl; } } - Shape* shape = body->create(vrmlShape); - - ::rl::math::Transform origin = ::rl::math::Transform::Identity(); - - if (path.eval("count(origin/@rpy) > 0").getValue()) + if (nullptr != vrmlShape->geometry.getValue()) { - ::std::vector< ::std::string> rpy; - ::std::string tmp = path.eval("string(origin/@rpy)").getValue< ::std::string>(); - ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); + Shape* shape = body->create(vrmlShape); + + ::rl::math::Transform origin = ::rl::math::Transform::Identity(); + + if (path.eval("count(origin/@rpy) > 0").getValue()) + { + ::std::vector< ::std::string> rpy; + ::std::string tmp = path.eval("string(origin/@rpy)").getValue< ::std::string>(); + ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\trpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << ::std::endl; + + origin.linear() = ::rl::math::AngleAxis( + ::boost::lexical_cast< ::rl::math::Real>(rpy[2]), + ::rl::math::Vector3::UnitZ() + ) * ::rl::math::AngleAxis( + ::boost::lexical_cast< ::rl::math::Real>(rpy[1]), + ::rl::math::Vector3::UnitY() + ) * ::rl::math::AngleAxis( + ::boost::lexical_cast< ::rl::math::Real>(rpy[0]), + ::rl::math::Vector3::UnitX() + ).toRotationMatrix(); + } - origin.linear() = ::rl::math::AngleAxis( - ::boost::lexical_cast< ::rl::math::Real>(rpy[2]), - ::rl::math::Vector3::UnitZ() - ) * ::rl::math::AngleAxis( - ::boost::lexical_cast< ::rl::math::Real>(rpy[1]), - ::rl::math::Vector3::UnitY() - ) * ::rl::math::AngleAxis( - ::boost::lexical_cast< ::rl::math::Real>(rpy[0]), - ::rl::math::Vector3::UnitX() - ).toRotationMatrix(); - } - - if (vrmlShape->geometry.getValue()->isOfType(SoVRMLCylinder::getClassTypeId())) - { - origin *= ::rl::math::AngleAxis(90.0f * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX()); - } - - if (path.eval("count(origin/@xyz) > 0").getValue()) - { - ::std::vector< ::std::string> xyz; - ::std::string tmp = path.eval("string(origin/@xyz)").getValue< ::std::string>(); - ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); + if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLCylinder::getClassTypeId())) + { + origin *= ::rl::math::AngleAxis(90.0f * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX()); + } + + if (path.eval("count(origin/@xyz) > 0").getValue()) + { + ::std::vector< ::std::string> xyz; + ::std::string tmp = path.eval("string(origin/@xyz)").getValue< ::std::string>(); + ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\txyz: " << xyz[0] << " " << xyz[1] << " " << xyz[2] << ::std::endl; + + origin.translation().x() = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); + origin.translation().y() = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); + origin.translation().z() = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); + } +::std::cout << "\torigin:" << ::std::endl << origin.matrix() << ::std::endl; - origin.translation().x() = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); - origin.translation().y() = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); - origin.translation().z() = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); + shape->setTransform(origin); } -::std::cout << "\torigin:" << ::std::endl << origin.matrix() << ::std::endl; - shape->setTransform(origin); + vrmlShape->unref(); } } } From f6a0ec56b1003e7ba6a48c7af903d0012cab8d2a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Jul 2018 15:54:45 +0200 Subject: [PATCH 135/546] Parse all links as bodies in rl::mdl::UrdfFactory --- src/rl/mdl/UrdfFactory.cpp | 92 ++++++++++++++++---------------------- 1 file changed, 39 insertions(+), 53 deletions(-) diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 5acc1479..1c6acc62 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -101,66 +101,52 @@ ::std::cout << model->getName() << ::std::endl; ::std::cout << "link: " << j << ::std::endl; ::rl::xml::Path path(document, links[j]); - if (path.eval("count(collision|inertial|visual) > 0").getValue()) + Body* b = new Body(); + + model->add(b); + + if (path.eval("count(inertial/origin/@xyz) > 0").getValue()) { - Body* b = new Body(); - - model->add(b); - - if (path.eval("count(inertial/origin/@xyz) > 0").getValue()) - { - ::std::vector< ::std::string> xyz; - ::std::string tmp = path.eval("string(inertial/origin/@xyz)").getValue< ::std::string>(); - ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); - - b->setCenterOfMass( - ::boost::lexical_cast< ::rl::math::Real>(xyz[0]), - ::boost::lexical_cast< ::rl::math::Real>(xyz[1]), - ::boost::lexical_cast< ::rl::math::Real>(xyz[2]) - ); - } - else - { - b->setCenterOfMass(0, 0, 0); - } -::std::cout << "\tcog: " << b->cm.transpose() << ::std::endl; - - if (path.eval("count(inertial/origin/@abc) > 0").getValue()) - { - throw Exception("URDF link/inertial/origin/@abc not supported"); - } - - b->setInertia( - path.eval("number(inertial/inertia/@ixx)").getValue< ::rl::math::Real>(1), - path.eval("number(inertial/inertia/@iyy)").getValue< ::rl::math::Real>(1), - path.eval("number(inertial/inertia/@izz)").getValue< ::rl::math::Real>(1), - path.eval("number(inertial/inertia/@iyz)").getValue< ::rl::math::Real>(0), - path.eval("number(inertial/inertia/@ixz)").getValue< ::rl::math::Real>(0), - path.eval("number(inertial/inertia/@ixy)").getValue< ::rl::math::Real>(0) - ); -::std::cout << "\tinertia: " << b->ic.voigt6().transpose() << ::std::endl; + ::std::vector< ::std::string> xyz; + ::std::string tmp = path.eval("string(inertial/origin/@xyz)").getValue< ::std::string>(); + ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); - b->setMass( - path.eval("number(inertial/mass/@value)").getValue< ::rl::math::Real>(1) + b->setCenterOfMass( + ::boost::lexical_cast< ::rl::math::Real>(xyz[0]), + ::boost::lexical_cast< ::rl::math::Real>(xyz[1]), + ::boost::lexical_cast< ::rl::math::Real>(xyz[2]) ); -::std::cout << "\tmass: " << b->m << ::std::endl; - - b->setName(path.eval("string(@name)").getValue< ::std::string>()); -::std::cout << "\tname: " << b->getName() << ::std::endl; - - name2frame[path.eval("string(@name)").getValue< ::std::string>()] = b; } else { - Frame* f = new Frame(); - - model->add(f); - - f->setName(path.eval("string(@name)").getValue< ::std::string>()); -::std::cout << "\tname: " << f->getName() << ::std::endl; - - name2frame[path.eval("string(@name)").getValue< ::std::string>()] = f; + b->setCenterOfMass(0, 0, 0); } +::std::cout << "\tcog: " << b->cm.transpose() << ::std::endl; + + if (path.eval("count(inertial/origin/@abc) > 0").getValue()) + { + throw Exception("URDF link/inertial/origin/@abc not supported"); + } + + b->setInertia( + path.eval("number(inertial/inertia/@ixx)").getValue< ::rl::math::Real>(1), + path.eval("number(inertial/inertia/@iyy)").getValue< ::rl::math::Real>(1), + path.eval("number(inertial/inertia/@izz)").getValue< ::rl::math::Real>(1), + path.eval("number(inertial/inertia/@iyz)").getValue< ::rl::math::Real>(0), + path.eval("number(inertial/inertia/@ixz)").getValue< ::rl::math::Real>(0), + path.eval("number(inertial/inertia/@ixy)").getValue< ::rl::math::Real>(0) + ); +::std::cout << "\tinertia: " << b->ic.voigt6().transpose() << ::std::endl; + + b->setMass( + path.eval("number(inertial/mass/@value)").getValue< ::rl::math::Real>(1) + ); +::std::cout << "\tmass: " << b->m << ::std::endl; + + b->setName(path.eval("string(@name)").getValue< ::std::string>()); +::std::cout << "\tname: " << b->getName() << ::std::endl; + + name2frame[path.eval("string(@name)").getValue< ::std::string>()] = b; } // joints From a7b641e0d9b032fd6cba37af1a7629a889a1d4b2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Jul 2018 16:25:56 +0200 Subject: [PATCH 136/546] Add reference counting for material map --- src/rl/sg/UrdfFactory.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 681f122c..596fe38b 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -116,6 +116,7 @@ ::std::cout << "material: " << j << ::std::endl; ::std::cout << "\trgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); + vrmlMaterial->ref(); vrmlMaterial->diffuseColor.setValue( ::boost::lexical_cast< ::rl::math::Real>(rgba[0]), @@ -366,6 +367,11 @@ ::std::cout << "\torigin:" << ::std::endl << origin.matrix() << ::std::endl; vrmlShape->unref(); } + + for (::std::unordered_map< ::std::string, ::SoVRMLMaterial*>::iterator j = name2material.begin(); j != name2material.end(); ++j) + { + j->second->unref(); + } } } } From 20039cb3cea1756770fbac7e6a5c59ffab999148 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Jul 2018 18:53:48 +0200 Subject: [PATCH 137/546] Parse URDF geometries in DFS order to match kinematics --- src/rl/sg/UrdfFactory.cpp | 85 ++++++++++++++++++++++++++++++++++----- 1 file changed, 74 insertions(+), 11 deletions(-) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 596fe38b..30f46485 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -24,7 +24,9 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include // TODO +#include +#include // TODO remove +#include #include #include #include @@ -132,18 +134,68 @@ ::std::cout << "\tname: " << path.eval("string(@name)").getValue< ::std::string> } } + // joints + + ::std::unordered_map< ::std::string, ::std::string> child2parent; + ::std::unordered_map< ::std::string, ::rl::xml::Node> name2link; + ::std::multimap< ::std::string, ::std::string> parent2child; + + ::rl::xml::NodeSet joints = path.eval("joint").getValue< ::rl::xml::NodeSet>(); + + for (int j = 0; j < joints.size(); ++j) + { +::std::cout << "joint: " << j << ::std::endl; + ::rl::xml::Path path(document, joints[j]); + + ::std::string child = path.eval("string(child/@link)").getValue< ::std::string>(); + ::std::string parent = path.eval("string(parent/@link)").getValue< ::std::string>(); + + child2parent[child] = parent; + parent2child.insert(::std::pair< ::std::string, ::std::string>(parent, child)); +::std::cout << "\tconnect: " << parent << " -> " << child << ::std::endl; + } + // links ::rl::xml::NodeSet links = path.eval("link").getValue< ::rl::xml::NodeSet>(); + ::std::string root; + for (int j = 0; j < links.size(); ++j) { -::std::cout << "link: " << j << ::std::endl; ::rl::xml::Path path(document, links[j]); + ::std::string name = path.eval("string(@name)").getValue< ::std::string>(); + + name2link[name] = links[j]; + + if (child2parent.end() == child2parent.find(name)) + { + if (root.empty()) + { + root = name; +::std::cout << "root: " << name << ::std::endl; + } + else + { + throw Exception("URDF has more than one root node"); + } + } + } + + ::std::deque< ::std::string> dfs; + dfs.push_front(root); + + while (!dfs.empty()) + { + ::std::string name = dfs.front(); +::std::cout << "link: " << name << ::std::endl; + + ::rl::xml::Path path(document, name2link[name]); + Body* body = model->create(); - body->setName(path.eval("string(@name)").getValue< ::std::string>()); + body->setName(name); ::std::cout << "\tname: " << body->getName() << ::std::endl; if (SimpleScene* simple = dynamic_cast(scene)) @@ -156,10 +208,6 @@ ::std::cout << "\tname: " << body->getName() << ::std::endl; { path.setNode(path.eval("visual").getValue< ::rl::xml::NodeSet>()[0]); } - else - { - continue; - } } else { @@ -171,10 +219,6 @@ ::std::cout << "\tname: " << body->getName() << ::std::endl; { path.setNode(path.eval("collision").getValue< ::rl::xml::NodeSet>()[0]); } - else - { - continue; - } } ::SoVRMLShape* vrmlShape = new ::SoVRMLShape(); @@ -366,6 +410,25 @@ ::std::cout << "\torigin:" << ::std::endl << origin.matrix() << ::std::endl; } vrmlShape->unref(); + + // depth first search + + dfs.pop_front(); + + ::std::pair< + ::std::multimap< ::std::string, ::std::string>::const_iterator, + ::std::multimap< ::std::string, ::std::string>::const_iterator + > range = parent2child.equal_range(name); + + // reverse order + + ::std::multimap< ::std::string, ::std::string>::const_iterator first = --range.second; + ::std::multimap< ::std::string, ::std::string>::const_iterator second = --range.first; + + for (::std::multimap< ::std::string, ::std::string>::const_iterator k = first; k != second; --k) + { + dfs.push_front(k->second); + } } for (::std::unordered_map< ::std::string, ::SoVRMLMaterial*>::iterator j = name2material.begin(); j != name2material.end(); ++j) From 2b8f8220a90bf35383d7b6fc0d2b306bd3f1e9e9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 10 Jul 2018 10:32:20 +0200 Subject: [PATCH 138/546] Update exception handling messages in factories --- src/rl/mdl/UrdfFactory.cpp | 14 +++++++------- src/rl/mdl/XmlFactory.cpp | 20 ++++++++++---------- src/rl/sg/UrdfFactory.cpp | 13 +++++++++---- src/rl/sg/XmlFactory.cpp | 8 ++++---- 4 files changed, 30 insertions(+), 25 deletions(-) diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 1c6acc62..860bb6bc 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -80,7 +80,7 @@ namespace rl if (robots.empty()) { - throw Exception("URDF is missing robot node"); + throw Exception("rl::mdl::UrdfFactory::load() - URDF is missing robot node"); } path.setNode(robots[0]); @@ -125,7 +125,7 @@ ::std::cout << "\tcog: " << b->cm.transpose() << ::std::endl; if (path.eval("count(inertial/origin/@abc) > 0").getValue()) { - throw Exception("URDF link/inertial/origin/@abc not supported"); + throw Exception("rl::mdl::UrdfFactory::load() - URDF link/inertial/origin/@abc not supported"); } b->setInertia( @@ -169,7 +169,7 @@ ::std::cout << "\tchild: " << child->getName() << ::std::endl; if (nullptr == parent || nullptr == child) { - throw Exception("URDF joint has missing parent or child link"); + throw Exception("rl::mdl::UrdfFactory::load() - URDF joint has missing parent or child link"); } // frame @@ -225,11 +225,11 @@ ::std::cout << "\tname: " << fixed->getName() << ::std::endl; } else if ("floating" == type) { - throw Exception("URDF floating joint not supported"); + throw Exception("rl::mdl::UrdfFactory::load() - URDF floating joint not supported"); } else if ("planar" == type) { - throw Exception("URDF planar joint not supported"); + throw Exception("rl::mdl::UrdfFactory::load() - URDF planar joint not supported"); } else if ("prismatic" == type) { @@ -328,14 +328,14 @@ ::std::cout << "root: " << root->getName() << ::std::endl; } else { - throw Exception("URDF has more than one root node"); + throw Exception("rl::mdl::UrdfFactory::load() - URDF has more than one root node"); } } } if (nullptr == root) { - throw Exception("URDF has no root node"); + throw Exception("rl::mdl::UrdfFactory::load() - URDF has no root node"); } model->update(); diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index d4d7e493..aab01701 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -184,7 +184,7 @@ namespace rl if (id2frame.find(frame->getName()) != id2frame.end()) { - throw Exception("Frame with ID " + frame->getName() + " not unique in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Frame with ID " + frame->getName() + " not unique in file " + filename); } id2frame[frame->getName()] = frame; @@ -203,7 +203,7 @@ namespace rl if (id2frame.find(b1Id) == id2frame.end()) { - throw Exception("Body with ID " + b1Id + " not found in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Body with ID " + b1Id + " not found in file " + filename); } Body* b1 = dynamic_cast(id2frame[b1Id]); @@ -218,7 +218,7 @@ namespace rl if (id2frame.find(b2IdRef) == id2frame.end()) { - throw Exception("Body with IDREF " + b2IdRef + " in Body with ID " + b1Id + " not found in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Body with IDREF " + b2IdRef + " in Body with ID " + b1Id + " not found in file " + filename); } Body* b2 = dynamic_cast(id2frame[b2IdRef]); @@ -248,7 +248,7 @@ namespace rl if (id2frame.find(aIdRef) == id2frame.end()) { - throw Exception("Frame A with IDREF " + aIdRef + " in Transform with ID " + name + " not found in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Frame A with IDREF " + aIdRef + " in Transform with ID " + name + " not found in file " + filename); } Frame* a = id2frame[aIdRef]; @@ -257,7 +257,7 @@ namespace rl if (id2frame.find(bIdRef) == id2frame.end()) { - throw Exception("Frame B with IDREF " + bIdRef + " in Transform with ID " + name + " not found in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Frame B with IDREF " + bIdRef + " in Transform with ID " + name + " not found in file " + filename); } Frame* b = id2frame[bIdRef]; @@ -424,7 +424,7 @@ namespace rl { if (home.size() != model->getDofPosition()) { - throw Exception("Incorrect size of home position vector in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect size of home position vector in file " + filename); } ::rl::math::Vector q(home.size()); @@ -453,7 +453,7 @@ namespace rl if (m != model->getDofPosition()) { - throw Exception("Incorrect number of rows in gamma position matrix in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of rows in gamma position matrix in file " + filename); } ::rl::math::Matrix G(m, n); @@ -466,7 +466,7 @@ namespace rl if (path.eval("count(col)").getValue< ::std::size_t>(0) != model->getDofPosition()) { - throw Exception("Incorrect number of columns in gamma position matrix in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of columns in gamma position matrix in file " + filename); } ::rl::xml::NodeSet cols = path.eval("col").getValue< ::rl::xml::NodeSet>(); @@ -491,7 +491,7 @@ namespace rl if (m != model->getDof()) { - throw Exception("Incorrect number of rows in gamma velocity matrix in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of rows in gamma velocity matrix in file " + filename); } ::rl::math::Matrix G(m, n); @@ -504,7 +504,7 @@ namespace rl if (path.eval("count(col)").getValue< ::std::size_t>(0) != model->getDof()) { - throw Exception("Incorrect number of columns in gamma velocity matrix in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of columns in gamma velocity matrix in file " + filename); } ::rl::xml::NodeSet cols = path.eval("col").getValue< ::rl::xml::NodeSet>(); diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 30f46485..1f342fa3 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -85,7 +85,7 @@ namespace rl if (robots.empty()) { - throw Exception("URDF is missing robot node"); + throw Exception("rl::sg::UrdfFactory::load() - URDF is missing robot node"); } for (int i = 0; i < robots.size(); ++i) @@ -178,7 +178,7 @@ ::std::cout << "root: " << name << ::std::endl; } else { - throw Exception("URDF has more than one root node"); + throw Exception("rl::sg::UrdfFactory::load() - URDF has more than one root node"); } } } @@ -312,12 +312,17 @@ ::std::cout << "\tmesh: " << filename << ::std::endl; if (!boost::iequals("stl", filename.substr(filename.length() - 3, 3))) { - throw Exception("Only STL meshes currently supported"); + throw Exception("rl::sg::UrdfFactory::load() - Only STL meshes currently supported"); } ::SoSTLFileKit* stlFileKit = new ::SoSTLFileKit(); stlFileKit->ref(); - stlFileKit->readFile(filename.c_str()); + + if (!stlFileKit->readFile(filename.c_str())) + { + throw Exception("rl::sg::UrdfFactory::load() - Failed to open file '" + filename + "'"); + } + ::SoSeparator* stl = stlFileKit->convert(); stl->ref(); stlFileKit->unref(); diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp index 04ff0334..6b4e1efb 100644 --- a/src/rl/sg/XmlFactory.cpp +++ b/src/rl/sg/XmlFactory.cpp @@ -81,14 +81,14 @@ namespace rl if (!input.openFile(scenes[i].getLocalPath(scenes[i].getProperty("href")).c_str() ,true)) { - throw Exception("::rl::sg::XmlFactory::load() - failed to open file"); + throw Exception("rl::sg::XmlFactory::load() - Failed to open file"); } ::SoVRMLGroup* root = SoDB::readAllVRML(&input); if (nullptr == root) { - throw Exception("::rl::sg::XmlFactory::load() - failed to read file"); + throw Exception("rl::sg::XmlFactory::load() - Failed to read file"); } ::SbViewportRegion viewportRegion; @@ -156,7 +156,7 @@ namespace rl { if (::std::abs(bodyScaleFactor[l] - 1.0f) > 1.0e-6f) { - throw Exception("::rl::sg::XmlFactory::load() - bodyScaleFactor not supported"); + throw Exception("rl::sg::XmlFactory::load() - bodyScaleFactor not supported"); } } } @@ -220,7 +220,7 @@ namespace rl { if (::std::abs(shapeScaleFactor[m] - 1.0f) > 1.0e-6f) { - throw Exception("::rl::sg::XmlFactory::load() - shapeScaleFactor not supported"); + throw Exception("rl::sg::XmlFactory::load() - shapeScaleFactor not supported"); } } } From 4969e297c7c6820508b07bbc9a576cbbbef7cf61 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 10 Jul 2018 18:12:59 +0200 Subject: [PATCH 139/546] Update debug output --- src/rl/sg/UrdfFactory.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 1f342fa3..93008db6 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -280,7 +280,7 @@ ::std::cout << "\tmaterial name: " << path.eval("string(material/@name)").getVal } vrmlShape->geometry = box; -::std::cout << "\tbox: " << box->size.getValue()[0] << " " << box->size.getValue()[1] << " " << box->size.getValue()[2] << ::std::endl; +::std::cout << "\tbox size: " << box->size.getValue()[0] << " " << box->size.getValue()[1] << " " << box->size.getValue()[2] << ::std::endl; } else if ("cylinder" == shapes[k].getName()) { @@ -301,14 +301,15 @@ ::std::cout << "\tbox: " << box->size.getValue()[0] << " " << box->size.getValue } vrmlShape->geometry = cylinder; -::std::cout << "\tcylinder: " << cylinder->height.getValue() << " " << cylinder->radius.getValue() << ::std::endl; +::std::cout << "\tcylinder height: " << cylinder->height.getValue() << ::std::endl; +::std::cout << "\tcylinder radius: " << cylinder->radius.getValue() << ::std::endl; } else if ("mesh" == shapes[k].getName()) { if (!shapes[k].getProperty("filename").empty()) { ::std::string filename = shapes[k].getLocalPath(shapes[k].getProperty("filename")); -::std::cout << "\tmesh: " << filename << ::std::endl; +::std::cout << "\tmesh filename: " << filename << ::std::endl; if (!boost::iequals("stl", filename.substr(filename.length() - 3, 3))) { @@ -364,7 +365,7 @@ ::std::cout << "\tmesh: " << filename << ::std::endl; } vrmlShape->geometry = sphere; -::std::cout << "\tsphere: " << sphere->radius.getValue() << ::std::endl; +::std::cout << "\tsphere radius: " << sphere->radius.getValue() << ::std::endl; } } @@ -379,7 +380,7 @@ ::std::cout << "\tsphere: " << sphere->radius.getValue() << ::std::endl; ::std::vector< ::std::string> rpy; ::std::string tmp = path.eval("string(origin/@rpy)").getValue< ::std::string>(); ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); -::std::cout << "\trpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << ::std::endl; +::std::cout << "\torigin rpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << ::std::endl; origin.linear() = ::rl::math::AngleAxis( ::boost::lexical_cast< ::rl::math::Real>(rpy[2]), @@ -403,13 +404,12 @@ ::std::cout << "\trpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << ::std::e ::std::vector< ::std::string> xyz; ::std::string tmp = path.eval("string(origin/@xyz)").getValue< ::std::string>(); ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); -::std::cout << "\txyz: " << xyz[0] << " " << xyz[1] << " " << xyz[2] << ::std::endl; +::std::cout << "\torigin xyz: " << xyz[0] << " " << xyz[1] << " " << xyz[2] << ::std::endl; origin.translation().x() = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); origin.translation().y() = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); origin.translation().z() = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); } -::std::cout << "\torigin:" << ::std::endl << origin.matrix() << ::std::endl; shape->setTransform(origin); } From 8cb29869c9275cd77f3126bddaab857ee796cf19 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 11 Jul 2018 18:19:42 +0200 Subject: [PATCH 140/546] Check for SoSTLFileKit.h availability --- cmake/FindCoin.cmake | 24 ++++++++++++++++++++++-- src/rl/sg/CMakeLists.txt | 10 ++++++++++ src/rl/sg/UrdfFactory.cpp | 8 +++++++- 3 files changed, 39 insertions(+), 3 deletions(-) diff --git a/cmake/FindCoin.cmake b/cmake/FindCoin.cmake index 42588126..b79d21a0 100644 --- a/cmake/FindCoin.cmake +++ b/cmake/FindCoin.cmake @@ -49,7 +49,7 @@ file( ) find_path( - Coin_INCLUDE_DIRS + Coin_INCLUDE_DIR NAMES Inventor/So.h HINTS @@ -58,7 +58,27 @@ find_path( ${Coin_INCLUDE_PATHS} ) -mark_as_advanced(Coin_INCLUDE_DIRS) +mark_as_advanced(Coin_INCLUDE_DIR) + +set(Coin_INCLUDE_DIRS ${Coin_INCLUDE_DIR}) + +find_path( + Coin_FOREIGN_FILES_INCLUDE_DIR + NAMES + ForeignFiles/SoForeignFileKit.h + HINTS + ${Coin_INCLUDE_HINTS} + PATHS + ${Coin_INCLUDE_PATHS} + PATH_SUFFIXES + Inventor/annex +) + +mark_as_advanced(Coin_FOREIGN_FILES_INCLUDE_DIR) + +if(Coin_FOREIGN_FILES_INCLUDE_DIR) + list(APPEND Coin_INCLUDE_DIRS ${Coin_FOREIGN_FILES_INCLUDE_DIR}) +endif() foreach(PATH ${CMAKE_PREFIX_PATH}) file( diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 52f16031..4feae569 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -1,3 +1,5 @@ +include(CheckIncludeFileCXX) + find_package(Bullet) find_package(ccd) find_package(Coin REQUIRED) @@ -193,6 +195,14 @@ if(CCD_FOUND AND (FCL_FOUND OR ODE_FOUND)) endif() if(Coin_FOUND) + set(CMAKE_REQUIRED_DEFINITIONS ${Coin_DEFINITIONS}) + set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) + set(CMAKE_REQUIRED_LIBRARIES ${Coin_LIBRARIES}) + check_include_file_cxx(ForeignFiles/SoSTLFileKit.h HAVE_SOSTLFILEKIT_H) + unset(CMAKE_REQUIRED_DEFINITIONS) + unset(CMAKE_REQUIRED_INCLUDES) + unset(CMAKE_REQUIRED_LIBRARIES) + target_compile_definitions(sg PRIVATE -DHAVE_SOSTLFILEKIT_H) target_compile_definitions(sg PUBLIC ${Coin_DEFINITIONS}) target_include_directories(sg PUBLIC ${Coin_INCLUDE_DIRS}) target_link_libraries(sg ${Coin_LIBRARIES}) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 93008db6..f5a4c360 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -32,7 +32,9 @@ #include #include #include +#ifdef HAVE_SOSTLFILEKIT_H #include +#endif #include #include #include @@ -311,10 +313,14 @@ ::std::cout << "\tcylinder radius: " << cylinder->radius.getValue() << ::std::en ::std::string filename = shapes[k].getLocalPath(shapes[k].getProperty("filename")); ::std::cout << "\tmesh filename: " << filename << ::std::endl; - if (!boost::iequals("stl", filename.substr(filename.length() - 3, 3))) +#ifdef HAVE_SOSTLFILEKIT_H + if (!boost::iends_with(filename, "stl")) { throw Exception("rl::sg::UrdfFactory::load() - Only STL meshes currently supported"); } +#else + throw Exception("rl::sg::UrdfFactory::load() - Mesh support currently not installed"); +#endif ::SoSTLFileKit* stlFileKit = new ::SoSTLFileKit(); stlFileKit->ref(); From b505f1edb8413781858b9a1a40cbbcef7ae712b1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 11 Jul 2018 18:23:57 +0200 Subject: [PATCH 141/546] Minor fix --- src/rl/sg/UrdfFactory.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index f5a4c360..d6b1ac6d 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -318,9 +318,6 @@ ::std::cout << "\tmesh filename: " << filename << ::std::endl; { throw Exception("rl::sg::UrdfFactory::load() - Only STL meshes currently supported"); } -#else - throw Exception("rl::sg::UrdfFactory::load() - Mesh support currently not installed"); -#endif ::SoSTLFileKit* stlFileKit = new ::SoSTLFileKit(); stlFileKit->ref(); @@ -357,6 +354,9 @@ ::std::cout << "\tmesh filename: " << filename << ::std::endl; } vrml2->unref(); +#else + throw Exception("rl::sg::UrdfFactory::load() - Mesh support currently not available"); +#endif } } else if ("sphere" == shapes[k].getName()) From 92d27bc2b5235017021737b8a7dc5f72522a15c7 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 11 Jul 2018 20:34:32 +0200 Subject: [PATCH 142/546] Check for SoSTLFileKit::convert() --- src/rl/sg/CMakeLists.txt | 7 ++++++- src/rl/sg/UrdfFactory.cpp | 2 +- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 4feae569..70d37480 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -1,3 +1,4 @@ +include(CheckCXXSourceCompiles) include(CheckIncludeFileCXX) find_package(Bullet) @@ -198,11 +199,15 @@ if(Coin_FOUND) set(CMAKE_REQUIRED_DEFINITIONS ${Coin_DEFINITIONS}) set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) set(CMAKE_REQUIRED_LIBRARIES ${Coin_LIBRARIES}) + check_cxx_source_compiles(" + #include + int main() { SoSTLFileKit* stlFileKit = new SoSTLFileKit(); stlFileKit->convert(); return 0; } + " HAVE_SOSTLFILEKIT_CONVERT) check_include_file_cxx(ForeignFiles/SoSTLFileKit.h HAVE_SOSTLFILEKIT_H) unset(CMAKE_REQUIRED_DEFINITIONS) unset(CMAKE_REQUIRED_INCLUDES) unset(CMAKE_REQUIRED_LIBRARIES) - target_compile_definitions(sg PRIVATE -DHAVE_SOSTLFILEKIT_H) + target_compile_definitions(sg PRIVATE -DHAVE_SOSTLFILEKIT_H -DHAVE_SOSTLFILEKIT_CONVERT) target_compile_definitions(sg PUBLIC ${Coin_DEFINITIONS}) target_include_directories(sg PUBLIC ${Coin_INCLUDE_DIRS}) target_link_libraries(sg ${Coin_LIBRARIES}) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index d6b1ac6d..0a1735d5 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -313,7 +313,7 @@ ::std::cout << "\tcylinder radius: " << cylinder->radius.getValue() << ::std::en ::std::string filename = shapes[k].getLocalPath(shapes[k].getProperty("filename")); ::std::cout << "\tmesh filename: " << filename << ::std::endl; -#ifdef HAVE_SOSTLFILEKIT_H +#if defined(HAVE_SOSTLFILEKIT_H) && defined(HAVE_SOSTLFILEKIT_CONVERT) if (!boost::iends_with(filename, "stl")) { throw Exception("rl::sg::UrdfFactory::load() - Only STL meshes currently supported"); From 076cf7e5c3a9caadd2c3aa3d3e12293a0a81f244 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 11 Jul 2018 21:33:26 +0200 Subject: [PATCH 143/546] Minor fix --- src/rl/sg/CMakeLists.txt | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 70d37480..0ffdb9ef 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -199,15 +199,20 @@ if(Coin_FOUND) set(CMAKE_REQUIRED_DEFINITIONS ${Coin_DEFINITIONS}) set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) set(CMAKE_REQUIRED_LIBRARIES ${Coin_LIBRARIES}) - check_cxx_source_compiles(" - #include - int main() { SoSTLFileKit* stlFileKit = new SoSTLFileKit(); stlFileKit->convert(); return 0; } - " HAVE_SOSTLFILEKIT_CONVERT) check_include_file_cxx(ForeignFiles/SoSTLFileKit.h HAVE_SOSTLFILEKIT_H) + if(HAVE_SOSTLFILEKIT_H) + target_compile_definitions(sg PRIVATE -DHAVE_SOSTLFILEKIT_H) + check_cxx_source_compiles(" + #include + int main() { SoSTLFileKit* stlFileKit = new SoSTLFileKit(); stlFileKit->convert(); return 0; } + " HAVE_SOSTLFILEKIT_CONVERT) + if(HAVE_SOSTLFILEKIT_CONVERT) + target_compile_definitions(sg PRIVATE -DHAVE_SOSTLFILEKIT_CONVERT) + endif() + endif() unset(CMAKE_REQUIRED_DEFINITIONS) unset(CMAKE_REQUIRED_INCLUDES) unset(CMAKE_REQUIRED_LIBRARIES) - target_compile_definitions(sg PRIVATE -DHAVE_SOSTLFILEKIT_H -DHAVE_SOSTLFILEKIT_CONVERT) target_compile_definitions(sg PUBLIC ${Coin_DEFINITIONS}) target_include_directories(sg PUBLIC ${Coin_INCLUDE_DIRS}) target_link_libraries(sg ${Coin_LIBRARIES}) From fed4a2471387f7a047ca24f27ed09347536b964b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 12 Jul 2018 14:14:38 +0200 Subject: [PATCH 144/546] Add wrapping to configuration delegates --- demos/rlCoachKin/ConfigurationDelegate.cpp | 4 ++++ demos/rlCoachMdl/ConfigurationDelegate.cpp | 3 +++ demos/rlPlanDemo/ConfigurationDelegate.cpp | 3 +++ src/rl/kin/Kinematics.cpp | 9 +++++++++ src/rl/kin/Kinematics.h | 2 ++ src/rl/mdl/Model.cpp | 13 +++++++++++++ src/rl/mdl/Model.h | 2 ++ src/rl/plan/Model.cpp | 15 +++++++++++++++ src/rl/plan/Model.h | 2 ++ 9 files changed, 53 insertions(+) diff --git a/demos/rlCoachKin/ConfigurationDelegate.cpp b/demos/rlCoachKin/ConfigurationDelegate.cpp index f43d327e..95a4ea68 100644 --- a/demos/rlCoachKin/ConfigurationDelegate.cpp +++ b/demos/rlCoachKin/ConfigurationDelegate.cpp @@ -51,6 +51,8 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& MainWindow::instance()->kinematicModels[this->id]->getMinimum(minimum); Eigen::Matrix qUnits(MainWindow::instance()->kinematicModels[this->id]->getDof()); MainWindow::instance()->kinematicModels[this->id]->getPositionUnits(qUnits); + Eigen::Matrix wraparounds(MainWindow::instance()->kinematicModels[this->id]->getDof()); + MainWindow::instance()->kinematicModels[this->id]->getWraparounds(wraparounds); if (rl::math::UNIT_RADIAN == qUnits(index.row())) { @@ -67,6 +69,8 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& editor->setSingleStep(0.01f); } + editor->setWrapping(wraparounds(index.row())); + QObject::connect(editor, SIGNAL(valueChanged(double)), this, SLOT(valueChanged(double))); return editor; diff --git a/demos/rlCoachMdl/ConfigurationDelegate.cpp b/demos/rlCoachMdl/ConfigurationDelegate.cpp index 2a6ba1e3..d1b71f23 100644 --- a/demos/rlCoachMdl/ConfigurationDelegate.cpp +++ b/demos/rlCoachMdl/ConfigurationDelegate.cpp @@ -51,6 +51,7 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& rl::math::Vector maximum = MainWindow::instance()->kinematicModels[this->id]->getMaximum(); rl::math::Vector minimum = MainWindow::instance()->kinematicModels[this->id]->getMinimum(); Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels[this->id]->getPositionUnits(); + Eigen::Matrix wraparounds = MainWindow::instance()->kinematicModels[this->id]->getWraparounds(); if (rl::math::UNIT_RADIAN == qUnits(index.row())) { @@ -67,6 +68,8 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& editor->setSingleStep(0.01f); } + editor->setWrapping(wraparounds(index.row())); + QObject::connect(editor, SIGNAL(valueChanged(double)), this, SLOT(valueChanged(double))); return editor; diff --git a/demos/rlPlanDemo/ConfigurationDelegate.cpp b/demos/rlPlanDemo/ConfigurationDelegate.cpp index df5bfa95..969a5500 100644 --- a/demos/rlPlanDemo/ConfigurationDelegate.cpp +++ b/demos/rlPlanDemo/ConfigurationDelegate.cpp @@ -47,6 +47,7 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& rl::math::Vector maximum = MainWindow::instance()->model->getMaximum(); rl::math::Vector minimum = MainWindow::instance()->model->getMinimum(); Eigen::Matrix qUnits = MainWindow::instance()->model->getPositionUnits(); + Eigen::Matrix wraparounds = MainWindow::instance()->model->getWraparounds(); if (rl::math::UNIT_RADIAN == qUnits(index.row())) { @@ -63,6 +64,8 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& editor->setSingleStep(0.01f); } + editor->setWrapping(wraparounds(index.row())); + QObject::connect(editor, SIGNAL(valueChanged(double)), this, SLOT(valueChanged(double))); return editor; diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index fc50a01c..7714923a 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -662,6 +662,15 @@ namespace rl } } + void + Kinematics::getWraparounds(::Eigen::Matrix& wraparounds) const + { + for (::std::size_t i = 0; i < this->joints.size(); ++i) + { + wraparounds(i) = this->joints[i]->wraparound; + } + } + void Kinematics::interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q) const { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index a1da3b32..f04d6b3e 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -189,6 +189,8 @@ namespace rl void getSpeedUnits(::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const; + void getWraparounds(::Eigen::Matrix& wraparounds) const; + virtual void interpolate(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2, const ::rl::math::Real& alpha, ::rl::math::Vector& q) const; /** diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 8750d4e3..48e97729 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -478,6 +478,19 @@ namespace rl return dynamic_cast(this->tree[this->root].get()); } + ::Eigen::Matrix + Model::getWraparounds() const + { + ::Eigen::Matrix wraparounds(this->getDof()); + + for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) + { + wraparounds.segment(j, this->joints[i]->getDof()) = this->joints[i]->wraparound; + } + + return wraparounds; + } + bool Model::isColliding(const ::std::size_t& i) const { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 5688ad9c..ce5a4f03 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -146,6 +146,8 @@ namespace rl World* getWorld() const; + ::Eigen::Matrix getWraparounds() const; + bool isColliding(const ::std::size_t& i) const; void replace(Compound* compound, Transform* transform); diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index c92dc5f1..6166a2b5 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -322,6 +322,21 @@ namespace rl } } + ::Eigen::Matrix + Model::getWraparounds() const + { + if (nullptr != this->kin) + { + ::Eigen::Matrix wraparounds(this->getDofPosition());; + this->kin->getWraparounds(wraparounds); + return wraparounds; + } + else + { + return this->mdl->getWraparounds(); + } + } + void Model::inverseForce(const ::rl::math::Vector& f, ::rl::math::Vector& tau) const { diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 28ceec8e..4b482fdd 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -89,6 +89,8 @@ namespace rl virtual ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getPositionUnits() const; + virtual ::Eigen::Matrix getWraparounds() const; + virtual void inverseForce(const ::rl::math::Vector& f, ::rl::math::Vector& tau) const; virtual ::rl::math::Real inverseOfTransformedDistance(const ::rl::math::Real& d) const; From dedf10fd984a75a6d600d3482fcdbe0539e925b1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 12 Jul 2018 14:15:09 +0200 Subject: [PATCH 145/546] Set +-180 degree limit for URDF continuous joints --- src/rl/mdl/UrdfFactory.cpp | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 860bb6bc..ebf47007 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -275,14 +275,24 @@ ::std::cout << "\tname: " << p->getName() << ::std::endl; model->add(fixed, parent, frame); model->add(r, frame, child); - r->max(0) = path.eval("number(limit/@upper)").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); + if ("continuous" == path.eval("string(@type)").getValue< ::std::string>()) + { + r->max(0) = 180.0f * ::rl::math::DEG2RAD; + r->min(0) = -180.0f * ::rl::math::DEG2RAD; + r->wraparound(0) = true; + } + else + { + r->max(0) = path.eval("number(limit/@upper)").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); + r->min(0) = path.eval("number(limit/@lower)").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); + r->wraparound(0) = false; + } ::std::cout << "\tmax: " << r->max(0) * ::rl::math::RAD2DEG << ::std::endl; - r->min(0) = path.eval("number(limit/@lower)").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); ::std::cout << "\tmin: " << r->min(0) * ::rl::math::RAD2DEG << ::std::endl; + r->offset(0) = 0; r->speed(0) = path.eval("number(limit/@velocity)").getValue< ::rl::math::Real>(0); ::std::cout << "\tspeed: " << r->speed(0) * ::rl::math::RAD2DEG << ::std::endl; - r->wraparound(0) = "continuous" == path.eval("string(@type)").getValue< ::std::string>() ? true : false; if (path.eval("count(axis/@xyz) > 0").getValue()) { From f10515f0996577227fda880da324d633c3fa3c69 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 12 Jul 2018 14:17:45 +0200 Subject: [PATCH 146/546] Add support for URDF floating joint --- src/rl/mdl/UrdfFactory.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index ebf47007..beb252dc 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -50,6 +50,7 @@ #include "Model.h" #include "Prismatic.h" #include "Revolute.h" +#include "SixDof.h" #include "Spherical.h" #include "UrdfFactory.h" #include "World.h" @@ -225,7 +226,13 @@ ::std::cout << "\tname: " << fixed->getName() << ::std::endl; } else if ("floating" == type) { - throw Exception("rl::mdl::UrdfFactory::load() - URDF floating joint not supported"); + SixDof* s = new SixDof(); + + model->add(fixed, parent, frame); + model->add(s, frame, child); + + s->setName(path.eval("string(@name)").getValue< ::std::string>()); +::std::cout << "\tname: " << s->getName() << ::std::endl; } else if ("planar" == type) { From cfdc965dfa4fe4699aaa1b7cb201813491fe71e3 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 28 Jul 2018 16:25:10 +0200 Subject: [PATCH 147/546] Add action to copy camera values to clipboard --- extras/wrlview/MainWindow.cpp | 23 +++++++++++++++++++++++ extras/wrlview/MainWindow.h | 2 ++ 2 files changed, 25 insertions(+) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 27bec90b..03eee6a1 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -24,6 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include +#include #include #include #include @@ -188,6 +190,21 @@ MainWindow::~MainWindow() } } +void +MainWindow::copyCameraValues() +{ + QApplication::clipboard()->setText( + "position " + QString(this->viewer->getCamera()->position.getValue().toString().getString()) + "\n" + + "orientation " + QString(this->viewer->getCamera()->orientation.getValue().toString().getString()) + "\n" + + "focalDistance " + QString::number(this->viewer->getCamera()->focalDistance.getValue()) + "\n" + + ( + SoPerspectiveCamera::getClassTypeId() == this->viewer->getCameraType() ? + "heightAngle " + QString::number(static_cast(this->viewer->getCamera())->heightAngle.getValue()) : + "height " + QString::number(static_cast(this->viewer->getCamera())->height.getValue()) + ) + "\n" + ); +} + void MainWindow::dragEnterEvent(QDragEnterEvent* event) { @@ -315,6 +332,12 @@ MainWindow::init() viewActionGroup->addAction(viewTopFrontRightAction); this->viewMenu->addAction(viewTopFrontRightAction); + this->viewMenu->addSeparator(); + + QAction* copyCameraValuesAction = new QAction("Copy Camera Values", this); + QObject::connect(copyCameraValuesAction, SIGNAL(triggered()), this, SLOT(copyCameraValues())); + this->viewMenu->addAction(copyCameraValuesAction); + this->displayMenu = this->menuBar()->addMenu("Display"); QAction* toggleAxisCrossAction = new QAction("Axis Cross", this); diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index 63668e62..71d7f3d0 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -146,6 +146,8 @@ class MainWindow : public QMainWindow private slots: void open(); + void copyCameraValues(); + void reload(); void replyFinished(QNetworkReply* reply); From 6bd0f400d14b7ea43c4d1187691552101f332e79 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 28 Jul 2018 16:26:37 +0200 Subject: [PATCH 148/546] Increase version number of wrlview --- extras/wrlview/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 99297a16..24044385 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -60,7 +60,7 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) set_target_properties( wrlview PROPERTIES - VERSION 0.1.11 + VERSION 0.1.12 ) install( From 80da06e12b6e0658347f9153530de3a84d6094c5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 28 Jul 2018 21:59:49 +0200 Subject: [PATCH 149/546] Fix whitespace --- src/rl/math/Spline.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 1c0ceff4..7e03f1f3 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -315,7 +315,7 @@ namespace rl { T yd = (y[n - 1] - y[n - 2]) / (x[n - 1] - x[n - 2]); T yBeforeParabolic = y[n - 1] - yd * (parabolicInterval / 2); - + Polynomial parabolic = Polynomial::Quadratic(yBeforeParabolic, TypeTraits::Zero(dim), yd, parabolicInterval); f.push_back(parabolic); } From c1a320cb1d32b1c446a4a8b72c3105c27a5a2575 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 29 Jul 2018 19:32:06 +0200 Subject: [PATCH 150/546] Fix bug in last segment of Spline::LinearParabolic --- src/rl/math/Spline.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 7e03f1f3..727549c2 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -316,7 +316,7 @@ namespace rl T yd = (y[n - 1] - y[n - 2]) / (x[n - 1] - x[n - 2]); T yBeforeParabolic = y[n - 1] - yd * (parabolicInterval / 2); - Polynomial parabolic = Polynomial::Quadratic(yBeforeParabolic, TypeTraits::Zero(dim), yd, parabolicInterval); + Polynomial parabolic = Polynomial::Quadratic(yBeforeParabolic, y[n - 1], yd, parabolicInterval); f.push_back(parabolic); } From fe99d4fee995e0cb0eff3730db637ce0f973dd44 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 31 Jul 2018 14:42:16 +0200 Subject: [PATCH 151/546] Add percentage versions for LinearParabolic, LinearQuartic, LinearSextic --- .../rlInterpolatorDemo/rlInterpolatorDemo.cpp | 6 + src/rl/math/Spline.h | 246 ++++++++++++++++++ 2 files changed, 252 insertions(+) diff --git a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp index c5b6ab45..9551e72c 100644 --- a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp +++ b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp @@ -193,10 +193,16 @@ main(int argc, char** argv) eval(f1); rl::math::Spline f2 = rl::math::Spline::LinearParabolic(x, y, 0.25f); eval(f2); + rl::math::Spline f2b = rl::math::Spline::LinearParabolicPercentage(x, y, 0.25f); + eval(f2b); rl::math::Spline f3 = rl::math::Spline::LinearQuartic(x, y, 0.25f); eval(f3); + rl::math::Spline f3b = rl::math::Spline::LinearQuarticPercentage(x, y, 0.25f); + eval(f3b); rl::math::Spline f4 = rl::math::Spline::LinearSextic(x, y, 0.25f); eval(f4); + rl::math::Spline f4b = rl::math::Spline::LinearSexticPercentage(x, y, 0.25f); + eval(f4b); } { diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 727549c2..5e165c0c 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -323,6 +323,88 @@ namespace rl return f; } + template + static Spline LinearParabolicPercentage(const Container1& x, const Container2& y, const Real& parabolicPercent) + { + assert(x.size() > 1); + assert(x.size() == y.size()); + + ::std::size_t n = y.size(); + ::std::size_t dim = TypeTraits::size(y[0]); + + Spline f; + + { + Real parabolicInterval = (x[1] - x[0]) * parabolicPercent; + T yd = (y[1] - y[0]) / (x[1] - x[0]); + T yBeforeLinear = y[0] + yd * (parabolicInterval / 2); + Real linearInterval = (x[1] - x[0]) - parabolicInterval; + assert(linearInterval > 0); + T yAfterLinear = y[0] + yd * (parabolicInterval / 2 + linearInterval); + + Polynomial parabolic = Polynomial::Quadratic(y[0], yBeforeLinear, TypeTraits::Zero(dim), parabolicInterval); + f.push_back(parabolic); + Polynomial linear = Polynomial::Linear(yBeforeLinear, yAfterLinear, linearInterval); + f.push_back(linear); + } + + for (::std::size_t i = 1; i < n - 2; ++i) + { + Real parabolicIntervalPrev = (x[i] - x[i - 1]) * parabolicPercent; + Real parabolicIntervalNext = (x[i + 1] - x[i]) * parabolicPercent; + Real parabolicIntervalNextNext = (x[i + 2] - x[i + 1]) * parabolicPercent; + parabolicIntervalPrev = std::min(parabolicIntervalPrev, parabolicIntervalNext); + parabolicIntervalNext = std::min(parabolicIntervalNext, parabolicIntervalNextNext); + Real deltaXPrev = x[i] - x[i - 1]; + Real deltaXNext = x[i + 1] - x[i]; + Real deltaXNextNext = x[i + 2] - x[i + 1]; + Real linearInterval = deltaXNext - (parabolicIntervalPrev/2) - (parabolicIntervalNext/2); + assert(deltaXPrev > parabolicIntervalPrev && deltaXNext > parabolicIntervalNext); + T ydPrev = (y[i] - y[i - 1]) / deltaXPrev; + T ydNext = (y[i + 1] - y[i]) / deltaXNext; + T yBeforeParabolic = y[i] + (-parabolicIntervalPrev / 2 * ydPrev); + T yBeforeLinear = y[i] + (parabolicIntervalPrev / 2 * ydNext); + T yAfterLinear = y[i] + ((parabolicIntervalPrev / 2 + linearInterval) * ydNext); + + Polynomial parabolic = Polynomial::Quadratic(yBeforeParabolic, yBeforeLinear, ydPrev, parabolicIntervalPrev); + f.push_back(parabolic); + Polynomial linear = Polynomial::Linear(yBeforeLinear, yAfterLinear, linearInterval); + f.push_back(linear); + } + + if (n > 2) + { + { + Real parabolicIntervalPrev = (x[n - 2] - x[n - 3]) * parabolicPercent; + Real parabolicIntervalNext = (x[n - 1] - x[n - 2]) * parabolicPercent; + parabolicIntervalPrev = std::min(parabolicIntervalPrev, parabolicIntervalNext); + Real deltaXPrev = x[n - 2] - x[n - 3]; + Real deltaXNext = x[n - 1] - x[n - 2]; + Real linearInterval = deltaXNext - (parabolicIntervalPrev/2) - (parabolicIntervalNext/2); + assert(deltaXPrev > parabolicIntervalPrev && deltaXNext > parabolicIntervalNext); + T ydPrev = (y[n - 2] - y[n - 3]) / deltaXPrev; + T ydNext = (y[n - 1] - y[n - 2]) / deltaXNext; + T yBeforeParabolic = y[n - 2] + (-parabolicIntervalPrev / 2 * ydPrev); + T yBeforeLinear = y[n - 2] + (parabolicIntervalPrev / 2 * ydNext); + T yAfterLinear = y[n - 2] + ((parabolicIntervalPrev / 2 + linearInterval) * ydNext); + + Polynomial parabolic = Polynomial::Quadratic(yBeforeParabolic, yBeforeLinear, ydPrev, parabolicIntervalPrev); + f.push_back(parabolic); + Polynomial linear = Polynomial::Linear(yBeforeLinear, yAfterLinear, linearInterval); + f.push_back(linear); + } + + Real parabolicInterval = (x[n - 1] - x[n - 2]) * parabolicPercent; + T yd = (y[n - 1] - y[n - 2]) / (x[n - 1] - x[n - 2]); + T yBeforeParabolic = y[n - 1] - (yd * (parabolicInterval)/2); + + Polynomial parabolic = Polynomial::Quadratic(yBeforeParabolic, y[n - 1], yd, parabolicInterval); + f.push_back(parabolic); + } + + return f; + } + /** * Generates a piecewise spline with quartic polynomial segments around * the given supporting points y and linear segments in between. @@ -388,6 +470,88 @@ namespace rl return f; } + template + static Spline LinearQuarticPercentage(const Container1& x, const Container2& y, const Real& quarticPercent) + { + assert(x.size() > 1); + assert(x.size() == y.size()); + + ::std::size_t n = y.size(); + ::std::size_t dim = TypeTraits::size(y[0]); + + Spline f; + + { + Real quarticInterval = (x[1] - x[0]) * quarticPercent; + T yd = (y[1] - y[0]) / (x[1] - x[0]); + T yBeforeLinear = y[0] + yd * (quarticInterval / 2); + Real linearInterval = (x[1] - x[0]) - quarticInterval; + assert(linearInterval > 0); + T yAfterLinear = y[0] + yd * (quarticInterval / 2 + linearInterval); + + Polynomial quartic = Polynomial::QuarticFirstSecond(y[0], yBeforeLinear, TypeTraits::Zero(dim), yd, TypeTraits::Zero(dim), quarticInterval); + f.push_back(quartic); + Polynomial linear = Polynomial::Linear(yBeforeLinear, yAfterLinear, linearInterval); + f.push_back(linear); + } + + for (::std::size_t i = 1; i < n - 2; ++i) + { + Real quarticIntervalPrev = (x[i] - x[i - 1]) * quarticPercent; + Real quarticIntervalNext = (x[i + 1] - x[i]) * quarticPercent; + Real quarticIntervalNextNext = (x[i + 2] - x[i + 1]) * quarticPercent; + quarticIntervalPrev = std::min(quarticIntervalPrev, quarticIntervalNext); + quarticIntervalNext = std::min(quarticIntervalNext, quarticIntervalNextNext); + Real deltaXPrev = x[i] - x[i - 1]; + Real deltaXNext = x[i + 1] - x[i]; + Real deltaXNextNext = x[i + 2] - x[i + 1]; + Real linearInterval = deltaXNext - (quarticIntervalPrev/2) - (quarticIntervalNext/2); + assert(deltaXPrev > quarticIntervalPrev && deltaXNext > quarticIntervalNext); + T ydPrev = (y[i] - y[i - 1]) / deltaXPrev; + T ydNext = (y[i + 1] - y[i]) / deltaXNext; + T yBeforeQuartic = y[i] + (-quarticIntervalPrev / 2 * ydPrev); + T yBeforeLinear = y[i] + (quarticIntervalPrev / 2 * ydNext); + T yAfterLinear = y[i] + ((quarticIntervalPrev / 2 + linearInterval) * ydNext); + + Polynomial quartic = Polynomial::QuarticFirstSecond(yBeforeQuartic, yBeforeLinear, ydPrev, ydNext, TypeTraits::Zero(dim), quarticIntervalPrev); + f.push_back(quartic); + Polynomial linear = Polynomial::Linear(yBeforeLinear, yAfterLinear, linearInterval); + f.push_back(linear); + } + + if (n > 2) + { + { + Real quarticIntervalPrev = (x[n - 2] - x[n - 3]) * quarticPercent; + Real quarticIntervalNext = (x[n - 1] - x[n - 2]) * quarticPercent; + quarticIntervalPrev = std::min(quarticIntervalPrev, quarticIntervalNext); + Real deltaXPrev = x[n - 2] - x[n - 3]; + Real deltaXNext = x[n - 1] - x[n - 2]; + Real linearInterval = deltaXNext - (quarticIntervalPrev/2) - (quarticIntervalNext/2); + assert(deltaXPrev > quarticIntervalPrev && deltaXNext > quarticIntervalNext); + T ydPrev = (y[n - 2] - y[n - 3]) / deltaXPrev; + T ydNext = (y[n - 1] - y[n - 2]) / deltaXNext; + T yBeforeQuartic = y[n - 2] + (-quarticIntervalPrev / 2 * ydPrev); + T yBeforeLinear = y[n - 2] + (quarticIntervalPrev / 2 * ydNext); + T yAfterLinear = y[n - 2] + ((quarticIntervalPrev / 2 + linearInterval) * ydNext); + + Polynomial quartic = Polynomial::QuarticFirstSecond(yBeforeQuartic, yBeforeLinear, ydPrev, ydNext, TypeTraits::Zero(dim), quarticIntervalPrev); + f.push_back(quartic); + Polynomial linear = Polynomial::Linear(yBeforeLinear, yAfterLinear, linearInterval); + f.push_back(linear); + } + + Real quarticInterval = (x[n - 1] - x[n - 2]) * quarticPercent; + T yd = (y[n - 1] - y[n - 2]) / (x[n - 1] - x[n - 2]); + T yBeforeQuartic = y[n - 1] - (yd * (quarticInterval)/2); + + Polynomial quartic = Polynomial::QuarticFirstSecond(yBeforeQuartic, y[n - 1], yd, TypeTraits::Zero(dim), TypeTraits::Zero(dim), quarticInterval); + f.push_back(quartic); + } + + return f; + } + /** * Generates a piecewise spline with sextic polynomial segments around * the given supporting points y and linear segments in between. @@ -453,6 +617,88 @@ namespace rl return f; } + template + static Spline LinearSexticPercentage(const Container1& x, const Container2& y, const Real& sexticPercent) + { + assert(x.size() > 1); + assert(x.size() == y.size()); + + ::std::size_t n = y.size(); + ::std::size_t dim = TypeTraits::size(y[0]); + + Spline f; + + { + Real sexticInterval = (x[1] - x[0]) * sexticPercent; + T yd = (y[1] - y[0]) / (x[1] - x[0]); + T yBeforeLinear = y[0] + yd * (sexticInterval / 2); + Real linearInterval = (x[1] - x[0]) - sexticInterval; + assert(linearInterval > 0); + T yAfterLinear = y[0] + yd * (sexticInterval / 2 + linearInterval); + + Polynomial sextic = Polynomial::SexticFirstSecondThird(y[0], yBeforeLinear, TypeTraits::Zero(dim), yd, TypeTraits::Zero(dim), TypeTraits::Zero(dim), TypeTraits::Zero(dim), sexticInterval); + f.push_back(sextic); + Polynomial linear = Polynomial::Linear(yBeforeLinear, yAfterLinear, linearInterval); + f.push_back(linear); + } + + for (::std::size_t i = 1; i < n - 2; ++i) + { + Real sexticIntervalPrev = (x[i] - x[i - 1]) * sexticPercent; + Real sexticIntervalNext = (x[i + 1] - x[i]) * sexticPercent; + Real sexticIntervalNextNext = (x[i + 2] - x[i + 1]) * sexticPercent; + sexticIntervalPrev = std::min(sexticIntervalPrev, sexticIntervalNext); + sexticIntervalNext = std::min(sexticIntervalNext, sexticIntervalNextNext); + Real deltaXPrev = x[i] - x[i - 1]; + Real deltaXNext = x[i + 1] - x[i]; + Real deltaXNextNext = x[i + 2] - x[i + 1]; + Real linearInterval = deltaXNext - (sexticIntervalPrev/2) - (sexticIntervalNext/2); + assert(deltaXPrev > sexticIntervalPrev && deltaXNext > sexticIntervalNext); + T ydPrev = (y[i] - y[i - 1]) / deltaXPrev; + T ydNext = (y[i + 1] - y[i]) / deltaXNext; + T yBeforeSextic = y[i] + (-sexticIntervalPrev / 2 * ydPrev); + T yBeforeLinear = y[i] + (sexticIntervalPrev / 2 * ydNext); + T yAfterLinear = y[i] + ((sexticIntervalPrev / 2 + linearInterval) * ydNext); + + Polynomial sextic = Polynomial::SexticFirstSecondThird(yBeforeSextic, yBeforeLinear, ydPrev, ydNext, TypeTraits::Zero(dim), TypeTraits::Zero(dim), TypeTraits::Zero(dim), sexticIntervalPrev); + f.push_back(sextic); + Polynomial linear = Polynomial::Linear(yBeforeLinear, yAfterLinear, linearInterval); + f.push_back(linear); + } + + if (n > 2) + { + { + Real sexticIntervalPrev = (x[n - 2] - x[n - 3]) * sexticPercent; + Real sexticIntervalNext = (x[n - 1] - x[n - 2]) * sexticPercent; + sexticIntervalPrev = std::min(sexticIntervalPrev, sexticIntervalNext); + Real deltaXPrev = x[n - 2] - x[n - 3]; + Real deltaXNext = x[n - 1] - x[n - 2]; + Real linearInterval = deltaXNext - (sexticIntervalPrev/2) - (sexticIntervalNext/2); + assert(deltaXPrev > sexticIntervalPrev && deltaXNext > sexticIntervalNext); + T ydPrev = (y[n - 2] - y[n - 3]) / deltaXPrev; + T ydNext = (y[n - 1] - y[n - 2]) / deltaXNext; + T yBeforeSextic = y[n - 2] + (-sexticIntervalPrev / 2 * ydPrev); + T yBeforeLinear = y[n - 2] + (sexticIntervalPrev / 2 * ydNext); + T yAfterLinear = y[n - 2] + ((sexticIntervalPrev / 2 + linearInterval) * ydNext); + + Polynomial sextic = Polynomial::SexticFirstSecondThird(yBeforeSextic, yBeforeLinear, ydPrev, ydNext, TypeTraits::Zero(dim), TypeTraits::Zero(dim), TypeTraits::Zero(dim), sexticIntervalPrev); + f.push_back(sextic); + Polynomial linear = Polynomial::Linear(yBeforeLinear, yAfterLinear, linearInterval); + f.push_back(linear); + } + + Real sexticInterval = (x[n - 1] - x[n - 2]) * sexticPercent; + T yd = (y[n - 1] - y[n - 2]) / (x[n - 1] - x[n - 2]); + T yBeforeSextic = y[n - 1] - (yd * (sexticInterval)/2); + + Polynomial sextic = Polynomial::SexticFirstSecondThird(yBeforeSextic, y[n - 1], yd, TypeTraits::Zero(dim), TypeTraits::Zero(dim), TypeTraits::Zero(dim), TypeTraits::Zero(dim), sexticInterval); + f.push_back(sextic); + } + + return f; + } + #if !(defined(_MSC_VER) && _MSC_VER < 1800) /** * Generates a spline of polynomials of degrees 4-1-4 from rest to rest From 8e226c2ddce0282d79b2cd1c8729ac2e039b87a0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 15 Aug 2018 17:57:48 +0200 Subject: [PATCH 152/546] Remove snprintf --- src/rl/hal/MitsubishiR3.cpp | 257 ++++++++++++++++-------------------- src/rl/hal/MitsubishiR3.h | 2 + 2 files changed, 115 insertions(+), 144 deletions(-) diff --git a/src/rl/hal/MitsubishiR3.cpp b/src/rl/hal/MitsubishiR3.cpp index bd1d835b..69726cee 100644 --- a/src/rl/hal/MitsubishiR3.cpp +++ b/src/rl/hal/MitsubishiR3.cpp @@ -24,6 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include #include #include #include @@ -32,9 +33,6 @@ #include "MitsubishiR3.h" #ifdef WIN32 -#ifndef snprintf -#define snprintf _snprintf_s -#endif // snprintf #ifndef strncpy_s #define strncpy strncpy_s #endif // strncpy_s @@ -67,10 +65,10 @@ namespace rl void MitsubishiR3::doCalib(CalibState& state) { - char buf[256] = "1;1;CALIB"; + this->send("1;1;CALIB"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) { @@ -106,7 +104,7 @@ namespace rl } else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -114,17 +112,14 @@ namespace rl void MitsubishiR3::doCntl(const bool& doOn) { - char buf[256]; + this->send("1;1;CNTL" + ::std::string(doOn ? "ON" : "OFF")); - ::snprintf(buf, 255, "1;1;CNTL%s", (doOn ? "ON" : "OFF")); - buf[255] = '\0'; - - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -132,17 +127,14 @@ namespace rl void MitsubishiR3::doDatinst(const ::std::string& j1, const ::std::string& j2, const ::std::string& j3, const ::std::string& j4, const ::std::string& j5, const ::std::string& j6, const ::std::string& checksum) { - char buf[256]; - - ::snprintf(buf, 255, "1;1;DATINST%s;%s;%s;%s;%s;%s;%s", j1.c_str(), j2.c_str(), j3.c_str(), j4.c_str(), j5.c_str(), j6.c_str(), checksum.c_str()); - buf[255] = '\0'; + this->send("1;1;DATINST" + j1 + ";" + j2 + ";" + j3 + ";" + j4 + ";" + j5 + ";" + j6 + ";" + checksum); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -150,17 +142,14 @@ namespace rl void MitsubishiR3::doDatinst(const ::std::string& j1, const ::std::string& j2, const ::std::string& j3, const ::std::string& j4, const ::std::string& j5, const ::std::string& j6, const ::std::string& j7, const ::std::string& j8, const ::std::string& checksum) { - char buf[256]; + this->send("1;1;DATINST" + j1 + ";" + j2 + ";" + j3 + ";" + j4 + ";" + j5 + ";" + j6 + ";" + j7 + ";" + j8 + ";" + checksum); - ::snprintf(buf, 255, "1;1;DATINST%s;%s;%s;%s;%s;%s;%s;%s;%s", j1.c_str(), j2.c_str(), j3.c_str(), j4.c_str(), j5.c_str(), j6.c_str(), j7.c_str(), j8.c_str(), checksum.c_str()); - buf[255] = '\0'; - - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -170,14 +159,14 @@ namespace rl { StopState state; - char buf[256] = "1;1;DSTATE"; + this->send("1;1;DSTATE"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) { - char* elem = buf + 2; + char* elem = buf.data() + 2; char* semicolon = nullptr; int i = 0; @@ -188,7 +177,7 @@ namespace rl if (nullptr != semicolon) { - buf[semicolon - buf] = '\0'; + buf[semicolon - buf.data()] = '\0'; } switch (i) @@ -262,7 +251,7 @@ namespace rl } else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } @@ -272,14 +261,14 @@ namespace rl void MitsubishiR3::doEclr() { - char buf[256] = "1;9;ECLR"; + this->send("1;9;ECLR"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -289,8 +278,8 @@ namespace rl { // max. 256 - 9 (::std::strlen("1;9;EMDAT")) - 1 = 246 chars + ::std::array buf; ::std::size_t begin = 0; - char buf[256]; ::std::size_t end = 0; ::std::string lines; @@ -313,10 +302,8 @@ namespace rl lines = lines.substr(0, end); } - lines = "1;9;EMDAT" + lines; - - this->socket.send(lines.c_str(), lines.length()); - this->socket.recv(buf, 256); + this->send("1;9;EMDAT" + lines); + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { @@ -324,7 +311,7 @@ namespace rl char* errorLine = nullptr; char* charPos = nullptr; - char* elem = buf + 2; + char* elem = buf.data() + 2; char* semicolon = nullptr; int i = 0; @@ -335,7 +322,7 @@ namespace rl if (nullptr != semicolon) { - buf[semicolon - buf] = '\0'; + buf[semicolon - buf.data()] = '\0'; } switch (i) @@ -370,37 +357,31 @@ namespace rl ::std::string MitsubishiR3::doErrormes(const int& errorNo) { - char buf[256]; + this->send("1;1;ERRORMES" + ::std::to_string(errorNo)); - ::snprintf(buf, 255, "1;1;ERRORMES%i", errorNo); - buf[255] = '\0'; - - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } - return buf + 3; + return buf.data() + 3; } void MitsubishiR3::doExec(const ::std::string& instruction) { - char buf[256]; - - ::snprintf(buf, 255, "1;9;EXEC%s", instruction.c_str()); - buf[255] = '\0'; + this->send("1;9;EXEC" + instruction); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -410,17 +391,14 @@ namespace rl { assert(0 < handNo && handNo < 9); - char buf[256]; + this->send("1;1;HND" + ::std::string(doOpen ? "ON" : "OFF") + ::std::to_string(handNo)); - ::snprintf(buf, 255, "1;1;HND%s%i", (doOpen ? "ON" : "OFF"), handNo); - buf[255] = '\0'; - - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -430,14 +408,14 @@ namespace rl { ::std::array state; - char buf[256] = "1;1;HNDSTS"; + this->send("1;1;HNDSTS"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) { - char* elem = buf + 2; + char* elem = buf.data() + 2; char* semicolon = nullptr; int i = 0; int j = 0; @@ -449,7 +427,7 @@ namespace rl if (nullptr != semicolon) { - buf[semicolon - buf] = '\0'; + buf[semicolon - buf.data()] = '\0'; } switch (j) @@ -506,7 +484,7 @@ namespace rl } else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } @@ -516,17 +494,14 @@ namespace rl void MitsubishiR3::doInEquals(const ::std::size_t& inNo, const ::std::string& inVal) { - char buf[256]; - - ::snprintf(buf, 255, "1;1;IN=%zi;%s", inNo, inVal.c_str()); - buf[255] = '\0'; + this->send("1;1;IN=" + ::std::to_string(inNo) + ";" + inVal); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -534,17 +509,14 @@ namespace rl void MitsubishiR3::doLoad(const ::std::string& programName) { - char buf[256]; + this->send("1;1;LOAD=" + programName); - ::snprintf(buf, 255, "1;1;LOAD=%s", programName.c_str()); - buf[255] = '\0'; - - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -552,14 +524,14 @@ namespace rl void MitsubishiR3::doNew() { - char buf[256] = "1;1;NEW"; + this->send("1;1;NEW"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -567,17 +539,14 @@ namespace rl void MitsubishiR3::doOutEquals(const ::std::size_t& outNo, const ::std::string& outVal) { - char buf[256]; - - ::snprintf(buf, 255, "1;1;OUT=%zi;%s", outNo, outVal.c_str()); - buf[255] = '\0'; + this->send("1;1;OUT=" + ::std::to_string(outNo) + ";" + outVal); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -585,14 +554,14 @@ namespace rl void MitsubishiR3::doRstalrm() { - char buf[256] = "1;1;RSTALRM"; + this->send("1;1;RSTALRM"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -600,14 +569,14 @@ namespace rl void MitsubishiR3::doRstpwr() { - char buf[256] = "1;1;RSTPWR"; + this->send("1;1;RSTPWR"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -615,17 +584,14 @@ namespace rl void MitsubishiR3::doRun(const ::std::string& programName, const bool& doModeCycle) { - char buf[256]; + this->send("1;1;RUN" + programName + ";" + ::std::string(doModeCycle ? "1" : "0")); - ::snprintf(buf, 255, "1;1;RUN%s;%i", programName.c_str(), (doModeCycle ? 1 : 0)); - buf[255] = '\0'; - - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -633,14 +599,14 @@ namespace rl void MitsubishiR3::doSave() { - char buf[256] = "1;1;SAVE"; + this->send("1;1;SAVE"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -648,14 +614,14 @@ namespace rl void MitsubishiR3::doSlotinit() { - char buf[256] = "1;1;SLOTINIT"; + this->send("1;1;SLOTINIT"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -663,17 +629,14 @@ namespace rl void MitsubishiR3::doSrv(const bool& doOn) { - char buf[256]; - - ::snprintf(buf, 255, "1;1;SRV%s", (doOn ? "ON" : "OFF")); - buf[255] = '\0'; + this->send("1;1;SRV" + ::std::string(doOn ? "ON" : "OFF")); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -683,14 +646,14 @@ namespace rl { RunState state; - char buf[256] = "1;1;STATE"; + this->send("1;1;STATE"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) { - char* elem = buf + 2; + char* elem = buf.data() + 2; char* semicolon = nullptr; int i = 0; @@ -701,7 +664,7 @@ namespace rl if (nullptr != semicolon) { - buf[semicolon - buf] = '\0'; + buf[semicolon - buf.data()] = '\0'; } switch (i) @@ -846,7 +809,7 @@ namespace rl } else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } @@ -856,14 +819,14 @@ namespace rl void MitsubishiR3::doStop() { - char buf[256] = "1;1;STOP"; + this->send("1;1;STOP"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } } @@ -873,14 +836,14 @@ namespace rl { StopSignalState state; - char buf[256] = "1;1;STPSIG"; + this->send("1;1;STPSIG"); - this->socket.send(buf, ::std::strlen(buf)); - this->socket.recv(buf, 256); + ::std::array buf; + this->socket.recv(buf.data(), buf.size()); if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) { - char* elem = buf + 2; + char* elem = buf.data() + 2; char* semicolon = nullptr; int i = 0; @@ -891,7 +854,7 @@ namespace rl if (nullptr != semicolon) { - buf[semicolon - buf] = '\0'; + buf[semicolon - buf.data()] = '\0'; } switch (i) @@ -932,7 +895,7 @@ namespace rl } else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) { - char* errorNo = buf + 3; + char* errorNo = buf.data() + 3; throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); } @@ -957,6 +920,12 @@ namespace rl this->setConnected(true); } + void + MitsubishiR3::send(const ::std::string& command) + { + this->socket.send(command.c_str(), command.size()); + } + void MitsubishiR3::startProgram(const ::std::string& name) { diff --git a/src/rl/hal/MitsubishiR3.h b/src/rl/hal/MitsubishiR3.h index 3a12b661..36a337ef 100644 --- a/src/rl/hal/MitsubishiR3.h +++ b/src/rl/hal/MitsubishiR3.h @@ -422,6 +422,8 @@ namespace rl protected: private: + void send(const ::std::string& command); + Socket socket; }; } From dec866055d7aac76627bf2b4cec6bb6b9cc2a643 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 15 Aug 2018 22:19:28 +0200 Subject: [PATCH 153/546] Modernize string parsing in rl::hal::MitsubishiR3 --- src/rl/hal/MitsubishiR3.cpp | 828 ++++++++---------------------------- src/rl/hal/MitsubishiR3.h | 10 +- 2 files changed, 188 insertions(+), 650 deletions(-) diff --git a/src/rl/hal/MitsubishiR3.cpp b/src/rl/hal/MitsubishiR3.cpp index 69726cee..c14a26ad 100644 --- a/src/rl/hal/MitsubishiR3.cpp +++ b/src/rl/hal/MitsubishiR3.cpp @@ -25,19 +25,12 @@ // #include +#include #include -#include -#include -#include +#include #include "MitsubishiR3.h" -#ifdef WIN32 -#ifndef strncpy_s -#define strncpy strncpy_s -#endif // strncpy_s -#endif // WIN32 - namespace rl { namespace hal @@ -62,17 +55,17 @@ namespace rl this->setConnected(false); } - void - MitsubishiR3::doCalib(CalibState& state) + MitsubishiR3::CalibState + MitsubishiR3::doCalib() { this->send("1;1;CALIB"); + ::std::string reply = this->recv(); - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); + CalibState state; - if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) + if ("QoK" == reply.substr(0, 3)) { - if ('N' == buf[3]) + if ("N" == reply.substr(3, 1)) { state.isDefined = true; } @@ -81,178 +74,75 @@ namespace rl state.isDefined = false; } - char hex[2] = {buf[4], '\0'}; - int dec = ::strtol(hex, nullptr, 16); - // 00000001 - state.isAxis[0] = (dec & 1) ? true : false; - // 00000010 - state.isAxis[1] = (dec & 2) ? true : false; - // 00000100 - state.isAxis[2] = (dec & 4) ? true : false; - // 00001000 - state.isAxis[3] = (dec & 8) ? true : false; - hex[0] = buf[5]; - dec = ::strtol(hex, nullptr, 16); - // 00010000 - state.isAxis[4] = (dec & 1) ? true : false; - // 00100000 - state.isAxis[5] = (dec & 2) ? true : false; - // 01000000 - state.isAxis[6] = (dec & 4) ? true : false; - // 10000000 - state.isAxis[7] = (dec & 8) ? true : false; - } - else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); + ::std::bitset<8> isAxis(::std::stoi(reply.substr(4, 2), nullptr, 16)); + + for (::std::size_t i = 0; i < 8; ++i) + { + state.isAxis[i] = isAxis[i]; + } } + + return state; } void MitsubishiR3::doCntl(const bool& doOn) { this->send("1;1;CNTL" + ::std::string(doOn ? "ON" : "OFF")); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doDatinst(const ::std::string& j1, const ::std::string& j2, const ::std::string& j3, const ::std::string& j4, const ::std::string& j5, const ::std::string& j6, const ::std::string& checksum) { this->send("1;1;DATINST" + j1 + ";" + j2 + ";" + j3 + ";" + j4 + ";" + j5 + ";" + j6 + ";" + checksum); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doDatinst(const ::std::string& j1, const ::std::string& j2, const ::std::string& j3, const ::std::string& j4, const ::std::string& j5, const ::std::string& j6, const ::std::string& j7, const ::std::string& j8, const ::std::string& checksum) { this->send("1;1;DATINST" + j1 + ";" + j2 + ";" + j3 + ";" + j4 + ";" + j5 + ";" + j6 + ";" + j7 + ";" + j8 + ";" + checksum); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } MitsubishiR3::StopState MitsubishiR3::doDstate() { - StopState state; - this->send("1;1;DSTATE"); + ::std::string reply = this->recv(); - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); + StopState state; - if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) + if ("QoK" == reply.substr(0, 3)) { - char* elem = buf.data() + 2; - char* semicolon = nullptr; - int i = 0; + ::std::bitset<8> runSts(::std::stoi(reply.substr(3, 2), nullptr, 16)); - while (nullptr != elem) - { - ++elem; - semicolon = ::strchr(elem, ';'); - - if (nullptr != semicolon) - { - buf[semicolon - buf.data()] = '\0'; - } - - switch (i) - { - case 0: - // run status - { - char hex[2] = {elem[1], '\0'}; - int dec = ::strtol(hex, nullptr, 16); - // 00000001 - state.runSts.isRepeat = (dec & 1) ? true : false; - // 00000010 - state.runSts.isCycleStopOff = (dec & 2) ? true : false; - // 00000100 - state.runSts.isMlockOn = (dec & 4) ? true : false; - // 00001000 - state.runSts.isTeach = (dec & 8) ? true : false; - hex[0] = elem[0]; - dec = ::strtol(hex, nullptr, 16); - // 00010000 - state.runSts.isTeachRunning = (dec & 1) ? true : false; - // 00100000 - state.runSts.isServoOn = (dec & 2) ? true : false; - // 01000000 - state.runSts.isRun = (dec & 4) ? true : false; - // 10000000 - state.runSts.isOperationEnable = (dec & 8) ? true : false; - } - // stop status - { - char hex[2] = {elem[1], '\0'}; - int dec = ::strtol(hex, nullptr, 16); - // 00000001 - state.stopSts.isEmgStop = (dec & 1) ? true : false; - // 00000010 - state.stopSts.isStop = (dec & 2) ? true : false; - // 00000100 - state.stopSts.isWait = (dec & 4) ? true : false; - // 00001000 - state.stopSts.isStopSignalOff = (dec & 8) ? true : false; - hex[0] = elem[0]; - dec = ::strtol(hex, nullptr, 16); - // 00010000 - state.stopSts.isProgramSelectEnable = (dec & 1) ? true : false; - // 00100000 - state.stopSts.isReserve = (dec & 2) ? true : false; - // 01000000 - state.stopSts.isPseudoInput = (dec & 4) ? true : false; - } - // error number - { - elem += 4; - state.errorNo = ::atoi(elem); - } - break; - case 1: - // execution step number - state.stepNo = ::atoi(elem); - break; - case 2: - // mech number under use - state.mechNo = ::atoi(elem); - break; - default: - break; - } - - elem = semicolon; - ++i; - } - } - else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); + state.runSts.isRepeat = runSts[0]; + state.runSts.isCycleStopOff = runSts[1]; + state.runSts.isMlockOn = runSts[2]; + state.runSts.isTeach = runSts[3]; + state.runSts.isTeachRunning = runSts[4]; + state.runSts.isServoOn = runSts[5]; + state.runSts.isRun = runSts[6]; + state.runSts.isOperationEnable = runSts[7]; + + ::std::bitset<8> stopSts(::std::stoi(reply.substr(5, 2), nullptr, 16)); + + state.stopSts.isEmgStop = stopSts[0]; + state.stopSts.isStop = stopSts[1]; + state.stopSts.isWait = stopSts[2]; + state.stopSts.isStopSignalOff = stopSts[3]; + state.stopSts.isProgramSelectEnable = stopSts[4]; + state.stopSts.isPseudoInput = stopSts[6]; + + ::std::vector< ::std::string> tokens; + ::std::string tmp = reply.substr(7); + ::boost::split(tokens, tmp, ::boost::is_any_of(";")); + + state.errorNo = ::std::stoi(tokens[0]); + state.stepNo = ::std::stoi(tokens[1]); + state.mechNo = ::std::stoi(tokens[2]); } return state; @@ -262,39 +152,26 @@ namespace rl MitsubishiR3::doEclr() { this->send("1;9;ECLR"); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doEmdat(const ::std::string& program) { - // max. 256 - 9 (::std::strlen("1;9;EMDAT")) - 1 = 246 chars - - ::std::array buf; - ::std::size_t begin = 0; - ::std::size_t end = 0; - ::std::string lines; + // max. 256 - (9 = strlen("1;9;EMDAT")) - 1 = 246 chars - while (begin < program.length()) + for (::std::size_t begin = 0, end = 0; begin < program.length(); begin += end + 1) { - lines = program.substr(begin, 246); + ::std::string lines = program.substr(begin, 246); if (lines.length() < 246) { + end = program.length(); + if ("\v" == lines.substr(lines.length() - 1)) { lines = lines.substr(0, lines.length() - 1); } - - end = program.length(); } else { @@ -303,54 +180,7 @@ namespace rl } this->send("1;9;EMDAT" + lines); - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = nullptr; - char* errorLine = nullptr; - char* charPos = nullptr; - - char* elem = buf.data() + 2; - char* semicolon = nullptr; - int i = 0; - - while (nullptr != elem) - { - ++elem; - semicolon = ::strchr(elem, ';'); - - if (nullptr != semicolon) - { - buf[semicolon - buf.data()] = '\0'; - } - - switch (i) - { - case 0: - // error number - errorNo = elem; - break; - case 1: - // error line - errorLine = elem; - break; - case 2: - // character position - charPos = elem; - break; - default: - break; - } - - elem = semicolon; - ++i; - } - - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } - - begin += end + 1; + this->recv(); } } @@ -358,135 +188,48 @@ namespace rl MitsubishiR3::doErrormes(const int& errorNo) { this->send("1;1;ERRORMES" + ::std::to_string(errorNo)); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } - - return buf.data() + 3; + ::std::string reply = this->recv(); + return reply.substr(3); } void MitsubishiR3::doExec(const ::std::string& instruction) { this->send("1;9;EXEC" + instruction); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doHnd(const bool& doOpen, const int& handNo) { assert(0 < handNo && handNo < 9); - this->send("1;1;HND" + ::std::string(doOpen ? "ON" : "OFF") + ::std::to_string(handNo)); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } ::std::array MitsubishiR3::doHndsts() { - ::std::array state; - this->send("1;1;HNDSTS"); + ::std::string reply = this->recv(); - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); + ::std::array state; - if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) + if ("QoK" == reply.substr(0, 3)) { - char* elem = buf.data() + 2; - char* semicolon = nullptr; - int i = 0; - int j = 0; + ::std::array state; + + ::std::vector< ::std::string> tokens; + ::std::string tmp = reply.substr(3); + ::boost::split(tokens, tmp, ::boost::is_any_of(";")); - while (nullptr != elem) + for (::std::size_t i = 0; i < 8; ++i) { - ++elem; - semicolon = ::strchr(elem, ';'); - - if (nullptr != semicolon) - { - buf[semicolon - buf.data()] = '\0'; - } - - switch (j) - { - case 0: - // signal number allocated in hand - state[i].outputNo = ::atoi(elem); - break; - case 1: - // hand output status - switch (::atoi(elem)) - { - case -1: - state[i].handSts = HANDSTS_NOTUSED; - break; - case 1: - state[i].handSts = HANDSTS_OPEN; - break; - case 2: - state[i].handSts = HANDSTS_CLOSED; - break; - default: - break; - } - break; - case 2: - // hand type - switch (::atoi(elem)) - { - case -1: - state[i].handType = HANDTYPE_NOTUSED; - break; - case 0: - state[i].handType = HANDTYPE_SINGLE; - break; - case 1: - state[i].handType = HANDTYPE_DOUBLE; - break; - default: - break; - } - - ++i; - - break; - default: - break; - } - - elem = semicolon; - ++j; - j %= 3; + state[i].outputNo = ::std::stoi(tokens[i * 3 + 0]); + state[i].handSts = static_cast(::std::stoi(tokens[i * 3 + 1])); + state[i].handType = static_cast(::std::stoi(tokens[i * 3 + 2])); } } - else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } return state; } @@ -495,322 +238,153 @@ namespace rl MitsubishiR3::doInEquals(const ::std::size_t& inNo, const ::std::string& inVal) { this->send("1;1;IN=" + ::std::to_string(inNo) + ";" + inVal); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doLoad(const ::std::string& programName) { this->send("1;1;LOAD=" + programName); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doNew() { this->send("1;1;NEW"); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doOutEquals(const ::std::size_t& outNo, const ::std::string& outVal) { this->send("1;1;OUT=" + ::std::to_string(outNo) + ";" + outVal); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doRstalrm() { this->send("1;1;RSTALRM"); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doRstpwr() { this->send("1;1;RSTPWR"); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doRun(const ::std::string& programName, const bool& doModeCycle) { this->send("1;1;RUN" + programName + ";" + ::std::string(doModeCycle ? "1" : "0")); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doSave() { this->send("1;1;SAVE"); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doSlotinit() { this->send("1;1;SLOTINIT"); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } void MitsubishiR3::doSrv(const bool& doOn) { this->send("1;1;SRV" + ::std::string(doOn ? "ON" : "OFF")); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } MitsubishiR3::RunState MitsubishiR3::doState() { - RunState state; - this->send("1;1;STATE"); + ::std::string reply = this->recv(); - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); + RunState state; - if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) + if ("QoK" == reply.substr(0, 3)) { - char* elem = buf.data() + 2; - char* semicolon = nullptr; - int i = 0; + ::std::vector< ::std::string> tokens; + ::std::string tmp = reply.substr(3); + ::boost::split(tokens, tmp, ::boost::is_any_of(";")); + + state.programName = tokens[0]; + + state.lineNo = ::std::stoi(tokens[1]); + state.override = ::std::stoi(tokens[2]); + + ::std::bitset<8> editSts(::std::stoi(tokens[3], nullptr, 16)); + + state.editSts.isEditing = editSts[0]; + state.editSts.isRunning = editSts[1]; + state.editSts.isChanged = editSts[2]; - while (nullptr != elem) + ::std::bitset<8> runSts(::std::stoi(tokens[4].substr(0, 2), nullptr, 16)); + + state.runSts.isRepeat = runSts[0]; + state.runSts.isCycleStopOff = runSts[1]; + state.runSts.isMlockOn = runSts[2]; + state.runSts.isTeach = runSts[3]; + state.runSts.isTeachRunning = runSts[4]; + state.runSts.isServoOn = runSts[5]; + state.runSts.isRun = runSts[6]; + state.runSts.isOperationEnable = runSts[7]; + + ::std::bitset<8> stopSts(::std::stoi(tokens[4].substr(2, 2), nullptr, 16)); + + state.stopSts.isEmgStop = stopSts[0]; + state.stopSts.isStop = stopSts[1]; + state.stopSts.isWait = stopSts[2]; + state.stopSts.isStopSignalOff = stopSts[3]; + state.stopSts.isProgramSelectEnable = stopSts[4]; + state.stopSts.isPseudoInput = stopSts[6]; + + state.errorNo = ::std::stoi(tokens[4].substr(4)); + state.stepNo = ::std::stoi(tokens[5]); + + ::std::bitset<8> mechInfo(::std::stoi(tokens[6], nullptr, 16)); + + for (::std::size_t i = 0; i < 3; ++i) { - ++elem; - semicolon = ::strchr(elem, ';'); - - if (nullptr != semicolon) - { - buf[semicolon - buf.data()] = '\0'; - } - - switch (i) - { - case 0: - // program name loaded into task slot - ::strncpy(state.programName, elem, 255); - state.programName[255] = '\0'; - break; - case 1: - // execution line number - state.lineNo = ::atoi(elem); - break; - case 2: - // a present override value is read - state.override = ::atoi(elem); - break; - case 3: - // edit status - { - int dec = ::strtol(elem, nullptr, 16); - // 00000001 - state.editSts.isEditing = (dec & 1) ? true : false; - // 00000010 - state.editSts.isRunning = (dec & 2) ? true : false; - // 00000100 - state.editSts.isChanged = (dec & 4) ? true : false; - } - break; - case 4: - // run status - { - char hex[2] = {elem[1], '\0'}; - int dec = ::strtol(hex, nullptr, 16); - // 00000001 - state.runSts.isRepeat = (dec & 1) ? true : false; - // 00000010 - state.runSts.isCycleStopOff = (dec & 2) ? true : false; - // 00000100 - state.runSts.isMlockOn = (dec & 4) ? true : false; - // 00001000 - state.runSts.isTeach = (dec & 8) ? true : false; - hex[0] = elem[0]; - dec = ::strtol(hex, nullptr, 16); - // 00010000 - state.runSts.isTeachRunning = (dec & 1) ? true : false; - // 00100000 - state.runSts.isServoOn = (dec & 2) ? true : false; - // 01000000 - state.runSts.isRun = (dec & 4) ? true : false; - // 10000000 - state.runSts.isOperationEnable = (dec & 8) ? true : false; - } - // stop status - { - char hex[2] = {elem[3], '\0'}; - int dec = ::strtol(hex, nullptr, 16); - // 00000001 - state.stopSts.isEmgStop = (dec & 1) ? true : false; - // 00000010 - state.stopSts.isStop = (dec & 2) ? true : false; - // 00000100 - state.stopSts.isWait = (dec & 4) ? true : false; - // 00001000 - state.stopSts.isStopSignalOff = (dec & 8) ? true : false; - hex[0] = elem[2]; - dec = ::strtol(hex, nullptr, 16); - // 00010000 - state.stopSts.isProgramSelectEnable = (dec & 1) ? true : false; - // 00100000 - state.stopSts.isReserve = (dec & 2) ? true : false; - // 01000000 - state.stopSts.isPseudoInput = (dec & 4) ? true : false; - } - // error number - { - state.errorNo = ::atoi(elem + 4); - } - break; - case 5: - // execution step number - state.stepNo = ::atoi(elem); - break; - case 6: - // mech info - { - int dec = ::strtol(elem, nullptr, 16); - // 00000001 - state.mechInfo[0] = (dec & 1) ? true : false; - // 00000010 - state.mechInfo[1] = (dec & 2) ? true : false; - // 00000100 - state.mechInfo[2] = (dec & 4) ? true : false; - } - break; - case 14: - // program name of slot table - ::strncpy(state.taskPrgName, elem, 255); - state.taskPrgName[255] = '\0'; - break; - case 15: - // operation mode of slot table - if (0 == ::std::strcmp(elem, "CYC")) - { - state.isTaskModeCycle = true; - } - else - { - state.isTaskModeCycle = false; - } - break; - case 16: - // stating conditions of slot table - if (0 == ::std::strcmp(elem, "START")) - { - state.taskCond = TASKCOND_START; - } - else if (0 == ::std::strcmp(elem, "ALWAYS")) - { - state.taskCond = TASKCOND_ALWAYS; - } - else if (0 == ::std::strcmp(elem, "ERROR")) - { - state.taskCond = TASKCOND_ERROR; - } - break; - case 17: - // priority of slot table - state.taskPri = ::atoi(elem); - break; - case 18: - // mech number under use - state.mechNo = ::atoi(elem); - break; - default: - break; - } - - elem = semicolon; - ++i; + state.mechInfo[i] = mechInfo[i]; } - } - else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); + + state.taskPrgName = tokens[14]; + + if ("CYC" == tokens[15]) + { + state.isTaskModeCycle = true; + } + else + { + state.isTaskModeCycle = false; + } + + if ("START" == tokens[16]) + { + state.taskCond = TASKCOND_START; + } + else if ("ALWAYS" == tokens[16]) + { + state.taskCond = TASKCOND_ALWAYS; + } + else if ("ERROR" == tokens[16]) + { + state.taskCond = TASKCOND_ERROR; + } + + state.taskPri = ::std::stoi(tokens[17]); + state.mechNo = ::std::stoi(tokens[18]); } return state; @@ -820,83 +394,31 @@ namespace rl MitsubishiR3::doStop() { this->send("1;1;STOP"); - - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); - - if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); - } + this->recv(); } MitsubishiR3::StopSignalState MitsubishiR3::doStpsig() { - StopSignalState state; - this->send("1;1;STPSIG"); + ::std::string reply = this->recv(); - ::std::array buf; - this->socket.recv(buf.data(), buf.size()); + StopSignalState state; - if ('Q' == buf[0] && 'o' == buf[1] && 'K' == buf[2]) + if ("QoK" == reply.substr(0, 3)) { - char* elem = buf.data() + 2; - char* semicolon = nullptr; - int i = 0; + ::std::bitset<4> stopSts(::std::stoi(reply.substr(3, 1), nullptr, 16)); - while (nullptr != elem) - { - ++elem; - semicolon = ::strchr(elem, ';'); - - if (nullptr != semicolon) - { - buf[semicolon - buf.data()] = '\0'; - } - - switch (i) - { - case 0: - // the state of the stop signal - { - int dec = ::strtol(elem, nullptr, 16); - // 00000001 - state.isTb = (dec & 1) ? true : false; - // 00000010 - state.isPc = (dec & 2) ? true : false; - // 00000100 - state.isIo = (dec & 4) ? true : false; - // 00001000 - state.isOp = (dec & 8) ? true : false; - } - break; - case 1: - // the state of the emg stop signal - { - int dec = ::strtol(elem, nullptr, 16); - // 00000001 - state.isIoEmg = (dec & 1) ? true : false; - // 00000010 - state.isOpEmg = (dec & 2) ? true : false; - // 00000100 - state.isTbEmg = (dec & 4) ? true : false; - } - break; - default: - break; - } - - elem = semicolon; - ++i; - } - } - else if ('Q' == buf[0] && 'e' == buf[1] && 'R' == buf[2]) - { - char* errorNo = buf.data() + 3; - throw Exception(::atoi(errorNo), ::std::string(this->doErrormes(::atoi(errorNo)) + " (" + errorNo + ")")); + state.isTb = stopSts[0]; + state.isPc = stopSts[1]; + state.isIo = stopSts[2]; + state.isOp = stopSts[3]; + + ::std::bitset<4> emgSts(::std::stoi(reply.substr(5, 1), nullptr, 16)); + + state.isIoEmg = emgSts[0]; + state.isOpEmg = emgSts[1]; + state.isTbEmg = emgSts[2]; } return state; @@ -920,6 +442,22 @@ namespace rl this->setConnected(true); } + ::std::string + MitsubishiR3::recv() + { + ::std::array buffer; + ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); + ::std::string reply(buffer.data(), size); + + if ("QeR" == reply.substr(0, 3)) + { + int errorNo = ::std::stoi(reply.substr(3)); + throw Exception(errorNo, ::std::string(this->doErrormes(errorNo) + " (" + ::std::to_string(errorNo) + ")")); + } + + return reply; + } + void MitsubishiR3::send(const ::std::string& command) { diff --git a/src/rl/hal/MitsubishiR3.h b/src/rl/hal/MitsubishiR3.h index 36a337ef..ff285d4e 100644 --- a/src/rl/hal/MitsubishiR3.h +++ b/src/rl/hal/MitsubishiR3.h @@ -143,8 +143,6 @@ namespace rl bool isStopSignalOff; /** Program select enable. */ bool isProgramSelectEnable; - /** (reserve). */ - bool isReserve; /** Pseudo input. */ bool isPseudoInput; }; @@ -160,7 +158,7 @@ namespace rl struct RunState { /** Program name loaded into task slot. */ - char programName[256]; + ::std::string programName; /** Execution line number. */ int lineNo; /** A present override value is read. */ @@ -178,7 +176,7 @@ namespace rl /** Mech info. */ MechInfo mechInfo; /** Program name of slot table. */ - char taskPrgName[256]; + ::std::string taskPrgName; /** Operation mode of slot table (REP / CYC). */ bool isTaskModeCycle; /** Stating conditions of slot table. */ @@ -235,7 +233,7 @@ namespace rl * * @param[out] state Install state */ - void doCalib(CalibState& state); + CalibState doCalib(); /** * Operation enable or disable. @@ -422,6 +420,8 @@ namespace rl protected: private: + ::std::string recv(); + void send(const ::std::string& command); Socket socket; From e356441eb8798ed442f7940ec75150eee82599c6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 15 Aug 2018 22:30:49 +0200 Subject: [PATCH 154/546] Remove unnecessary compiler definitions --- CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 75ab204e..031603ac 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -30,9 +30,7 @@ endif() if(WIN32) add_definitions( - -D_CRT_SECURE_NO_WARNINGS -D_ENABLE_EXTENDED_ALIGNED_STORAGE - -D_SCL_SECURE_NO_WARNINGS -D_USE_MATH_DEFINES -D_WIN32_WINNT=0x501 -DNOMINMAX From 2ada8da4377ad13030009fd759c7906b99575410 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 28 Aug 2018 17:58:40 +0200 Subject: [PATCH 155/546] Add device driver for Robotiq gripper model C --- demos/rlGripperDemo/CMakeLists.txt | 10 + demos/rlGripperDemo/rlRobotiqModelCDemo.cpp | 90 +++++ src/rl/hal/CMakeLists.txt | 2 + src/rl/hal/RobotiqModelC.cpp | 387 ++++++++++++++++++++ src/rl/hal/RobotiqModelC.h | 170 +++++++++ 5 files changed, 659 insertions(+) create mode 100644 demos/rlGripperDemo/rlRobotiqModelCDemo.cpp create mode 100644 src/rl/hal/RobotiqModelC.cpp create mode 100644 src/rl/hal/RobotiqModelC.h diff --git a/demos/rlGripperDemo/CMakeLists.txt b/demos/rlGripperDemo/CMakeLists.txt index 64bfdf55..66648623 100644 --- a/demos/rlGripperDemo/CMakeLists.txt +++ b/demos/rlGripperDemo/CMakeLists.txt @@ -29,3 +29,13 @@ target_link_libraries( if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_link_libraries(rlGripperDemo ${Boost_LIBRARIES}) endif() + +add_executable( + rlRobotiqModelCDemo + rlRobotiqModelCDemo.cpp +) + +target_link_libraries( + rlRobotiqModelCDemo + hal +) diff --git a/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp b/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp new file mode 100644 index 00000000..f5e940f7 --- /dev/null +++ b/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp @@ -0,0 +1,90 @@ +// +// Copyright (c) 2013, Andre Gaschler +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 + +int +main(int argc, char** argv) +{ + try + { +#ifdef WIN32 + rl::hal::RobotiqModelC gripper("COM3"); +#else + rl::hal::RobotiqModelC gripper("/dev/ttyUSB0"); +#endif + + gripper.open(); + gripper.start(); + + do + { + gripper.step(); + std::cout << "activationStatus: " << gripper.getActivationStatus() << " - gripperStatus: " << gripper.getGripperStatus() << std::endl; + } + while (!gripper.isRunning()); + + gripper.setForcePercentage(0.1f); + gripper.setPositionPercentage(1.0f); + gripper.setSpeedPercentage(0.25f); + + do + { + gripper.step(); + std::cout << "position: " << gripper.getPositionPercentage() << " - current: " << gripper.getCurrent() << std::endl; + } + while (rl::hal::RobotiqModelC::OBJECT_STATUS_MOTION == gripper.getObjectStatus()); + + for (std::size_t i = 0; i < 100; ++i) + { + gripper.step(); + std::cout << "position: " << gripper.getPositionPercentage() << " - current: " << gripper.getCurrent() << std::endl; + } + + gripper.setForcePercentage(0.1f); + gripper.setPositionPercentage(0.0f); + gripper.setSpeedPercentage(0.5f); + + do + { + gripper.step(); + std::cout << "position: " << gripper.getPositionPercentage() << " - current: " << gripper.getCurrent() << std::endl; + } + while (rl::hal::RobotiqModelC::OBJECT_STATUS_MOTION == gripper.getObjectStatus()); + + gripper.stop(); + gripper.close(); + } + catch (const std::exception& e) + { + std::cerr << e.what() << std::endl; + return EXIT_FAILURE; + } + + return EXIT_SUCCESS; +} diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index aceea90f..527eb094 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -58,6 +58,7 @@ set( MitsubishiH7.h MitsubishiR3.h RangeSensor.h + RobotiqModelC.h SchmersalLss300.h SchunkFpsF5.h Serial.h @@ -120,6 +121,7 @@ set( MitsubishiH7.cpp MitsubishiR3.cpp RangeSensor.cpp + RobotiqModelC.cpp SchmersalLss300.cpp SchunkFpsF5.cpp Serial.cpp diff --git a/src/rl/hal/RobotiqModelC.cpp b/src/rl/hal/RobotiqModelC.cpp new file mode 100644 index 00000000..c0555602 --- /dev/null +++ b/src/rl/hal/RobotiqModelC.cpp @@ -0,0 +1,387 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Endian.h" +#include "RobotiqModelC.h" + +namespace rl +{ + namespace hal + { + RobotiqModelC::RobotiqModelC(const ::std::string& filename) : + CyclicDevice(::std::chrono::microseconds(5)), + Gripper(), + in(), + out(), + serial( + filename, + Serial::BAUDRATE_115200BPS, + Serial::DATABITS_8BITS, + Serial::FLOWCONTROL_OFF, + Serial::PARITY_NOPARITY, + Serial::STOPBITS_1BIT + ) + { + this->in.fill(0x00); + this->out.fill(0x00); + } + + RobotiqModelC::~RobotiqModelC() + { + } + + void + RobotiqModelC::close() + { + assert(this->isConnected()); + + this->serial.close(); + this->setConnected(false); + } + + ::std::uint16_t + RobotiqModelC::crc(const ::std::uint8_t* buf, const ::std::size_t& len) const + { + ::std::uint16_t checksum = 0xFFFF; + + for (::std::size_t i = 0; i < len; ++i) + { + checksum ^= buf[i]; + + for (::std::size_t i = 8; i != 0; --i) + { + if (checksum & 0x0001) + { + checksum >>= 1; + checksum ^= 0xA001; + } + else + { + checksum >>= 1; + } + } + } + + return checksum; + } + + RobotiqModelC::ActionStatus + RobotiqModelC::getActionStatus() const + { + return static_cast((this->in[3] >> 3) & 0x01); + } + + RobotiqModelC::ActivationStatus + RobotiqModelC::getActivationStatus() const + { + return static_cast(this->in[3] & 0x01); + } + + ::rl::math::Real + RobotiqModelC::getCurrent() const + { + return this->in[8] * ::rl::math::MILLI2UNIT; + } + + RobotiqModelC::FaultStatus + RobotiqModelC::getFaultStatus() const + { + return static_cast(this->in[5] & 0x0F); + } + + RobotiqModelC::GripperStatus + RobotiqModelC::getGripperStatus() const + { + return static_cast((this->in[3] >> 4) & 0x03); + } + + RobotiqModelC::ObjectStatus + RobotiqModelC::getObjectStatus() const + { + return static_cast((this->in[3] >> 6) & 0x03); + } + + ::rl::math::Real + RobotiqModelC::getPositionPercentage() const + { + return this->in[7] / static_cast< ::rl::math::Real>(0xFF); + } + + ::rl::math::Real + RobotiqModelC::getPositionRequestEchoPercentage() const + { + return this->in[6] / static_cast< ::rl::math::Real>(0xFF); + } + + void + RobotiqModelC::halt() + { + this->out[10] = this->in[6]; + } + + void + RobotiqModelC::open() + { + this->serial.open(); + this->setConnected(true); + } + + ::std::size_t + RobotiqModelC::recv(::std::uint8_t* buf, const ::std::size_t& len) + { + assert(this->isConnected()); + + ::std::uint8_t* ptr = buf; + ::std::size_t sumbytes = 0; + ::std::size_t numbytes = 0; + + while (sumbytes < len) + { + numbytes = this->serial.read(ptr, len - sumbytes); + ptr += numbytes; + sumbytes += numbytes; + } + + if (this->crc(buf, sumbytes - 2) != Endian::hostWord(buf[sumbytes - 1], buf[sumbytes - 2])) + { + throw DeviceException("checksum error"); + } + + return sumbytes; + } + + void + RobotiqModelC::release() + { + this->out[10] = 0x00; + } + + void + RobotiqModelC::send(::std::uint8_t* buf, const ::std::size_t& len) + { + assert(this->isConnected()); + + buf[0] = 0x09; + + ::std::uint16_t checksum = this->crc(buf, len - 2); + + buf[len - 2] = Endian::hostLowByte(checksum); + buf[len - 1] = Endian::hostHighByte(checksum); + + if (len != this->serial.write(buf, len)) + { + throw DeviceException("could not send complete data"); + } + } + + void + RobotiqModelC::setForcePercentage(const ::rl::math::Real& forcePercentage) + { + this->out[12] = static_cast< ::std::uint8_t>(0xFF * forcePercentage); + } + + void + RobotiqModelC::setPositionPercentage(const ::rl::math::Real& positionPercentage) + { + this->out[10] = static_cast< ::std::uint8_t>(0xFF * positionPercentage); + } + + void + RobotiqModelC::setSpeedPercentage(const ::rl::math::Real& speedPercentage) + { + this->out[11] = static_cast< ::std::uint8_t>(0xFF * speedPercentage); + } + + void + RobotiqModelC::shut() + { + this->out[10] = 0xFF; + } + + void + RobotiqModelC::start() + { + this->step(); + + if (ACTIVATION_STATUS_READY != this->getActivationStatus() || GRIPPER_STATUS_READY != this->getGripperStatus()) + { + this->out[1] = 0x10; // function code + + this->out[2] = 0x03; // address of register to write + this->out[3] = 0xE8; // address of register to write + + this->out[4] = 0x00; // number of registers to write + this->out[5] = 0x01; // number of registers to write + + this->out[6] = 0x02; // number of data bytes + + this->out[7] = 0x00; // value written to register 03E8 (action request) + this->out[8] = 0x00; // value written to register 03E8 (gripper options) + + this->send(this->out.data(), 1 + 1 + 2 + 2 + 1 + 2 + 2); + this->recv(this->in.data(), 1 + 1 + 2 + 2 + 2); + + this->out[1] = 0x10; // function code + + this->out[2] = 0x03; // address of register to write + this->out[3] = 0xE8; // address of register to write + + this->out[4] = 0x00; // number of registers to write + this->out[5] = 0x01; // number of registers to write + + this->out[6] = 0x02; // number of data bytes + + this->out[7] = 0x01; // value written to register 03E8 (action request) + this->out[8] = 0x00; // value written to register 03E8 (gripper options) + + this->send(this->out.data(), 1 + 1 + 2 + 2 + 1 + 2 + 2); + this->recv(this->in.data(), 1 + 1 + 2 + 2 + 2); + } + } + + void + RobotiqModelC::step() + { + if (0x03 == this->in[1] && this->out[10] != this->in[6]) + { + this->out[1] = 0x10; // function code + + this->out[2] = 0x03; // address of register to write + this->out[3] = 0xE8; // address of register to write + + this->out[4] = 0x00; // number of registers to write + this->out[5] = 0x03; // number of registers to write + + this->out[6] = 0x06; // number of data bytes + + this->out[7] = 0x09; // value written to register 03E8 (action request) + this->out[8] = 0x00; // value written to register 03E8 (gripper options) + + this->out[9] = 0x00; // value written to register 03E9 (gripper options 2) +#if 0 + this->out[10] = 0x00; // value written to register 03E9 (position request) + + this->out[11] = 0x00; // value written to register 03EA (speed) + this->out[12] = 0x00; // value written to register 03EA (force) +#endif + + this->send(this->out.data(), 1 + 1 + 2 + 2 + 1 + 3 * 2 + 2); + this->recv(this->in.data(), 1 + 1 + 2 + 2 + 2); + } + + this->out[1] = 0x03; // function code + + this->out[2] = 0x07; // address of register to read + this->out[3] = 0xD0; // address of register to read + + this->out[4] = 0x00; // number of registers to read + this->out[5] = 0x03; // number of registers to read + + this->send(this->out.data(), 1 + 1 + 2 + 2 + 2); + this->recv(this->in.data(), 1 + 1 + 1 + 6 + 2); + + if (this->getFaultStatus() >= 0x0A) + { + throw Exception(this->getFaultStatus()); + } + + if (ACTIVATION_STATUS_READY == this->getActivationStatus() && GRIPPER_STATUS_READY == this->getGripperStatus()) + { + this->setRunning(true); + } + else + { + this->setRunning(false); + } + } + + void + RobotiqModelC::stop() + { + this->setRunning(false); + } + + RobotiqModelC::Exception::Exception(const FaultStatus& faultStatus) : + DeviceException(""), + faultStatus(faultStatus) + { + } + + RobotiqModelC::Exception::~Exception() + { + } + + RobotiqModelC::FaultStatus + RobotiqModelC::Exception::getFaultStatus() const + { + return this->faultStatus; + } + + const char* + RobotiqModelC::Exception::what() const throw() + { + switch (this->faultStatus) + { + case FAULT_STATUS_NONE: + return "No fault."; + break; + case FAULT_STATUS_NOTICE_ACTIVATION_NEEDED: + return "The activation bit must be set prior to action"; + break; + case FAULT_STATUS_WARNING_TEMPERATURE: + return "Maximum operating temperature exceeded, wait for cool-down"; + break; + case FAULT_STATUS_WARNING_COMM_NOT_READY: + return "The communication chip is not ready (may be booting)."; + break; + case FAULT_STATUS_WARNING_VOLTAGE: + return "Under minimum operating voltage."; + break; + case FAULT_STATUS_WARNING_AUTOMATIC_RELEASE: + return "Automatic release in progress."; + break; + case FAULT_STATUS_ERROR_INTERNAL: + return "Internal fault."; + break; + case FAULT_STATUS_ERROR_ACTIVATION_FAULT: + return "Activation fault, verify that no interference or other error occurred."; + break; + case FAULT_STATUS_ERROR_MODE_FAULT: + return "Overcurrent triggered."; + break; + case FAULT_STATUS_ERROR_AUTOMATIC_RELEASE_COMPLETE: + return "Automatic release completed."; + break; + default: + return "Unknown fault."; + break; + } + } + } +} diff --git a/src/rl/hal/RobotiqModelC.h b/src/rl/hal/RobotiqModelC.h new file mode 100644 index 00000000..40a64c2c --- /dev/null +++ b/src/rl/hal/RobotiqModelC.h @@ -0,0 +1,170 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_HAL_ROBOTIQMODELC_H +#define RL_HAL_ROBOTIQMODELC_H + +#include +#include + +#include "CyclicDevice.h" +#include "DeviceException.h" +#include "Gripper.h" +#include "Serial.h" + +namespace rl +{ + namespace hal + { + class RobotiqModelC : public CyclicDevice, public Gripper + { + public: + enum ActionStatus + { + ACTION_STATUS_STOPPED = 0x00, + ACTION_STATUS_GOING = 0x01 + }; + + enum ActivationStatus + { + ACTIVATION_STATUS_RESET = 0x00, + ACTIVATION_STATUS_READY = 0x01 + }; + + enum FaultStatus + { + FAULT_STATUS_NONE = 0x00, + FAULT_STATUS_UNKNOWN_1 = 0x01, + FAULT_STATUS_UNKNOWN_2 = 0x02, + FAULT_STATUS_UNKNOWN_3 = 0x03, + FAULT_STATUS_UNKNOWN_4 = 0x04, + FAULT_STATUS_NOTICE_ACTIVATION_DELAYED = 0x05, + FAULT_STATUS_NOTICE_MODE_DELAYED = 0x06, + FAULT_STATUS_NOTICE_ACTIVATION_NEEDED = 0x07, + FAULT_STATUS_WARNING_TEMPERATURE = 0x08, + FAULT_STATUS_WARNING_COMM_NOT_READY = 0x09, + FAULT_STATUS_WARNING_VOLTAGE = 0x0A, + FAULT_STATUS_WARNING_AUTOMATIC_RELEASE = 0x0B, + FAULT_STATUS_ERROR_INTERNAL = 0x0C, + FAULT_STATUS_ERROR_ACTIVATION_FAULT = 0x0D, + FAULT_STATUS_ERROR_MODE_FAULT = 0x0E, + FAULT_STATUS_ERROR_AUTOMATIC_RELEASE_COMPLETE = 0x0F + }; + + enum GripperStatus + { + GRIPPER_STATUS_RESET = 0x00, + GRIPPER_STATUS_ACTIVATING = 0x01, + GRIPPER_STATUS_UNUSED = 0x02, + GRIPPER_STATUS_READY = 0x03 + }; + + enum ObjectStatus + { + OBJECT_STATUS_MOTION = 0x00, + OBJECT_STATUS_CONTACT_OPEN = 0x01, + OBJECT_STATUS_CONTACT_CLOSE = 0x02, + OBJECT_STATUS_MOTION_COMPLETE = 0x03 + }; + + class Exception : public DeviceException + { + public: + Exception(const FaultStatus& faultStatus); + + virtual ~Exception() throw(); + + FaultStatus getFaultStatus() const; + + virtual const char* what() const throw(); + + protected: + + private: + FaultStatus faultStatus; + }; + + RobotiqModelC(const ::std::string& filename); + + virtual ~RobotiqModelC(); + + void close(); + + ActionStatus getActionStatus() const; + + ActivationStatus getActivationStatus() const; + + ::rl::math::Real getCurrent() const; + + FaultStatus getFaultStatus() const; + + GripperStatus getGripperStatus() const; + + ObjectStatus getObjectStatus() const; + + ::rl::math::Real getPositionPercentage() const; + + ::rl::math::Real getPositionRequestEchoPercentage() const; + + void halt(); + + void open(); + + void release(); + + void setForcePercentage(const ::rl::math::Real& forcePercentage); + + void setPositionPercentage(const ::rl::math::Real& positionPercentage); + + void setSpeedPercentage(const ::rl::math::Real& speedPercentage); + + void shut(); + + void start(); + + void step(); + + void stop(); + + protected: + + private: + ::std::uint16_t crc(const ::std::uint8_t* buf, const ::std::size_t& len) const; + + ::std::size_t recv(::std::uint8_t* buf, const ::std::size_t& len); + + void send(::std::uint8_t* buf, const ::std::size_t& len); + + ::std::array< ::std::uint8_t, 32> in; + + ::std::array< ::std::uint8_t, 32> out; + + Serial serial; + }; + } +} + +#endif // RL_HAL_ROBOTIQMODELC_H From 3243134428c10052c66e9b49ce6e1f4a7e0f92ef Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 28 Aug 2018 19:54:48 +0200 Subject: [PATCH 156/546] Add rl::hal::RobotiqModelC to mainpage.dox --- src/rl/mainpage.dox | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/mainpage.dox b/src/rl/mainpage.dox index 5f8a3615..2d6b8421 100644 --- a/src/rl/mainpage.dox +++ b/src/rl/mainpage.dox @@ -29,7 +29,7 @@ For first time users, please have a look at our getPosition(); - if (kinematic->calculateInversePosition(x, index.row(), 1.0f)) +#ifdef RL_MDL_NLOPT + rl::mdl::NloptInverseKinematics ik(kinematic); +#else + rl::mdl::JacobianInverseKinematics ik(kinematic); + ik.delta = 1.0f; +#endif + ik.goals.push_back(std::make_pair(x, index.row())); + + if (ik.solve()) { kinematic->forwardPosition(); diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 89e228f7..79b12cd2 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -53,51 +53,6 @@ namespace rl { } - bool - Kinematic::calculateInversePosition(const ::rl::math::Transform& x, const ::std::size_t& leaf, const ::rl::math::Real& delta, const ::rl::math::Real& epsilon, const ::std::size_t& iterations) - { - ::rl::math::Vector q = this->getPosition(); - ::rl::math::Vector dq(this->getDofPosition()); - ::rl::math::Vector dx(6 * this->getOperationalDof()); - dx.setZero(); - - ::rl::math::Real norm = 1; - - for (::std::size_t i = 0; i < iterations && norm > epsilon; ++i) - { - this->forwardPosition(); - - ::rl::math::VectorBlock dxi = dx.segment(6 * leaf, 6); - dxi = this->getOperationalPosition(leaf).toDelta(x); - - this->calculateJacobian(); - this->calculateJacobianInverse(); - dq = this->invJ * dx; - - norm = dq.norm(); - - if (norm > delta) - { - dq *= delta / norm; - norm = dq.norm(); - } - - q += dq; - - this->setPosition(q); - } - - if (norm > epsilon) - { - return false; - } - - this->normalize(q); - this->setPosition(q); - - return this->isValid(q); - } - void Kinematic::calculateJacobian(const bool& inWorldFrame) { diff --git a/src/rl/mdl/Kinematic.h b/src/rl/mdl/Kinematic.h index 1e851327..4d4cb248 100644 --- a/src/rl/mdl/Kinematic.h +++ b/src/rl/mdl/Kinematic.h @@ -46,23 +46,6 @@ namespace rl Model* clone() const; - /** - * Resolved motion rate control. - * - * @pre setPosition() - * @post getPosition() - * - * @see calculateJacobian() - * @see calculateJacobianInverse() - */ - bool calculateInversePosition( - const ::rl::math::Transform& x, - const ::std::size_t& leaf = 0, - const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(), - const ::rl::math::Real& epsilon = 1.0e-3f, - const ::std::size_t& iterations = 1000 - ); - /** * Calculate Jacobian matrix. * diff --git a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp index 45dc3919..ad296776 100644 --- a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp +++ b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp @@ -32,6 +32,12 @@ #include #include +#ifdef RL_MDL_NLOPT +#include +#else +#include +#endif + int main(int argc, char** argv) { @@ -62,6 +68,13 @@ main(int argc, char** argv) nTests = 100; +#ifdef RL_MDL_NLOPT + rl::mdl::NloptInverseKinematics ik(kinematics); +#else + rl::mdl::JacobianInverseKinematics ik(kinematics); + ik.delta = 0.5f; +#endif + for (n = 0, wrongs = 0, wrongT = 0, ngotinverse = 0; n < nTests && wrongT < 100 && wrongs < 100; ++n) { for (std::size_t i = 0; i < 6; ++i) @@ -78,7 +91,10 @@ main(int argc, char** argv) kinematics->setPosition(qzero); kinematics->forwardPosition(); - if (!kinematics->calculateInversePosition(t, 0, 0.5)) + ik.goals.clear(); + ik.goals.push_back(std::make_pair(t, 0)); + + if (!ik.solve()) { continue; } From d50fcea16907e130715587e30035a396fd25b7c5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 8 Sep 2018 14:33:41 +0200 Subject: [PATCH 158/546] Add getMinimumMaximum() to rl::math::Polynomial and rl::math::Spline --- src/rl/math/Polynomial.h | 44 ++++++++++++++++++++++++++++++++++++++++ src/rl/math/Spline.h | 28 ++++++++++++++++++++++++- 2 files changed, 71 insertions(+), 1 deletion(-) diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index d9286815..4bf8b6d5 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -266,6 +266,50 @@ namespace rl return maximum; } + ::std::pair getMinimumMaximum() const + { + Polynomial derivative = this->derivative(); + + T minimum = (*this)(this->x0); + T maximum = (*this)(this->x0); + T y1 = (*this)(this->x1); + + for (::std::ptrdiff_t row = 0; row < TypeTraits::size(minimum); ++row) + { + minimum[row] = ::std::min(minimum[row], y1[row]); + maximum[row] = ::std::max(maximum[row], y1[row]); + + ::std::vector coefficients(derivative.degree() + 1); + + for (::std::size_t i = 0; i < derivative.degree() + 1; ++i) + { + coefficients[i] = derivative.coefficient(i)[row]; + } + + ::std::vector extrema = this->realRoots(coefficients); + + for (::std::vector::const_iterator x = extrema.begin(); x < extrema.end(); ++x) + { + if (this->x0 < *x && *x < this->x1) + { + Real y = (*this)(*x)[row]; + + if (y < minimum[row]) + { + minimum[row] = y; + } + + if (y > maximum[row]) + { + maximum[row] = y; + } + } + } + } + + return ::std::pair(minimum, maximum); + } + Polynomial integral() const { Polynomial f(this->degree() + 1); diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 5e165c0c..de6f0788 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -1214,10 +1214,36 @@ namespace rl } } } - + return maximum; } + ::std::pair getMinimumMaximum() const + { + T minimum = (*this)(this->x0); + T maximum = (*this)(this->x0); + + for (::std::size_t i = 0; i < this->size(); ++i) + { + ::std::pair minmaxOfPolynomial = this->polynomials[i].getMinimumMaximum(); + + for (::std::ptrdiff_t row = 0; row < maximum.size(); ++row) + { + if (minmaxOfPolynomial.first[row] < minimum[row]) + { + minimum[row] = minmaxOfPolynomial.first[row]; + } + + if (minmaxOfPolynomial.second[row] > maximum[row]) + { + maximum[row] = minmaxOfPolynomial.second[row]; + } + } + } + + return ::std::pair(minimum, maximum); + } + /** * Verifies that the spline is smooth and has no jumps * at the piecewise function boundaries. From 7cc0c7e7f4df23c550499a0e1234cc52ce4f0972 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 12 Sep 2018 18:40:07 +0200 Subject: [PATCH 159/546] Add common base class for rl::sg --- src/rl/sg/Base.cpp | 41 ++++++++++++++++++++++++++++++++++ src/rl/sg/Base.h | 48 ++++++++++++++++++++++++++++++++++++++++ src/rl/sg/Body.cpp | 1 + src/rl/sg/Body.h | 4 +++- src/rl/sg/CMakeLists.txt | 2 ++ src/rl/sg/Model.cpp | 1 + src/rl/sg/Model.h | 4 +++- src/rl/sg/Scene.cpp | 1 + src/rl/sg/Scene.h | 4 +++- src/rl/sg/Shape.cpp | 1 + src/rl/sg/Shape.h | 4 +++- 11 files changed, 107 insertions(+), 4 deletions(-) create mode 100644 src/rl/sg/Base.cpp create mode 100644 src/rl/sg/Base.h diff --git a/src/rl/sg/Base.cpp b/src/rl/sg/Base.cpp new file mode 100644 index 00000000..1fe525eb --- /dev/null +++ b/src/rl/sg/Base.cpp @@ -0,0 +1,41 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Base.h" + +namespace rl +{ + namespace sg + { + Base::Base() + { + } + + Base::~Base() + { + } + } +} diff --git a/src/rl/sg/Base.h b/src/rl/sg/Base.h new file mode 100644 index 00000000..f573130b --- /dev/null +++ b/src/rl/sg/Base.h @@ -0,0 +1,48 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_SG_BASE_H +#define RL_SG_BASE_H + +namespace rl +{ + namespace sg + { + class Base + { + public: + virtual ~Base(); + + protected: + Base(); + + private: + + }; + } +} + +#endif // RL_SG_BASE_H diff --git a/src/rl/sg/Body.cpp b/src/rl/sg/Body.cpp index 153e7e40..1a858c13 100644 --- a/src/rl/sg/Body.cpp +++ b/src/rl/sg/Body.cpp @@ -40,6 +40,7 @@ namespace rl namespace sg { Body::Body(Model* model) : + Base(), center(::rl::math::Vector3::Zero()), max(::rl::math::Vector3::Zero()), min(::rl::math::Vector3::Zero()), diff --git a/src/rl/sg/Body.h b/src/rl/sg/Body.h index 9df2e342..45b63a33 100644 --- a/src/rl/sg/Body.h +++ b/src/rl/sg/Body.h @@ -34,6 +34,8 @@ #include #include +#include "Base.h" + namespace rl { namespace sg @@ -41,7 +43,7 @@ namespace rl class Model; class Shape; - class Body + class Body : public Base { public: typedef ::std::vector::iterator Iterator; diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 0ffdb9ef..08864814 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -11,6 +11,7 @@ find_package(SOLID3) set( BASE_HDRS + Base.h Body.h DepthScene.h DistanceScene.h @@ -28,6 +29,7 @@ list(APPEND HDRS ${BASE_HDRS}) set( BASE_SRCS + Base.cpp Body.cpp DepthScene.cpp DistanceScene.cpp diff --git a/src/rl/sg/Model.cpp b/src/rl/sg/Model.cpp index 2cdeadd5..86188d9c 100644 --- a/src/rl/sg/Model.cpp +++ b/src/rl/sg/Model.cpp @@ -38,6 +38,7 @@ namespace rl namespace sg { Model::Model(Scene* scene) : + Base(), bodies(), scene(scene), name() diff --git a/src/rl/sg/Model.h b/src/rl/sg/Model.h index 06601fc5..df24a388 100644 --- a/src/rl/sg/Model.h +++ b/src/rl/sg/Model.h @@ -32,6 +32,8 @@ #include #include +#include "Base.h" + namespace rl { namespace sg @@ -39,7 +41,7 @@ namespace rl class Body; class Scene; - class Model + class Model : public Base { public: typedef ::std::vector::iterator Iterator; diff --git a/src/rl/sg/Scene.cpp b/src/rl/sg/Scene.cpp index 0e22d42e..bc981561 100644 --- a/src/rl/sg/Scene.cpp +++ b/src/rl/sg/Scene.cpp @@ -33,6 +33,7 @@ namespace rl namespace sg { Scene::Scene() : + Base(), models(), name() { diff --git a/src/rl/sg/Scene.h b/src/rl/sg/Scene.h index 7a978a5d..2ef7401e 100644 --- a/src/rl/sg/Scene.h +++ b/src/rl/sg/Scene.h @@ -30,6 +30,8 @@ #include #include +#include "Base.h" + namespace rl { /** @@ -39,7 +41,7 @@ namespace rl { class Model; - class Scene + class Scene : public Base { public: typedef ::std::vector::iterator Iterator; diff --git a/src/rl/sg/Shape.cpp b/src/rl/sg/Shape.cpp index 44ec0cdb..88865165 100644 --- a/src/rl/sg/Shape.cpp +++ b/src/rl/sg/Shape.cpp @@ -32,6 +32,7 @@ namespace rl namespace sg { Shape::Shape(::SoVRMLShape* shape, Body* body) : + Base(), body(body), name() { diff --git a/src/rl/sg/Shape.h b/src/rl/sg/Shape.h index f5935e43..bab5ae02 100644 --- a/src/rl/sg/Shape.h +++ b/src/rl/sg/Shape.h @@ -31,13 +31,15 @@ #include #include +#include "Base.h" + namespace rl { namespace sg { class Body; - class Shape + class Shape : public Base { public: Shape(::SoVRMLShape* shape, Body* body); From 6f05c38152aea4a4576a9cfc4921137c8d905dcd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 24 Sep 2018 20:46:00 +0200 Subject: [PATCH 160/546] Fix white space --- examples/rlmdl/unimation-puma560.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/examples/rlmdl/unimation-puma560.xml b/examples/rlmdl/unimation-puma560.xml index 31790bb9..c5f9dbc4 100644 --- a/examples/rlmdl/unimation-puma560.xml +++ b/examples/rlmdl/unimation-puma560.xml @@ -249,7 +249,6 @@ 0 0 - From d6814cceabec2a3934789b30d2423c4bd30a1169 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 28 Sep 2018 00:54:50 +0200 Subject: [PATCH 161/546] Update rl::math::Function constructor and add default constructor for rl::math::Polynomial --- src/rl/math/Function.h | 6 +++--- src/rl/math/Polynomial.h | 8 +++++++- src/rl/math/Spline.h | 4 +--- 3 files changed, 11 insertions(+), 7 deletions(-) diff --git a/src/rl/math/Function.h b/src/rl/math/Function.h index 5034cf64..56c20925 100644 --- a/src/rl/math/Function.h +++ b/src/rl/math/Function.h @@ -44,9 +44,9 @@ namespace rl class Function { public: - Function() : - x0(0), - x1(1) + Function(const Real& x0 = 0, const Real& x1 = 1) : + x0(x0), + x1(x1) { } diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index 4bf8b6d5..42235928 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -59,8 +59,14 @@ namespace rl class Polynomial : public Function { public: + Polynomial() : + Function(0, 0), + c() + { + } + Polynomial(const ::std::size_t& degree) : - Function(), + Function(0, 0), c(degree + 1) { } diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index de6f0788..9d7f0963 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -58,11 +58,9 @@ namespace rl typedef typename ::std::vector>::reverse_iterator ReverseIterator; Spline() : - Function(), + Function(0, 0), polynomials() { - this->x0 = 0; - this->x1 = 0; } virtual ~Spline() From 1198532b41134a4cf7a0783bd87d281800eb6781 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 29 Sep 2018 17:00:31 +0200 Subject: [PATCH 162/546] Fix clipboard handling in rlRotationConverterDemo --- demos/rlRotationConverterDemo/TableView.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/demos/rlRotationConverterDemo/TableView.cpp b/demos/rlRotationConverterDemo/TableView.cpp index ddba8c4f..bb1ea082 100644 --- a/demos/rlRotationConverterDemo/TableView.cpp +++ b/demos/rlRotationConverterDemo/TableView.cpp @@ -94,8 +94,10 @@ TableView::keyPressEvent(QKeyEvent* event) } } } - - QTableView::keyPressEvent(event); + else + { + QTableView::keyPressEvent(event); + } } QSize From da159a8ff5972ed6d8f63acf58b0967dac9cecc8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 30 Sep 2018 00:40:18 +0200 Subject: [PATCH 163/546] Optimize window flags and size policy in rlRotationConverterDemo --- demos/rlRotationConverterDemo/MainWindow.cpp | 10 ++++++++++ demos/rlRotationConverterDemo/MainWindow.h | 2 +- 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/demos/rlRotationConverterDemo/MainWindow.cpp b/demos/rlRotationConverterDemo/MainWindow.cpp index b1d8a32d..f1e6b813 100644 --- a/demos/rlRotationConverterDemo/MainWindow.cpp +++ b/demos/rlRotationConverterDemo/MainWindow.cpp @@ -224,6 +224,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputRotationMatrixTableView->precision = &this->inputPrecision; inputRotationMatrixTableView->setItemDelegate(inputDelegate); inputRotationMatrixTableView->setModel(inputRotationMatrixModel); + inputRotationMatrixTableView->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); inputRotationMatrixTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* inputRotationMatrixLayout = new QVBoxLayout(inputRotationMatrixGroupBox); @@ -255,6 +256,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputRotationMatrixTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); outputRotationMatrixTableView->setItemDelegate(outputDelegate); outputRotationMatrixTableView->setModel(outputRotationMatrixModel); + outputRotationMatrixTableView->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); outputRotationMatrixTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* outputRotationMatrixLayout = new QVBoxLayout(outputRotationMatrixGroupBox); @@ -273,6 +275,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputAngleAxisTableView->precision = &this->inputPrecision; inputAngleAxisTableView->setItemDelegate(inputDelegate); inputAngleAxisTableView->setModel(inputAngleAxisModel); + inputAngleAxisTableView->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); inputAngleAxisTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* inputAngleAxisLayout = new QVBoxLayout(inputAngleAxisGroupBox); @@ -305,6 +308,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputAngleAxisTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); outputAngleAxisTableView->setItemDelegate(outputDelegate); outputAngleAxisTableView->setModel(outputAngleAxisModel); + outputAngleAxisTableView->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); outputAngleAxisTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* outputAngleAxisLayout = new QVBoxLayout(outputAngleAxisGroupBox); @@ -322,6 +326,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputQuaternionTableView->precision = &this->inputPrecision; inputQuaternionTableView->setItemDelegate(inputDelegate); inputQuaternionTableView->setModel(inputQuaternionModel); + inputQuaternionTableView->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); inputQuaternionTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* inputQuaternionLayout = new QVBoxLayout(inputQuaternionGroupBox); @@ -353,6 +358,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputQuaternionTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); outputQuaternionTableView->setItemDelegate(outputDelegate); outputQuaternionTableView->setModel(outputQuaternionModel); + outputQuaternionTableView->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); outputQuaternionTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* outputQuaternionLayout = new QVBoxLayout(outputQuaternionGroupBox); @@ -372,6 +378,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputEulerAnglesTableView->precision = &this->inputPrecision; inputEulerAnglesTableView->setItemDelegate(inputDelegate); inputEulerAnglesTableView->setModel(inputEulerAnglesModel); + inputEulerAnglesTableView->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); inputEulerAnglesTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* inputEulerAnglesLayout = new QVBoxLayout(inputEulerAnglesGroupBox); @@ -405,6 +412,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : outputEulerAnglesTableView->setEditTriggers(QAbstractItemView::NoEditTriggers); outputEulerAnglesTableView->setItemDelegate(outputDelegate); outputEulerAnglesTableView->setModel(outputEulerAnglesModel); + outputEulerAnglesTableView->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed); outputEulerAnglesTableView->verticalHeader()->setMinimumWidth(20); QVBoxLayout* outputEulerAnglesLayout = new QVBoxLayout(outputEulerAnglesGroupBox); @@ -413,6 +421,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : inputAngleAxisGroupBox->setChecked(false); inputQuaternionGroupBox->setChecked(false); inputEulerAnglesGroupBox->setChecked(false); + + this->layout()->setSizeConstraint(QLayout::SetFixedSize); } MainWindow::~MainWindow() diff --git a/demos/rlRotationConverterDemo/MainWindow.h b/demos/rlRotationConverterDemo/MainWindow.h index 9e2c590f..174e689e 100644 --- a/demos/rlRotationConverterDemo/MainWindow.h +++ b/demos/rlRotationConverterDemo/MainWindow.h @@ -80,7 +80,7 @@ public slots: void rotationMatrixToggled(bool on); protected: - MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); + MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::Window | Qt::MSWindowsFixedSizeDialogHint); private: void fromAngleAxis(); From 44c61bfa8ef7fa2369127abb20cc061c8fa6b451 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Oct 2018 16:27:01 +0200 Subject: [PATCH 164/546] Remove clone functions --- src/rl/kin/Kinematics.cpp | 6 ------ src/rl/kin/Kinematics.h | 2 -- src/rl/kin/Puma.cpp | 6 ------ src/rl/kin/Puma.h | 2 -- src/rl/kin/Rhino.cpp | 6 ------ src/rl/kin/Rhino.h | 2 -- src/rl/mdl/Dynamic.cpp | 6 ------ src/rl/mdl/Dynamic.h | 2 -- src/rl/mdl/Kinematic.cpp | 6 ------ src/rl/mdl/Kinematic.h | 2 -- src/rl/mdl/Metric.cpp | 6 ------ src/rl/mdl/Model.cpp | 6 ------ src/rl/mdl/Model.h | 2 -- 13 files changed, 54 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 7714923a..94974821 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -115,12 +115,6 @@ namespace rl } } - Kinematics* - Kinematics::clone() const - { - return new Kinematics(*this); - } - Kinematics* Kinematics::create(const ::std::string& filename) { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index f04d6b3e..1bb4b761 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -69,8 +69,6 @@ namespace rl */ virtual void clamp(::rl::math::Vector& q) const; - virtual Kinematics* clone() const; - static Kinematics* create(const ::std::string& filename); /** diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index 6091e649..7bb3f53c 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -48,12 +48,6 @@ namespace rl { } - Kinematics* - Puma::clone() const - { - return new Puma(*this); - } - Puma::Arm Puma::getArm() const { diff --git a/src/rl/kin/Puma.h b/src/rl/kin/Puma.h index d2ae048f..738b6b2b 100644 --- a/src/rl/kin/Puma.h +++ b/src/rl/kin/Puma.h @@ -61,8 +61,6 @@ namespace rl virtual ~Puma(); - virtual Kinematics* clone() const; - Arm getArm() const; Elbow getElbow() const; diff --git a/src/rl/kin/Rhino.cpp b/src/rl/kin/Rhino.cpp index d71c5dc4..51f06c2d 100644 --- a/src/rl/kin/Rhino.cpp +++ b/src/rl/kin/Rhino.cpp @@ -47,12 +47,6 @@ namespace rl { } - Kinematics* - Rhino::clone() const - { - return new Rhino(*this); - } - Rhino::Arm Rhino::getArm() const { diff --git a/src/rl/kin/Rhino.h b/src/rl/kin/Rhino.h index 631eed31..f4162ce6 100644 --- a/src/rl/kin/Rhino.h +++ b/src/rl/kin/Rhino.h @@ -55,8 +55,6 @@ namespace rl virtual ~Rhino(); - virtual Kinematics* clone() const; - Arm getArm() const; Elbow getElbow() const; diff --git a/src/rl/mdl/Dynamic.cpp b/src/rl/mdl/Dynamic.cpp index d790d933..0784c89a 100644 --- a/src/rl/mdl/Dynamic.cpp +++ b/src/rl/mdl/Dynamic.cpp @@ -179,12 +179,6 @@ namespace rl invMx = J * invM * J.transpose(); // TODO } - Model* - Dynamic::clone() const - { - return new Dynamic(*this); - } - void Dynamic::forwardDynamics() { diff --git a/src/rl/mdl/Dynamic.h b/src/rl/mdl/Dynamic.h index 865d5ae2..0d5255ec 100644 --- a/src/rl/mdl/Dynamic.h +++ b/src/rl/mdl/Dynamic.h @@ -146,8 +146,6 @@ namespace rl */ void calculateOperationalMassMatrixInverse(const ::rl::math::Matrix& J, const ::rl::math::Matrix& invM, ::rl::math::Matrix& invMx) const; - Model* clone() const; - /** * Forward dynamics via articulated-body algorithm. * diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 79b12cd2..c04ce71d 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -171,12 +171,6 @@ namespace rl return ::std::sqrt((J * J.transpose()).determinant()); } - Model* - Kinematic::clone() const - { - return new Kinematic(*this); - } - void Kinematic::forwardAcceleration() { diff --git a/src/rl/mdl/Kinematic.h b/src/rl/mdl/Kinematic.h index 4d4cb248..f8f9d4ee 100644 --- a/src/rl/mdl/Kinematic.h +++ b/src/rl/mdl/Kinematic.h @@ -44,8 +44,6 @@ namespace rl virtual ~Kinematic(); - Model* clone() const; - /** * Calculate Jacobian matrix. * diff --git a/src/rl/mdl/Metric.cpp b/src/rl/mdl/Metric.cpp index fc91e792..37e8f725 100644 --- a/src/rl/mdl/Metric.cpp +++ b/src/rl/mdl/Metric.cpp @@ -51,12 +51,6 @@ namespace rl } } - Model* - Metric::clone() const - { - return new Metric(*this); - } - ::rl::math::Real Metric::distance(const ::rl::math::Vector& q1, const ::rl::math::Vector& q2) const { diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 48e97729..7cf979d7 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -106,12 +106,6 @@ namespace rl } } - Model* - Model::clone() const - { - return new Model(*this); - } - ::rl::math::Vector Model::generatePositionGaussian(const ::rl::math::Vector& rand, const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma) const { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index ce5a4f03..9f7360ba 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -68,8 +68,6 @@ namespace rl bool areColliding(const ::std::size_t& i, const ::std::size_t& j) const; - Model* clone() const; - ::rl::math::Vector generatePositionGaussian(const ::rl::math::Vector& rand, const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma) const; ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand) const; From cce97c88c999cb98865c6c684fd15732bc4491c9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Oct 2018 22:45:16 +0200 Subject: [PATCH 165/546] Cleanup PolynomialQuaternion and SplineQuaternion --- src/rl/math/PolynomialQuaternion.h | 42 +++++++----------------------- src/rl/math/SplineQuaternion.h | 37 ++------------------------ 2 files changed, 11 insertions(+), 68 deletions(-) diff --git a/src/rl/math/PolynomialQuaternion.h b/src/rl/math/PolynomialQuaternion.h index a43db14e..2eb879be 100644 --- a/src/rl/math/PolynomialQuaternion.h +++ b/src/rl/math/PolynomialQuaternion.h @@ -44,12 +44,17 @@ namespace rl class Polynomial : public Function { public: + Polynomial() : + Function(0, 0), + y0(), + c() + { + } + Polynomial(const ::std::size_t& degree) : - Function(), + Function(0, 0), y0(), - c(degree + 1), - x0(0), - x1(1) + c(degree + 1) { } @@ -127,21 +132,6 @@ namespace rl return this->c.size() - 1; } - Real duration() const - { - return this->upper() - this->lower(); - } - - Real& lower() - { - return this->x0; - } - - const Real& lower() const - { - return this->x0; - } - Quaternion operator()(const Real& x, const ::std::size_t& derivative = 0) const { assert(derivative <= 2 && "Polynomial: higher derivatives not implemented"); @@ -213,25 +203,11 @@ namespace rl return Quaternion(); } - Real& upper() - { - return this->x1; - } - - const Real& upper() const - { - return this->x1; - } - Quaternion y0; protected: ::std::vector c; - Real x0; - - Real x1; - private: Polynomial derivative() const { diff --git a/src/rl/math/SplineQuaternion.h b/src/rl/math/SplineQuaternion.h index 782b57c1..9181c293 100644 --- a/src/rl/math/SplineQuaternion.h +++ b/src/rl/math/SplineQuaternion.h @@ -50,13 +50,9 @@ namespace rl typedef ::std::vector>::reverse_iterator ReverseIterator; Spline() : - Function(), - polynomials(), - x0(0), - x1(0) + Function(0, 0), + polynomials() { - this->x0 = 0; - this->x1 = 0; } virtual ~Spline() @@ -204,11 +200,6 @@ namespace rl return new Spline(*this); } - Real duration() const - { - return this->upper() - this->lower(); - } - bool empty() { return this->polynomials.empty(); @@ -234,16 +225,6 @@ namespace rl return this->polynomials.front(); } - Real& lower() - { - return this->x0; - } - - const Real& lower() const - { - return this->x0; - } - Quaternion operator()(const Real& x, const ::std::size_t& derivative = 0) const { assert(x >= this->lower() - FUNCTION_BOUNDARY); @@ -321,23 +302,9 @@ namespace rl return this->polynomials.rend(); } - Real& upper() - { - return this->x1; - } - - const Real& upper() const - { - return this->x1; - } - protected: ::std::vector> polynomials; - Real x0; - - Real x1; - private: static Vector3 B(const Vector3& e, const Real& dtheta, const Vector3& x) { From 5a54cc201002676fde57c456a462725187aa46b8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 7 Oct 2018 00:50:37 +0200 Subject: [PATCH 166/546] Add missing copyright --- src/rl/mdl/EulerCauchyIntegrator.cpp | 26 ++++++++++++++++++++++ src/rl/mdl/EulerCauchyIntegrator.h | 26 ++++++++++++++++++++++ src/rl/mdl/Integrator.cpp | 26 ++++++++++++++++++++++ src/rl/mdl/Integrator.h | 26 ++++++++++++++++++++++ src/rl/mdl/InverseKinematics.cpp | 26 ++++++++++++++++++++++ src/rl/mdl/InverseKinematics.h | 26 ++++++++++++++++++++++ src/rl/mdl/JacobianInverseKinematics.cpp | 26 ++++++++++++++++++++++ src/rl/mdl/JacobianInverseKinematics.h | 26 ++++++++++++++++++++++ src/rl/mdl/NloptInverseKinematics.cpp | 26 ++++++++++++++++++++++ src/rl/mdl/NloptInverseKinematics.h | 26 ++++++++++++++++++++++ src/rl/mdl/RungeKuttaNystromIntegrator.cpp | 26 ++++++++++++++++++++++ src/rl/mdl/RungeKuttaNystromIntegrator.h | 26 ++++++++++++++++++++++ 12 files changed, 312 insertions(+) diff --git a/src/rl/mdl/EulerCauchyIntegrator.cpp b/src/rl/mdl/EulerCauchyIntegrator.cpp index a88c91e6..82790376 100644 --- a/src/rl/mdl/EulerCauchyIntegrator.cpp +++ b/src/rl/mdl/EulerCauchyIntegrator.cpp @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Dynamic.h" #include "EulerCauchyIntegrator.h" diff --git a/src/rl/mdl/EulerCauchyIntegrator.h b/src/rl/mdl/EulerCauchyIntegrator.h index e2d518fb..8680853a 100644 --- a/src/rl/mdl/EulerCauchyIntegrator.h +++ b/src/rl/mdl/EulerCauchyIntegrator.h @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MDL_EULERCAUCHYINTEGRATOR_H #define RL_MDL_EULERCAUCHYINTEGRATOR_H diff --git a/src/rl/mdl/Integrator.cpp b/src/rl/mdl/Integrator.cpp index 2b6d4454..1326a99e 100644 --- a/src/rl/mdl/Integrator.cpp +++ b/src/rl/mdl/Integrator.cpp @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Integrator.h" namespace rl diff --git a/src/rl/mdl/Integrator.h b/src/rl/mdl/Integrator.h index aa85938d..3aa9c49e 100644 --- a/src/rl/mdl/Integrator.h +++ b/src/rl/mdl/Integrator.h @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MDL_INTEGRATOR_H #define RL_MDL_INTEGRATOR_H diff --git a/src/rl/mdl/InverseKinematics.cpp b/src/rl/mdl/InverseKinematics.cpp index 8c69a4af..d74db651 100644 --- a/src/rl/mdl/InverseKinematics.cpp +++ b/src/rl/mdl/InverseKinematics.cpp @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "InverseKinematics.h" namespace rl diff --git a/src/rl/mdl/InverseKinematics.h b/src/rl/mdl/InverseKinematics.h index 312ad89f..924b86e6 100644 --- a/src/rl/mdl/InverseKinematics.h +++ b/src/rl/mdl/InverseKinematics.h @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MDL_INVERSEKINEMATICS_H #define RL_MDL_INVERSEKINEMATICS_H diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index f37a8cd4..eff487d9 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Kinematic.h" #include "JacobianInverseKinematics.h" diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index 5fd2fbb9..570c07fb 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MDL_JACOBIANINVERSEKINEMATICS_H #define RL_MDL_JACOBIANINVERSEKINEMATICS_H diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 30716f5a..0d19afe2 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Kinematic.h" diff --git a/src/rl/mdl/NloptInverseKinematics.h b/src/rl/mdl/NloptInverseKinematics.h index 734fdf1d..a5c33bbb 100644 --- a/src/rl/mdl/NloptInverseKinematics.h +++ b/src/rl/mdl/NloptInverseKinematics.h @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MDL_NLOPTINVERSEKINEMATICS_H #define RL_MDL_NLOPTINVERSEKINEMATICS_H diff --git a/src/rl/mdl/RungeKuttaNystromIntegrator.cpp b/src/rl/mdl/RungeKuttaNystromIntegrator.cpp index fa165848..108e5380 100644 --- a/src/rl/mdl/RungeKuttaNystromIntegrator.cpp +++ b/src/rl/mdl/RungeKuttaNystromIntegrator.cpp @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Dynamic.h" #include "RungeKuttaNystromIntegrator.h" diff --git a/src/rl/mdl/RungeKuttaNystromIntegrator.h b/src/rl/mdl/RungeKuttaNystromIntegrator.h index 9d3f5ac1..e24e3c5a 100644 --- a/src/rl/mdl/RungeKuttaNystromIntegrator.h +++ b/src/rl/mdl/RungeKuttaNystromIntegrator.h @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MDL_RUNGEKUTTANYSTROMINTEGRATOR_H #define RL_MDL_RUNGEKUTTANYSTROMINTEGRATOR_H From a118941be5e094d17f4efeb28404338ff985eabd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 8 Oct 2018 22:23:45 +0200 Subject: [PATCH 167/546] Add upper and lower bounds to NLopt inverse kinematics and generatePositionUniform() --- src/rl/mdl/Joint.cpp | 9 +++++++++ src/rl/mdl/Joint.h | 2 ++ src/rl/mdl/Model.cpp | 18 ++++++++++++++++++ src/rl/mdl/Model.h | 2 ++ src/rl/mdl/NloptInverseKinematics.cpp | 23 +++++++++++++++++------ src/rl/mdl/NloptInverseKinematics.h | 8 ++++++++ src/rl/mdl/SixDof.cpp | 11 +++++++++++ src/rl/mdl/SixDof.h | 2 ++ src/rl/mdl/Spherical.cpp | 6 ++++++ src/rl/mdl/Spherical.h | 2 ++ 10 files changed, 77 insertions(+), 6 deletions(-) diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index b248b3bd..e8fc907e 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -184,6 +184,15 @@ namespace rl } } + void + Joint::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& min, const ::rl::math::ConstVectorRef& max, ::rl::math::VectorRef q) const + { + for (::std::size_t i = 0; i < q.size(); ++i) + { + q(i) = min(i) + rand(i) * (max(i) - min(i)); + } + } + const ::rl::math::Vector& Joint::getAcceleration() const { diff --git a/src/rl/mdl/Joint.h b/src/rl/mdl/Joint.h index aba80306..1fcb4a34 100644 --- a/src/rl/mdl/Joint.h +++ b/src/rl/mdl/Joint.h @@ -61,6 +61,8 @@ namespace rl virtual void generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const; + virtual void generatePositionUniform(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& min, const ::rl::math::ConstVectorRef& max, ::rl::math::VectorRef q) const; + const ::rl::math::Vector& getAcceleration() const; const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& getAccelerationUnits() const; diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 7cf979d7..ef0bd6a0 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -140,6 +140,24 @@ namespace rl return q; } + ::rl::math::Vector + Model::generatePositionUniform(const ::rl::math::Vector& rand, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const + { + ::rl::math::Vector q(this->getDofPosition()); + + for (::std::size_t i = 0, j = 0, k = 0; i < this->joints.size(); k += this->joints[i]->getDof(), j += this->joints[i]->getDofPosition(), ++i) + { + this->joints[i]->generatePositionUniform( + rand.segment(k, this->joints[i]->getDof()), + min.segment(k, this->joints[i]->getDof()), + max.segment(k, this->joints[i]->getDof()), + q.segment(j, this->joints[i]->getDofPosition()) + ); + } + + return q; + } + ::rl::math::Vector Model::getAcceleration() const { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 9f7360ba..207c696b 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -72,6 +72,8 @@ namespace rl ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand) const; + ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; + ::rl::math::Vector getAcceleration() const; ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getAccelerationUnits() const; diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 0d19afe2..b7715e5c 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -43,6 +43,8 @@ namespace rl randDistribution(0, 1), randEngine(::std::random_device()()) { + this->lb = this->kinematic->getMinimum(); + this->ub = this->kinematic->getMaximum(); } NloptInverseKinematics::~NloptInverseKinematics() @@ -110,6 +112,18 @@ namespace rl return result; } + void + NloptInverseKinematics::setLowerBound(const ::rl::math::Vector& lb) + { + this->lb = lb; + } + + void + NloptInverseKinematics::setUpperBound(const ::rl::math::Vector& ub) + { + this->ub = ub; + } + bool NloptInverseKinematics::solve() { @@ -121,9 +135,6 @@ namespace rl ::nlopt_destroy ); - ::rl::math::Vector lb = this->kinematic->getMinimum(); - ::rl::math::Vector ub = this->kinematic->getMaximum(); - ::std::vector tolerance(this->kinematic->getDofPosition(), this->tolerance); if (::nlopt_set_xtol_abs(opt.get(), tolerance.data()) < 0) @@ -136,12 +147,12 @@ namespace rl return false; } - if (::nlopt_set_lower_bounds(opt.get(), lb.data()) < 0) + if (::nlopt_set_lower_bounds(opt.get(), this->lb.data()) < 0) { return false; } - if (::nlopt_set_upper_bounds(opt.get(), ub.data()) < 0) + if (::nlopt_set_upper_bounds(opt.get(), this->ub.data()) < 0) { return false; } @@ -172,7 +183,7 @@ namespace rl rand(i) = this->randDistribution(this->randEngine); } - q = this->kinematic->generatePositionUniform(rand); + q = this->kinematic->generatePositionUniform(rand, this->lb, this->ub); remaining = ::std::chrono::duration(this->duration - (::std::chrono::steady_clock::now() - start)).count(); } diff --git a/src/rl/mdl/NloptInverseKinematics.h b/src/rl/mdl/NloptInverseKinematics.h index a5c33bbb..fe9d02e9 100644 --- a/src/rl/mdl/NloptInverseKinematics.h +++ b/src/rl/mdl/NloptInverseKinematics.h @@ -45,6 +45,10 @@ namespace rl virtual ~NloptInverseKinematics(); + void setLowerBound(const ::rl::math::Vector& lb); + + void setUpperBound(const ::rl::math::Vector& ub); + bool solve(); ::rl::math::Real delta; @@ -66,7 +70,11 @@ namespace rl ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::rl::math::Vector lb; + ::std::mt19937 randEngine; + + ::rl::math::Vector ub; }; } } diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index dd5ae813..8987ab12 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -118,6 +118,17 @@ namespace rl q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>()).coeffs(); } + void + SixDof::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& min, const ::rl::math::ConstVectorRef& max, ::rl::math::VectorRef q) const + { + for (::std::size_t i = 0; i < 3; ++i) + { + q(i) = min(i) + rand(i) * (max(i) - min(i)); + } + + q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>()).coeffs(); + } + void SixDof::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { diff --git a/src/rl/mdl/SixDof.h b/src/rl/mdl/SixDof.h index 963f8ba5..450c960e 100644 --- a/src/rl/mdl/SixDof.h +++ b/src/rl/mdl/SixDof.h @@ -48,6 +48,8 @@ namespace rl void generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const; + void generatePositionUniform(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& min, const ::rl::math::ConstVectorRef& max, ::rl::math::VectorRef q) const; + void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; bool isValid(const ::rl::math::ConstVectorRef& q) const; diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 282c3978..6bcbe884 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -88,6 +88,12 @@ namespace rl q = ::rl::math::Quaternion::Random(rand).coeffs(); } + void + Spherical::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& min, const ::rl::math::ConstVectorRef& max, ::rl::math::VectorRef q) const + { + q = ::rl::math::Quaternion::Random(rand).coeffs(); + } + void Spherical::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { diff --git a/src/rl/mdl/Spherical.h b/src/rl/mdl/Spherical.h index 6058e144..6b6f699f 100644 --- a/src/rl/mdl/Spherical.h +++ b/src/rl/mdl/Spherical.h @@ -48,6 +48,8 @@ namespace rl void generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const; + void generatePositionUniform(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& min, const ::rl::math::ConstVectorRef& max, ::rl::math::VectorRef q) const; + void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; bool isValid(const ::rl::math::ConstVectorRef& q) const; From c4b5e40452949ed1f5d87f1b885772c09be227c1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 10 Oct 2018 15:35:45 +0200 Subject: [PATCH 168/546] Fix whitespace --- cmake/WixExtra.wxs.in | 3 +-- src/rl/hal/RobotiqModelC.cpp | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/cmake/WixExtra.wxs.in b/cmake/WixExtra.wxs.in index 614785ca..dda5a943 100644 --- a/cmake/WixExtra.wxs.in +++ b/cmake/WixExtra.wxs.in @@ -1,7 +1,6 @@ - + diff --git a/src/rl/hal/RobotiqModelC.cpp b/src/rl/hal/RobotiqModelC.cpp index c0555602..d99bfe2e 100644 --- a/src/rl/hal/RobotiqModelC.cpp +++ b/src/rl/hal/RobotiqModelC.cpp @@ -39,7 +39,7 @@ namespace rl Gripper(), in(), out(), - serial( + serial( filename, Serial::BAUDRATE_115200BPS, Serial::DATABITS_8BITS, From e9dce98f0cf521de9cec62e24833b863e387721c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Oct 2018 22:37:17 +0200 Subject: [PATCH 169/546] Update casting to real precision --- .../rlAxisControllerDemo.cpp | 4 +- demos/rlCoachKin/ConfigurationDelegate.cpp | 4 +- demos/rlCoachKin/OperationalDelegate.cpp | 4 +- demos/rlCoachKin/OperationalModel.cpp | 2 +- demos/rlCoachMdl/ConfigurationDelegate.cpp | 4 +- demos/rlCoachMdl/OperationalDelegate.cpp | 4 +- demos/rlCollisionDemo/BodyDelegate.cpp | 4 +- .../rlDenavitHartenbergDemo.cpp | 8 +-- demos/rlGripperDemo/rlRobotiqModelCDemo.cpp | 12 ++--- .../rlInterpolatorDemo/rlInterpolatorDemo.cpp | 18 +++---- demos/rlJacobianDemo/rlJacobianDemo.cpp | 2 +- demos/rlPlanDemo/ConfigurationDelegate.cpp | 4 +- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 12 ++--- demos/rlPlanDemo/ConfigurationSpaceThread.cpp | 4 +- demos/rlPlanDemo/MainWindow.cpp | 38 ++++++------- demos/rlPlanDemo/Thread.cpp | 16 +++--- demos/rlPlanDemo/Viewer.cpp | 4 +- demos/rlPrmDemo/rlPrmDemo.cpp | 2 +- demos/rlQuaternionDemo/rlQuaternionDemo.cpp | 54 +++++++++---------- demos/rlSimulator/ConfigurationDelegate.cpp | 14 ++--- demos/rlSimulator/MainWindow.cpp | 10 ++-- demos/rlSimulator/OperationalDelegate.cpp | 4 +- demos/rlSimulator/OperationalModel.cpp | 2 +- .../rlTrapezoidalVelocityDemo.cpp | 4 +- src/rl/hal/LeuzeRs4.cpp | 10 ++-- src/rl/hal/MitsubishiH7.cpp | 28 +++++----- src/rl/hal/SchmersalLss300.cpp | 12 ++--- src/rl/hal/SchunkFpsF5.cpp | 16 +++--- src/rl/hal/SickLms200.cpp | 28 +++++----- src/rl/hal/SickS300.cpp | 12 ++--- src/rl/kin/Kinematics.cpp | 20 +++---- src/rl/kin/Kinematics.h | 4 +- src/rl/kin/Puma.cpp | 18 +++---- src/rl/kin/Puma.h | 8 +-- src/rl/kin/Rhino.cpp | 20 +++---- src/rl/kin/Rhino.h | 8 +-- src/rl/math/Function.h | 2 +- src/rl/math/MatrixBaseAddons.h | 6 +-- src/rl/math/Polynomial.h | 2 +- src/rl/math/PolynomialQuaternion.h | 2 +- src/rl/math/QuaternionBaseAddons.h | 4 +- src/rl/math/Spline.h | 2 +- src/rl/math/SplineQuaternion.h | 6 +-- src/rl/math/TransformAddons.h | 34 ++++++------ src/rl/math/Unit.h | 30 +++++------ src/rl/math/algorithm.h | 4 +- src/rl/mdl/JacobianInverseKinematics.cpp | 2 +- src/rl/mdl/Joint.cpp | 2 +- src/rl/mdl/Kinematic.cpp | 2 +- src/rl/mdl/Kinematic.h | 4 +- src/rl/mdl/Metric.cpp | 4 +- src/rl/mdl/NloptInverseKinematics.cpp | 8 +-- src/rl/mdl/Revolute.cpp | 14 ++--- src/rl/mdl/RungeKuttaNystromIntegrator.cpp | 2 +- src/rl/mdl/SixDof.cpp | 4 +- src/rl/mdl/Spherical.cpp | 2 +- src/rl/mdl/UrdfFactory.cpp | 4 +- src/rl/plan/AddRrtConCon.cpp | 10 ++-- src/rl/plan/AdvancedOptimizer.cpp | 6 +-- src/rl/plan/BridgeSampler.cpp | 4 +- src/rl/plan/Eet.cpp | 20 +++---- src/rl/plan/Model.h | 2 +- src/rl/plan/PrmUtilityGuided.cpp | 12 ++--- src/rl/plan/Rrt.cpp | 4 +- src/rl/plan/RrtGoalBias.cpp | 2 +- src/rl/plan/Verifier.cpp | 2 +- src/rl/plan/WorkspaceSphereExplorer.cpp | 4 +- src/rl/sg/UrdfFactory.cpp | 6 +-- src/rl/sg/XmlFactory.cpp | 4 +- src/rl/sg/ode/Body.cpp | 6 +-- src/rl/sg/ode/Shape.cpp | 6 +-- src/rl/sg/pqp/Scene.cpp | 8 +-- tests/rlEetTest/rlEetTest.cpp | 12 ++--- .../rlInverseKinematicsMdlTest.cpp | 2 +- tests/rlPrmTest/rlPrmTest.cpp | 2 +- .../rlSpatialForceVectorTest.cpp | 8 +-- .../rlSpatialMotionVectorTest.cpp | 8 +-- .../rlTrapezoidalAccelerationTest.cpp | 6 +-- 78 files changed, 346 insertions(+), 346 deletions(-) diff --git a/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp b/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp index ed0559bf..bf77cc38 100644 --- a/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp +++ b/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp @@ -50,7 +50,7 @@ main(int argc, char** argv) rl::hal::Coach controller(6, std::chrono::microseconds(7110), 0, "localhost"); #endif // COACH #ifdef GNUPLOT - rl::hal::Gnuplot controller(6, std::chrono::microseconds(7110), -10.0f * rl::math::DEG2RAD, 10.0f * rl::math::DEG2RAD); + rl::hal::Gnuplot controller(6, std::chrono::microseconds(7110), -10 * rl::math::DEG2RAD, 10 * rl::math::DEG2RAD); #endif // GNUPLOT #ifdef MITSUBISHI rl::hal::MitsubishiH7 controller(6, "left", "lefthost"); @@ -67,7 +67,7 @@ main(int argc, char** argv) controller.step(); rl::math::Vector q0 = controller.getJointPosition(); - rl::math::Vector q1 = q0 + rl::math::Vector::Constant(controller.getDof(), 5.0f * rl::math::DEG2RAD); + rl::math::Vector q1 = q0 + rl::math::Vector::Constant(controller.getDof(), 5 * rl::math::DEG2RAD); rl::math::Real te = updateRate * 300.0f; diff --git a/demos/rlCoachKin/ConfigurationDelegate.cpp b/demos/rlCoachKin/ConfigurationDelegate.cpp index 95a4ea68..dee7c273 100644 --- a/demos/rlCoachKin/ConfigurationDelegate.cpp +++ b/demos/rlCoachKin/ConfigurationDelegate.cpp @@ -59,14 +59,14 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& editor->setDecimals(2); editor->setMinimum(minimum(index.row()) * rl::math::RAD2DEG); editor->setMaximum(maximum(index.row()) * rl::math::RAD2DEG); - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); } else { editor->setDecimals(4); editor->setMinimum(minimum(index.row())); editor->setMaximum(maximum(index.row())); - editor->setSingleStep(0.01f); + editor->setSingleStep(0.01); } editor->setWrapping(wraparounds(index.row())); diff --git a/demos/rlCoachKin/OperationalDelegate.cpp b/demos/rlCoachKin/OperationalDelegate.cpp index a71f3f12..a33a5b61 100644 --- a/demos/rlCoachKin/OperationalDelegate.cpp +++ b/demos/rlCoachKin/OperationalDelegate.cpp @@ -53,13 +53,13 @@ OperationalDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& o case 1: case 2: editor->setDecimals(4); - editor->setSingleStep(0.01f); + editor->setSingleStep(0.01); break; case 3: case 4: case 5: editor->setDecimals(2); - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); break; default: break; diff --git a/demos/rlCoachKin/OperationalModel.cpp b/demos/rlCoachKin/OperationalModel.cpp index 1474d8da..847c8490 100644 --- a/demos/rlCoachKin/OperationalModel.cpp +++ b/demos/rlCoachKin/OperationalModel.cpp @@ -232,7 +232,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r MainWindow::instance()->kinematicModels[this->id]->getPosition(q); rl::math::Vector qInv(MainWindow::instance()->kinematicModels[this->id]->getDof()); - if (MainWindow::instance()->kinematicModels[this->id]->inversePosition(transform, qInv, index.row(), 1.0f)) + if (MainWindow::instance()->kinematicModels[this->id]->inversePosition(transform, qInv, index.row(), 1)) { MainWindow::instance()->kinematicModels[this->id]->setPosition(qInv); MainWindow::instance()->kinematicModels[this->id]->updateFrames(); diff --git a/demos/rlCoachMdl/ConfigurationDelegate.cpp b/demos/rlCoachMdl/ConfigurationDelegate.cpp index d1b71f23..46fc3bbd 100644 --- a/demos/rlCoachMdl/ConfigurationDelegate.cpp +++ b/demos/rlCoachMdl/ConfigurationDelegate.cpp @@ -58,14 +58,14 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& editor->setDecimals(2); editor->setMinimum(minimum(index.row()) * rl::math::RAD2DEG); editor->setMaximum(maximum(index.row()) * rl::math::RAD2DEG); - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); } else { editor->setDecimals(4); editor->setMinimum(minimum(index.row())); editor->setMaximum(maximum(index.row())); - editor->setSingleStep(0.01f); + editor->setSingleStep(0.01); } editor->setWrapping(wraparounds(index.row())); diff --git a/demos/rlCoachMdl/OperationalDelegate.cpp b/demos/rlCoachMdl/OperationalDelegate.cpp index a71f3f12..a33a5b61 100644 --- a/demos/rlCoachMdl/OperationalDelegate.cpp +++ b/demos/rlCoachMdl/OperationalDelegate.cpp @@ -53,13 +53,13 @@ OperationalDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& o case 1: case 2: editor->setDecimals(4); - editor->setSingleStep(0.01f); + editor->setSingleStep(0.01); break; case 3: case 4: case 5: editor->setDecimals(2); - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); break; default: break; diff --git a/demos/rlCollisionDemo/BodyDelegate.cpp b/demos/rlCollisionDemo/BodyDelegate.cpp index c9860dfa..f3efa20c 100644 --- a/demos/rlCollisionDemo/BodyDelegate.cpp +++ b/demos/rlCollisionDemo/BodyDelegate.cpp @@ -54,13 +54,13 @@ BodyDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& option, case 1: case 2: editor->setDecimals(4); - editor->setSingleStep(0.01f); + editor->setSingleStep(0.01); break; case 3: case 4: case 5: editor->setDecimals(2); - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); break; default: break; diff --git a/demos/rlDenavitHartenbergDemo/rlDenavitHartenbergDemo.cpp b/demos/rlDenavitHartenbergDemo/rlDenavitHartenbergDemo.cpp index 875217a2..72f248b7 100644 --- a/demos/rlDenavitHartenbergDemo/rlDenavitHartenbergDemo.cpp +++ b/demos/rlDenavitHartenbergDemo/rlDenavitHartenbergDemo.cpp @@ -34,10 +34,10 @@ int main(int argc, char** argv) { - rl::math::Real a = 31.0f; - rl::math::Real alpha = 271.0f * rl::math::DEG2RAD; - rl::math::Real d = 101.0f; - rl::math::Real theta = 181.0f * rl::math::DEG2RAD; + rl::math::Real a = 31; + rl::math::Real alpha = 271 * rl::math::DEG2RAD; + rl::math::Real d = 101; + rl::math::Real theta = 181 * rl::math::DEG2RAD; rl::math::Transform t_d(rl::math::Translation(0, 0, d)); diff --git a/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp b/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp index f5e940f7..5ba97d8a 100644 --- a/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp +++ b/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp @@ -49,9 +49,9 @@ main(int argc, char** argv) } while (!gripper.isRunning()); - gripper.setForcePercentage(0.1f); - gripper.setPositionPercentage(1.0f); - gripper.setSpeedPercentage(0.25f); + gripper.setForcePercentage(static_cast(0.1)); + gripper.setPositionPercentage(1); + gripper.setSpeedPercentage(static_cast(0.25)); do { @@ -66,9 +66,9 @@ main(int argc, char** argv) std::cout << "position: " << gripper.getPositionPercentage() << " - current: " << gripper.getCurrent() << std::endl; } - gripper.setForcePercentage(0.1f); - gripper.setPositionPercentage(0.0f); - gripper.setSpeedPercentage(0.5f); + gripper.setForcePercentage(static_cast(0.1)); + gripper.setPositionPercentage(0); + gripper.setSpeedPercentage(static_cast(0.5)); do { diff --git a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp index 9551e72c..07abdac3 100644 --- a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp +++ b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp @@ -191,17 +191,17 @@ main(int argc, char** argv) eval(f0); rl::math::Spline f1 = rl::math::Spline::CubicNatural(x, y); eval(f1); - rl::math::Spline f2 = rl::math::Spline::LinearParabolic(x, y, 0.25f); + rl::math::Spline f2 = rl::math::Spline::LinearParabolic(x, y, static_cast(0.25)); eval(f2); - rl::math::Spline f2b = rl::math::Spline::LinearParabolicPercentage(x, y, 0.25f); + rl::math::Spline f2b = rl::math::Spline::LinearParabolicPercentage(x, y, static_cast(0.25)); eval(f2b); - rl::math::Spline f3 = rl::math::Spline::LinearQuartic(x, y, 0.25f); + rl::math::Spline f3 = rl::math::Spline::LinearQuartic(x, y, static_cast(0.25)); eval(f3); - rl::math::Spline f3b = rl::math::Spline::LinearQuarticPercentage(x, y, 0.25f); + rl::math::Spline f3b = rl::math::Spline::LinearQuarticPercentage(x, y, static_cast(0.25)); eval(f3b); - rl::math::Spline f4 = rl::math::Spline::LinearSextic(x, y, 0.25f); + rl::math::Spline f4 = rl::math::Spline::LinearSextic(x, y, static_cast(0.25)); eval(f4); - rl::math::Spline f4b = rl::math::Spline::LinearSexticPercentage(x, y, 0.25f); + rl::math::Spline f4b = rl::math::Spline::LinearSexticPercentage(x, y, static_cast(0.25)); eval(f4b); } @@ -229,11 +229,11 @@ main(int argc, char** argv) eval(f0); rl::math::Spline f1 = rl::math::Spline::CubicNatural(x, y); eval(f1); - rl::math::Spline f2 = rl::math::Spline::LinearParabolic(x, y, 0.25f); + rl::math::Spline f2 = rl::math::Spline::LinearParabolic(x, y, static_cast(0.25)); eval(f2); - rl::math::Spline f3 = rl::math::Spline::LinearQuartic(x, y, 0.25f); + rl::math::Spline f3 = rl::math::Spline::LinearQuartic(x, y, static_cast(0.25)); eval(f3); - rl::math::Spline f4 = rl::math::Spline::LinearSextic(x, y, 0.25f); + rl::math::Spline f4 = rl::math::Spline::LinearSextic(x, y, static_cast(0.25)); eval(f4); } diff --git a/demos/rlJacobianDemo/rlJacobianDemo.cpp b/demos/rlJacobianDemo/rlJacobianDemo.cpp index 21715aae..644168ed 100644 --- a/demos/rlJacobianDemo/rlJacobianDemo.cpp +++ b/demos/rlJacobianDemo/rlJacobianDemo.cpp @@ -75,7 +75,7 @@ main(int argc, char** argv) std::cout << i << " " << xdot.transpose() << std::endl; } - kinematics->updateJacobianInverse(1.0e-9f); + kinematics->updateJacobianInverse(static_cast(1.0e-9)); std::cout << "invJ=" << std::endl << kinematics->getJacobianInverse() << std::endl; diff --git a/demos/rlPlanDemo/ConfigurationDelegate.cpp b/demos/rlPlanDemo/ConfigurationDelegate.cpp index 969a5500..d4c93bc5 100644 --- a/demos/rlPlanDemo/ConfigurationDelegate.cpp +++ b/demos/rlPlanDemo/ConfigurationDelegate.cpp @@ -54,14 +54,14 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& editor->setDecimals(2); editor->setMinimum(minimum(index.row()) * rl::math::RAD2DEG); editor->setMaximum(maximum(index.row()) * rl::math::RAD2DEG); - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); } else { editor->setDecimals(4); editor->setMinimum(minimum(index.row())); editor->setMaximum(maximum(index.row())); - editor->setSingleStep(0.01f); + editor->setSingleStep(0.01); } editor->setWrapping(wraparounds(index.row())); diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 1b1fe279..f810529b 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -38,8 +38,8 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : QGraphicsScene(parent), axis0(0), axis1(1), - delta0(1.0f), - delta1(1.0f), + delta0(1), + delta1(1), model(nullptr), edges(), path(), @@ -65,8 +65,8 @@ void ConfigurationSpaceScene::addCollision(const qreal& x, const qreal& y, const qreal& w, const qreal& h, const int& rgb) { QGraphicsRectItem* rect = this->addRect( - x - w / 2.0f, - -y - h / 2.0f, + x - w * static_cast(0.5), + -y - h * static_cast(0.5), w, h, QPen(Qt::NoPen), @@ -104,7 +104,7 @@ ConfigurationSpaceScene::drawConfigurationEdge(const rl::math::Vector& u, const -u(this->axis1), v(this->axis0), -v(this->axis1), - free ? QPen(QBrush(QColor(0, 128, 0)), 0.0f) : QPen(QBrush(QColor(128, 0, 0)), 0.0f) + free ? QPen(QBrush(QColor(0, 128, 0)), 0) : QPen(QBrush(QColor(128, 0, 0)), 0) ); line->setParentItem(this->scene); @@ -133,7 +133,7 @@ ConfigurationSpaceScene::drawConfigurationPath(const rl::plan::VectorList& path) -(*i)(this->axis1), (*j)(this->axis0), -(*j)(this->axis1), - QPen(QBrush(QColor(0, 255, 0)), 0.0f) + QPen(QBrush(QColor(0, 255, 0)), 0) ); line->setParentItem(this->scene); diff --git a/demos/rlPlanDemo/ConfigurationSpaceThread.cpp b/demos/rlPlanDemo/ConfigurationSpaceThread.cpp index f52ef0b2..9488e7c0 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceThread.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceThread.cpp @@ -34,8 +34,8 @@ ConfigurationSpaceThread::ConfigurationSpaceThread(QObject* parent) : QThread(parent), axis0(0), axis1(1), - delta0(1.0f), - delta1(1.0f), + delta0(1), + delta1(1), model(nullptr), running(false) { diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index dc369501..b3cbb707 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -1184,7 +1184,7 @@ MainWindow::load(const QString& filename) { this->sampler = std::make_shared(); rl::plan::BridgeSampler* bridgeSampler = static_cast(this->sampler.get()); - bridgeSampler->ratio = path.eval("number((/rl/plan|/rlplan)//bridgeSampler/ratio)").getValue(5.0f / 6.0f); + bridgeSampler->ratio = path.eval("number((/rl/plan|/rlplan)//bridgeSampler/ratio)").getValue(static_cast(5) / static_cast(6)); if (path.eval("count((/rl/plan|/rlplan)//bridgeSampler/seed) > 0").getValue()) { @@ -1277,7 +1277,7 @@ MainWindow::load(const QString& filename) advancedOptimizer->length *= rl::math::DEG2RAD; } - advancedOptimizer->ratio = path.eval("number((/rl/plan|/rlplan)//advancedOptimizer/ratio)").getValue(0.1f); + advancedOptimizer->ratio = path.eval("number((/rl/plan|/rlplan)//advancedOptimizer/ratio)").getValue(static_cast(0.1)); } if (nullptr != this->optimizer) @@ -1296,7 +1296,7 @@ MainWindow::load(const QString& filename) { this->planner = std::make_shared(); rl::plan::AddRrtConCon* addRrtConCon = static_cast(this->planner.get()); - addRrtConCon->alpha = path.eval("number(alpha)").getValue(0.05f); + addRrtConCon->alpha = path.eval("number(alpha)").getValue(static_cast(0.05)); addRrtConCon->delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) @@ -1304,7 +1304,7 @@ MainWindow::load(const QString& filename) addRrtConCon->delta *= rl::math::DEG2RAD; } - addRrtConCon->epsilon = path.eval("number(epsilon)").getValue(1.0e-3f); + addRrtConCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { @@ -1331,7 +1331,7 @@ MainWindow::load(const QString& filename) { this->planner = std::make_shared(); rl::plan::Eet* eet = static_cast(this->planner.get()); - eet->alpha = path.eval("number(alpha)").getValue(0.01f); + eet->alpha = path.eval("number(alpha)").getValue(static_cast(0.01)); eet->alternativeDistanceComputation = path.eval("count(alternativeDistanceComputation) > 0").getValue() ? true : false; eet->beta = path.eval("number(beta)").getValue(0); eet->delta = path.eval("number(delta)").getValue(1); @@ -1341,16 +1341,16 @@ MainWindow::load(const QString& filename) eet->delta *= rl::math::DEG2RAD; } - eet->distanceWeight = path.eval("number(distanceWeight)").getValue(0.1f); - eet->epsilon = path.eval("number(epsilon)").getValue(1.0e-3f); + eet->distanceWeight = path.eval("number(distanceWeight)").getValue(static_cast(0.1)); + eet->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { eet->epsilon *= rl::math::DEG2RAD; } - eet->gamma = path.eval("number(gamma)").getValue(1.0f / 3.0f); - eet->goalEpsilon = path.eval("number(goalEpsilon)").getValue(0.1f); + eet->gamma = path.eval("number(gamma)").getValue(static_cast(1) / static_cast(3)); + eet->goalEpsilon = path.eval("number(goalEpsilon)").getValue(static_cast(0.1)); if (path.eval("translate(string(goalEpsilon/@orientation), 'TRUE', 'true') = 'true' or string(goalEpsilon/@orientation) = '1'").getValue()) { @@ -1558,7 +1558,7 @@ MainWindow::load(const QString& filename) rrt->delta *= rl::math::DEG2RAD; } - rrt->epsilon = path.eval("number(epsilon)").getValue(1.0e-3f); + rrt->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { @@ -1578,14 +1578,14 @@ MainWindow::load(const QString& filename) rrtCon->delta *= rl::math::DEG2RAD; } - rrtCon->epsilon = path.eval("number(epsilon)").getValue(1.0e-3f); + rrtCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { rrtCon->epsilon *= rl::math::DEG2RAD; } - rrtCon->probability = path.eval("number(probability)").getValue(0.05f); + rrtCon->probability = path.eval("number(probability)").getValue(static_cast(0.05)); rrtCon->sampler = this->sampler.get(); if (path.eval("count(seed) > 0").getValue()) @@ -1610,7 +1610,7 @@ MainWindow::load(const QString& filename) rrtConCon->delta *= rl::math::DEG2RAD; } - rrtConCon->epsilon = path.eval("number(epsilon)").getValue(1.0e-3f); + rrtConCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { @@ -1630,7 +1630,7 @@ MainWindow::load(const QString& filename) rrtDual->delta *= rl::math::DEG2RAD; } - rrtDual->epsilon = path.eval("number(epsilon)").getValue(1.0e-3f); + rrtDual->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { @@ -1650,7 +1650,7 @@ MainWindow::load(const QString& filename) rrtExtCon->delta *= rl::math::DEG2RAD; } - rrtExtCon->epsilon = path.eval("number(epsilon)").getValue(1.0e-3f); + rrtExtCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { @@ -1670,7 +1670,7 @@ MainWindow::load(const QString& filename) rrtExtExt->delta *= rl::math::DEG2RAD; } - rrtExtExt->epsilon = path.eval("number(epsilon)").getValue(1.0e-3f); + rrtExtExt->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { @@ -1690,14 +1690,14 @@ MainWindow::load(const QString& filename) rrtGoalBias->delta *= rl::math::DEG2RAD; } - rrtGoalBias->epsilon = path.eval("number(epsilon)").getValue(1.0e-3f); + rrtGoalBias->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { rrtGoalBias->epsilon *= rl::math::DEG2RAD; } - rrtGoalBias->probability = path.eval("number(probability)").getValue(0.05f); + rrtGoalBias->probability = path.eval("number(probability)").getValue(static_cast(0.05)); rrtGoalBias->sampler = this->sampler.get(); if (path.eval("count(seed) > 0").getValue()) @@ -1917,7 +1917,7 @@ MainWindow::load(const QString& filename) } this->viewer->viewer->getCamera()->scaleHeight( - path.eval("number((/rl/plan|/rlplan)//viewer/camera/scale)").getValue(1.0f) + path.eval("number((/rl/plan|/rlplan)//viewer/camera/scale)").getValue(1) ); this->viewer->drawConfiguration(*this->start); diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index 94e014a1..49d5e2cf 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -174,7 +174,7 @@ Thread::run() { emit statusChanged("Showing start configuration."); this->drawConfiguration(*MainWindow::instance()->planner->start); - usleep(static_cast(2.0f * 1000.0f * 1000.0f)); + usleep(static_cast(2.0 * 1000.0 * 1000.0)); } if (!this->running) return; @@ -183,7 +183,7 @@ Thread::run() { emit statusChanged("Showing goal configuration."); this->drawConfiguration(*MainWindow::instance()->planner->goal); - usleep(static_cast(2.0f * 1000.0f * 1000.0f)); + usleep(static_cast(2.0 * 1000.0 * 1000.0)); } if (!this->running) return; @@ -305,7 +305,7 @@ Thread::run() } else { - benchmark << 0.0f; + benchmark << 0; } benchmark << ","; @@ -355,7 +355,7 @@ Thread::run() { if (nullptr != MainWindow::instance()->planner->viewer) { - usleep(static_cast(2.0f * 1000.0f * 1000.0f)); + usleep(static_cast(2.0 * 1000.0 * 1000.0)); } emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration) + " ms. Optimizing..."); @@ -394,7 +394,7 @@ Thread::run() if (i != path.end() && j != path.end()) { this->drawConfiguration(*i); - usleep(static_cast(0.01f * 1000.0f * 1000.0f)); + usleep(static_cast(0.01 * 1000.0 * 1000.0)); } rl::math::Real delta = MainWindow::instance()->viewer->delta; @@ -411,7 +411,7 @@ Thread::run() MainWindow::instance()->model->interpolate(*i, *j, k / steps, inter); this->drawConfiguration(inter); - usleep(static_cast(0.01f * 1000.0f * 1000.0f)); + usleep(static_cast(0.01 * 1000.0 * 1000.0)); } } @@ -423,7 +423,7 @@ Thread::run() if (ri != path.rend() && rj != path.rend()) { this->drawConfiguration(*ri); - usleep(static_cast(0.01f * 1000.0f * 1000.0f)); + usleep(static_cast(0.01 * 1000.0 * 1000.0)); } for (; ri != path.rend() && rj != path.rend(); ++ri, ++rj) @@ -438,7 +438,7 @@ Thread::run() MainWindow::instance()->model->interpolate(*ri, *rj, k / steps, inter); this->drawConfiguration(inter); - usleep(static_cast(0.01f * 1000.0f * 1000.0f)); + usleep(static_cast(0.01 * 1000.0 * 1000.0)); } } } diff --git a/demos/rlPlanDemo/Viewer.cpp b/demos/rlPlanDemo/Viewer.cpp index 76351827..4754d394 100644 --- a/demos/rlPlanDemo/Viewer.cpp +++ b/demos/rlPlanDemo/Viewer.cpp @@ -43,8 +43,8 @@ Viewer::Viewer(QWidget* parent, Qt::WindowFlags f) : QWidget(parent, f), - delta(1.0f), - deltaSwept(100.0f), + delta(1), + deltaSwept(100), model(nullptr), sceneGroup(new SoVRMLGroup()), viewer(new SoQtExaminerViewer(this, nullptr, true, SoQtFullViewer::BUILD_POPUP)), diff --git a/demos/rlPrmDemo/rlPrmDemo.cpp b/demos/rlPrmDemo/rlPrmDemo.cpp index 9257da07..1469ff42 100644 --- a/demos/rlPrmDemo/rlPrmDemo.cpp +++ b/demos/rlPrmDemo/rlPrmDemo.cpp @@ -74,7 +74,7 @@ main(int argc, char** argv) sampler.model = &model; - verifier.delta = 1.0f * rl::math::DEG2RAD; + verifier.delta = 1 * rl::math::DEG2RAD; verifier.model = &model; rl::math::Vector start(kinematics->getDof()); diff --git a/demos/rlQuaternionDemo/rlQuaternionDemo.cpp b/demos/rlQuaternionDemo/rlQuaternionDemo.cpp index d6116933..96427513 100644 --- a/demos/rlQuaternionDemo/rlQuaternionDemo.cpp +++ b/demos/rlQuaternionDemo/rlQuaternionDemo.cpp @@ -41,9 +41,9 @@ main(int argc, char** argv) { { rl::math::Matrix33 r1( - rl::math::AngleAxis(90.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(0.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(0.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(90 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) ); std::cout << "r1 = " << std::endl << r1 << std::endl; @@ -54,9 +54,9 @@ main(int argc, char** argv) std::cout << "r1 = " << std::endl << r1 << std::endl; rl::math::Matrix33 r2( - rl::math::AngleAxis(-90.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(0.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(0.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(-90 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) ); std::cout << "r2 = " << std::endl << r2 << std::endl; @@ -82,9 +82,9 @@ main(int argc, char** argv) std::cout << "(q1^2)^0.5 = " << q1.pow(2).pow(0.5).coeffs().transpose() << std::endl; rl::math::Vector3 omega( - 45.0f * rl::math::DEG2RAD, - 90.0f * rl::math::DEG2RAD, - 135.0f * rl::math::DEG2RAD + 45 * rl::math::DEG2RAD, + 90 * rl::math::DEG2RAD, + 135 * rl::math::DEG2RAD ); std::cout << "omega = " << omega.transpose() * rl::math::RAD2DEG << std::endl; @@ -95,9 +95,9 @@ main(int argc, char** argv) std::cout << "omega = " << omega.transpose() * rl::math::RAD2DEG << std::endl; rl::math::Vector3 omegad( - 450.0f * rl::math::DEG2RAD, - 900.0f * rl::math::DEG2RAD, - 1350.0f * rl::math::DEG2RAD + 450 * rl::math::DEG2RAD, + 900 * rl::math::DEG2RAD, + 1350 * rl::math::DEG2RAD ); std::cout << "omegad = " << omegad.transpose() * rl::math::RAD2DEG << std::endl; @@ -110,24 +110,24 @@ main(int argc, char** argv) { rl::math::Quaternion q0( - rl::math::AngleAxis(90.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(0.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(0.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(90 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) ); rl::math::Quaternion q1( - rl::math::AngleAxis(45.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(60.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(45.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(45 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(60 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(45 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) ); rl::math::Quaternion q2( - rl::math::AngleAxis(45.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(10.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(30.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(45 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(10 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(30 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) ); rl::math::Quaternion q3( - rl::math::AngleAxis(90.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(10.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(0.0f * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(90 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(10 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) ); rl::math::Vector3 p(1, 0, 0); @@ -238,9 +238,9 @@ main(int argc, char** argv) { std::vector y; y.push_back(rl::math::Quaternion(1, 0, 0, 0)); - y.push_back(rl::math::Quaternion(0.5f * std::sqrt(2.0f), 0, -0.5f * std::sqrt(2.0f), 0)); - y.push_back(rl::math::Quaternion(0.5, -0.5, -0.5, 0.5)); - y.push_back(rl::math::Quaternion(0.5f * std::sqrt(2.0f), 0, 0, 0.5f * std::sqrt(2.0f))); + y.push_back(rl::math::Quaternion(static_cast(0.5) * std::sqrt(static_cast(2)), 0, -static_cast(0.5) * std::sqrt(static_cast(2)), 0)); + y.push_back(rl::math::Quaternion(static_cast(0.5), -static_cast(0.5), -static_cast(0.5), static_cast(0.5))); + y.push_back(rl::math::Quaternion(static_cast(0.5) * std::sqrt(static_cast(2)), 0, 0, static_cast(0.5) * std::sqrt(static_cast(2)))); y.push_back(rl::math::Quaternion(1, 0, 0, 0)); std::vector x; diff --git a/demos/rlSimulator/ConfigurationDelegate.cpp b/demos/rlSimulator/ConfigurationDelegate.cpp index 74d2b7c6..d39778e1 100644 --- a/demos/rlSimulator/ConfigurationDelegate.cpp +++ b/demos/rlSimulator/ConfigurationDelegate.cpp @@ -86,13 +86,13 @@ PositionDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& opti { editor->setMinimum(minimum(index.row()) * rl::math::RAD2DEG); editor->setMaximum(maximum(index.row()) * rl::math::RAD2DEG); - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); } else { editor->setMinimum(minimum(index.row())); editor->setMaximum(maximum(index.row())); - editor->setSingleStep(0.1f); + editor->setSingleStep(0.1); } QObject::connect(editor, SIGNAL(valueChanged(double)), this, SLOT(valueChanged(double))); @@ -110,11 +110,11 @@ VelocityDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& opti editor->setRange(-10000, 10000); //TODO? if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); } else { - editor->setSingleStep(0.1f); + editor->setSingleStep(0.1); } QObject::connect(editor, SIGNAL(valueChanged(double)), this, SLOT(valueChanged(double))); @@ -132,11 +132,11 @@ AccelerationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& editor->setRange(-10000, 10000); if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - editor->setSingleStep(10.0f); + editor->setSingleStep(10.0); } else { - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); } QObject::connect(editor, SIGNAL(valueChanged(double)), this, SLOT(valueChanged(double))); @@ -150,7 +150,7 @@ TorqueDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& option QDoubleSpinBox* editor = new QDoubleSpinBox(parent); editor->setRange(-1000, 1000); - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); QObject::connect(editor, SIGNAL(valueChanged(double)), this, SLOT(valueChanged(double))); diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index 6ceef391..ed2b620d 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -80,10 +80,10 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : server(new Server(this)), serverConnectionStatus(nullptr), simulationDampingFactor(nullptr), - simulationDampingValue(0.001f), + simulationDampingValue(static_cast(0.001)), simulationDockWidget(new QDockWidget(this)), simulationGravity(nullptr), - simulationGravityValue(9.81f), + simulationGravityValue(rl::math::GRAVITY), simulationIsRunning(true), simulationPause(nullptr), simulationReset(nullptr), @@ -96,7 +96,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : simulationStepsPerFrame(50), simulationTime(nullptr), simulationTimeElapsed(0), - simulationTimeStep(0.001f), + simulationTimeStep(static_cast(0.001)), timer(), torqueDelegate(nullptr), torqueDockWidget(new QDockWidget(this)), @@ -269,7 +269,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : simulationSettingsLayout->addWidget(new QLabel("Gravity [m/s^2]", simulationSettings), 0, 0); simulationSettingsLayout->addWidget(simulationGravity, 0, 1); simulationGravity->setRange(0, 100); - simulationGravity->setSingleStep(0.1f); + simulationGravity->setSingleStep(0.1); simulationGravity->setDecimals(2); simulationGravity->setValue(simulationGravityValue); QObject::connect(simulationGravity, SIGNAL(valueChanged(double)), this, SLOT(changeSimulationGravity(double))); @@ -277,7 +277,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : simulationSettingsLayout->addWidget(new QLabel("Damping Factor", simulationSettings), 1, 0); simulationSettingsLayout->addWidget(simulationDampingFactor, 1, 1); simulationDampingFactor->setRange(0, 1.5); - simulationDampingFactor->setSingleStep(0.0001f); + simulationDampingFactor->setSingleStep(0.0001); simulationDampingFactor->setDecimals(5); simulationDampingFactor->setValue(simulationDampingValue); simulationDampingFactor->setToolTip(QString("0.0 gives a frictionless system, 1.0 damps almost all motion; try 0.001--0.005 for typical viscous friction")); diff --git a/demos/rlSimulator/OperationalDelegate.cpp b/demos/rlSimulator/OperationalDelegate.cpp index 4fefd6c7..29a074fb 100644 --- a/demos/rlSimulator/OperationalDelegate.cpp +++ b/demos/rlSimulator/OperationalDelegate.cpp @@ -52,12 +52,12 @@ OperationalDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& o case 0: case 1: case 2: - editor->setSingleStep(0.01f); + editor->setSingleStep(0.01); break; case 3: case 4: case 5: - editor->setSingleStep(1.0f); + editor->setSingleStep(1.0); break; default: break; diff --git a/demos/rlSimulator/OperationalModel.cpp b/demos/rlSimulator/OperationalModel.cpp index 590b22c8..2cb69900 100644 --- a/demos/rlSimulator/OperationalModel.cpp +++ b/demos/rlSimulator/OperationalModel.cpp @@ -239,7 +239,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r rl::mdl::NloptInverseKinematics ik(kinematic); #else rl::mdl::JacobianInverseKinematics ik(kinematic); - ik.delta = 1.0f; + ik.delta = 1; #endif ik.goals.push_back(std::make_pair(x, index.row())); diff --git a/demos/rlTrapezoidalVelocityDemo/rlTrapezoidalVelocityDemo.cpp b/demos/rlTrapezoidalVelocityDemo/rlTrapezoidalVelocityDemo.cpp index 4420fd23..b37a92bd 100644 --- a/demos/rlTrapezoidalVelocityDemo/rlTrapezoidalVelocityDemo.cpp +++ b/demos/rlTrapezoidalVelocityDemo/rlTrapezoidalVelocityDemo.cpp @@ -55,9 +55,9 @@ main(int argc, char** argv) std::cout << " "; std::cout << x; std::cout << " "; - std::cout << v * 100.0f; + std::cout << v * 100; std::cout << " "; - std::cout << a * 1000.0f; + std::cout << a * 1000; std::cout << std::endl; interpolator.x0 = x; interpolator.v0 = v; diff --git a/src/rl/hal/LeuzeRs4.cpp b/src/rl/hal/LeuzeRs4.cpp index 407b1af4..c203f840 100644 --- a/src/rl/hal/LeuzeRs4.cpp +++ b/src/rl/hal/LeuzeRs4.cpp @@ -198,7 +198,7 @@ namespace rl { assert(i < this->getDistancesCount()); - return 4.0f; + return 4; } ::rl::math::Real @@ -206,7 +206,7 @@ namespace rl { assert(i < this->getDistancesCount()); - return 0.0f; + return 0; } ::rl::math::Real @@ -214,7 +214,7 @@ namespace rl { assert(this->isConnected()); - return this->stepSize * 0.36f * ::rl::math::DEG2RAD; + return this->stepSize * static_cast< ::rl::math::Real>(0.36) * ::rl::math::DEG2RAD; } ::rl::math::Real @@ -222,7 +222,7 @@ namespace rl { assert(this->isConnected()); - return (-5 + this->startIndex * 0.36f) * ::rl::math::DEG2RAD; + return (-5 + this->startIndex * static_cast< ::rl::math::Real>(0.36)) * ::rl::math::DEG2RAD; } ::rl::math::Real @@ -230,7 +230,7 @@ namespace rl { assert(this->isConnected()); - return (185 - (528 - this->stopIndex) * 0.36f) * ::rl::math::DEG2RAD; + return (185 - (528 - this->stopIndex) * static_cast< ::rl::math::Real>(0.36)) * ::rl::math::DEG2RAD; } void diff --git a/src/rl/hal/MitsubishiH7.cpp b/src/rl/hal/MitsubishiH7.cpp index 80a5f0f7..2c9e0946 100644 --- a/src/rl/hal/MitsubishiH7.cpp +++ b/src/rl/hal/MitsubishiH7.cpp @@ -94,9 +94,9 @@ namespace rl ::rl::math::AngleAxis(this->in.dat1.pos.w.a, ::rl::math::Vector3::UnitX()) ).matrix(); - x.translation().x() = this->in.dat1.pos.w.x / 1000.0f; - x.translation().y() = this->in.dat1.pos.w.y / 1000.0f; - x.translation().z() = this->in.dat1.pos.w.z / 1000.0f; + x.translation().x() = this->in.dat1.pos.w.x / 1000; + x.translation().y() = this->in.dat1.pos.w.y / 1000; + x.translation().z() = this->in.dat1.pos.w.z / 1000; return x; } @@ -249,9 +249,9 @@ namespace rl this->out.dat.pos.w.b = static_cast(abc(1)); this->out.dat.pos.w.c = static_cast(abc(2)); - this->out.dat.pos.w.x = static_cast(x.translation().x() * 1000.0f); - this->out.dat.pos.w.y = static_cast(x.translation().y() * 1000.0f); - this->out.dat.pos.w.z = static_cast(x.translation().z() * 1000.0f); + this->out.dat.pos.w.x = static_cast(x.translation().x() * 1000); + this->out.dat.pos.w.y = static_cast(x.translation().y() * 1000); + this->out.dat.pos.w.z = static_cast(x.translation().z() * 1000); this->out.command = MXT_COMMAND_MOVE; this->out.sendType = MXT_TYPE_POSE; @@ -276,14 +276,14 @@ namespace rl { assert(q.size() >= this->getDof()); - this->out.dat.jnt.j1 = 0.0f; - this->out.dat.jnt.j2 = 0.0f; - this->out.dat.jnt.j3 = 0.0f; - this->out.dat.jnt.j4 = 0.0f; - this->out.dat.jnt.j5 = 0.0f; - this->out.dat.jnt.j6 = 0.0f; - this->out.dat.jnt.j7 = 0.0f; - this->out.dat.jnt.j8 = 0.0f; + this->out.dat.jnt.j1 = 0; + this->out.dat.jnt.j2 = 0; + this->out.dat.jnt.j3 = 0; + this->out.dat.jnt.j4 = 0; + this->out.dat.jnt.j5 = 0; + this->out.dat.jnt.j6 = 0; + this->out.dat.jnt.j7 = 0; + this->out.dat.jnt.j8 = 0; switch (this->getDof()) { diff --git a/src/rl/hal/SchmersalLss300.cpp b/src/rl/hal/SchmersalLss300.cpp index 84846181..5c0bb0e7 100644 --- a/src/rl/hal/SchmersalLss300.cpp +++ b/src/rl/hal/SchmersalLss300.cpp @@ -122,7 +122,7 @@ namespace rl ::rl::math::Vector distances(this->getDistancesCount()); - ::rl::math::Real scale = 0.01f; + ::rl::math::Real scale = static_cast< ::rl::math::Real>(0.01); ::std::uint16_t count = Endian::hostWord(this->data[8], this->data[7]); ::std::uint8_t mask = 0x1F; @@ -153,7 +153,7 @@ namespace rl { assert(i < this->getDistancesCount()); - return 60.0f; + return 60; } ::rl::math::Real @@ -161,7 +161,7 @@ namespace rl { assert(i < this->getDistancesCount()); - return 0.0f; + return 0; } SchmersalLss300::Monitoring @@ -177,7 +177,7 @@ namespace rl { assert(this->isConnected()); - return 0.36f * ::rl::math::DEG2RAD; + return static_cast< ::rl::math::Real>(0.36) * ::rl::math::DEG2RAD; } ::rl::math::Real @@ -185,7 +185,7 @@ namespace rl { assert(this->isConnected()); - return 0.0f; + return 0; } ::rl::math::Real @@ -193,7 +193,7 @@ namespace rl { assert(this->isConnected()); - return 180.0f * ::rl::math::DEG2RAD; + return 180 * ::rl::math::DEG2RAD; } ::std::string diff --git a/src/rl/hal/SchunkFpsF5.cpp b/src/rl/hal/SchunkFpsF5.cpp index 6ee86f98..6b1b6be8 100644 --- a/src/rl/hal/SchunkFpsF5.cpp +++ b/src/rl/hal/SchunkFpsF5.cpp @@ -120,7 +120,7 @@ namespace rl SchunkFpsF5::getDistancesMaximum(const ::std::size_t& i) const { assert(i < this->getDistancesCount()); - return 0.06f; + return static_cast< ::rl::math::Real>(0.06); } ::rl::math::Real @@ -297,8 +297,8 @@ namespace rl for (int i = 0; i < ::std::min(size, 31); ++i) { this->fulcrums.insert(::std::make_pair( - 5.0f * (Endian::hostWord(~buf[9 + i * 4], ~buf[9 + i * 4 + 1]) - 0x0000) / (0xFFF0 - 0x0000), - Endian::hostWord(buf[11 + i * 4], buf[11 + i * 4 + 1]) / 1000.0f / 1000.0f + static_cast< ::rl::math::Real>(5) * (Endian::hostWord(~buf[9 + i * 4], ~buf[9 + i * 4 + 1]) - 0x0000) / (0xFFF0 - 0x0000), + Endian::hostWord(buf[11 + i * 4], buf[11 + i * 4 + 1]) / static_cast< ::rl::math::Real>(1000) / static_cast< ::rl::math::Real>(1000) )); } @@ -315,8 +315,8 @@ namespace rl for (int i = 0; i < ::std::min(size - 31, 31); ++i) { this->fulcrums.insert(::std::make_pair( - 5.0f * (Endian::hostWord(~buf[5 + i * 4], ~buf[5 + i * 4 + 1]) - 0x0000) / (0xFFF0 - 0x0000), - Endian::hostWord(buf[7 + i * 4], buf[7 + i * 4 + 1]) / 1000.0f / 1000.0f + static_cast< ::rl::math::Real>(5) * (Endian::hostWord(~buf[5 + i * 4], ~buf[5 + i * 4 + 1]) - 0x0000) / (0xFFF0 - 0x0000), + Endian::hostWord(buf[7 + i * 4], buf[7 + i * 4 + 1]) / static_cast< ::rl::math::Real>(1000) / static_cast< ::rl::math::Real>(1000) )); } } @@ -347,7 +347,7 @@ namespace rl // 10000000 this->closed = (buf[5] & 128) ? true : false; - this->value = 5.0f * (Endian::hostWord(~buf[31], ~buf[32]) - 0x0000) / (0xFFF0 - 0x0000); + this->value = static_cast< ::rl::math::Real>(5) * (Endian::hostWord(~buf[31], ~buf[32]) - 0x0000) / (0xFFF0 - 0x0000); ::std::set< ::std::pair< ::rl::math::Real, ::rl::math::Real>>::iterator lower = this->fulcrums.upper_bound(::std::make_pair(this->value, ::std::numeric_limits< ::rl::math::Real>::max())); @@ -372,8 +372,8 @@ namespace rl this->interpolated = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); } - this->voltage = 23.0f * (Endian::hostWord(buf[33], buf[34]) - 0x3D00) / (0xB700 - 0x3D00) + 12.0f; - this->temperature = 90.0f * (Endian::hostWord(buf[35], 0x0) - 0x0A00) / (0xC300 - 0x0A00) - 20.0f; + this->voltage = static_cast< ::rl::math::Real>(23) * (Endian::hostWord(buf[33], buf[34]) - 0x3D00) / (0xB700 - 0x3D00) + static_cast< ::rl::math::Real>(12); + this->temperature = static_cast< ::rl::math::Real>(90) * (Endian::hostWord(buf[35], 0x0) - 0x0A00) / (0xC300 - 0x0A00) - static_cast< ::rl::math::Real>(20); // 00000001 this->area = (buf[36] & 1) ? true : false; diff --git a/src/rl/hal/SickLms200.cpp b/src/rl/hal/SickLms200.cpp index 5e9c39cd..2155caa3 100644 --- a/src/rl/hal/SickLms200.cpp +++ b/src/rl/hal/SickLms200.cpp @@ -312,10 +312,10 @@ namespace rl switch (this->data[6] & 192) { case 0: - scale = 0.01f; + scale = static_cast< ::rl::math::Real>(0.01); break; case 64: - scale = 0.001f; + scale = static_cast< ::rl::math::Real>(0.001); break; default: throw DeviceException("unknown scale"); @@ -501,7 +501,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; break; } - return 0.0f; + return 0; } ::rl::math::Real @@ -510,7 +510,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; assert(this->isConnected()); assert(i < this->getDistancesCount()); - return 0.0f; + return 0; } SickLms200::Measuring @@ -537,21 +537,21 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (this->variant) { case VARIANT_100_25: - return 0.25f * ::rl::math::DEG2RAD; + return static_cast< ::rl::math::Real>(0.25) * ::rl::math::DEG2RAD; break; case VARIANT_100_50: case VARIANT_180_50: - return 0.5f * ::rl::math::DEG2RAD; + return static_cast< ::rl::math::Real>(0.5) * ::rl::math::DEG2RAD; break; case VARIANT_100_100: case VARIANT_180_100: - return 1.0f * ::rl::math::DEG2RAD; + return 1 * ::rl::math::DEG2RAD; break; default: break; } - return 0.0f; + return 0; } ::rl::math::Real @@ -564,17 +564,17 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; case VARIANT_100_25: case VARIANT_100_50: case VARIANT_100_100: - return 40.0f * ::rl::math::DEG2RAD; + return 40 * ::rl::math::DEG2RAD; break; case VARIANT_180_50: case VARIANT_180_100: - return 0.0f; + return 0; break; default: break; } - return 0.0f; + return 0; } ::rl::math::Real @@ -587,17 +587,17 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; case VARIANT_100_25: case VARIANT_100_50: case VARIANT_100_100: - return 140.0f * ::rl::math::DEG2RAD; + return 140 * ::rl::math::DEG2RAD; break; case VARIANT_180_50: case VARIANT_180_100: - return 180.0f * ::rl::math::DEG2RAD; + return 180 * ::rl::math::DEG2RAD; break; default: break; } - return 0.0f; + return 0; } ::std::string diff --git a/src/rl/hal/SickS300.cpp b/src/rl/hal/SickS300.cpp index 9ad5cc07..995675d5 100644 --- a/src/rl/hal/SickS300.cpp +++ b/src/rl/hal/SickS300.cpp @@ -124,7 +124,7 @@ namespace rl ::rl::math::Vector distances(this->getDistancesCount()); - ::rl::math::Real scale = 0.01f; + ::rl::math::Real scale = static_cast< ::rl::math::Real>(0.01); for (::std::size_t i = 0; i < this->getDistancesCount(); ++i) { @@ -163,7 +163,7 @@ ::std::cerr << "Glare (dazzling) detected" << ::std::endl; assert(this->isConnected()); assert(i < this->getDistancesCount()); - return 10.0f; + return 10; } ::rl::math::Real @@ -172,7 +172,7 @@ ::std::cerr << "Glare (dazzling) detected" << ::std::endl; assert(this->isConnected()); assert(i < this->getDistancesCount()); - return 0.0f; + return 0; } ::rl::math::Real @@ -180,7 +180,7 @@ ::std::cerr << "Glare (dazzling) detected" << ::std::endl; { assert(this->isConnected()); - return std::abs(this->getStopAngle() - this->getStartAngle()) / (this->getDistancesCount() - 1.0f); + return ::std::abs(this->getStopAngle() - this->getStartAngle()) / (this->getDistancesCount() - 1); } ::std::size_t @@ -197,7 +197,7 @@ ::std::cerr << "Glare (dazzling) detected" << ::std::endl; { assert(this->isConnected()); - return -45.0f * ::rl::math::DEG2RAD; + return -45 * ::rl::math::DEG2RAD; } ::rl::math::Real @@ -205,7 +205,7 @@ ::std::cerr << "Glare (dazzling) detected" << ::std::endl; { assert(this->isConnected()); - return 225.0f * ::rl::math::DEG2RAD; + return 225 * ::rl::math::DEG2RAD; } ::std::size_t diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 94974821..f810d0ed 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -670,8 +670,8 @@ namespace rl { assert(q1.size() == this->getDof()); assert(q2.size() == this->getDof()); - assert(alpha >= 0.0f); - assert(alpha <= 1.0f); + assert(alpha >= 0); + assert(alpha <= 1); assert(q.size() == this->getDof()); for (::std::size_t i = 0; i < this->getDof(); ++i) @@ -685,11 +685,11 @@ namespace rl { if (q1(i) > q2(i)) { - q(i) = (1.0f - alpha) * q1(i) + alpha * (q2(i) + range); + q(i) = (1 - alpha) * q1(i) + alpha * (q2(i) + range); } else { - q(i) = (1.0f - alpha) * (q1(i) + range) + alpha * q2(i); + q(i) = (1 - alpha) * (q1(i) + range) + alpha * q2(i); } while (q(i) > this->joints[i]->max) @@ -704,12 +704,12 @@ namespace rl } else { - q(i) = (1.0f - alpha) * q1(i) + alpha * q2(i); + q(i) = (1 - alpha) * q1(i) + alpha * q2(i); } } else { - q(i) = (1.0f - alpha) * q1(i) + alpha * q2(i); + q(i) = (1 - alpha) * q1(i) + alpha * q2(i); } } } @@ -772,11 +772,11 @@ namespace rl for (::std::size_t i = 0; i < this->getDof(); ++i) { - q(i) = ::std::fmod(q(i), 2.0f * static_cast< ::rl::math::Real>(M_PI)); + q(i) = ::std::fmod(q(i), 2 * static_cast< ::rl::math::Real>(M_PI)); if (q(i) < this->joints[i]->min) { - q(i) += 2.0f * static_cast< ::rl::math::Real>(M_PI); + q(i) += 2 * static_cast< ::rl::math::Real>(M_PI); if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) { @@ -785,7 +785,7 @@ namespace rl } else if (q(i) > this->joints[i]->max) { - q(i) -= 2.0f * static_cast< ::rl::math::Real>(M_PI); + q(i) -= 2 * static_cast< ::rl::math::Real>(M_PI); if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) { @@ -1073,7 +1073,7 @@ namespace rl ::Eigen::JacobiSVD< ::rl::math::Matrix> svd(this->jacobian, ::Eigen::ComputeFullU | ::Eigen::ComputeFullV); ::rl::math::Real wMin = svd.singularValues().minCoeff(); - ::rl::math::Real lambdaSqr = wMin < 1.0e-9f ? (1 - ::std::pow((wMin / 1.0e-9f), 2)) * ::std::pow(lambda, 2) : 0; + ::rl::math::Real lambdaSqr = wMin < static_cast< ::rl::math::Real>(1.0e-9) ? (1 - ::std::pow((wMin / static_cast< ::rl::math::Real>(1.0e-9)), 2)) * ::std::pow(lambda, 2) : 0; for (::std::ptrdiff_t i = 0; i < svd.nonzeroSingularValues(); ++i) { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 1bb4b761..8b884f65 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -213,7 +213,7 @@ namespace rl ::rl::math::Vector& q, const ::std::size_t& leaf = 0, const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(), - const ::rl::math::Real& epsilon = 1.0e-3f, + const ::rl::math::Real& epsilon = static_cast< ::rl::math::Real>(1.0e-3), const ::std::size_t& iterations = 1000 ); @@ -304,7 +304,7 @@ namespace rl * * @pre updateJacobian() */ - virtual void updateJacobianInverse(const ::rl::math::Real& lambda = 0.0f, const bool& doSvd = true); + virtual void updateJacobianInverse(const ::rl::math::Real& lambda = 0, const bool& doSvd = true); ::rl::math::Transform& world(); diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index 7bb3f53c..0b3b2d34 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -249,11 +249,11 @@ namespace rl // fit into min max angles for (::std::size_t i = 0; i < this->getDof(); ++i) { - q(i) = ::std::fmod(q(i), 2.0f * static_cast< ::rl::math::Real>(M_PI)); + q(i) = ::std::fmod(q(i), 2 * static_cast< ::rl::math::Real>(M_PI)); if (q(i) < this->joints[i]->min) { - q(i) += 2.0f * static_cast< ::rl::math::Real>(M_PI); + q(i) += 2 * static_cast< ::rl::math::Real>(M_PI); if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) { @@ -262,7 +262,7 @@ namespace rl } else if (q(i) > this->joints[i]->max) { - q(i) -= 2.0f * static_cast< ::rl::math::Real>(M_PI); + q(i) -= 2 * static_cast< ::rl::math::Real>(M_PI); if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) { @@ -277,7 +277,7 @@ namespace rl bool Puma::isSingular() const { - return (::std::abs(this->jacobian.determinant()) > 1.0e-9f) ? false : true ; + return (::std::abs(this->jacobian.determinant()) > static_cast< ::rl::math::Real>(1.0e-9)) ? false : true ; } void @@ -292,11 +292,11 @@ namespace rl myq(i) = q(i) + this->joints[i]->theta + this->joints[i]->offset; myq(i) = ::std::fmod( myq(i) + static_cast< ::rl::math::Real>(M_PI), - 2.0f * static_cast< ::rl::math::Real>(M_PI) + 2 * static_cast< ::rl::math::Real>(M_PI) ) - static_cast< ::rl::math::Real>(M_PI); } - if (myq(4) < 0.0f) + if (myq(4) < 0) { wrist = WRIST_FLIP; } @@ -321,11 +321,11 @@ namespace rl // y_2 component of wrist location ::rl::math::Real tmp2 = a3 * s3 + d4 * c3; - if (tmp < 0.0f) + if (tmp < 0) { arm = ARM_LEFT; - if (tmp2 < 0.0f) + if (tmp2 < 0) { elbow = ELBOW_BELOW; } @@ -338,7 +338,7 @@ namespace rl { arm = ARM_RIGHT; - if (tmp2 < 0.0f) + if (tmp2 < 0) { elbow = ELBOW_ABOVE; } diff --git a/src/rl/kin/Puma.h b/src/rl/kin/Puma.h index 738b6b2b..3d38649f 100644 --- a/src/rl/kin/Puma.h +++ b/src/rl/kin/Puma.h @@ -72,7 +72,7 @@ namespace rl ::rl::math::Vector& q, const ::std::size_t& leaf = 0, const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(), - const ::rl::math::Real& epsilon = 1.0e-3f, + const ::rl::math::Real& epsilon = static_cast< ::rl::math::Real>(1.0e-3), const ::std::size_t& iterations = 1000 ); @@ -92,19 +92,19 @@ namespace rl template T atan2(const T& y, const T& x) const { T a = ::std::atan2(y, x); - return (::std::abs(a) <= 1.0e-6f) ? 0.0f : a; + return (::std::abs(a) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : a; } template T cos(const T& x) const { T c = ::std::cos(x); - return (::std::abs(c) <= 1.0e-6f) ? 0.0f : c; + return (::std::abs(c) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : c; } template T sin(const T& x) const { T s = ::std::sin(x); - return (::std::abs(s) <= 1.0e-6f) ? 0.0f : s; + return (::std::abs(s) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : s; } Arm arm; diff --git a/src/rl/kin/Rhino.cpp b/src/rl/kin/Rhino.cpp index 51f06c2d..b46a38f3 100644 --- a/src/rl/kin/Rhino.cpp +++ b/src/rl/kin/Rhino.cpp @@ -125,14 +125,14 @@ namespace rl ::rl::math::Real sinAlpha = -pz0 / Q; ::rl::math::Real cosAlpha = -r * arm / Q; - ::rl::math::Real cosBeta = (Q_2 + a2_2 - a3_2) / (2.0f * a2 * Q); + ::rl::math::Real cosBeta = (Q_2 + a2_2 - a3_2) / (2 * a2 * Q); - if (::std::abs(cosBeta) > 1.0f) + if (::std::abs(cosBeta) > 1) { return false; } - ::rl::math::Real sinBeta = ::std::sqrt(1.0f - ::std::pow(cosBeta, 2)); + ::rl::math::Real sinBeta = ::std::sqrt(1 - ::std::pow(cosBeta, 2)); ::rl::math::Real s2 = sinAlpha * cosBeta + K * cosAlpha * sinBeta; ::rl::math::Real c2 = cosAlpha * cosBeta - K * sinAlpha * sinBeta; @@ -141,7 +141,7 @@ namespace rl ::rl::math::Real theta2 = this->atan2(s2, c2) + static_cast< ::rl::math::Real>(M_PI_2); ::rl::math::Real c3 = (a2_2 + a3_2 - Q_2) / (2 * a2 * a3); - ::rl::math::Real s3 = K * ::std::sqrt(1.0f - ::std::pow(c3, 2)); + ::rl::math::Real s3 = K * ::std::sqrt(1 - ::std::pow(c3, 2)); // elbow ::rl::math::Real theta3 = this->atan2(s3, c3) + static_cast< ::rl::math::Real>(M_PI); @@ -175,11 +175,11 @@ namespace rl for (::std::size_t i = 0; i < this->getDof(); ++i) { - q(i) = ::std::fmod(q(i), 2.0f * static_cast< ::rl::math::Real>(M_PI)); + q(i) = ::std::fmod(q(i), 2 * static_cast< ::rl::math::Real>(M_PI)); if (q(i) < this->joints[i]->min) { - q(i) += 2.0f * static_cast< ::rl::math::Real>(M_PI); + q(i) += 2 * static_cast< ::rl::math::Real>(M_PI); if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) { @@ -188,7 +188,7 @@ namespace rl } else if (q(i) > this->joints[i]->max) { - q(i) -= 2.0f * static_cast< ::rl::math::Real>(M_PI); + q(i) -= 2 * static_cast< ::rl::math::Real>(M_PI); if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) { @@ -217,11 +217,11 @@ namespace rl ::rl::math::Real tmp = s2 * a3 * c3 + c2 * a3 * s3 + a2 * s2; ::rl::math::Real tmp2 = a3 * s3; - if (tmp < 0.0f) + if (tmp < 0) { arm = ARM_RIGHT; - if (tmp2 < 0.0f) + if (tmp2 < 0) { elbow = ELBOW_ABOVE; } @@ -234,7 +234,7 @@ namespace rl { arm = ARM_LEFT; - if (tmp2 < 0.0f) + if (tmp2 < 0) { elbow = ELBOW_BELOW; } diff --git a/src/rl/kin/Rhino.h b/src/rl/kin/Rhino.h index f4162ce6..bb4cc9df 100644 --- a/src/rl/kin/Rhino.h +++ b/src/rl/kin/Rhino.h @@ -64,7 +64,7 @@ namespace rl ::rl::math::Vector& q, const ::std::size_t& leaf = 0, const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(), - const ::rl::math::Real& epsilon = 1.0e-3f, + const ::rl::math::Real& epsilon = static_cast< ::rl::math::Real>(1.0e-3), const ::std::size_t& iterations = 1000 ); @@ -80,19 +80,19 @@ namespace rl template T atan2(const T& y, const T& x) const { T a = ::std::atan2(y, x); - return (::std::abs(a) <= 1.0e-6f) ? 0.0f : a; + return (::std::abs(a) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : a; } template T cos(const T& x) const { T c = ::std::cos(x); - return (::std::abs(c) <= 1.0e-6f) ? 0.0f : c; + return (::std::abs(c) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : c; } template T sin(const T& x) const { T s = ::std::sin(x); - return (::std::abs(s) <= 1.0e-6f) ? 0.0f : s; + return (::std::abs(s) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : s; } Arm arm; diff --git a/src/rl/math/Function.h b/src/rl/math/Function.h index 56c20925..2bbc3fe8 100644 --- a/src/rl/math/Function.h +++ b/src/rl/math/Function.h @@ -107,7 +107,7 @@ namespace rl }; - static const Real FUNCTION_BOUNDARY = 1.0e-8f; + static const Real FUNCTION_BOUNDARY = static_cast(1.0e-8); } } diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index 761d9f7f..1e9ef9ce 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -149,7 +149,7 @@ static RandomOnCircle(const Scalar& rand) eigen_assert(rand >= Scalar(0)); eigen_assert(rand <= Scalar(1)); - Scalar theta = Scalar(2 * M_PI) * rand; + Scalar theta = Scalar(2) * Scalar(M_PI) * rand; return Matrix( cos(theta), @@ -190,9 +190,9 @@ static RandomOnSphere(const DenseBase& rand) eigen_assert(rand(1) >= Scalar(0)); eigen_assert(rand(1) <= Scalar(1)); - Scalar theta = Scalar(2 * M_PI) * rand(0); + Scalar theta = Scalar(2) * Scalar(M_PI) * rand(0); Scalar z = Scalar(2) * rand(1) - Scalar(1); - Scalar sqrt_1_z_2 = sqrt(1 - pow(z, 2)); + Scalar sqrt_1_z_2 = sqrt(Scalar(1) - pow(z, 2)); return Matrix( sqrt_1_z_2 * cos(theta), diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index 42235928..6777e7bf 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -132,7 +132,7 @@ namespace rl f.c[1] = yd0; f.c[2] = ydd0 / 2; f.c[3] = -(::std::pow(x1, 2) * ydd0 + 3 * x1 * yd0 + x1 * yd1 + 4 * y0 - 4 * y1) / ::std::pow(x1, 3); - f.c[4] = 0.5f * (::std::pow(x1, 2) * ydd0 + 4 * x1 * yd0 + 2 * x1 * yd1 + 6 * y0 - 6 * y1) / ::std::pow(x1, 4); + f.c[4] = static_cast(0.5) * (::std::pow(x1, 2) * ydd0 + 4 * x1 * yd0 + 2 * x1 * yd1 + 6 * y0 - 6 * y1) / ::std::pow(x1, 4); f.x1 = x1; return f; diff --git a/src/rl/math/PolynomialQuaternion.h b/src/rl/math/PolynomialQuaternion.h index 2eb879be..2f34e94d 100644 --- a/src/rl/math/PolynomialQuaternion.h +++ b/src/rl/math/PolynomialQuaternion.h @@ -257,7 +257,7 @@ namespace rl Real cosdtheta = ::std::cos(dtheta); Real sindtheta = ::std::sin(dtheta); - return e.dot(x) * e + 0.5f * (dtheta * sindtheta) / (1 - cosdtheta) * e.cross(x).cross(e) + 0.5f * dtheta * e.cross(x); + return e.dot(x) * e + static_cast(0.5) * (dtheta * sindtheta) / (1 - cosdtheta) * e.cross(x).cross(e) + static_cast(0.5) * dtheta * e.cross(x); } }; } diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 8f76f109..56f96c4e 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -96,8 +96,8 @@ static Quaternion Random(const MatrixBase& rand) Scalar sigma1 = sqrt(Scalar(1) - rand(0)); Scalar sigma2 = sqrt(rand(0)); - Scalar theta1 = Scalar(2 * M_PI) * rand(1); - Scalar theta2 = Scalar(2 * M_PI) * rand(2); + Scalar theta1 = Scalar(2) * Scalar(M_PI) * rand(1); + Scalar theta2 = Scalar(2) * Scalar(M_PI) * rand(2); return Quaternion( cos(theta2) * sigma2, diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 9d7f0963..3eed1651 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -1057,7 +1057,7 @@ namespace rl { // Useful positions and velocities to compute spline vLin(i) = (q1(i) - q0(i)) / (tAccMax + tLinMax); - qBeforeLin(i) = (q1(i) + q0(i)) / 2.0f - (tLinMax / 2.0f) * vLin(i); + qBeforeLin(i) = (q1(i) + q0(i)) / 2 - (tLinMax / 2) * vLin(i); aAcc(i) = vLin(i) / (tAccMax - tjFixed); vAfterJerk(i) = aAcc(i) * tjFixed / 2; xAfterJerk(i) = aAcc(i) * tjFixed * tjFixed / 6; diff --git a/src/rl/math/SplineQuaternion.h b/src/rl/math/SplineQuaternion.h index 9181c293..7e42fa40 100644 --- a/src/rl/math/SplineQuaternion.h +++ b/src/rl/math/SplineQuaternion.h @@ -140,7 +140,7 @@ namespace rl dOmega += (omega[i] - omegaprev[i]).norm(); } } - while (dOmega > 1.0e-6f); + while (dOmega > static_cast(1.0e-6)); omega[0] = yd0; omega[n - 1] = yd1; @@ -329,7 +329,7 @@ namespace rl Real cosdtheta = ::std::cos(dtheta); Real sindtheta = ::std::sin(dtheta); - return e.dot(x) * e + 0.5f * (dtheta * sindtheta) / (1 - cosdtheta) * e.cross(x).cross(e) + 0.5f * dtheta * e.cross(x); + return e.dot(x) * e + static_cast(0.5) * (dtheta * sindtheta) / (1 - cosdtheta) * e.cross(x).cross(e) + static_cast(0.5) * dtheta * e.cross(x); } static Vector3 R(const Vector3& e, const Real& dtheta, const Vector3& omega) @@ -342,7 +342,7 @@ namespace rl Real cosdtheta = ::std::cos(dtheta); Real sindtheta = ::std::sin(dtheta); - Real r0 = 0.5f * (dtheta - sindtheta) / (1 - cosdtheta); + Real r0 = static_cast(0.5) * (dtheta - sindtheta) / (1 - cosdtheta); Real r1 = (dtheta * sindtheta - 2 * (1 - cosdtheta)) / (dtheta * (1 - cosdtheta)); return r0 * (omega.dot(omega) - ::std::pow(e.dot(omega), 2)) * e + r1 * e.dot(omega) * e.cross(omega).cross(e); diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index a9986d6e..defa5c8d 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -77,10 +77,10 @@ fromDelta(const Transform& other, const Matrix& delta) { - (*this)(0, 0) = 0; + (*this)(0, 0) = Scalar(0); (*this)(0, 1) = -delta(5); (*this)(0, 2) = delta(4); (*this)(0, 3) = delta(0); (*this)(1, 0) = delta(5); - (*this)(1, 1) = 0; + (*this)(1, 1) = Scalar(0); (*this)(1, 2) = -delta(3); (*this)(1, 3) = delta(1); (*this)(2, 0) = -delta(4); (*this)(2, 1) = delta(3); - (*this)(2, 2) = 0; + (*this)(2, 2) = Scalar(0); (*this)(2, 3) = delta(2); - (*this)(3, 0) = 0; - (*this)(3, 1) = 0; - (*this)(3, 2) = 0; - (*this)(3, 3) = 1; + (*this)(3, 0) = Scalar(0); + (*this)(3, 1) = Scalar(0); + (*this)(3, 2) = Scalar(0); + (*this)(3, 3) = Scalar(1); } /** @@ -182,9 +182,9 @@ toDelta(const Transform& other, const bool& useAppro if (useApproximation) { - res(3) = ((*this)(1, 0) * other(2, 0) - (*this)(2, 0) * other(1, 0) + (*this)(1, 1) * other(2, 1) - (*this)(2, 1) * other(1, 1) + (*this)(1, 2) * other(2, 2) - (*this)(2, 2) * other(1, 2)) / 2.0f; - res(4) = ((*this)(2, 0) * other(0, 0) - (*this)(0, 0) * other(2, 0) + (*this)(2, 1) * other(0, 1) - (*this)(0, 1) * other(2, 1) + (*this)(2, 2) * other(0, 2) - (*this)(0, 2) * other(2, 2)) / 2.0f; - res(5) = ((*this)(0, 0) * other(1, 0) - (*this)(1, 0) * other(0, 0) + (*this)(0, 1) * other(1, 1) - (*this)(1, 1) * other(0, 1) + (*this)(0, 2) * other(1, 2) - (*this)(1, 2) * other(0, 2)) / 2.0f; + res(3) = ((*this)(1, 0) * other(2, 0) - (*this)(2, 0) * other(1, 0) + (*this)(1, 1) * other(2, 1) - (*this)(2, 1) * other(1, 1) + (*this)(1, 2) * other(2, 2) - (*this)(2, 2) * other(1, 2)) * Scalar(0.5); + res(4) = ((*this)(2, 0) * other(0, 0) - (*this)(0, 0) * other(2, 0) + (*this)(2, 1) * other(0, 1) - (*this)(0, 1) * other(2, 1) + (*this)(2, 2) * other(0, 2) - (*this)(0, 2) * other(2, 2)) * Scalar(0.5); + res(5) = ((*this)(0, 0) * other(1, 0) - (*this)(1, 0) * other(0, 0) + (*this)(0, 1) * other(1, 1) - (*this)(1, 1) * other(0, 1) + (*this)(0, 2) * other(1, 2) - (*this)(1, 2) * other(0, 2)) * Scalar(0.5); } else { diff --git a/src/rl/math/Unit.h b/src/rl/math/Unit.h index 160cc5a7..66007877 100644 --- a/src/rl/math/Unit.h +++ b/src/rl/math/Unit.h @@ -182,36 +182,36 @@ namespace rl UNIT_NEWTON_METER }; - static const Real DEG2RAD = static_cast(M_PI) / 180.0f; + static const Real DEG2RAD = static_cast(M_PI) / static_cast(180); - static const Real GIGA2UNIT = 1.0e+9f; + static const Real GIGA2UNIT = static_cast(1.0e+9); /** [m · s-2] */ - static const Real GRAVITY = 9.80665f; + static const Real GRAVITY = static_cast(9.80665); - static const Real KILO2UNIT = 1.0e+3f; + static const Real KILO2UNIT = static_cast(1.0e+3); - static const Real MEGA2UNIT = 1.0e+6f; + static const Real MEGA2UNIT = static_cast(1.0e+6); - static const Real MICRO2UNIT = 1.0e-6f; + static const Real MICRO2UNIT = static_cast(1.0e-6); - static const Real MILLI2UNIT = 1.0e-3f; + static const Real MILLI2UNIT = static_cast(1.0e-3); - static const Real NANO2UNIT = 1.0e-9f; + static const Real NANO2UNIT = static_cast(1.0e-9); - static const Real RAD2DEG = 180.0f / static_cast(M_PI); + static const Real RAD2DEG = static_cast(180) / static_cast(M_PI); - static const Real UNIT2GIGA = 1.0e-9f; + static const Real UNIT2GIGA = static_cast(1.0e-9); - static const Real UNIT2KILO = 1.0e-3f; + static const Real UNIT2KILO = static_cast(1.0e-3); - static const Real UNIT2MEGA = 1.0e-6f; + static const Real UNIT2MEGA = static_cast(1.0e-6); - static const Real UNIT2MICRO = 1.0e+6f; + static const Real UNIT2MICRO = static_cast(1.0e+6); - static const Real UNIT2MILLI = 1.0e+3f; + static const Real UNIT2MILLI = static_cast(1.0e+3); - static const Real UNIT2NANO = 1.0e+9f; + static const Real UNIT2NANO = static_cast(1.0e+9); } } diff --git a/src/rl/math/algorithm.h b/src/rl/math/algorithm.h index c35f568d..7917d9a8 100644 --- a/src/rl/math/algorithm.h +++ b/src/rl/math/algorithm.h @@ -40,11 +40,11 @@ namespace rl { if (arg < 0) { - return -::std::pow(-arg, static_cast(1.0 / 3.0)); + return -::std::pow(-arg, static_cast(1) / static_cast(3)); } else { - return ::std::pow(arg, static_cast(1.0 / 3.0)); + return ::std::pow(arg, static_cast(1) / static_cast(3)); } } diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index eff487d9..689501ba 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -35,7 +35,7 @@ namespace rl InverseKinematics(kinematic), delta(::std::numeric_limits< ::rl::math::Real>::infinity()), duration(::std::chrono::milliseconds(100)), - epsilon(1.0e-3f), + epsilon(static_cast< ::rl::math::Real>(1.0e-3)), iterations(1000), svd(true), transpose(false), diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index e8fc907e..71f9178d 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -280,7 +280,7 @@ namespace rl void Joint::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { - q = (1.0f - alpha) * q1 + alpha * q2; + q = (1 - alpha) * q1 + alpha * q2; } void diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index c04ce71d..85b73436 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -140,7 +140,7 @@ namespace rl ::Eigen::JacobiSVD< ::rl::math::Matrix> svd(J, ::Eigen::ComputeFullU | ::Eigen::ComputeFullV); ::rl::math::Real wMin = svd.singularValues().minCoeff(); - ::rl::math::Real lambdaSqr = wMin < 1.0e-9f ? (1 - ::std::pow((wMin / 1.0e-9f), 2)) * ::std::pow(lambda, 2) : 0; + ::rl::math::Real lambdaSqr = wMin < static_cast< ::rl::math::Real>(1.0e-9) ? (1 - ::std::pow((wMin / static_cast< ::rl::math::Real>(1.0e-9)), 2)) * ::std::pow(lambda, 2) : 0; for (::std::ptrdiff_t i = 0; i < svd.nonzeroSingularValues(); ++i) { diff --git a/src/rl/mdl/Kinematic.h b/src/rl/mdl/Kinematic.h index f8f9d4ee..96820396 100644 --- a/src/rl/mdl/Kinematic.h +++ b/src/rl/mdl/Kinematic.h @@ -109,7 +109,7 @@ namespace rl * @pre calculateJacobian() * @post getJacobianInverse() */ - void calculateJacobianInverse(const ::rl::math::Real& lambda = 0.0f, const bool& doSvd = true); + void calculateJacobianInverse(const ::rl::math::Real& lambda = 0, const bool& doSvd = true); /** * Calculate Jacobian matrix inverse. @@ -125,7 +125,7 @@ namespace rl * @pre setPosition() * @pre calculateJacobian() */ - void calculateJacobianInverse(const ::rl::math::Matrix& J, ::rl::math::Matrix& invJ, const ::rl::math::Real& lambda = 0.0f, const bool& doSvd = true) const; + void calculateJacobianInverse(const ::rl::math::Matrix& J, ::rl::math::Matrix& invJ, const ::rl::math::Real& lambda = 0, const bool& doSvd = true) const; /** * Calculate manipulability measure. diff --git a/src/rl/mdl/Metric.cpp b/src/rl/mdl/Metric.cpp index 37e8f725..779c9414 100644 --- a/src/rl/mdl/Metric.cpp +++ b/src/rl/mdl/Metric.cpp @@ -75,8 +75,8 @@ namespace rl { assert(q1.size() == this->getDofPosition()); assert(q2.size() == this->getDofPosition()); - assert(alpha >= 0.0f); - assert(alpha <= 1.0f); + assert(alpha >= 0); + assert(alpha <= 1); assert(q.size() == this->getDofPosition()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index b7715e5c..4f03ae96 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -35,11 +35,11 @@ namespace rl { NloptInverseKinematics::NloptInverseKinematics(Kinematic* kinematic) : InverseKinematics(kinematic), - delta(1.0e-8f), + delta(static_cast< ::rl::math::Real>(1.0e-8)), duration(::std::chrono::milliseconds(100)), - epsilonRotation(1.0e-6f), - epsilonTranslation(1.0e-6f), - tolerance(1.0e-8f), + epsilonRotation(static_cast< ::rl::math::Real>(1.0e-6)), + epsilonTranslation(static_cast< ::rl::math::Real>(1.0e-6)), + tolerance(static_cast< ::rl::math::Real>(1.0e-8)), randDistribution(0, 1), randEngine(::std::random_device()()) { diff --git a/src/rl/mdl/Revolute.cpp b/src/rl/mdl/Revolute.cpp index fc9a5200..702defee 100644 --- a/src/rl/mdl/Revolute.cpp +++ b/src/rl/mdl/Revolute.cpp @@ -75,11 +75,11 @@ namespace rl { if (q1(0) > q2(0)) { - q(0) = (1.0f - alpha) * q1(0) + alpha * (q2(0) + range); + q(0) = (1 - alpha) * q1(0) + alpha * (q2(0) + range); } else { - q(0) = (1.0f - alpha) * (q1(0) + range) + alpha * q2(0); + q(0) = (1 - alpha) * (q1(0) + range) + alpha * q2(0); } while (q(0) > this->max(0)) @@ -94,27 +94,27 @@ namespace rl } else { - q(0) = (1.0f - alpha) * q1(0) + alpha * q2(0); + q(0) = (1 - alpha) * q1(0) + alpha * q2(0); } } else { - q(0) = (1.0f - alpha) * q1(0) + alpha * q2(0); + q(0) = (1 - alpha) * q1(0) + alpha * q2(0); } } void Revolute::normalize(::rl::math::VectorRef q) const { - q(0) = ::std::fmod(q(0), 2.0f * static_cast< ::rl::math::Real>(M_PI)); + q(0) = ::std::fmod(q(0), 2 * static_cast< ::rl::math::Real>(M_PI)); if (q(0) < this->min(0)) { - q(0) += 2.0f * static_cast< ::rl::math::Real>(M_PI); + q(0) += 2 * static_cast< ::rl::math::Real>(M_PI); } else if (q(0) > this->max(0)) { - q(0) -= 2.0f * static_cast< ::rl::math::Real>(M_PI); + q(0) -= 2 * static_cast< ::rl::math::Real>(M_PI); } } diff --git a/src/rl/mdl/RungeKuttaNystromIntegrator.cpp b/src/rl/mdl/RungeKuttaNystromIntegrator.cpp index 108e5380..cf9193e8 100644 --- a/src/rl/mdl/RungeKuttaNystromIntegrator.cpp +++ b/src/rl/mdl/RungeKuttaNystromIntegrator.cpp @@ -89,7 +89,7 @@ namespace rl // y_0 + dy_0 * dt + dt / 3 * (k_1 + k_2 + k_3) y = y0 + dy0 * dt + dt / 3 * (k1 + k2 + k3); // dy_0 + 1 / 3 * (k_1 + 2 * k_2 + 2 * k_3 + k_4) - dy = dy0 + 1.0f / 3.0f * (k1 + 2 * k2 + 2 * k3 + k4); + dy = dy0 + static_cast< ::rl::math::Real>(1) / static_cast< ::rl::math::Real>(3) * (k1 + 2 * k2 + 2 * k3 + k4); this->dynamic->setPosition(y); this->dynamic->setVelocity(dy); diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index 8987ab12..d9d60b48 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -132,7 +132,7 @@ namespace rl void SixDof::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { - q.head<3>() = (1.0f - alpha) * q1.head<3>() + alpha * q2.head<3>(); + q.head<3>() = (1 - alpha) * q1.head<3>() + alpha * q2.head<3>(); ::Eigen::Map quaternion1(q1.tail<4>().data()); ::Eigen::Map quaternion2(q2.tail<4>().data()); q.tail<4>() = quaternion1.slerp(alpha, quaternion2).coeffs(); @@ -149,7 +149,7 @@ namespace rl } } - return ::Eigen::internal::isApprox(q.tail<4>().norm(), static_cast< ::rl::math::Real>(1), 1.0e-3f); + return ::Eigen::internal::isApprox(q.tail<4>().norm(), static_cast< ::rl::math::Real>(1), static_cast< ::rl::math::Real>(1.0e-3)); } void diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 6bcbe884..3f95b523 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -105,7 +105,7 @@ namespace rl bool Spherical::isValid(const ::rl::math::ConstVectorRef& q) const { - return ::Eigen::internal::isApprox(q.norm(), static_cast< ::rl::math::Real>(1), 1.0e-3f); + return ::Eigen::internal::isApprox(q.norm(), static_cast< ::rl::math::Real>(1), static_cast< ::rl::math::Real>(1.0e-3)); } void diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index beb252dc..492e16c8 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -284,8 +284,8 @@ ::std::cout << "\tname: " << p->getName() << ::std::endl; if ("continuous" == path.eval("string(@type)").getValue< ::std::string>()) { - r->max(0) = 180.0f * ::rl::math::DEG2RAD; - r->min(0) = -180.0f * ::rl::math::DEG2RAD; + r->max(0) = 180 * ::rl::math::DEG2RAD; + r->min(0) = -180 * ::rl::math::DEG2RAD; r->wraparound(0) = true; } else diff --git a/src/rl/plan/AddRrtConCon.cpp b/src/rl/plan/AddRrtConCon.cpp index 4dffa0c1..be5cad0d 100644 --- a/src/rl/plan/AddRrtConCon.cpp +++ b/src/rl/plan/AddRrtConCon.cpp @@ -34,9 +34,9 @@ namespace rl { AddRrtConCon::AddRrtConCon() : RrtConCon(), - alpha(0.05f), - lower(2.0f), - radius(20.0f) + alpha(static_cast< ::rl::math::Real>(0.05)), + lower(2), + radius(20) { } @@ -109,7 +109,7 @@ namespace rl { if (get(*a, aNearest.second)->radius < ::std::numeric_limits< ::rl::math::Real>::max()) { - get(*a, aNearest.second)->radius *= (1.0f + this->alpha); + get(*a, aNearest.second)->radius *= (1 + this->alpha); } Neighbor bNearest = this->nearest(*b, chosen); @@ -129,7 +129,7 @@ namespace rl { if (get(*a, aNearest.second)->radius < ::std::numeric_limits< ::rl::math::Real>::max()) { - get(*a, aNearest.second)->radius *= (1.0f - this->alpha); + get(*a, aNearest.second)->radius *= (1 - this->alpha); get(*a, aNearest.second)->radius = ::std::max(this->lower, get(*a, aNearest.second)->radius); } else diff --git a/src/rl/plan/AdvancedOptimizer.cpp b/src/rl/plan/AdvancedOptimizer.cpp index 71003e4d..9f492403 100644 --- a/src/rl/plan/AdvancedOptimizer.cpp +++ b/src/rl/plan/AdvancedOptimizer.cpp @@ -35,8 +35,8 @@ namespace rl { AdvancedOptimizer::AdvancedOptimizer() : SimpleOptimizer(), - length(1.0f), - ratio(0.1f) + length(1), + ratio(static_cast< ::rl::math::Real>(0.1)) { } @@ -117,7 +117,7 @@ namespace rl { if (this->model->distance(*i, *j) > this->length) { - this->model->interpolate(*i, *j, 0.5f, inter); + this->model->interpolate(*i, *j, static_cast< ::rl::math::Real>(0.5), inter); j = path.insert(j, inter); diff --git a/src/rl/plan/BridgeSampler.cpp b/src/rl/plan/BridgeSampler.cpp index 4a18d9ca..a50b738a 100644 --- a/src/rl/plan/BridgeSampler.cpp +++ b/src/rl/plan/BridgeSampler.cpp @@ -33,7 +33,7 @@ namespace rl { BridgeSampler::BridgeSampler() : GaussianSampler(), - ratio(5.0f / 6.0f) + ratio(static_cast< ::rl::math::Real>(5) / static_cast< ::rl::math::Real>(6)) { } @@ -71,7 +71,7 @@ namespace rl if (this->model->isColliding()) { - this->model->interpolate(q2, q3, 0.5f, q); + this->model->interpolate(q2, q3, static_cast< ::rl::math::Real>(0.5), q); this->model->setPosition(q); this->model->updateFrames(); diff --git a/src/rl/plan/Eet.cpp b/src/rl/plan/Eet.cpp index 267ab438..39672dc8 100644 --- a/src/rl/plan/Eet.cpp +++ b/src/rl/plan/Eet.cpp @@ -52,14 +52,14 @@ namespace rl { Eet::Eet() : RrtCon(), - alpha(0.01f), + alpha(static_cast< ::rl::math::Real>(0.01)), alternativeDistanceComputation(false), beta(0), - distanceWeight(0.1f), + distanceWeight(static_cast< ::rl::math::Real>(0.1)), explorers(), explorersSetup(), - gamma(1.0f / 3.0f), - goalEpsilon(0.1f), + gamma(static_cast< ::rl::math::Real>(1) / static_cast< ::rl::math::Real>(3)), + goalEpsilon(static_cast< ::rl::math::Real>(0.1)), goalEpsilonUseOrientation(false), max(::rl::math::Vector3::Zero()), min(::rl::math::Vector3::Zero()), @@ -201,7 +201,7 @@ namespace rl this->model->step(*nearest->q, qdot, *expanded.q); - if (this->model->getManipulabilityMeasure() < 1.0e-3f) // within singularity + if (this->model->getManipulabilityMeasure() < static_cast< ::rl::math::Real>(1.0e-3)) // within singularity { *expanded.q = this->sampler->generate(); // uniform sampling for singularities ::rl::math::Real tmp = this->model->distance(*nearest->q, *expanded.q); @@ -412,11 +412,11 @@ namespace rl while ((::std::chrono::steady_clock::now() - this->time) < this->duration) // search until goal reached { - if (sigma < 1.0f) // sample is within current sphere + if (sigma < 1) // sample is within current sphere { Neighbor nearest; - if (path.end() == i + 1 && this->rand() < 0.5f) // within last sphere + if (path.end() == i + 1 && this->rand() < static_cast< ::rl::math::Real>(0.5)) // within last sphere { chosen = goal; // select goal position and orientation nearest = this->nearest(this->tree[0], chosen); // nearest vertex in tree @@ -479,8 +479,8 @@ namespace rl } } - sigma *= 1.0f - this->alpha; // increase exploitation - sigma = ::std::max(static_cast< ::rl::math::Real>(0.1f), sigma); + sigma *= 1 - this->alpha; // increase exploitation + sigma = ::std::max(static_cast< ::rl::math::Real>(0.1), sigma); for (WorkspaceSphereVector::reverse_iterator k = ++path.rbegin(); k.base() != i; ++k) // search spheres backwards { @@ -494,7 +494,7 @@ namespace rl } else // expansion unsuccessful { - sigma *= 1.0f + this->alpha; // decrease exploitation + sigma *= 1 + this->alpha; // decrease exploitation } } else // perform backtracking to previous sphere diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 4b482fdd..7bdb7466 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -121,7 +121,7 @@ namespace rl virtual void updateJacobian(); - virtual void updateJacobianInverse(const ::rl::math::Real& lambda = 0.0f, const bool& doSvd = true); + virtual void updateJacobianInverse(const ::rl::math::Real& lambda = 0, const bool& doSvd = true); ::rl::kin::Kinematics* kin; diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index ad32f1fc..192ae744 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -61,7 +61,7 @@ namespace rl { Sample sample(this->model->getDofPosition()); Sample bestSample(this->model->getDofPosition()); - ::rl::math::Real pBest = -1.0f; + ::rl::math::Real pBest = -1; // From numSamples samples, get the one with the best probability for being free. for (::std::size_t j = 0; j < this->numSamples; ++j) @@ -81,7 +81,7 @@ namespace rl } #else // This works better in our examples. Here we define entropy by using samples where we are unsure, if they are colliding. - if (::std::fabs(pFree - 0.5f) < ::std::fabs(pBest - 0.5f)) + if (::std::fabs(pFree - static_cast< ::rl::math::Real>(0.5)) < ::std::fabs(pBest - static_cast< ::rl::math::Real>(0.5))) { pBest = pFree; bestSample = sample; @@ -116,7 +116,7 @@ namespace rl #else // here we always pick a component containing the beginning or end vertex // this prevents roadmap building in remote areas. - ::std::size_t randIndex1 = static_cast< ::std::size_t>(::std::floor(this->rand() * 2.0f)); + ::std::size_t randIndex1 = static_cast< ::std::size_t>(::std::floor(this->rand() * 2)); #endif ::std::size_t randIndex2 = static_cast< ::std::size_t>(::std::floor(this->rand() * this->getNumVertices())); @@ -140,12 +140,12 @@ namespace rl while (boost::same_component(sample1, sample2, this->ds)); // The point in the middle of the two samples. - ::rl::math::Vector midPoint = 0.5f * (*this->graph[sample1].q + *this->graph[sample2].q); + ::rl::math::Vector midPoint = static_cast< ::rl::math::Real>(0.5) * (*this->graph[sample1].q + *this->graph[sample2].q); // add variance drawn randomly from [-variance, variance] to the point for (::std::ptrdiff_t i = 0; i < midPoint.size(); ++i) { - q[i] = midPoint[i] + (2.0f * this->rand() - 1.0f) * this->variance; + q[i] = midPoint[i] + (2 * this->rand() - 1) * this->variance; } } @@ -179,7 +179,7 @@ namespace rl queue.pop(); } - return 1.0f - static_cast< ::rl::math::Real>(collisionCount) / static_cast< ::rl::math::Real>(count); + return 1 - static_cast< ::rl::math::Real>(collisionCount) / static_cast< ::rl::math::Real>(count); } ::std::string diff --git a/src/rl/plan/Rrt.cpp b/src/rl/plan/Rrt.cpp index bc25f780..4e0f7439 100644 --- a/src/rl/plan/Rrt.cpp +++ b/src/rl/plan/Rrt.cpp @@ -35,8 +35,8 @@ namespace rl { Rrt::Rrt(const ::std::size_t& trees) : Planner(), - delta(1.0f), - epsilon(1.0e-3f), + delta(1), + epsilon(static_cast< ::rl::math::Real>(1.0e-3)), sampler(nullptr), begin(trees, nullptr), end(trees, nullptr), diff --git a/src/rl/plan/RrtGoalBias.cpp b/src/rl/plan/RrtGoalBias.cpp index 82aa7d9a..1224a832 100644 --- a/src/rl/plan/RrtGoalBias.cpp +++ b/src/rl/plan/RrtGoalBias.cpp @@ -35,7 +35,7 @@ namespace rl { RrtGoalBias::RrtGoalBias() : Rrt(), - probability(0.05f), + probability(static_cast< ::rl::math::Real>(0.05)), randDistribution(0, 1), randEngine(::std::random_device()()) { diff --git a/src/rl/plan/Verifier.cpp b/src/rl/plan/Verifier.cpp index 9cf47481..16776e53 100644 --- a/src/rl/plan/Verifier.cpp +++ b/src/rl/plan/Verifier.cpp @@ -31,7 +31,7 @@ namespace rl namespace plan { Verifier::Verifier() : - delta(1.0f), + delta(1), model(nullptr) { } diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index c004e72f..aefe6d97 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -40,7 +40,7 @@ namespace rl goal(), greedy(GREEDY_SPACE), model(nullptr), - radius(0.0f), + radius(0), range(::std::numeric_limits< ::rl::math::Real>::max()), samples(10), start(), @@ -186,7 +186,7 @@ namespace rl sphere.priority = (*this->goal - *sphere.center).norm() - sphere.radius + top.radiusSum; break; case GREEDY_SPACE: - sphere.priority = 1.0f / sphere.radius; + sphere.priority = 1 / sphere.radius; break; default: break; diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 0a1735d5..28b1cf62 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -128,7 +128,7 @@ ::std::cout << "\trgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " ::boost::lexical_cast< ::rl::math::Real>(rgba[2]) ); vrmlMaterial->transparency.setValue( - 1.0f - ::boost::lexical_cast< ::rl::math::Real>(rgba[3]) + 1 - ::boost::lexical_cast< ::rl::math::Real>(rgba[3]) ); name2material[path.eval("string(@name)").getValue< ::std::string>()] = vrmlMaterial; @@ -244,7 +244,7 @@ ::std::cout << "\tmaterial rgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2 ::boost::lexical_cast< ::rl::math::Real>(rgba[2]) ); vrmlMaterial->transparency.setValue( - 1.0f - ::boost::lexical_cast< ::rl::math::Real>(rgba[3]) + 1 - ::boost::lexical_cast< ::rl::math::Real>(rgba[3]) ); vrmlAppearance->material = vrmlMaterial; @@ -402,7 +402,7 @@ ::std::cout << "\torigin rpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << : if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLCylinder::getClassTypeId())) { - origin *= ::rl::math::AngleAxis(90.0f * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX()); + origin *= ::rl::math::AngleAxis(90 * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX()); } if (path.eval("count(origin/@xyz) > 0").getValue()) diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp index 6b4e1efb..52d3ae06 100644 --- a/src/rl/sg/XmlFactory.cpp +++ b/src/rl/sg/XmlFactory.cpp @@ -154,7 +154,7 @@ namespace rl for (int l = 0; l < 3; ++l) { - if (::std::abs(bodyScaleFactor[l] - 1.0f) > 1.0e-6f) + if (::std::abs(bodyScaleFactor[l] - 1) > static_cast< ::rl::math::Real>(1.0e-6)) { throw Exception("rl::sg::XmlFactory::load() - bodyScaleFactor not supported"); } @@ -218,7 +218,7 @@ namespace rl for (int m = 0; m < 3; ++m) { - if (::std::abs(shapeScaleFactor[m] - 1.0f) > 1.0e-6f) + if (::std::abs(shapeScaleFactor[m] - 1) > static_cast< ::rl::math::Real>(1.0e-6)) { throw Exception("rl::sg::XmlFactory::load() - shapeScaleFactor not supported"); } diff --git a/src/rl/sg/ode/Body.cpp b/src/rl/sg/ode/Body.cpp index 5de735c3..bec1bca5 100644 --- a/src/rl/sg/ode/Body.cpp +++ b/src/rl/sg/ode/Body.cpp @@ -102,9 +102,9 @@ namespace rl } } - rotation[3] = 0.0f; - rotation[7] = 0.0f; - rotation[11] = 0.0f; + rotation[3] = 0; + rotation[7] = 0; + rotation[11] = 0; ::dBodySetRotation(this->body, rotation); } diff --git a/src/rl/sg/ode/Shape.cpp b/src/rl/sg/ode/Shape.cpp index be28fe74..006c5a19 100644 --- a/src/rl/sg/ode/Shape.cpp +++ b/src/rl/sg/ode/Shape.cpp @@ -180,9 +180,9 @@ namespace rl } } - rotation[3] = 0.0f; - rotation[7] = 0.0f; - rotation[11] = 0.0f; + rotation[3] = 0; + rotation[7] = 0; + rotation[11] = 0; ::dGeomSetOffsetRotation(this->geom, rotation); } diff --git a/src/rl/sg/pqp/Scene.cpp b/src/rl/sg/pqp/Scene.cpp index 7ec10b58..6b920dff 100644 --- a/src/rl/sg/pqp/Scene.cpp +++ b/src/rl/sg/pqp/Scene.cpp @@ -117,7 +117,7 @@ namespace rl { Shape* shape1 = static_cast(shape); - ::rl::math::Real p[3] = {0.0f, 0.0f, 0.0f}; + ::rl::math::Real p[3] = {0, 0, 0}; ::PQP_Model model; model.BeginModel(1); @@ -125,9 +125,9 @@ namespace rl model.EndModel(); PQP_REAL rotation[3][3] = { - {1.0f, 0.0f, 0.0f}, - {0.0f, 1.0f, 0.0f}, - {0.0f, 0.0f, 1.0f} + {1, 0, 0}, + {0, 1, 0}, + {0, 0, 1} }; PQP_REAL translation[3] = {point(0), point(1), point(2)}; diff --git a/tests/rlEetTest/rlEetTest.cpp b/tests/rlEetTest/rlEetTest.cpp index 6e18e12f..a88114d8 100644 --- a/tests/rlEetTest/rlEetTest.cpp +++ b/tests/rlEetTest/rlEetTest.cpp @@ -152,17 +152,17 @@ main(int argc, char** argv) explorerSetup.startConfiguration = &start; explorerSetup.startFrame = -1; - planner.alpha = 0.01f; + planner.alpha = static_cast(0.01); planner.alternativeDistanceComputation = false; planner.beta = 0; - planner.delta = 1.0f * rl::math::DEG2RAD; - planner.distanceWeight = 0.1f; - planner.epsilon = 1.0e-9f; + planner.delta = 1 * rl::math::DEG2RAD; + planner.distanceWeight = static_cast(0.1); + planner.epsilon = static_cast(1.0e-9); planner.explorers.push_back(&explorer); planner.explorersSetup.push_back(explorerSetup); - planner.gamma = 1.0f / 3.0f; + planner.gamma = static_cast(1) / static_cast(3); planner.goal = &goal; - planner.goalEpsilon = 0.1f; + planner.goalEpsilon = static_cast(0.1); planner.goalEpsilonUseOrientation = false; planner.max.x() = 30; planner.max.y() = 30; diff --git a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp index ad296776..eb9ee2b2 100644 --- a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp +++ b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp @@ -72,7 +72,7 @@ main(int argc, char** argv) rl::mdl::NloptInverseKinematics ik(kinematics); #else rl::mdl::JacobianInverseKinematics ik(kinematics); - ik.delta = 0.5f; + ik.delta = static_cast(0.5); #endif for (n = 0, wrongs = 0, wrongT = 0, ngotinverse = 0; n < nTests && wrongT < 100 && wrongs < 100; ++n) diff --git a/tests/rlPrmTest/rlPrmTest.cpp b/tests/rlPrmTest/rlPrmTest.cpp index 153d6edc..dfb32769 100644 --- a/tests/rlPrmTest/rlPrmTest.cpp +++ b/tests/rlPrmTest/rlPrmTest.cpp @@ -142,7 +142,7 @@ main(int argc, char** argv) sampler.model = &model; - verifier.delta = 1.0f * rl::math::DEG2RAD; + verifier.delta = 1 * rl::math::DEG2RAD; verifier.model = &model; rl::math::Vector start(kinematics->getDof()); diff --git a/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp b/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp index 79bef654..6583be69 100644 --- a/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp +++ b/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp @@ -94,8 +94,8 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } - rl::math::Vector6 v5 = v1 * 1.23f; - rl::math::ForceVector fv5 = fv1 * 1.23f; + rl::math::Vector6 v5 = v1 * static_cast(1.23); + rl::math::ForceVector fv5 = fv1 * static_cast(1.23); if (!fv5.matrix().isApprox(v5)) { @@ -105,8 +105,8 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } - rl::math::Vector6 v6 = v1 / 1.23f; - rl::math::ForceVector fv6 = fv1 / 1.23f; + rl::math::Vector6 v6 = v1 / static_cast(1.23); + rl::math::ForceVector fv6 = fv1 / static_cast(1.23); if (!fv6.matrix().isApprox(v6)) { diff --git a/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp b/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp index e684d8e5..b43431f4 100644 --- a/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp +++ b/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp @@ -94,8 +94,8 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } - rl::math::Vector6 v5 = v1 * 1.23f; - rl::math::MotionVector mv5 = mv1 * 1.23f; + rl::math::Vector6 v5 = v1 * static_cast(1.23); + rl::math::MotionVector mv5 = mv1 * static_cast(1.23); if (!mv5.matrix().isApprox(v5)) { @@ -105,8 +105,8 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } - rl::math::Vector6 v6 = v1 / 1.23f; - rl::math::MotionVector mv6 = mv1 / 1.23f; + rl::math::Vector6 v6 = v1 / static_cast(1.23); + rl::math::MotionVector mv6 = mv1 / static_cast(1.23); if (!mv6.matrix().isApprox(v6)) { diff --git a/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp b/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp index 732e51b1..addb4042 100644 --- a/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp +++ b/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp @@ -149,9 +149,9 @@ main(int argc, char** argv) rl::math::ArrayX maxAcc = f.derivative().derivative().getAbsoluteMaximum(); rl::math::ArrayX maxJerk = f.derivative().derivative().derivative().getAbsoluteMaximum(); - if ((maxVel / vmax > 1.001f).any() || - (maxAcc / amax > 1.001f).any() || - (maxJerk / jmax > 1.001f).any()) + if ((maxVel / vmax > static_cast(1.001)).any() || + (maxAcc / amax > static_cast(1.001)).any() || + (maxJerk / jmax > static_cast(1.001)).any()) { std::cerr << "rlTrapeziodalAccelerationTest must not exceed given bounds (by more than 1e-3)." << std::endl; std::cout << "Time: " << f.duration() << std::endl; From 35280288c0b61ce3a1a5ba8a819ea9437b88ce90 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Oct 2018 21:29:25 +0200 Subject: [PATCH 170/546] Fix TransformAddons.h template parameters --- src/rl/math/TransformAddons.h | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index defa5c8d..7f411de6 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -31,10 +31,10 @@ namespace Eigen { template class Transform { #endif -template +template inline Scalar -distance(const Transform& other, const Scalar& weight = 1) const +distance(const Transform& other, const OtherScalar2& weight = 1) const { using ::std::pow; using ::std::sqrt; @@ -58,10 +58,10 @@ distance(const Transform& other, const Scalar& weigh * rotations larger than 90 degrees, this approximation would be * completely wrong. */ -template +template inline void -fromDelta(const Transform& other, const Matrix& delta, const bool& useApproximation = false) +fromDelta(const Transform& other, const Matrix& delta, const bool& useApproximation = false) { if (useApproximation) { @@ -91,9 +91,10 @@ fromDelta(const Transform& other, const Matrix inline void -fromDenavitHartenbergPaul(const Scalar& d, const Scalar& theta, const Scalar& a, const Scalar& alpha) +fromDenavitHartenbergPaul(const OtherScalar& d, const OtherScalar& theta, const OtherScalar& a, const OtherScalar& alpha) { using ::std::cos; using ::std::sin; @@ -137,10 +138,10 @@ getDelta() const return res; } -template +template inline void -setDelta(const Matrix& delta) +setDelta(const Matrix& delta) { (*this)(0, 0) = Scalar(0); (*this)(0, 1) = -delta(5); @@ -169,10 +170,10 @@ setDelta(const Matrix& delta) * vector will be accurate up to 1e-9.) For rotations larger than 90 * degrees, this approximation would be completely wrong. */ -template +template inline Matrix -toDelta(const Transform& other, const bool& useApproximation = false) const +toDelta(const Transform& other, const bool& useApproximation = false) const { Matrix res; @@ -195,9 +196,10 @@ toDelta(const Transform& other, const bool& useAppro return res; } +template inline void -toDenavitHartenbergPaul(Scalar& d, Scalar& theta, Scalar& a, Scalar& alpha) const +toDenavitHartenbergPaul(OtherScalar& d, OtherScalar& theta, OtherScalar& a, OtherScalar& alpha) const { using ::std::abs; using ::std::atan2; From 3363010f717db23521234c38e4eb9f1bdbaf63b9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 14:07:18 +0100 Subject: [PATCH 171/546] Minor fix --- src/rl/plan/PrmUtilityGuided.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index 192ae744..75795146 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -137,7 +137,7 @@ namespace rl sample2 = ::boost::vertex(randIndex2, this->graph); // The two vertices have to be from two unconnected components. } - while (boost::same_component(sample1, sample2, this->ds)); + while (::boost::same_component(sample1, sample2, this->ds)); // The point in the middle of the two samples. ::rl::math::Vector midPoint = static_cast< ::rl::math::Real>(0.5) * (*this->graph[sample1].q + *this->graph[sample2].q); From 602aacfceded699e7dcbe4a4fc96542cf8ee4b49 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 15:22:48 +0100 Subject: [PATCH 172/546] Fix RobotiqModelC::Exception::~Exception() declaration --- src/rl/hal/RobotiqModelC.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/hal/RobotiqModelC.cpp b/src/rl/hal/RobotiqModelC.cpp index d99bfe2e..be26181f 100644 --- a/src/rl/hal/RobotiqModelC.cpp +++ b/src/rl/hal/RobotiqModelC.cpp @@ -333,7 +333,7 @@ namespace rl { } - RobotiqModelC::Exception::~Exception() + RobotiqModelC::Exception::~Exception() throw() { } From 9fb1759e834eb657b065cffc987f519157097caf Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 15:55:42 +0100 Subject: [PATCH 173/546] Support old Coin versions without toString() function --- extras/wrlview/MainWindow.cpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 03eee6a1..1e328030 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -194,8 +194,15 @@ void MainWindow::copyCameraValues() { QApplication::clipboard()->setText( - "position " + QString(this->viewer->getCamera()->position.getValue().toString().getString()) + "\n" + - "orientation " + QString(this->viewer->getCamera()->orientation.getValue().toString().getString()) + "\n" + + "position " + + QString::number(this->viewer->getCamera()->position.getValue()[0]) + " " + + QString::number(this->viewer->getCamera()->position.getValue()[1]) + " " + + QString::number(this->viewer->getCamera()->position.getValue()[2]) + "\n" + + "orientation " + + QString::number(this->viewer->getCamera()->orientation.getValue().getValue()[0]) + " " + + QString::number(this->viewer->getCamera()->orientation.getValue().getValue()[1]) + " " + + QString::number(this->viewer->getCamera()->orientation.getValue().getValue()[2]) + " " + + QString::number(this->viewer->getCamera()->orientation.getValue().getValue()[3]) + "\n" + "focalDistance " + QString::number(this->viewer->getCamera()->focalDistance.getValue()) + "\n" + ( SoPerspectiveCamera::getClassTypeId() == this->viewer->getCameraType() ? From 155a2a5f54641d235732facbe3cc7e4d837b6975 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 16:07:37 +0100 Subject: [PATCH 174/546] Fix unknown-pragmas warning --- src/rl/math/GnatNearestNeighbors.h | 8 ++++++-- src/rl/math/LinearNearestNeighbors.h | 6 +++++- 2 files changed, 11 insertions(+), 3 deletions(-) diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index 041ee803..d3877a41 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -667,10 +667,14 @@ namespace rl node.data.clear(); node.data.shrink_to_fit(); - + +#ifdef _OPENMP #pragma omp parallel for if (size > 2 * this->nodeDataMax) -#if defined(_OPENMP) && _OPENMP < 200805 +#if _OPENMP < 200805 for (::std::ptrdiff_t i = 0; i < node.children.size(); ++i) +#else + for (::std::size_t i = 0; i < node.children.size(); ++i) +#endif #else for (::std::size_t i = 0; i < node.children.size(); ++i) #endif diff --git a/src/rl/math/LinearNearestNeighbors.h b/src/rl/math/LinearNearestNeighbors.h index acf500e2..d07534a2 100644 --- a/src/rl/math/LinearNearestNeighbors.h +++ b/src/rl/math/LinearNearestNeighbors.h @@ -251,9 +251,13 @@ namespace rl ::std::vector distances(this->container.size()); +#ifdef _OPENMP #pragma omp parallel for -#if defined(_OPENMP) && _OPENMP < 200805 +#if _OPENMP < 200805 for (::std::ptrdiff_t i = 0; i < this->container.size(); ++i) +#else + for (::std::size_t i = 0; i < this->container.size(); ++i) +#endif #else for (::std::size_t i = 0; i < this->container.size(); ++i) #endif From 6ca263b0149567ecfba8195426d295beea4f7fa2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Oct 2018 16:14:39 +0100 Subject: [PATCH 175/546] Remove unused variable --- src/rl/math/GnatNearestNeighbors.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index d3877a41..7facabcd 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -663,8 +663,6 @@ namespace rl } } - ::std::size_t size = node.data.size(); - node.data.clear(); node.data.shrink_to_fit(); From d96c8b4cfdbed8ad81015f1879c27d0a79d18688 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 31 Oct 2018 11:50:34 +0100 Subject: [PATCH 176/546] Update TransformAddons.h template parameters --- src/rl/math/TransformAddons.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index 7f411de6..28a19d26 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -91,10 +91,10 @@ fromDelta(const Transform& othe } } -template +template inline void -fromDenavitHartenbergPaul(const OtherScalar& d, const OtherScalar& theta, const OtherScalar& a, const OtherScalar& alpha) +fromDenavitHartenbergPaul(const OtherScalar1& d, const OtherScalar2& theta, const OtherScalar3& a, const OtherScalar4& alpha) { using ::std::cos; using ::std::sin; @@ -196,10 +196,10 @@ toDelta(const Transform& other, return res; } -template +template inline void -toDenavitHartenbergPaul(OtherScalar& d, OtherScalar& theta, OtherScalar& a, OtherScalar& alpha) const +toDenavitHartenbergPaul(OtherScalar1& d, OtherScalar2& theta, OtherScalar3& a, OtherScalar4& alpha) const { using ::std::abs; using ::std::atan2; From 597c5b9bf7578713e38107c16eb4855867677e39 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 19 Feb 2019 16:32:33 +0100 Subject: [PATCH 177/546] Remove trailing whitespace --- src/rl/hal/MitsubishiR3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/hal/MitsubishiR3.cpp b/src/rl/hal/MitsubishiR3.cpp index c14a26ad..ba1cf427 100644 --- a/src/rl/hal/MitsubishiR3.cpp +++ b/src/rl/hal/MitsubishiR3.cpp @@ -27,7 +27,7 @@ #include #include #include -#include +#include #include "MitsubishiR3.h" From 72fc89c4bde877f1096e665725f2fc9306e0829e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 27 Feb 2019 17:52:04 +0100 Subject: [PATCH 178/546] Minor fix --- src/rl/plan/RrtDual.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/plan/RrtDual.cpp b/src/rl/plan/RrtDual.cpp index 4c9da13d..95a9d82c 100644 --- a/src/rl/plan/RrtDual.cpp +++ b/src/rl/plan/RrtDual.cpp @@ -69,7 +69,7 @@ namespace rl i = ::boost::source(*::boost::in_edges(i, this->tree[1]).first, this->tree[1]); } - path.push_back(*this->tree[1][i]->q); + path.push_back(*get(this->tree[1], i)->q); return path; } From c02d15a708a957d4e7d260cc6eb7cd0666c881d6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 27 Feb 2019 17:52:17 +0100 Subject: [PATCH 179/546] Update Rrt::getPath and RrtDual::getPath to support multiple root vertices --- src/rl/plan/Rrt.cpp | 2 +- src/rl/plan/RrtDual.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rl/plan/Rrt.cpp b/src/rl/plan/Rrt.cpp index 4e0f7439..c57c007d 100644 --- a/src/rl/plan/Rrt.cpp +++ b/src/rl/plan/Rrt.cpp @@ -243,7 +243,7 @@ namespace rl Vertex i = this->end[0]; - while (i != this->begin[0]) + while (::boost::in_degree(i, this->tree[0]) > 0) { path.push_front(*get(this->tree[0], i)->q); i = ::boost::source(*::boost::in_edges(i, this->tree[0]).first, this->tree[0]); diff --git a/src/rl/plan/RrtDual.cpp b/src/rl/plan/RrtDual.cpp index 95a9d82c..b21d4904 100644 --- a/src/rl/plan/RrtDual.cpp +++ b/src/rl/plan/RrtDual.cpp @@ -53,7 +53,7 @@ namespace rl Vertex i = this->end[0]; - while (i != this->begin[0]) + while (::boost::in_degree(i, this->tree[0]) > 0) { path.push_front(*get(this->tree[0], i)->q); i = ::boost::source(*::boost::in_edges(i, this->tree[0]).first, this->tree[0]); @@ -63,7 +63,7 @@ namespace rl i = ::boost::source(*::boost::in_edges(this->end[1], this->tree[1]).first, this->tree[1]); - while (i != this->begin[1]) + while (::boost::in_degree(i, this->tree[1]) > 0) { path.push_back(*get(this->tree[1], i)->q); i = ::boost::source(*::boost::in_edges(i, this->tree[1]).first, this->tree[1]); From 46a76412c97762d977c2206b2ebce1cd6979eb4b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 27 Mar 2019 16:47:10 +0100 Subject: [PATCH 180/546] Read speed scaling value in UR RTDE interface --- src/rl/hal/UniversalRobotsRtde.cpp | 2 ++ src/rl/hal/UniversalRobotsRtde.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 1e9ed63c..66542686 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -511,6 +511,7 @@ namespace rl "robot_mode", "joint_mode", "safety_mode", + "speed_scaling", "actual_digital_output_bits", "runtime_state", "robot_status_bits", @@ -723,6 +724,7 @@ namespace rl this->unserialize(ptr, this->output.robotMode); this->unserialize(ptr, this->output.jointMode); this->unserialize(ptr, this->output.safetyMode); + this->unserialize(ptr, this->output.speedScaling); this->unserialize(ptr, this->output.actualDigitalOutputBits); this->unserialize(ptr, this->output.runtimeState); this->unserialize(ptr, this->output.robotStatusBits); diff --git a/src/rl/hal/UniversalRobotsRtde.h b/src/rl/hal/UniversalRobotsRtde.h index bc922de5..a8292fa9 100644 --- a/src/rl/hal/UniversalRobotsRtde.h +++ b/src/rl/hal/UniversalRobotsRtde.h @@ -339,6 +339,8 @@ namespace rl ::std::uint32_t safetyStatusBits; + double speedScaling; + double standardAnalogInput0; double standardAnalogInput1; From c37886bf2ad7bcd639b32d18aff582985131e5f8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 3 Apr 2019 21:37:09 +0200 Subject: [PATCH 181/546] Use static_cast to handle USE_MSVC_DISABLE_RTTI option --- src/rl/sg/bullet/Scene.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rl/sg/bullet/Scene.cpp b/src/rl/sg/bullet/Scene.cpp index 281665dc..df8bf736 100644 --- a/src/rl/sg/bullet/Scene.cpp +++ b/src/rl/sg/bullet/Scene.cpp @@ -129,8 +129,8 @@ namespace rl ::btVoronoiSimplexSolver simplexSolver; ::btGjkEpaPenetrationDepthSolver penetrationDepthSolver; ::btGjkPairDetector pairDetector( - dynamic_cast< ::btConvexShape*>(shape1->shape), - dynamic_cast< ::btConvexShape*>(shape2->shape), + static_cast< ::btConvexShape*>(shape1->shape), + static_cast< ::btConvexShape*>(shape2->shape), &simplexSolver, &penetrationDepthSolver ); @@ -163,8 +163,8 @@ namespace rl ::btGjkEpaPenetrationDepthSolver epa; ::btGjkPairDetector convexConvex( - dynamic_cast< ::btConvexShape*>(static_cast(shape)->shape), - dynamic_cast< ::btConvexShape*>(&sphere), + static_cast< ::btConvexShape*>(static_cast(shape)->shape), + static_cast< ::btConvexShape*>(&sphere), &sGjkSimplexSolver, &epa ); From 7fef19aa2b800549c869a73a0da898a94b2c2cbe Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 3 Apr 2019 22:08:09 +0200 Subject: [PATCH 182/546] Update Bullet Physics external project --- 3rdparty/bullet/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/bullet/CMakeLists.txt b/3rdparty/bullet/CMakeLists.txt index 7e1146aa..c7f3b475 100644 --- a/3rdparty/bullet/CMakeLists.txt +++ b/3rdparty/bullet/CMakeLists.txt @@ -7,10 +7,10 @@ include(ExternalProject) ExternalProject_Add( bullet #GIT_REPOSITORY git://github.com/bulletphysics/bullet3.git - #GIT_TAG 2.86.1 + #GIT_TAG 2.88 URL https://github.com/roboticslibrary/bullet3/archive/patch.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/bullet3-2.86.1.tar.gz - #URL_MD5 439f78f567ee340b0cd1ffb8c31def1e + #URL ${CMAKE_CURRENT_SOURCE_DIR}/bullet3-2.88.tar.gz + #URL_MD5 d389e7235f00c66abf257bb7b21477ac CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_BULLET2_DEMOS=OFF -DBUILD_CPU_DEMOS=OFF -DBUILD_EXTRAS=ON -DBUILD_OPENGL3_DEMOS=OFF -DBUILD_PYBULLET=OFF -DBUILD_UNIT_TESTS=OFF -DINSTALL_EXTRA_LIBS=ON -DINSTALL_LIBS=ON -DUSE_MSVC_RUNTIME_LIBRARY_DLL=ON INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From 0eb7b199e291cdab0198d8fd2123892d214e3eb4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Apr 2019 13:14:40 +0200 Subject: [PATCH 183/546] Update remaining project website links to https --- debian/control | 2 +- debian/copyright | 2 +- examples/README | 2 +- src/rl/mainpage.dox | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/debian/control b/debian/control index 2e2d66b5..5edca03f 100644 --- a/debian/control +++ b/debian/control @@ -22,7 +22,7 @@ Build-Depends: debhelper (>= 7.0.50~), libxslt1-dev (>= 1.1.26) Standards-Version: 3.9.1 Section: libs -Homepage: http://www.roboticslibrary.org/ +Homepage: https://www.roboticslibrary.org/ Package: librl Section: libs diff --git a/debian/copyright b/debian/copyright index f8ba5c03..f0e46410 100644 --- a/debian/copyright +++ b/debian/copyright @@ -1,7 +1,7 @@ Format: http://dep.debian.net/deps/dep5 Upstream-Name: Robotics Library Upstream-Contact: Robotics Library Team -Source: http://www.roboticslibrary.org/ +Source: https://www.roboticslibrary.org/ Files: * Copyright: Copyright 2009 Robotics Library Team diff --git a/examples/README b/examples/README index cdd0be27..7d860b44 100644 --- a/examples/README +++ b/examples/README @@ -1 +1 @@ -For further example files see http://www.roboticslibrary.org/ \ No newline at end of file +For further example files see https://www.roboticslibrary.org/ \ No newline at end of file diff --git a/src/rl/mainpage.dox b/src/rl/mainpage.dox index 2d6b8421..a0f442cf 100644 --- a/src/rl/mainpage.dox +++ b/src/rl/mainpage.dox @@ -3,7 +3,7 @@ namespace rl /** \mainpage Robotics Library -For first time users, please have a look at our website. Also, please refer to the website for tutorials, a high-level API description and answers on frequently asked questions (FAQ). +For first time users, please have a look at our website. Also, please refer to the website for tutorials, a high-level API description and answers on frequently asked questions (FAQ). \section api API Overview From 3a8c2b087f5a8ad7ed577a26df1eada8904461e8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Apr 2019 15:50:29 +0200 Subject: [PATCH 184/546] Update Boost to 1.69.0 --- 3rdparty/boost/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/boost/CMakeLists.txt b/3rdparty/boost/CMakeLists.txt index 44fc315f..0859acc1 100644 --- a/3rdparty/boost/CMakeLists.txt +++ b/3rdparty/boost/CMakeLists.txt @@ -7,9 +7,9 @@ include(GNUInstallDirs) ExternalProject_Add( boost - URL https://dl.bintray.com/boostorg/release/1.67.0/source/boost_1_67_0.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_67_0.tar.bz2 - URL_MD5 ced776cb19428ab8488774e1415535ab + URL https://dl.bintray.com/boostorg/release/1.69.0/source/boost_1_69_0.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_69_0.tar.bz2 + URL_MD5 a1332494397bf48332cb152abfefcec2 CONFIGURE_COMMAND "" BUILD_COMMAND "" BUILD_IN_SOURCE 1 From 26571c8b8464577bc11a3c52c35ccfa1cd2716c8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Apr 2019 15:50:43 +0200 Subject: [PATCH 185/546] Update Boost_ADDITIONAL_VERSIONS to support 1.69 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 031603ac..4102b5e2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -38,7 +38,7 @@ if(WIN32) ) endif() -set(Boost_ADDITIONAL_VERSIONS "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") +set(Boost_ADDITIONAL_VERSIONS "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") include(Qt4AutomocMocOptionsBoost) From 992d0dd78b1de40d3f140c18f4180b44529cb953 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Apr 2019 15:50:56 +0200 Subject: [PATCH 186/546] Update ODE to 0.16 --- 3rdparty/ode/CMakeLists.txt | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/3rdparty/ode/CMakeLists.txt b/3rdparty/ode/CMakeLists.txt index 9f6929fe..57648fdc 100644 --- a/3rdparty/ode/CMakeLists.txt +++ b/3rdparty/ode/CMakeLists.txt @@ -6,9 +6,11 @@ include(ExternalProject) ExternalProject_Add( ode - URL https://bitbucket.org/roboticslibrary/ode/get/patch-cmake-0.15.x.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/ode-0.15.2.tar.bz2 - #URL_MD5 c235fbbbc2c2381b8b3259a8328f7826 + #HG_REPOSITORY https://bitbucket.org/odedevs/ode + #HG_TAG 0.16 + URL https://bitbucket.org/odedevs/ode/downloads/ode-0.16.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/ode-0.16.tar.gz + URL_MD5 5da260bdc3f7de1636ce85e72807bffb CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DODE_WITH_DEMOS=OFF -DODE_WITH_TESTS=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From 51e96927933107a4f7915601968b911659973347 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Apr 2019 15:51:04 +0200 Subject: [PATCH 187/546] Update Eigen to 3.3.7 --- 3rdparty/eigen/CMakeLists.txt | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/3rdparty/eigen/CMakeLists.txt b/3rdparty/eigen/CMakeLists.txt index 91500d32..b2ba5c77 100644 --- a/3rdparty/eigen/CMakeLists.txt +++ b/3rdparty/eigen/CMakeLists.txt @@ -7,10 +7,10 @@ include(ExternalProject) ExternalProject_Add( eigen #HG_REPOSITORY https://bitbucket.org/eigen/eigen/ - #HG_TAG 3.3.4 - URL http://bitbucket.org/eigen/eigen/get/3.3.4.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/eigen-eigen-5a0156e40feb.tar.gz - #URL_MD5 1a47e78efe365a97de0c022d127607c3 - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + #HG_TAG 3.3.7 + URL https://bitbucket.org/eigen/eigen/get/3.3.7.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/eigen-eigen-323c052e1731.tar.gz + URL_MD5 f2a417d083fe8ca4b8ed2bc613d20f07 + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_TESTING=OFF -DEIGEN_TEST_NOQT=ON INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From 4cde400291f65563d50fa224383d273ca15725b4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Apr 2019 22:37:27 +0200 Subject: [PATCH 188/546] Update Coin3D external projects --- 3rdparty/CMakeLists.txt | 1 - .../coin3d/boost-header-libs-full/CMakeLists.txt | 12 ------------ 3rdparty/coin3d/coin/CMakeLists.txt | 7 +++---- 3rdparty/coin3d/soqt/CMakeLists.txt | 2 +- 4 files changed, 4 insertions(+), 18 deletions(-) delete mode 100644 3rdparty/coin3d/boost-header-libs-full/CMakeLists.txt diff --git a/3rdparty/CMakeLists.txt b/3rdparty/CMakeLists.txt index 5c210820..5da37e1b 100644 --- a/3rdparty/CMakeLists.txt +++ b/3rdparty/CMakeLists.txt @@ -28,7 +28,6 @@ else() set(PATCH_EXECUTABLE patch) endif() -add_subdirectory(coin3d/boost-header-libs-full) add_subdirectory(coin3d/cpack.d) add_subdirectory(coin3d/soanydata) add_subdirectory(coin3d/sogui) diff --git a/3rdparty/coin3d/boost-header-libs-full/CMakeLists.txt b/3rdparty/coin3d/boost-header-libs-full/CMakeLists.txt deleted file mode 100644 index 57eaf0ab..00000000 --- a/3rdparty/coin3d/boost-header-libs-full/CMakeLists.txt +++ /dev/null @@ -1,12 +0,0 @@ -include(ExternalProject) - -ExternalProject_Add( - boost-header-libs-full - #HG_REPOSITORY https://bitbucket.org/Coin3D/boost-header-libs-full - #HG_TAG default - URL https://bitbucket.org/Coin3D/boost-header-libs-full/get/default.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" -) diff --git a/3rdparty/coin3d/coin/CMakeLists.txt b/3rdparty/coin3d/coin/CMakeLists.txt index 90534031..30aca357 100644 --- a/3rdparty/coin3d/coin/CMakeLists.txt +++ b/3rdparty/coin3d/coin/CMakeLists.txt @@ -4,14 +4,13 @@ list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) ExternalProject_Add( coin - DEPENDS boost-header-libs-full cpack.d simage + DEPENDS boost cpack.d simage #HG_REPOSITORY https://bitbucket.org/Coin3D/coin #HG_TAG default URL https://bitbucket.org/Coin3D/coin/get/default.tar.bz2 #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 PATCH_COMMAND - ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d && - ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../boost-header-libs-full/boost-header-libs-full-prefix/src/boost-header-libs-full /include/boost - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DCOIN_BUILD_DOCUMENTATION=OFF + ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DCOIN_BUILD_DOCUMENTATION=OFF -DCOIN_BUILD_TESTS=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) diff --git a/3rdparty/coin3d/soqt/CMakeLists.txt b/3rdparty/coin3d/soqt/CMakeLists.txt index 4400e0a6..bb16b8ac 100644 --- a/3rdparty/coin3d/soqt/CMakeLists.txt +++ b/3rdparty/coin3d/soqt/CMakeLists.txt @@ -4,7 +4,7 @@ list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) ExternalProject_Add( soqt - DEPENDS cpack.d soanydata sogui coin + DEPENDS coin cpack.d soanydata sogui #HG_REPOSITORY https://bitbucket.org/Coin3D/soqt #HG_TAG default URL https://bitbucket.org/Coin3D/soqt/get/default.tar.bz2 From 038243bf3f96e95f4a36d4fdf538775ad943527a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 13 Apr 2019 18:12:33 +0200 Subject: [PATCH 189/546] Add missing copyright --- src/rl/sg/solid/Body.h | 26 ++++++++++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/src/rl/sg/solid/Body.h b/src/rl/sg/solid/Body.h index a9e3eb8f..19a9c19b 100644 --- a/src/rl/sg/solid/Body.h +++ b/src/rl/sg/solid/Body.h @@ -1,3 +1,29 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_SG_SOLID_BODY_H #define RL_SG_SOLID_BODY_H From f0e31e824bb2af8db7e4ed789fc7216008066d19 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 13 Apr 2019 20:12:25 +0200 Subject: [PATCH 190/546] Update add_test definitions --- tests/rlCircularTest/CMakeLists.txt | 4 +- tests/rlCollisionTest/CMakeLists.txt | 8 +- tests/rlDynamicsTest/CMakeLists.txt | 8 +- tests/rlEetTest/CMakeLists.txt | 16 +-- tests/rlHalEndianTest/CMakeLists.txt | 4 +- .../rlInverseKinematicsKinTest/CMakeLists.txt | 14 +- .../rlInverseKinematicsMdlTest/CMakeLists.txt | 14 +- tests/rlJacobianKinTest/CMakeLists.txt | 8 +- tests/rlJacobianMdlTest/CMakeLists.txt | 8 +- tests/rlMathDeltaTest/CMakeLists.txt | 4 +- tests/rlNearestNeighborsTest/CMakeLists.txt | 4 +- tests/rlPrmTest/CMakeLists.txt | 40 +++--- tests/rlSpatialTest/CMakeLists.txt | 2 +- tests/rlSplineTest/CMakeLists.txt | 123 ++---------------- 14 files changed, 71 insertions(+), 186 deletions(-) diff --git a/tests/rlCircularTest/CMakeLists.txt b/tests/rlCircularTest/CMakeLists.txt index 54007f4e..894b3868 100644 --- a/tests/rlCircularTest/CMakeLists.txt +++ b/tests/rlCircularTest/CMakeLists.txt @@ -9,6 +9,6 @@ target_link_libraries( ) add_test( - rlCircularTest1 - ${CMAKE_CURRENT_BINARY_DIR}/rlCircularTest + NAME rlCircularTest + COMMAND rlCircularTest ) diff --git a/tests/rlCollisionTest/CMakeLists.txt b/tests/rlCollisionTest/CMakeLists.txt index 33c164e0..b8883f26 100644 --- a/tests/rlCollisionTest/CMakeLists.txt +++ b/tests/rlCollisionTest/CMakeLists.txt @@ -26,8 +26,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 ) add_test( - rlCollisionTestPuma560Boxes - ${CMAKE_CURRENT_BINARY_DIR}/rlCollisionTest + NAME rlCollisionTestPuma560Boxes + COMMAND rlCollisionTest ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 0 0 0 0 0 0 @@ -44,8 +44,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 ) add_test( - rlSceneCollisionTestTwoTori1 - ${CMAKE_CURRENT_BINARY_DIR}/rlSceneCollisionTest + NAME rlSceneCollisionTestTwoTori1 + COMMAND rlSceneCollisionTest ${CMAKE_CURRENT_SOURCE_DIR}/twotori.xml ) endif() diff --git a/tests/rlDynamicsTest/CMakeLists.txt b/tests/rlDynamicsTest/CMakeLists.txt index 84beda03..9f694fec 100644 --- a/tests/rlDynamicsTest/CMakeLists.txt +++ b/tests/rlDynamicsTest/CMakeLists.txt @@ -10,15 +10,15 @@ target_link_libraries( ) add_test( - rlDynamicsTestMitsubishiRv6sl - ${CMAKE_CURRENT_BINARY_DIR}/rlDynamicsTest + NAME rlDynamicsTestMitsubishiRv6sl + COMMAND rlDynamicsTest ${rl_SOURCE_DIR}/examples/rlmdl/mitsubishi-rv6sl.xml 100 ) add_test( - rlDynamicsTestPlanar2 - ${CMAKE_CURRENT_BINARY_DIR}/rlDynamicsTest + NAME rlDynamicsTestPlanar2 + COMMAND rlDynamicsTest ${rl_SOURCE_DIR}/examples/rlmdl/planar2.xml 100 ) diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index 4c9f9257..4e14f464 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -27,8 +27,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) if(BULLET_FOUND) add_test( - rlEetTestBulletBox6d300505Maze - ${CMAKE_CURRENT_BINARY_DIR}/rlEetTest + NAME rlEetTestBulletBox6d300505Maze + COMMAND rlEetTest bullet ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml @@ -40,8 +40,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) if(CCD_FOUND AND FCL_FOUND) add_test( - rlEetTestFclBox6d300505Maze - ${CMAKE_CURRENT_BINARY_DIR}/rlEetTest + NAME rlEetTestFclBox6d300505Maze + COMMAND rlEetTest fcl ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml @@ -53,8 +53,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) if(PQP_FOUND) add_test( - rlEetTestPqpBox6d300505Maze - ${CMAKE_CURRENT_BINARY_DIR}/rlEetTest + NAME rlEetTestPqpBox6d300505Maze + COMMAND rlEetTest pqp ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml @@ -66,8 +66,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) if(SOLID3_FOUND) add_test( - rlEetTestSolidBox6d300505Maze - ${CMAKE_CURRENT_BINARY_DIR}/rlEetTest + NAME rlEetTestSolidBox6d300505Maze + COMMAND rlEetTest solid ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml diff --git a/tests/rlHalEndianTest/CMakeLists.txt b/tests/rlHalEndianTest/CMakeLists.txt index 65b5fdae..8a9284f2 100644 --- a/tests/rlHalEndianTest/CMakeLists.txt +++ b/tests/rlHalEndianTest/CMakeLists.txt @@ -9,6 +9,6 @@ target_link_libraries( ) add_test( - rlHalEndianTest - ${CMAKE_CURRENT_BINARY_DIR}/rlHalEndianTest + NAME rlHalEndianTest + COMMAND rlHalEndianTest ) diff --git a/tests/rlInverseKinematicsKinTest/CMakeLists.txt b/tests/rlInverseKinematicsKinTest/CMakeLists.txt index 34ab468b..5aec19b3 100644 --- a/tests/rlInverseKinematicsKinTest/CMakeLists.txt +++ b/tests/rlInverseKinematicsKinTest/CMakeLists.txt @@ -3,25 +3,19 @@ add_executable( rlInverseKinematicsKinTest.cpp ) -target_compile_definitions( - rlInverseKinematicsKinTest - PRIVATE - -DCMAKE_CURRENT_SOURCE_DIR="${CMAKE_CURRENT_SOURCE_DIR}" -) - target_link_libraries( rlInverseKinematicsKinTest kin ) add_test( - rlInverseKinematicsKinTestMitsubishiRv6sl - ${CMAKE_CURRENT_BINARY_DIR}/rlInverseKinematicsKinTest + NAME rlInverseKinematicsKinTestMitsubishiRv6sl + COMMAND rlInverseKinematicsKinTest ${rl_SOURCE_DIR}/examples/rlkin/mitsubishi-rv6sl.xml ) add_test( - rlInverseKinematicsKinTestStaeubliTx60l - ${CMAKE_CURRENT_BINARY_DIR}/rlInverseKinematicsKinTest + NAME rlInverseKinematicsKinTestStaeubliTx60l + COMMAND rlInverseKinematicsKinTest ${rl_SOURCE_DIR}/examples/rlkin/staeubli-tx60l.xml ) diff --git a/tests/rlInverseKinematicsMdlTest/CMakeLists.txt b/tests/rlInverseKinematicsMdlTest/CMakeLists.txt index 5afe7504..862c9220 100644 --- a/tests/rlInverseKinematicsMdlTest/CMakeLists.txt +++ b/tests/rlInverseKinematicsMdlTest/CMakeLists.txt @@ -3,25 +3,19 @@ add_executable( rlInverseKinematicsMdlTest.cpp ) -target_compile_definitions( - rlInverseKinematicsMdlTest - PRIVATE - -DCMAKE_CURRENT_SOURCE_DIR="${CMAKE_CURRENT_SOURCE_DIR}" -) - target_link_libraries( rlInverseKinematicsMdlTest mdl ) add_test( - rlInverseKinematicsMdlTestMitsubishiRv6sl - ${CMAKE_CURRENT_BINARY_DIR}/rlInverseKinematicsMdlTest + NAME rlInverseKinematicsMdlTestMitsubishiRv6sl + COMMAND rlInverseKinematicsMdlTest ${rl_SOURCE_DIR}/examples/rlmdl/mitsubishi-rv6sl.xml ) add_test( - rlInverseKinematicsMdlTestUnimationPuma560 - ${CMAKE_CURRENT_BINARY_DIR}/rlInverseKinematicsMdlTest + NAME rlInverseKinematicsMdlTestUnimationPuma560 + COMMAND rlInverseKinematicsMdlTest ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml ) diff --git a/tests/rlJacobianKinTest/CMakeLists.txt b/tests/rlJacobianKinTest/CMakeLists.txt index a40fc8ff..a2822c89 100644 --- a/tests/rlJacobianKinTest/CMakeLists.txt +++ b/tests/rlJacobianKinTest/CMakeLists.txt @@ -9,13 +9,13 @@ target_link_libraries( ) add_test( - rlJacobianKinTestMitsubishiRv6sl - ${CMAKE_CURRENT_BINARY_DIR}/rlJacobianKinTest + NAME rlJacobianKinTestMitsubishiRv6sl + COMMAND rlJacobianKinTest ${rl_SOURCE_DIR}/examples/rlkin/mitsubishi-rv6sl.xml ) add_test( - rlJacobianKinTestStaeubliTx60l - ${CMAKE_CURRENT_BINARY_DIR}/rlJacobianKinTest + NAME rlJacobianKinTestStaeubliTx60l + COMMAND rlJacobianKinTest ${rl_SOURCE_DIR}/examples/rlkin/staeubli-tx60l.xml ) diff --git a/tests/rlJacobianMdlTest/CMakeLists.txt b/tests/rlJacobianMdlTest/CMakeLists.txt index 18597168..315b75a8 100644 --- a/tests/rlJacobianMdlTest/CMakeLists.txt +++ b/tests/rlJacobianMdlTest/CMakeLists.txt @@ -9,13 +9,13 @@ target_link_libraries( ) add_test( - rlJacobianMdlTestMitsubishiRv6sl - ${CMAKE_CURRENT_BINARY_DIR}/rlJacobianMdlTest + NAME rlJacobianMdlTestMitsubishiRv6sl + COMMAND rlJacobianMdlTest ${rl_SOURCE_DIR}/examples/rlmdl/mitsubishi-rv6sl.xml ) add_test( - rlJacobianMdlTestComauSmart5Nj422027 - ${CMAKE_CURRENT_BINARY_DIR}/rlJacobianMdlTest + NAME rlJacobianMdlTestComauSmart5Nj422027 + COMMAND rlJacobianMdlTest ${rl_SOURCE_DIR}/examples/rlmdl/comau-smart5-nj4-220-27.xml ) diff --git a/tests/rlMathDeltaTest/CMakeLists.txt b/tests/rlMathDeltaTest/CMakeLists.txt index 668344f1..42cd32c7 100644 --- a/tests/rlMathDeltaTest/CMakeLists.txt +++ b/tests/rlMathDeltaTest/CMakeLists.txt @@ -9,6 +9,6 @@ target_link_libraries( ) add_test( - rlMathDeltaTest1 - ${CMAKE_CURRENT_BINARY_DIR}/rlMathDeltaTest + NAME rlMathDeltaTest + COMMAND rlMathDeltaTest ) diff --git a/tests/rlNearestNeighborsTest/CMakeLists.txt b/tests/rlNearestNeighborsTest/CMakeLists.txt index 5dc883d1..764c26e6 100644 --- a/tests/rlNearestNeighborsTest/CMakeLists.txt +++ b/tests/rlNearestNeighborsTest/CMakeLists.txt @@ -29,6 +29,6 @@ target_link_libraries( ) add_test( - rlNearestNeighborsTest - ${CMAKE_CURRENT_BINARY_DIR}/rlNearestNeighborsTest + NAME rlNearestNeighborsTest + COMMAND rlNearestNeighborsTest ) diff --git a/tests/rlPrmTest/CMakeLists.txt b/tests/rlPrmTest/CMakeLists.txt index a990632f..8b5e6e3f 100644 --- a/tests/rlPrmTest/CMakeLists.txt +++ b/tests/rlPrmTest/CMakeLists.txt @@ -28,8 +28,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 if(BULLET_FOUND) add_test( - rlPrmTestBulletUnimationPuma560Boxes1 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestBulletUnimationPuma560Boxes1 + COMMAND rlPrmTest bullet ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml @@ -40,8 +40,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 ) add_test( - rlPrmTestBulletUnimationPuma560Boxes2 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestBulletUnimationPuma560Boxes2 + COMMAND rlPrmTest bullet ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml @@ -54,8 +54,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 if(CCD_FOUND AND FCL_FOUND) add_test( - rlPrmTestFclUnimationPuma560Boxes1 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestFclUnimationPuma560Boxes1 + COMMAND rlPrmTest fcl ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml @@ -66,8 +66,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 ) add_test( - rlPrmTestFclUnimationPuma560Boxes2 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestFclUnimationPuma560Boxes2 + COMMAND rlPrmTest fcl ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml @@ -80,8 +80,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 if(ODE_FOUND) add_test( - rlPrmTestOdeUnimationPuma560Boxes1 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestOdeUnimationPuma560Boxes1 + COMMAND rlPrmTest ode ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml @@ -92,8 +92,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 ) add_test( - rlPrmTestOdeUnimationPuma560Boxes2 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestOdeUnimationPuma560Boxes2 + COMMAND rlPrmTest ode ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml @@ -106,8 +106,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 if(PQP_FOUND) add_test( - rlPrmTestPqpUnimationPuma560Boxes1 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestPqpUnimationPuma560Boxes1 + COMMAND rlPrmTest pqp ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml @@ -118,8 +118,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 ) add_test( - rlPrmTestPqpUnimationPuma560Boxes2 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestPqpUnimationPuma560Boxes2 + COMMAND rlPrmTest pqp ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml @@ -132,8 +132,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 if(SOLID3_FOUND) add_test( - rlPrmTestSolidUnimationPuma560Boxes1 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestSolidUnimationPuma560Boxes1 + COMMAND rlPrmTest solid ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml @@ -144,8 +144,8 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 ) add_test( - rlPrmTestSolidUnimationPuma560Boxes2 - ${CMAKE_CURRENT_BINARY_DIR}/rlPrmTest + NAME rlPrmTestSolidUnimationPuma560Boxes2 + COMMAND rlPrmTest solid ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml diff --git a/tests/rlSpatialTest/CMakeLists.txt b/tests/rlSpatialTest/CMakeLists.txt index 27eea0c2..72b1e7a1 100644 --- a/tests/rlSpatialTest/CMakeLists.txt +++ b/tests/rlSpatialTest/CMakeLists.txt @@ -13,5 +13,5 @@ set( foreach(TEST ${TESTS}) add_executable(${TEST} ${TEST}.cpp) target_link_libraries(${TEST} math) - add_test(${TEST} ${CMAKE_CURRENT_BINARY_DIR}/${TEST}) + add_test(NAME ${TEST} COMMAND ${TEST}) endforeach() diff --git a/tests/rlSplineTest/CMakeLists.txt b/tests/rlSplineTest/CMakeLists.txt index f7269332..9f229edb 100644 --- a/tests/rlSplineTest/CMakeLists.txt +++ b/tests/rlSplineTest/CMakeLists.txt @@ -1,120 +1,17 @@ -add_executable( - rlPolynomialTest - rlPolynomialTest.cpp -) - -target_link_libraries( - rlPolynomialTest - math -) - -add_test( +set( + TESTS + rlPolynomialExtremaTest rlPolynomialTest - ${CMAKE_CURRENT_BINARY_DIR}/rlPolynomialTest -) - -add_executable( rlQuarticLinearQuarticTest - rlQuarticLinearQuarticTest.cpp -) - -target_link_libraries( - rlQuarticLinearQuarticTest - math -) - -add_test( - rlQuarticLinearQuarticTest - ${CMAKE_CURRENT_BINARY_DIR}/rlQuarticLinearQuarticTest -) - -add_executable( rlSexticLinearSexticTest - rlSexticLinearSexticTest.cpp -) - -target_link_libraries( - rlSexticLinearSexticTest - math -) - -add_test( - rlSexticLinearSexticTest - ${CMAKE_CURRENT_BINARY_DIR}/rlSexticLinearSexticTest -) - -add_executable( - rlSplineTest - rlSplineTest.cpp -) - -target_link_libraries( - rlSplineTest - math -) - -add_test( - rlSplineTest - ${CMAKE_CURRENT_BINARY_DIR}/rlSplineTest -) - -add_executable( - rlTrapezoidalAccelerationTest - rlTrapezoidalAccelerationTest.cpp -) - -target_link_libraries( - rlTrapezoidalAccelerationTest - math -) - -add_test( - rlTrapezoidalAccelerationTest - ${CMAKE_CURRENT_BINARY_DIR}/rlTrapezoidalAccelerationTest -) - -add_executable( rlSplineScaleTest - rlSplineScaleTest.cpp -) - -target_link_libraries( - rlSplineScaleTest - math -) - -add_test( - rlSplineScaleTest - ${CMAKE_CURRENT_BINARY_DIR}/rlSplineScaleTest -) - -add_executable( - rlSplineTranslationTest - rlSplineTranslationTest.cpp -) - -target_link_libraries( - rlSplineTranslationTest - math -) - -add_test( + rlSplineTest rlSplineTranslationTest - ${CMAKE_CURRENT_BINARY_DIR}/rlSplineTranslationTest -) - - -add_executable( - rlPolynomialExtremaTest - rlPolynomialExtremaTest.cpp -) - -target_link_libraries( - rlPolynomialExtremaTest - math + rlTrapezoidalAccelerationTest ) -add_test( - rlPolynomialExtremaTest - ${CMAKE_CURRENT_BINARY_DIR}/rlPolynomialExtremaTest -) +foreach(TEST ${TESTS}) + add_executable(${TEST} ${TEST}.cpp) + target_link_libraries(${TEST} math) + add_test(NAME ${TEST} COMMAND ${TEST}) +endforeach() From 7e17a431ff049ace9eeb3a8bd3f71b08a585fb60 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 13 Apr 2019 20:53:52 +0200 Subject: [PATCH 191/546] Change rl::hal::Exception::strerror to private --- src/rl/hal/Exception.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/rl/hal/Exception.h b/src/rl/hal/Exception.h index cdb5744f..1858b628 100644 --- a/src/rl/hal/Exception.h +++ b/src/rl/hal/Exception.h @@ -43,12 +43,10 @@ namespace rl virtual ~Exception() throw(); - static ::std::string strerror(const int& errnum); - protected: private: - + static ::std::string strerror(const int& errnum); }; } } From 8bfd262f7eaf23e298396ae0d3f7c360f20d2db1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 13 Apr 2019 22:52:31 +0200 Subject: [PATCH 192/546] Add CMAKE_OSX_SYSROOT to find_path() for macOS 10.14 --- cmake/Findlibiconv.cmake | 1 + cmake/Findlibxml2.cmake | 2 ++ cmake/Findlibxslt.cmake | 2 ++ cmake/Findzlib.cmake | 1 + 4 files changed, 6 insertions(+) diff --git a/cmake/Findlibiconv.cmake b/cmake/Findlibiconv.cmake index 4cbc3e35..08537f05 100644 --- a/cmake/Findlibiconv.cmake +++ b/cmake/Findlibiconv.cmake @@ -46,6 +46,7 @@ file( /usr/include $ENV{ProgramW6432}/GnuWin32/include $ENV{ProgramFiles}/GnuWin32/include + ${CMAKE_OSX_SYSROOT}/usr/include ) find_path( diff --git a/cmake/Findlibxml2.cmake b/cmake/Findlibxml2.cmake index 4fffbd57..b8c17d71 100644 --- a/cmake/Findlibxml2.cmake +++ b/cmake/Findlibxml2.cmake @@ -54,6 +54,8 @@ file( /opt/local/include /usr/include/libxml2 /usr/include + ${CMAKE_OSX_SYSROOT}/usr/include/libxml2 + ${CMAKE_OSX_SYSROOT}/usr/include ) find_path( diff --git a/cmake/Findlibxslt.cmake b/cmake/Findlibxslt.cmake index ec117ae9..88542b99 100644 --- a/cmake/Findlibxslt.cmake +++ b/cmake/Findlibxslt.cmake @@ -54,6 +54,8 @@ file( /opt/local/include /usr/include/libxslt /usr/include + ${CMAKE_OSX_SYSROOT}/usr/include/libxslt + ${CMAKE_OSX_SYSROOT}/usr/include ) find_path( diff --git a/cmake/Findzlib.cmake b/cmake/Findzlib.cmake index d5e59474..d1666f5a 100644 --- a/cmake/Findzlib.cmake +++ b/cmake/Findzlib.cmake @@ -46,6 +46,7 @@ file( /usr/include $ENV{ProgramW6432}/GnuWin32/include $ENV{ProgramFiles}/GnuWin32/include + ${CMAKE_OSX_SYSROOT}/usr/include ) find_path( From a4de0a557d6df1eb77e7c65788fd7c3572db649c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 15 Apr 2019 23:41:55 +0200 Subject: [PATCH 193/546] Avoid empty blocks --- extras/tris2wrl/tris2wrl.cpp | 3 --- src/rl/hal/UniversalRobotsDashboard.cpp | 15 +++++++++++++++ 2 files changed, 15 insertions(+), 3 deletions(-) diff --git a/extras/tris2wrl/tris2wrl.cpp b/extras/tris2wrl/tris2wrl.cpp index 5c5aba17..3b51aeb7 100644 --- a/extras/tris2wrl/tris2wrl.cpp +++ b/extras/tris2wrl/tris2wrl.cpp @@ -111,9 +111,6 @@ main(int argc, char** argv) { fprintf(stderr, "Error couldn't parse a material (%s)\n", line); } - else - { - } } else { diff --git a/src/rl/hal/UniversalRobotsDashboard.cpp b/src/rl/hal/UniversalRobotsDashboard.cpp index 955e216d..9658d2a5 100644 --- a/src/rl/hal/UniversalRobotsDashboard.cpp +++ b/src/rl/hal/UniversalRobotsDashboard.cpp @@ -66,6 +66,7 @@ namespace rl if ("Added log message\n" == reply) { + return; } else if ("No log message to add\n" == reply) { @@ -88,6 +89,7 @@ namespace rl if ("Brake releasing\n" == reply) { + return; } else { @@ -106,6 +108,7 @@ namespace rl if ("closing popup\n" == reply) { + return; } else { @@ -124,6 +127,7 @@ namespace rl if ("closing safety popup\n" == reply) { + return; } else { @@ -188,6 +192,7 @@ namespace rl if ("Loading program" == reply.substr(0, 15)) { + return; } else if ("File not found" == reply.substr(0, 14)) { @@ -214,6 +219,7 @@ namespace rl if ("Loading installation" == reply.substr(0, 20)) { + return; } else if ("File not found" == reply.substr(0, 14)) { @@ -240,6 +246,7 @@ namespace rl if ("Pausing program\n" == reply) { + return; } else if ("Failed to execute: pause\n" == reply) { @@ -262,6 +269,7 @@ namespace rl if ("Starting program\n" == reply) { + return; } else if ("Failed to execute: play\n" == reply) { @@ -296,6 +304,7 @@ namespace rl if ("showing popup\n" == reply) { + return; } else { @@ -314,6 +323,7 @@ namespace rl if ("Powering off\n" == reply) { + return; } else { @@ -332,6 +342,7 @@ namespace rl if ("Powering on\n" == reply) { + return; } else { @@ -502,6 +513,7 @@ namespace rl if ("Shutting down\n" == reply) { + return; } else { @@ -520,6 +532,7 @@ namespace rl if ("Stopped\n" == reply) { + return; } else if ("Failed to execute: stop\n" == reply) { @@ -542,6 +555,7 @@ namespace rl if ("Disconnected\n" == reply) { + return; } else { @@ -560,6 +574,7 @@ namespace rl if ("Protective stop releasing\n" == reply) { + return; } else { From bdc6a442895ee2aacf943fa9fddb9646e6a6f9d0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 15 Apr 2019 23:42:32 +0200 Subject: [PATCH 194/546] Minor fix --- src/rl/hal/LeuzeRs4.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/hal/LeuzeRs4.cpp b/src/rl/hal/LeuzeRs4.cpp index c203f840..23b7fd4f 100644 --- a/src/rl/hal/LeuzeRs4.cpp +++ b/src/rl/hal/LeuzeRs4.cpp @@ -165,7 +165,7 @@ namespace rl const ::std::uint8_t& number4 = this->get(ptr); this->get(ptr); - /*int number = */Endian::hostDoubleWord(Endian::hostWord(number1, number2), Endian::hostWord(number3, number4)); + int number = Endian::hostDoubleWord(Endian::hostWord(number1, number2), Endian::hostWord(number3, number4)); int step = this->get(ptr); From 050625c8fd220a883bf670ffa5f8a9551971038d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 14:20:30 +0200 Subject: [PATCH 195/546] Add default random distribution and engine for generating positions --- src/rl/kin/Kinematics.cpp | 42 +++++++++++++++++++++++++++++- src/rl/kin/Kinematics.h | 11 ++++++++ src/rl/mdl/Model.cpp | 55 ++++++++++++++++++++++++++++++++++++++- src/rl/mdl/Model.h | 13 +++++++++ 4 files changed, 119 insertions(+), 2 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index f810d0ed..c5b68911 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -65,7 +65,9 @@ namespace rl root(), tools(), transforms(), - tree() + tree(), + randDistribution(0, 1), + randEngine(::std::random_device()()) { } @@ -492,6 +494,19 @@ namespace rl xdot = this->jacobian * qdot; } + ::rl::math::Vector + Kinematics::generatePositionGaussian(const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma) + { + ::rl::math::Vector rand(this->getDof()); + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + rand(i) = this->rand(); + } + + return this->generatePositionGaussian(rand, mean, sigma); + } + ::rl::math::Vector Kinematics::generatePositionGaussian(const ::rl::math::Vector& rand, const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma) const { @@ -507,6 +522,19 @@ namespace rl return q; } + ::rl::math::Vector + Kinematics::generatePositionUniform() + { + ::rl::math::Vector rand(this->getDof()); + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + rand(i) = this->rand(); + } + + return this->generatePositionUniform(rand); + } + ::rl::math::Vector Kinematics::generatePositionUniform(const ::rl::math::Vector& rand) const { @@ -841,6 +869,18 @@ namespace rl return true; } + ::std::uniform_real_distribution< ::rl::math::Real>::result_type + Kinematics::rand() + { + return this->randDistribution(this->randEngine); + } + + void + Kinematics::seed(const ::std::mt19937::result_type& value) + { + this->randEngine.seed(value); + } + void Kinematics::setColliding(const ::std::size_t& i, const bool& doesCollide) { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 8b884f65..481034ef 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -28,6 +28,7 @@ #define RL_KIN_KINEMATICS_H #include +#include #include #include #include @@ -113,8 +114,12 @@ namespace rl */ virtual void forwardVelocity(const ::rl::math::Vector& qdot, ::rl::math::Vector& xdot) const; + ::rl::math::Vector generatePositionGaussian(const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma); + ::rl::math::Vector generatePositionGaussian(const ::rl::math::Vector& rand, const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma) const; + ::rl::math::Vector generatePositionUniform(); + ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand) const; /** @@ -246,6 +251,8 @@ namespace rl */ virtual bool isValid(const ::rl::math::Vector& q) const; + void seed(const ::std::mt19937::result_type& value); + /** * Set if specified body should be tested for collisions with the environment. */ @@ -372,7 +379,11 @@ namespace rl Tree tree; private: + ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + + ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::mt19937 randEngine; }; } } diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index ef0bd6a0..7f059941 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -51,7 +51,9 @@ namespace rl root(0), tools(), transforms(), - tree() + tree(), + randDistribution(0, 1), + randEngine(::std::random_device()()) { } @@ -106,6 +108,19 @@ namespace rl } } + ::rl::math::Vector + Model::generatePositionGaussian(const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma) + { + ::rl::math::Vector rand(this->getDof()); + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + rand(i) = this->rand(); + } + + return this->generatePositionGaussian(rand, mean, sigma); + } + ::rl::math::Vector Model::generatePositionGaussian(const ::rl::math::Vector& rand, const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma) const { @@ -124,6 +139,19 @@ namespace rl return q; } + ::rl::math::Vector + Model::generatePositionUniform() + { + ::rl::math::Vector rand(this->getDof()); + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + rand(i) = this->rand(); + } + + return this->generatePositionUniform(rand); + } + ::rl::math::Vector Model::generatePositionUniform(const ::rl::math::Vector& rand) const { @@ -140,6 +168,19 @@ namespace rl return q; } + ::rl::math::Vector + Model::generatePositionUniform(const ::rl::math::Vector& min, const ::rl::math::Vector& max) + { + ::rl::math::Vector rand(this->getDof()); + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + rand(i) = this->rand(); + } + + return this->generatePositionUniform(rand, min, max); + } + ::rl::math::Vector Model::generatePositionUniform(const ::rl::math::Vector& rand, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const { @@ -511,6 +552,12 @@ namespace rl return this->bodies[i]->collision; } + ::std::uniform_real_distribution< ::rl::math::Real>::result_type + Model::rand() + { + return this->randDistribution(this->randEngine); + } + void Model::replace(Compound* compound, Transform* transform) { @@ -551,6 +598,12 @@ namespace rl ::boost::remove_edge(transform->getEdgeDescriptor(), this->tree); } + void + Model::seed(const ::std::mt19937::result_type& value) + { + this->randEngine.seed(value); + } + void Model::setAcceleration(const ::rl::math::Vector& ydd) { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 207c696b..5c2a7ecc 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -28,6 +28,7 @@ #define RL_MDL_MODEL_H #include +#include #include #include #include @@ -68,10 +69,16 @@ namespace rl bool areColliding(const ::std::size_t& i, const ::std::size_t& j) const; + ::rl::math::Vector generatePositionGaussian(const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma); + ::rl::math::Vector generatePositionGaussian(const ::rl::math::Vector& rand, const ::rl::math::Vector& mean, const ::rl::math::Vector& sigma) const; + ::rl::math::Vector generatePositionUniform(); + ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand) const; + ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& min, const ::rl::math::Vector& max); + ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; ::rl::math::Vector getAcceleration() const; @@ -160,6 +167,8 @@ namespace rl void remove(Transform* transform); + void seed(const ::std::mt19937::result_type& value); + void setAcceleration(const ::rl::math::Vector& qdd); void setGammaPosition(const ::rl::math::Matrix& gammaPosition); @@ -264,7 +273,11 @@ namespace rl Tree tree; private: + ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + + ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::mt19937 randEngine; }; } } From f30cde2d7b4f7b0cc86f91201f7194ddc5eb9f77 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 16:15:28 +0200 Subject: [PATCH 196/546] Add rl::kin::Kinematics::normalize function --- src/rl/kin/Kinematics.cpp | 18 ++++++++++++++++++ src/rl/kin/Kinematics.h | 2 ++ 2 files changed, 20 insertions(+) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index c5b68911..ba2b0d46 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -869,6 +869,24 @@ namespace rl return true; } + void + Kinematics::normalize(::rl::math::Vector& q) const + { + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + q(i) = ::std::fmod(q(i), 2 * static_cast< ::rl::math::Real>(M_PI)); + + if (q(i) < this->joints[i]->min) + { + q(i) += 2 * static_cast< ::rl::math::Real>(M_PI); + } + else if (q(i) > this->joints[i]->max) + { + q(i) -= 2 * static_cast< ::rl::math::Real>(M_PI); + } + } + } + ::std::uniform_real_distribution< ::rl::math::Real>::result_type Kinematics::rand() { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 481034ef..a2f4461f 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -251,6 +251,8 @@ namespace rl */ virtual bool isValid(const ::rl::math::Vector& q) const; + void normalize(::rl::math::Vector& q) const; + void seed(const ::std::mt19937::result_type& value); /** From f61d6ee5250af1962d10cf85b2cae372fdcb4bcd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 16:16:20 +0200 Subject: [PATCH 197/546] Add random restarts to rl::kin::Kinematics::inversePosition --- src/rl/kin/Kinematics.cpp | 83 ++++++++++++++++++--------------------- src/rl/kin/Kinematics.h | 4 +- 2 files changed, 42 insertions(+), 45 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index ba2b0d46..5ea9cad6 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -758,69 +758,64 @@ namespace rl } bool - Kinematics::inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const ::std::size_t& leaf, const ::rl::math::Real& delta, const ::rl::math::Real& epsilon, const ::std::size_t& iterations) + Kinematics::inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const ::std::size_t& leaf, const ::rl::math::Real& delta, const ::rl::math::Real& epsilon, const ::std::size_t& iterations, const ::std::chrono::nanoseconds& duration) { assert(q.size() == this->getDof()); + ::std::chrono::steady_clock::time_point start = ::std::chrono::steady_clock::now(); + double remaining = ::std::chrono::duration(duration).count(); + this->getPosition(q); - ::rl::math::Vector dx(6 * this->getOperationalDof()); - dx.setZero(); + ::rl::math::Vector q2(this->getDof()); ::rl::math::Vector dq(this->getDof()); + ::rl::math::Vector dx(6 * this->getOperationalDof()); - ::rl::math::Real norm = 1; - - for (::std::size_t i = 0; i < iterations && norm > epsilon; ++i) - { - this->updateFrames(); - - ::rl::math::VectorBlock dxi = dx.segment(6 * leaf, 6); - dxi = this->forwardPosition(leaf).toDelta(x); - - this->updateJacobian(); - this->updateJacobianInverse(); - this->inverseVelocity(dx, dq); - - norm = dq.norm(); - - if (norm > delta) - { - dq *= delta / norm; - norm = dq.norm(); - } - - q += dq; - - this->setPosition(q); - } - - if (norm > epsilon) - { - return false; - } - - for (::std::size_t i = 0; i < this->getDof(); ++i) + do { - q(i) = ::std::fmod(q(i), 2 * static_cast< ::rl::math::Real>(M_PI)); + ::rl::math::Real delta2 = 1; - if (q(i) < this->joints[i]->min) + for (::std::size_t i = 0; i < iterations && delta2 > epsilon; ++i) { - q(i) += 2 * static_cast< ::rl::math::Real>(M_PI); + this->updateFrames(); + dx.setZero(); + + ::rl::math::VectorBlock dxi = dx.segment(6 * leaf, 6); + dxi = this->forwardPosition(leaf).toDelta(x); + + this->updateJacobian(); + this->updateJacobianInverse(); + this->inverseVelocity(dx, dq); + + this->step(q, dq, q2); + delta2 = this->distance(q, q2); - if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) + if (delta2 > delta) { - return false; + this->interpolate(q, q2, delta, q2); } + + q = q2; + this->setPosition(q); } - else if (q(i) > this->joints[i]->max) + + + if (dx.squaredNorm() < epsilon) { - q(i) -= 2 * static_cast< ::rl::math::Real>(M_PI); + this->normalize(q); + this->setPosition(q); - if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) + if (this->isValid(q)) { - return false; + return true; } } + + q = this->generatePositionUniform(); + this->setPosition(q); + + remaining = ::std::chrono::duration(duration - (::std::chrono::steady_clock::now() - start)).count(); } + while (remaining > 0); return true; } diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index a2f4461f..18ed9567 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -27,6 +27,7 @@ #ifndef RL_KIN_KINEMATICS_H #define RL_KIN_KINEMATICS_H +#include #include #include #include @@ -219,7 +220,8 @@ namespace rl const ::std::size_t& leaf = 0, const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(), const ::rl::math::Real& epsilon = static_cast< ::rl::math::Real>(1.0e-3), - const ::std::size_t& iterations = 1000 + const ::std::size_t& iterations = 1000, + const ::std::chrono::nanoseconds& duration = ::std::chrono::milliseconds(100) ); /** From 87e8fbea8afe076718896901ea83020fb1b1dffa Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 16:18:25 +0200 Subject: [PATCH 198/546] Use rl::kin::Kinematics::normalize Remove unused parameters Add option to ignore joint limits --- src/rl/kin/Puma.cpp | 27 +++++---------------------- src/rl/kin/Puma.h | 9 +-------- src/rl/kin/Rhino.cpp | 27 +++++---------------------- src/rl/kin/Rhino.h | 9 +-------- 4 files changed, 12 insertions(+), 60 deletions(-) diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index 0b3b2d34..88d25edb 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -67,7 +67,7 @@ namespace rl } bool - Puma::inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const ::std::size_t& leaf, const ::rl::math::Real& delta, const ::rl::math::Real& epsilon, const ::std::size_t& iterations) + Puma::inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const bool& ignoreLimits) { assert(q.size() == this->getDof()); @@ -247,28 +247,11 @@ namespace rl q(5) = theta6 - this->joints[5]->theta - this->joints[5]->offset; // fit into min max angles - for (::std::size_t i = 0; i < this->getDof(); ++i) + this->normalize(q); + + if (!ignoreLimits && !this->isValid(q)) { - q(i) = ::std::fmod(q(i), 2 * static_cast< ::rl::math::Real>(M_PI)); - - if (q(i) < this->joints[i]->min) - { - q(i) += 2 * static_cast< ::rl::math::Real>(M_PI); - - if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) - { - return false; - } - } - else if (q(i) > this->joints[i]->max) - { - q(i) -= 2 * static_cast< ::rl::math::Real>(M_PI); - - if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) - { - return false; - } - } + return false; } return true; diff --git a/src/rl/kin/Puma.h b/src/rl/kin/Puma.h index 3d38649f..d48e2636 100644 --- a/src/rl/kin/Puma.h +++ b/src/rl/kin/Puma.h @@ -67,14 +67,7 @@ namespace rl Wrist getWrist() const; - bool inversePosition( - const ::rl::math::Transform& x, - ::rl::math::Vector& q, - const ::std::size_t& leaf = 0, - const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(), - const ::rl::math::Real& epsilon = static_cast< ::rl::math::Real>(1.0e-3), - const ::std::size_t& iterations = 1000 - ); + bool inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const bool& ignoreLimits = false); bool isSingular() const; diff --git a/src/rl/kin/Rhino.cpp b/src/rl/kin/Rhino.cpp index b46a38f3..838cc82d 100644 --- a/src/rl/kin/Rhino.cpp +++ b/src/rl/kin/Rhino.cpp @@ -60,7 +60,7 @@ namespace rl } bool - Rhino::inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const ::std::size_t& leaf, const ::rl::math::Real& delta, const ::rl::math::Real& epsilon, const ::std::size_t& iterations) + Rhino::inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const bool& ignoreLimits) { assert(q.size() == this->getDof()); @@ -173,28 +173,11 @@ namespace rl q(3) = theta4; q(4) = theta5; - for (::std::size_t i = 0; i < this->getDof(); ++i) + this->normalize(q); + + if (!ignoreLimits && !this->isValid(q)) { - q(i) = ::std::fmod(q(i), 2 * static_cast< ::rl::math::Real>(M_PI)); - - if (q(i) < this->joints[i]->min) - { - q(i) += 2 * static_cast< ::rl::math::Real>(M_PI); - - if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) - { - return false; - } - } - else if (q(i) > this->joints[i]->max) - { - q(i) -= 2 * static_cast< ::rl::math::Real>(M_PI); - - if (q(i) < this->joints[i]->min || q(i) > this->joints[i]->max) - { - return false; - } - } + return false; } return true; diff --git a/src/rl/kin/Rhino.h b/src/rl/kin/Rhino.h index bb4cc9df..3bf4482c 100644 --- a/src/rl/kin/Rhino.h +++ b/src/rl/kin/Rhino.h @@ -59,14 +59,7 @@ namespace rl Elbow getElbow() const; - bool inversePosition( - const ::rl::math::Transform& x, - ::rl::math::Vector& q, - const ::std::size_t& leaf = 0, - const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(), - const ::rl::math::Real& epsilon = static_cast< ::rl::math::Real>(1.0e-3), - const ::std::size_t& iterations = 1000 - ); + bool inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const bool& ignoreLimits = false); void parameters(const ::rl::math::Vector& q, Arm& arm, Elbow& elbow) const; From cfadd10b0decfe8dd93570d35dc8b3a9bce0a9fb Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 13 Apr 2019 16:18:41 +0200 Subject: [PATCH 199/546] Refactor rl::mdl::InverseKinematics --- demos/rlCoachMdl/OperationalModel.cpp | 19 +++-- .../rlInversePositionDemo.cpp | 6 +- demos/rlSimulator/OperationalModel.cpp | 2 +- src/rl/mdl/AnalyticalInverseKinematics.cpp | 49 ++++++++++++ src/rl/mdl/AnalyticalInverseKinematics.h | 54 +++++++++++++ src/rl/mdl/CMakeLists.txt | 4 + src/rl/mdl/InverseKinematics.cpp | 24 ++++++ src/rl/mdl/InverseKinematics.h | 14 +++- src/rl/mdl/IterativeInverseKinematics.cpp | 55 +++++++++++++ src/rl/mdl/IterativeInverseKinematics.h | 58 ++++++++++++++ src/rl/mdl/JacobianInverseKinematics.cpp | 80 ++++++++++++++++--- src/rl/mdl/JacobianInverseKinematics.h | 45 ++++++++--- src/rl/mdl/NloptInverseKinematics.cpp | 53 +++++++++++- src/rl/mdl/NloptInverseKinematics.h | 36 ++++++--- .../rlInverseKinematicsMdlTest.cpp | 4 +- 15 files changed, 453 insertions(+), 50 deletions(-) create mode 100644 src/rl/mdl/AnalyticalInverseKinematics.cpp create mode 100644 src/rl/mdl/AnalyticalInverseKinematics.h create mode 100644 src/rl/mdl/IterativeInverseKinematics.cpp create mode 100644 src/rl/mdl/IterativeInverseKinematics.h diff --git a/demos/rlCoachMdl/OperationalModel.cpp b/demos/rlCoachMdl/OperationalModel.cpp index 9f4d6f29..d57869fb 100644 --- a/demos/rlCoachMdl/OperationalModel.cpp +++ b/demos/rlCoachMdl/OperationalModel.cpp @@ -246,25 +246,32 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r { ik = std::make_shared(kinematic); rl::mdl::JacobianInverseKinematics* jacobianIk = static_cast(ik.get()); - jacobianIk->duration = std::chrono::milliseconds(MainWindow::instance()->ikDurationSpinBox->cleanText().toUInt()); - jacobianIk->svd = "SVD" == MainWindow::instance()->ikJacobianInverseComboBox->currentText() ? true : false; - jacobianIk->transpose = "Transpose" == MainWindow::instance()->ikJacobianComboBox->currentText() ? true : false; + jacobianIk->setDuration(std::chrono::milliseconds(MainWindow::instance()->ikDurationSpinBox->cleanText().toUInt())); + + if ("SVD" == MainWindow::instance()->ikJacobianInverseComboBox->currentText()) + { + jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_SVD); + } + else if ("Transpose" == MainWindow::instance()->ikJacobianComboBox->currentText()) + { + jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE); + } } #ifdef RL_MDL_NLOPT else if ("NloptInverseKinematics" == MainWindow::instance()->ikAlgorithmComboBox->currentText()) { ik = std::make_shared(kinematic); rl::mdl::NloptInverseKinematics* nloptIk = static_cast(ik.get()); - nloptIk->duration = std::chrono::milliseconds(MainWindow::instance()->ikDurationSpinBox->cleanText().toUInt()); + nloptIk->setDuration(std::chrono::milliseconds(MainWindow::instance()->ikDurationSpinBox->cleanText().toUInt())); } #endif #if 0 - ik->goals.push_back(::std::make_pair(transform, index.row())); + ik->addGoal(transform, index.row()); #else for (std::size_t i = 0; i < kinematic->getOperationalDof(); ++i) { - ik->goals.push_back(::std::make_pair(i == index.row() ? transform : kinematic->getOperationalPosition(i), i)); + ik->addGoal(i == index.row() ? transform : kinematic->getOperationalPosition(i), i); } #endif diff --git a/demos/rlInversePositionDemo/rlInversePositionDemo.cpp b/demos/rlInversePositionDemo/rlInversePositionDemo.cpp index bce49821..89e38209 100644 --- a/demos/rlInversePositionDemo/rlInversePositionDemo.cpp +++ b/demos/rlInversePositionDemo/rlInversePositionDemo.cpp @@ -97,9 +97,9 @@ main(int argc, char** argv) rl::mdl::JacobianInverseKinematics ik(kinematic); std::cout << "IK using rl::mdl::JacobianInverseKinematics"; #endif - ik.duration = std::chrono::seconds(1); - std::cout << " with timeout of " << std::chrono::duration_cast(ik.duration).count() << " ms" << std::endl; - ik.goals.push_back(::std::make_pair(kinematic->getOperationalPosition(0), 0)); + ik.setDuration(std::chrono::seconds(1)); + std::cout << " with timeout of " << std::chrono::duration_cast(ik.getDuration()).count() << " ms" << std::endl; + ik.addGoal(kinematic->getOperationalPosition(0), 0); rl::math::Vector min = kinematic->getMinimum(); rl::math::Vector max = kinematic->getMaximum(); diff --git a/demos/rlSimulator/OperationalModel.cpp b/demos/rlSimulator/OperationalModel.cpp index 2cb69900..0884cfa7 100644 --- a/demos/rlSimulator/OperationalModel.cpp +++ b/demos/rlSimulator/OperationalModel.cpp @@ -241,7 +241,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r rl::mdl::JacobianInverseKinematics ik(kinematic); ik.delta = 1; #endif - ik.goals.push_back(std::make_pair(x, index.row())); + ik.addGoal(x, index.row()); if (ik.solve()) { diff --git a/src/rl/mdl/AnalyticalInverseKinematics.cpp b/src/rl/mdl/AnalyticalInverseKinematics.cpp new file mode 100644 index 00000000..c3272751 --- /dev/null +++ b/src/rl/mdl/AnalyticalInverseKinematics.cpp @@ -0,0 +1,49 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "AnalyticalInverseKinematics.h" + +namespace rl +{ + namespace mdl + { + AnalyticalInverseKinematics::AnalyticalInverseKinematics(Kinematic* kinematic) : + InverseKinematics(kinematic), + solutions() + { + } + + AnalyticalInverseKinematics::~AnalyticalInverseKinematics() + { + } + + const ::std::vector< ::rl::math::Vector>& + AnalyticalInverseKinematics::getSolutions() const + { + return this->solutions; + } + } +} diff --git a/src/rl/mdl/AnalyticalInverseKinematics.h b/src/rl/mdl/AnalyticalInverseKinematics.h new file mode 100644 index 00000000..7bb404ab --- /dev/null +++ b/src/rl/mdl/AnalyticalInverseKinematics.h @@ -0,0 +1,54 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MDL_ANALYTICALINVERSEKINEMATICS_H +#define RL_MDL_ANALYTICALINVERSEKINEMATICS_H + +#include "InverseKinematics.h" + +namespace rl +{ + namespace mdl + { + class AnalyticalInverseKinematics : public InverseKinematics + { + public: + AnalyticalInverseKinematics(Kinematic* kinematic); + + virtual ~AnalyticalInverseKinematics(); + + const ::std::vector< ::rl::math::Vector>& getSolutions() const; + + protected: + ::std::vector< ::rl::math::Vector> solutions; + + private: + + }; + } +} + +#endif // RL_MDL_ANALYTICALINVERSEKINEMATICS_H diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 3160ce21..89aca169 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(NLopt) set( HDRS + AnalyticalInverseKinematics.h Body.h Compound.h Cylindrical.h @@ -16,6 +17,7 @@ set( Helical.h Integrator.h InverseKinematics.h + IterativeInverseKinematics.h JacobianInverseKinematics.h Joint.h Kinematic.h @@ -34,6 +36,7 @@ set( set( SRCS + AnalyticalInverseKinematics.cpp Body.cpp Compound.cpp Cylindrical.cpp @@ -47,6 +50,7 @@ set( Helical.cpp Integrator.cpp InverseKinematics.cpp + IterativeInverseKinematics.cpp JacobianInverseKinematics.cpp Joint.cpp Kinematic.cpp diff --git a/src/rl/mdl/InverseKinematics.cpp b/src/rl/mdl/InverseKinematics.cpp index d74db651..63c20ea7 100644 --- a/src/rl/mdl/InverseKinematics.cpp +++ b/src/rl/mdl/InverseKinematics.cpp @@ -39,5 +39,29 @@ namespace rl InverseKinematics::~InverseKinematics() { } + + void + InverseKinematics::addGoal(const Goal& goal) + { + this->goals.push_back(goal); + } + + void + InverseKinematics::addGoal(const ::rl::math::Transform& x, const ::std::size_t& i) + { + this->addGoal(::std::make_pair(x, i)); + } + + void + InverseKinematics::clearGoals() + { + this->goals.clear(); + } + + const ::std::vector& + InverseKinematics::getGoals() const + { + return this->goals; + } } } diff --git a/src/rl/mdl/InverseKinematics.h b/src/rl/mdl/InverseKinematics.h index 924b86e6..c3987cf7 100644 --- a/src/rl/mdl/InverseKinematics.h +++ b/src/rl/mdl/InverseKinematics.h @@ -39,15 +39,25 @@ namespace rl class InverseKinematics { public: + typedef ::std::pair< ::rl::math::Transform, ::std::size_t> Goal; + InverseKinematics(Kinematic* kinematic); virtual ~InverseKinematics(); - virtual bool solve() = 0; + void addGoal(const Goal& goal); + + void addGoal(const ::rl::math::Transform& x, const ::std::size_t& i); + + void clearGoals(); - ::std::vector< ::std::pair< ::rl::math::Transform, ::std::size_t>> goals; + const ::std::vector& getGoals() const; + + virtual bool solve() = 0; protected: + ::std::vector goals; + Kinematic* kinematic; private: diff --git a/src/rl/mdl/IterativeInverseKinematics.cpp b/src/rl/mdl/IterativeInverseKinematics.cpp new file mode 100644 index 00000000..5b663e6d --- /dev/null +++ b/src/rl/mdl/IterativeInverseKinematics.cpp @@ -0,0 +1,55 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "IterativeInverseKinematics.h" + +namespace rl +{ + namespace mdl + { + IterativeInverseKinematics::IterativeInverseKinematics(Kinematic* kinematic) : + InverseKinematics(kinematic), + duration(::std::chrono::milliseconds(100)) + { + } + + IterativeInverseKinematics::~IterativeInverseKinematics() + { + } + + const ::std::chrono::nanoseconds& + IterativeInverseKinematics::getDuration() const + { + return this->duration; + } + + void + IterativeInverseKinematics::setDuration(const ::std::chrono::nanoseconds& duration) + { + this->duration = duration; + } + } +} diff --git a/src/rl/mdl/IterativeInverseKinematics.h b/src/rl/mdl/IterativeInverseKinematics.h new file mode 100644 index 00000000..0dccc59f --- /dev/null +++ b/src/rl/mdl/IterativeInverseKinematics.h @@ -0,0 +1,58 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MDL_ITERATIVEINVERSEKINEMATICS_H +#define RL_MDL_ITERATIVEINVERSEKINEMATICS_H + +#include + +#include "InverseKinematics.h" + +namespace rl +{ + namespace mdl + { + class IterativeInverseKinematics : public InverseKinematics + { + public: + IterativeInverseKinematics(Kinematic* kinematic); + + virtual ~IterativeInverseKinematics(); + + const ::std::chrono::nanoseconds& getDuration() const; + + void setDuration(const ::std::chrono::nanoseconds& duration); + + protected: + ::std::chrono::nanoseconds duration; + + private: + + }; + } +} + +#endif // RL_MDL_ITERATIVEINVERSEKINEMATICS_H diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index 689501ba..a8b632d2 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -24,21 +24,19 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include "Kinematic.h" #include "JacobianInverseKinematics.h" +#include "Kinematic.h" namespace rl { namespace mdl { JacobianInverseKinematics::JacobianInverseKinematics(Kinematic* kinematic) : - InverseKinematics(kinematic), + IterativeInverseKinematics(kinematic), delta(::std::numeric_limits< ::rl::math::Real>::infinity()), - duration(::std::chrono::milliseconds(100)), epsilon(static_cast< ::rl::math::Real>(1.0e-3)), iterations(1000), - svd(true), - transpose(false), + method(METHOD_SVD), randDistribution(0, 1), randEngine(::std::random_device()()) { @@ -48,6 +46,54 @@ namespace rl { } + const math::Real& + JacobianInverseKinematics::getDelta() const + { + return this->delta; + } + + const ::rl::math::Real& + JacobianInverseKinematics::getEpsilon() const + { + return this->epsilon; + } + + const ::std::size_t& + JacobianInverseKinematics::getIterations() const + { + return this->iterations; + } + + const JacobianInverseKinematics::Method& + JacobianInverseKinematics::getMethod() const + { + return this->method; + } + + void + JacobianInverseKinematics::setDelta(const::rl::math::Real& delta) + { + this->delta = delta; + } + + void + JacobianInverseKinematics::setEpsilon(const::rl::math::Real& epsilon) + { + this->epsilon = epsilon; + } + + void + JacobianInverseKinematics::setIterations(const ::std::size_t& iterations) + { + this->iterations = iterations; + } + + void + JacobianInverseKinematics::setMethod(const Method& method) + { + this->method = method; + } + bool JacobianInverseKinematics::solve() { @@ -78,15 +124,25 @@ namespace rl this->kinematic->calculateJacobian(); - if (this->transpose) + switch (this->method) { - ::rl::math::Vector tmp = this->kinematic->getJacobian() * this->kinematic->getJacobian().transpose() * dx; - dq = dx.dot(tmp) / tmp.dot(tmp) * this->kinematic->getJacobian().transpose() * dx; - } - else - { - this->kinematic->calculateJacobianInverse(0, this->svd); + case METHOD_DLS: + this->kinematic->calculateJacobianInverse(0, false); + dq = this->kinematic->getJacobianInverse() * dx; + break; + case METHOD_SVD: + this->kinematic->calculateJacobianInverse(0, true); dq = this->kinematic->getJacobianInverse() * dx; + break; + case METHOD_TRANSPOSE: + { + ::rl::math::Vector tmp = this->kinematic->getJacobian() * this->kinematic->getJacobian().transpose() * dx; + ::rl::math::Real alpha = dx.dot(tmp) / tmp.dot(tmp); + dq = alpha * this->kinematic->getJacobian().transpose() * dx; + } + break; + default: + break; } this->kinematic->step(q, dq, q2); diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index 570c07fb..4e81553c 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -31,36 +31,63 @@ #include #include -#include "InverseKinematics.h" +#include "IterativeInverseKinematics.h" namespace rl { namespace mdl { - class JacobianInverseKinematics : public InverseKinematics + /** + * Iterative inverse kinematics using Jacobian with random restarts. + * + * Samuel R. Buss, Introduction to Inverse Kinematics with Jacobian + * Transpose, Pseudoinverse and Damped Least Squares Methods, 2009. + * + * https://www.math.ucsd.edu/~sbuss/ResearchWeb/ikmethods/iksurvey.pdf + */ + class JacobianInverseKinematics : public IterativeInverseKinematics { public: + enum Method + { + METHOD_DLS, + METHOD_SVD, + METHOD_TRANSPOSE + }; + JacobianInverseKinematics(Kinematic* kinematic); virtual ~JacobianInverseKinematics(); - bool solve(); + const ::rl::math::Real& getDelta() const; - ::rl::math::Real delta; + const ::rl::math::Real& getEpsilon() const; - ::std::chrono::nanoseconds duration; + const ::std::size_t& getIterations() const; - ::rl::math::Real epsilon; + const Method& getMethod() const; - ::std::size_t iterations; + void setDelta(const::rl::math::Real& delta); + + void setEpsilon(const::rl::math::Real& epsilon); - bool svd; + void setIterations(const ::std::size_t& iterations); - bool transpose; + void setMethod(const Method& method); + + bool solve(); protected: private: + ::rl::math::Real delta; + + ::rl::math::Real epsilon; + + ::std::size_t iterations; + + Method method; + ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; ::std::mt19937 randEngine; diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 4f03ae96..0f23c015 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -34,14 +34,13 @@ namespace rl namespace mdl { NloptInverseKinematics::NloptInverseKinematics(Kinematic* kinematic) : - InverseKinematics(kinematic), + IterativeInverseKinematics(kinematic), delta(static_cast< ::rl::math::Real>(1.0e-8)), - duration(::std::chrono::milliseconds(100)), epsilonRotation(static_cast< ::rl::math::Real>(1.0e-6)), epsilonTranslation(static_cast< ::rl::math::Real>(1.0e-6)), - tolerance(static_cast< ::rl::math::Real>(1.0e-8)), randDistribution(0, 1), - randEngine(::std::random_device()()) + randEngine(::std::random_device()()), + tolerance(static_cast< ::rl::math::Real>(1.0e-8)) { this->lb = this->kinematic->getMinimum(); this->ub = this->kinematic->getMaximum(); @@ -112,12 +111,58 @@ namespace rl return result; } + const ::rl::math::Real& + NloptInverseKinematics::getEpsilonRotation() const + { + return this->epsilonRotation; + } + + const ::rl::math::Real& + NloptInverseKinematics::getEpsilonTranslation() const + { + return this->epsilonTranslation; + } + + const ::rl::math::Real& + NloptInverseKinematics::getDelta() const + { + return this->delta; + } + + const double& + NloptInverseKinematics::getTolerance() const + { + return this->tolerance; + } + + void + NloptInverseKinematics::setDelta(const::rl::math::Real& delta) + { + this->delta = delta; + } + + void NloptInverseKinematics::setEpsilonRotation(const::rl::math::Real& epsilonRotation) + { + this->epsilonRotation = epsilonRotation; + } + + void NloptInverseKinematics::setEpsilonTranslation(const::rl::math::Real& epsilonTranslation) + { + this->epsilonTranslation = epsilonTranslation; + } + void NloptInverseKinematics::setLowerBound(const ::rl::math::Vector& lb) { this->lb = lb; } + void + NloptInverseKinematics::setTolerance(const double& tolerance) + { + this->tolerance = tolerance; + } + void NloptInverseKinematics::setUpperBound(const ::rl::math::Vector& ub) { diff --git a/src/rl/mdl/NloptInverseKinematics.h b/src/rl/mdl/NloptInverseKinematics.h index fe9d02e9..b04fa5c8 100644 --- a/src/rl/mdl/NloptInverseKinematics.h +++ b/src/rl/mdl/NloptInverseKinematics.h @@ -32,34 +32,40 @@ #include #include -#include "InverseKinematics.h" +#include "IterativeInverseKinematics.h" namespace rl { namespace mdl { - class NloptInverseKinematics : public InverseKinematics + class NloptInverseKinematics : public IterativeInverseKinematics { public: NloptInverseKinematics(Kinematic* kinematic); virtual ~NloptInverseKinematics(); - void setLowerBound(const ::rl::math::Vector& lb); + const ::rl::math::Real& getDelta() const; - void setUpperBound(const ::rl::math::Vector& ub); + const ::rl::math::Real& getEpsilonRotation() const; - bool solve(); + const ::rl::math::Real& getEpsilonTranslation() const; - ::rl::math::Real delta; + const double& getTolerance() const; - ::std::chrono::nanoseconds duration; + void setDelta(const::rl::math::Real& delta); - ::rl::math::Real epsilonRotation; + void setEpsilonRotation(const::rl::math::Real& epsilonRotation); - ::rl::math::Real epsilonTranslation; + void setEpsilonTranslation(const::rl::math::Real& epsilonTranslation); - double tolerance; + void setLowerBound(const ::rl::math::Vector& lb); + + void setTolerance(const double& tolerance); + + void setUpperBound(const ::rl::math::Vector& ub); + + bool solve(); protected: @@ -68,12 +74,20 @@ namespace rl static ::rl::math::Real f(unsigned n, const double* x, double* grad, void* data); - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::rl::math::Real delta; + + ::rl::math::Real epsilonRotation; + + ::rl::math::Real epsilonTranslation; ::rl::math::Vector lb; + ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::mt19937 randEngine; + double tolerance; + ::rl::math::Vector ub; }; } diff --git a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp index eb9ee2b2..9173ef9f 100644 --- a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp +++ b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp @@ -91,8 +91,8 @@ main(int argc, char** argv) kinematics->setPosition(qzero); kinematics->forwardPosition(); - ik.goals.clear(); - ik.goals.push_back(std::make_pair(t, 0)); + ik.clearGoals(); + ik.addGoal(t, 0); if (!ik.solve()) { From 2e9dcbfeff1b1a8ab7c0b0fbb69f0689d95277bf Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 16:19:24 +0200 Subject: [PATCH 200/546] Update rlInverseKinematicsMdlTest --- .../rlInverseKinematicsMdlTest.cpp | 144 +++++++----------- 1 file changed, 54 insertions(+), 90 deletions(-) diff --git a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp index 9173ef9f..9a3c7d7b 100644 --- a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp +++ b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp @@ -27,15 +27,12 @@ #include #include #include -#include -#include +#include #include #include #ifdef RL_MDL_NLOPT #include -#else -#include #endif int @@ -49,107 +46,74 @@ main(int argc, char** argv) try { - std::mt19937 randomGenerator(0); - std::uniform_real_distribution randomDistribution(-180 * rl::math::DEG2RAD, 180 * rl::math::DEG2RAD); + std::string filename = argv[1]; rl::mdl::XmlFactory factory; - std::shared_ptr model(factory.create(argv[1])); + std::shared_ptr model(factory.create(filename)); rl::mdl::Kinematic* kinematics = dynamic_cast(model.get()); + kinematics->seed(0); - std::size_t nTests; + std::vector, std::string>> ik; - rl::math::Vector q(6); - rl::math::Vector qinv(6); - rl::math::Vector qzero(6); - std::size_t n; - std::size_t wrongs; - std::size_t wrongT; - std::size_t ngotinverse; + std::shared_ptr jacobianSvd = std::make_shared(kinematics); + jacobianSvd->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_SVD); + ik.push_back(std::make_pair(jacobianSvd, "rl::mdl::JacobianInverseKinematics::METHOD_SVD")); - nTests = 100; + std::shared_ptr jacobianDls = std::make_shared(kinematics); + jacobianDls->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_DLS); + ik.push_back(std::make_pair(jacobianDls, "rl::mdl::JacobianInverseKinematics::METHOD_DLS")); + + std::shared_ptr jacobianTranspose = std::make_shared(kinematics); + jacobianTranspose->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE); + ik.push_back(std::make_pair(jacobianTranspose, "rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE")); #ifdef RL_MDL_NLOPT - rl::mdl::NloptInverseKinematics ik(kinematics); -#else - rl::mdl::JacobianInverseKinematics ik(kinematics); - ik.delta = static_cast(0.5); + std::shared_ptr nlopt = std::make_shared(kinematics); + ik.push_back(std::make_pair(nlopt, "rl::mdl::NloptInverseKinematics")); #endif - for (n = 0, wrongs = 0, wrongT = 0, ngotinverse = 0; n < nTests && wrongT < 100 && wrongs < 100; ++n) + for (std::size_t i = 0; i < ik.size(); ++i) { - for (std::size_t i = 0; i < 6; ++i) - { - q(i) = randomDistribution(randomGenerator); - qzero(i) = 0; - } - - kinematics->setPosition(q); - kinematics->forwardPosition(); - rl::math::Transform t = kinematics->getOperationalPosition(0); - - // For iterative inverse, set starting point far away - kinematics->setPosition(qzero); - kinematics->forwardPosition(); - - ik.clearGoals(); - ik.addGoal(t, 0); - - if (!ik.solve()) - { - continue; - } - - qinv = kinematics->getPosition(); - kinematics->forwardPosition(); - rl::math::Transform tinv = kinematics->getOperationalPosition(0); - - if ((t.matrix() - tinv.matrix()).norm() > 1e-5) - { - ++wrongT; - } - - if ((q - qinv).norm() > 1e-4) - { - ++wrongs; - } - - if (wrongT < 3 && (t.matrix() - tinv.matrix()).norm() > 1e-5) - { - std::cout << " q = " << q.transpose() << std::endl; - std::cout << " T = " << t.matrix() << std::endl; - std::cout << " qinv = " << qinv.transpose() << std::endl; - std::cout << " Tinv = " << tinv.matrix() << std::endl; - std::cout << std::endl; - } - - ++ngotinverse; - - - if (wrongT > 0) - { - std::cerr << "Error: " - << "Iterative inverse kinematics " << "on file " << argv[1] - << " gave incorrect poses." << std::endl; - return EXIT_FAILURE; - } + ik[i].first->setDuration(std::chrono::seconds(10)); - if (0 == ngotinverse) + for (std::size_t n = 0; n < 100; ++n) { - std::cerr << "Error: " - << "Iterative inverse kinematics "<< "on file " << argv[1] - << " gave no solutions." - << std::endl; - return EXIT_FAILURE; + rl::math::Vector q1 = kinematics->generatePositionUniform(); + kinematics->setPosition(q1); + kinematics->forwardPosition(); + rl::math::Transform t1 = kinematics->getOperationalPosition(0); + + rl::math::Vector q2 = kinematics->generatePositionUniform(); + kinematics->setPosition(q2); + ik[i].first->clearGoals(); + ik[i].first->addGoal(t1, 0); + + if (!ik[i].first->solve()) + { + std::cerr << ik[i].second << " on file " << filename << " with no solution." << std::endl; + std::cerr << "t1 = " << std::endl << t1.matrix() << std::endl; + std::cerr << "q1 = " << q1.transpose() << std::endl; + std::cerr << "q2 = " << q2.transpose() << std::endl; + return EXIT_FAILURE; + } + + rl::math::Vector q3 = kinematics->getPosition(); + kinematics->forwardPosition(); + rl::math::Transform t3 = kinematics->getOperationalPosition(0); + + if (!t3.isApprox(t1, static_cast(1.03-6))) + { + std::cerr << ik[i].second << " on file " << filename << " with incorrect operational position." << std::endl; + std::cerr << "norm(t1 - t3) = " << (t1.matrix() - t3.matrix()).norm() << std::endl; + std::cerr << "t1 = " << std::endl << t1.matrix() << std::endl; + std::cerr << "t3 = " << std::endl << t3.matrix() << std::endl; + std::cerr << "q1 = " << q1.transpose() << std::endl; + std::cerr << "q2 = " << q2.transpose() << std::endl; + std::cerr << "q3 = " << q3.transpose() << std::endl; + return EXIT_FAILURE; + } } } - std::cout << "Notice: " - << "Iterative inverse kinematics " - << "on file " << argv[1] << " " - << "tested with " << n << " cases, " - << ngotinverse << " returned a solution, " - << "thereof " << wrongs << " in wrong configuration, and " - << wrongT << " with completely wrong pose." - << std::endl; } catch (const std::exception& e) { From c98f8dde695842582b98fbc25782e150b97916e7 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 16:19:38 +0200 Subject: [PATCH 201/546] Update rlInverseKinematicsKinTest --- .../rlInverseKinematicsKinTest.cpp | 168 ++++++++---------- 1 file changed, 73 insertions(+), 95 deletions(-) diff --git a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp index 784f6ccc..da159f7e 100644 --- a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp +++ b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp @@ -27,10 +27,8 @@ #include #include #include -#include #include #include -#include int main(int argc, char** argv) @@ -43,112 +41,92 @@ main(int argc, char** argv) try { - std::mt19937 randomGenerator(0); - std::uniform_real_distribution randomDistribution(-180 * rl::math::DEG2RAD, 180 * rl::math::DEG2RAD); + std::string filename = argv[1]; - std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[1])); + std::shared_ptr kinematics(rl::kin::Kinematics::create(filename)); + kinematics->seed(0); - std::size_t nTests; - - rl::math::Vector q(6); - rl::math::Vector qinv(6); - rl::math::Vector qzero(6); - std::size_t n; - std::size_t wrongs; - std::size_t wrongT; - std::size_t ngotinverse; - - for (std::size_t ispuma = 0; ispuma < 2; ++ispuma) + for (std::size_t n = 0; n < 100; ++n) { - nTests = 0 == ispuma ? 1000 : 100; + rl::math::Vector q1 = kinematics->generatePositionUniform(); + kinematics->setPosition(q1); + kinematics->updateFrames(); + rl::math::Transform t1 = kinematics->forwardPosition(); + + rl::math::Vector q2 = kinematics->generatePositionUniform(); + kinematics->setPosition(q2); + + rl::math::Vector q3(kinematics->getDof()); - for (n = 0, wrongs = 0, wrongT = 0, ngotinverse = 0; n < nTests && wrongT < 100 && wrongs < 100; ++n) + bool solved = kinematics->inversePosition( + t1, + q3, + 0, + std::numeric_limits< ::rl::math::Real>::infinity(), + static_cast(1.0e-3), + 1000, + std::chrono::seconds(10) + ); + + if (!solved) { - for (std::size_t i = 0; i < 6; ++i) - { - q(i) = randomDistribution(randomGenerator); - qzero(i) = 0; - } - - kinematics->setPosition(q); - kinematics->updateFrames(); - - rl::math::Transform t = kinematics->forwardPosition(); - - // For iterative inverse, set starting point far away - kinematics->setPosition(qzero); - kinematics->updateFrames(); - - if (0 == ispuma) - { - rl::kin::Puma::Arm arm; - rl::kin::Puma::Elbow elbow; - rl::kin::Puma::Wrist wrist; - dynamic_cast(kinematics.get())->parameters(q, arm, elbow, wrist); - dynamic_cast(kinematics.get())->setArm(arm); - dynamic_cast(kinematics.get())->setElbow(elbow); - dynamic_cast(kinematics.get())->setWrist(wrist); - } - - if ( - 0 == ispuma - ? dynamic_cast< ::rl::kin::Puma*>(kinematics.get())->inversePosition(t, qinv) - : dynamic_cast< ::rl::kin::Kinematics*>(kinematics.get())->inversePosition(t, qinv, 0, 100) - ) - { - kinematics->setPosition(qinv); - kinematics->updateFrames(); - rl::math::Transform tinv = kinematics->forwardPosition(); - - if ((t.matrix() - tinv.matrix()).norm() > 1e-6) - { - ++wrongT; - } - - if ((q - qinv).norm() > 1e-4) - { - ++wrongs; - } - - if (true) //wrongT < 3 && (t.matrix() - tinv.matrix()).norm() > 1e-6) - { - std::cout << " q = " << q.transpose() << std::endl; - std::cout << " T = " << t.matrix() << std::endl; - std::cout << " qinv = " << qinv.transpose() << std::endl; - std::cout << " Tinv = " << tinv.matrix() << std::endl; - std::cout << std::endl; - } - - ++ngotinverse; - } + std::cerr << "rl::kin::Kinematics::inversePosition on file " << filename << " with no solution." << std::endl; + std::cerr << "t1 = " << std::endl << t1.matrix() << std::endl; + std::cerr << "q1 = " << q1.transpose() << std::endl; + std::cerr << "q2 = " << q2.transpose() << std::endl; + return EXIT_FAILURE; } - std::cout << "Notice: " - << (0 == ispuma ? "Puma direct " : "Iterative ") << "inverse kinematics " - << "on file " << argv[1] << " " - << "tested with " << n << " cases, " - << ngotinverse << " returned a solution, " - << "thereof " << wrongs << " in wrong configuration, and " - << wrongT << " with completely wrong pose." - << std::endl; + kinematics->setPosition(q3); + kinematics->updateFrames(); + rl::math::Transform t3 = kinematics->forwardPosition(); - if (wrongT > 0) + if (!t3.isApprox(t1, static_cast(1.03-6))) { - std::cerr << "Error: " - << (0 == ispuma ? "Puma direct " : "Iterative ") - << "inverse kinematics " << "on file " << argv[1] - << " gave incorrect poses." << std::endl; + std::cerr << "rl::kin::Kinematics::inversePosition on file " << filename << " with incorrect operational position." << std::endl; + std::cerr << "norm(t1 - t3) = " << (t1.matrix() - t3.matrix()).norm() << std::endl; + std::cerr << "t1 = " << std::endl << t1.matrix() << std::endl; + std::cerr << "t3 = " << std::endl << t3.matrix() << std::endl; + std::cerr << "q1 = " << q1.transpose() << std::endl; + std::cerr << "q2 = " << q2.transpose() << std::endl; + std::cerr << "q3 = " << q3.transpose() << std::endl; return EXIT_FAILURE; } - if (0 == ngotinverse) + if (rl::kin::Puma* puma = dynamic_cast(kinematics.get())) { - std::cerr << "Error: " - << (0 == ispuma ? "Puma direct " : "Iterative ") - << "inverse kinematics "<< "on file " << argv[1] - << " gave no solutions." - << std::endl; - return EXIT_FAILURE; + rl::kin::Puma::Arm arm; + rl::kin::Puma::Elbow elbow; + rl::kin::Puma::Wrist wrist; + puma->parameters(q1, arm, elbow, wrist); + puma->setArm(arm); + puma->setElbow(elbow); + puma->setWrist(wrist); + + rl::math::Vector q4(puma->getDof()); + + if (!puma->inversePosition(t1, q4, true)) + { + std::cerr << "rl::kin::Puma::inversePosition on file " << filename << " with no solution." << std::endl; + std::cerr << "t1 = " << std::endl << t1.matrix() << std::endl; + std::cerr << "q1 = " << q1.transpose() << std::endl; + return EXIT_FAILURE; + } + + puma->setPosition(q4); + puma->updateFrames(); + rl::math::Transform t4 = puma->forwardPosition(); + + if (!t4.isApprox(t1, static_cast(1.03-6))) + { + std::cerr << "rl::kin::Puma::inversePosition on file " << filename << " with incorrect operational position." << std::endl; + std::cerr << "norm(t1 - t4) = " << (t1.matrix() - t4.matrix()).norm() << std::endl; + std::cerr << "t1 = " << std::endl << t1.matrix() << std::endl; + std::cerr << "t4 = " << std::endl << t4.matrix() << std::endl; + std::cerr << "q1 = " << q1.transpose() << std::endl; + std::cerr << "q4 = " << q4.transpose() << std::endl; + return EXIT_FAILURE; + } } } } From 946498bf4426c11b2228f3f19464c7d4b0a2dfc0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 16:40:45 +0200 Subject: [PATCH 202/546] Add copy assignment operator --- src/rl/hal/Socket.cpp | 17 +++++++++++++++++ src/rl/hal/Socket.h | 4 ++++ 2 files changed, 21 insertions(+) diff --git a/src/rl/hal/Socket.cpp b/src/rl/hal/Socket.cpp index 26723973..342f625f 100644 --- a/src/rl/hal/Socket.cpp +++ b/src/rl/hal/Socket.cpp @@ -356,6 +356,16 @@ namespace rl this->setConnected(true); } + Socket& + Socket::operator=(const Socket& other) + { + this->address = other.address; + this->fd = other.fd; + this->protocol = other.protocol; + this->type = other.type; + return *this; + } + ::std::size_t Socket::recv(void* buf, const ::std::size_t& count) { @@ -764,6 +774,13 @@ namespace rl return host; } + Socket::Address& + Socket::Address::operator=(const Socket::Address& other) + { + this->addr = other.addr; + return *this; + } + void Socket::Address::setInfo(const ::std::string& string, const unsigned short int& port, const bool& asNumeric) { diff --git a/src/rl/hal/Socket.h b/src/rl/hal/Socket.h index d84adf0e..b20129db 100644 --- a/src/rl/hal/Socket.h +++ b/src/rl/hal/Socket.h @@ -72,6 +72,8 @@ namespace rl ::std::string getNameInfo(const bool& asNumeric = false) const; + Socket::Address& operator=(const Socket::Address& other); + void setInfo(const ::std::string& string, const unsigned short int& port, const bool& asNumeric = false); void setInfo(const ::std::string& string, const ::std::string& port, const bool& asNumeric = false); @@ -126,6 +128,8 @@ namespace rl void open(); + Socket& operator=(const Socket& other); + ::std::size_t recv(void* buf, const ::std::size_t& count); ::std::size_t recvfrom(void* buf, const ::std::size_t& count, Address& address); From 5bbd77315ec5b510d0945451f9d339a937c887e0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 16:46:42 +0200 Subject: [PATCH 203/546] Minor update --- src/rl/sg/UrdfFactory.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 28b1cf62..99801730 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -310,11 +310,11 @@ ::std::cout << "\tcylinder radius: " << cylinder->radius.getValue() << ::std::en { if (!shapes[k].getProperty("filename").empty()) { - ::std::string filename = shapes[k].getLocalPath(shapes[k].getProperty("filename")); -::std::cout << "\tmesh filename: " << filename << ::std::endl; + ::std::string meshFilename = shapes[k].getLocalPath(shapes[k].getProperty("filename")); +::std::cout << "\tmesh filename: " << meshFilename << ::std::endl; #if defined(HAVE_SOSTLFILEKIT_H) && defined(HAVE_SOSTLFILEKIT_CONVERT) - if (!boost::iends_with(filename, "stl")) + if (!boost::iends_with(meshFilename, "stl")) { throw Exception("rl::sg::UrdfFactory::load() - Only STL meshes currently supported"); } @@ -322,9 +322,9 @@ ::std::cout << "\tmesh filename: " << filename << ::std::endl; ::SoSTLFileKit* stlFileKit = new ::SoSTLFileKit(); stlFileKit->ref(); - if (!stlFileKit->readFile(filename.c_str())) + if (!stlFileKit->readFile(meshFilename.c_str())) { - throw Exception("rl::sg::UrdfFactory::load() - Failed to open file '" + filename + "'"); + throw Exception("rl::sg::UrdfFactory::load() - Failed to open file '" + meshFilename + "'"); } ::SoSeparator* stl = stlFileKit->convert(); From be750e483b11352a48a6b0d252063828be247176 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 13 Apr 2019 23:23:08 +0200 Subject: [PATCH 204/546] Use C++ visibility support and export symbols --- CMakeLists.txt | 16 ++++++++++++---- src/rl/hal/AnalogInput.h | 2 +- src/rl/hal/AnalogInputReader.h | 2 +- src/rl/hal/AnalogInputWriter.h | 2 +- src/rl/hal/AnalogOutput.h | 2 +- src/rl/hal/AnalogOutputReader.h | 2 +- src/rl/hal/AnalogOutputWriter.h | 2 +- src/rl/hal/Ati.h | 2 +- src/rl/hal/AxisController.h | 2 +- src/rl/hal/CMakeLists.txt | 9 +++++++++ src/rl/hal/Camera.h | 2 +- src/rl/hal/CartesianForceSensor.h | 2 +- src/rl/hal/CartesianPositionActuator.h | 2 +- src/rl/hal/CartesianPositionSensor.h | 2 +- src/rl/hal/CartesianVelocitySensor.h | 2 +- src/rl/hal/Coach.h | 2 +- src/rl/hal/Com.h | 4 +++- src/rl/hal/ComException.h | 2 +- src/rl/hal/Comedi.h | 2 +- src/rl/hal/CyclicDevice.h | 2 +- src/rl/hal/Dc1394Camera.h | 2 +- src/rl/hal/Device.h | 3 ++- src/rl/hal/DeviceException.h | 2 +- src/rl/hal/DigitalInput.h | 2 +- src/rl/hal/DigitalInputReader.h | 2 +- src/rl/hal/DigitalInputWriter.h | 2 +- src/rl/hal/DigitalOutput.h | 2 +- src/rl/hal/DigitalOutputReader.h | 2 +- src/rl/hal/DigitalOutputWriter.h | 2 +- src/rl/hal/Endian.h | 3 ++- src/rl/hal/Exception.h | 1 + src/rl/hal/Fieldbus.h | 2 +- src/rl/hal/ForceSensor.h | 2 +- src/rl/hal/Gnuplot.h | 2 +- src/rl/hal/Gripper.h | 2 +- src/rl/hal/HilscherCifx.h | 2 +- src/rl/hal/JointAccelerationActuator.h | 2 +- src/rl/hal/JointCurrentSensor.h | 2 +- src/rl/hal/JointPositionActuator.h | 2 +- src/rl/hal/JointPositionSensor.h | 2 +- src/rl/hal/JointTorqueActuator.h | 2 +- src/rl/hal/JointTorqueSensor.h | 2 +- src/rl/hal/JointVelocityActuator.h | 2 +- src/rl/hal/JointVelocitySensor.h | 2 +- src/rl/hal/Jr3.h | 2 +- src/rl/hal/LeuzeRs4.h | 2 +- src/rl/hal/Lidar.h | 2 +- src/rl/hal/MitsubishiH7.h | 2 +- src/rl/hal/MitsubishiR3.h | 2 +- src/rl/hal/RangeSensor.h | 2 +- src/rl/hal/RobotiqModelC.h | 2 +- src/rl/hal/SchmersalLss300.h | 2 +- src/rl/hal/SchunkFpsF5.h | 2 +- src/rl/hal/Serial.h | 2 +- src/rl/hal/SickLms200.h | 2 +- src/rl/hal/SickS300.h | 2 +- src/rl/hal/SixAxisForceTorqueSensor.h | 2 +- src/rl/hal/Socket.h | 4 ++-- src/rl/hal/TimeoutException.h | 2 +- src/rl/hal/TorqueSensor.h | 2 +- src/rl/hal/UniversalRobotsDashboard.h | 2 +- src/rl/hal/UniversalRobotsRealtime.h | 2 +- src/rl/hal/UniversalRobotsRtde.h | 2 +- src/rl/hal/WeissException.h | 2 +- src/rl/hal/WeissKms40.h | 2 +- src/rl/hal/WeissWsg50.h | 2 +- src/rl/kin/CMakeLists.txt | 9 +++++++++ src/rl/kin/Element.h | 3 ++- src/rl/kin/Exception.h | 3 ++- src/rl/kin/Frame.h | 2 +- src/rl/kin/Joint.h | 2 +- src/rl/kin/Kinematics.h | 3 ++- src/rl/kin/Link.h | 2 +- src/rl/kin/Prismatic.h | 2 +- src/rl/kin/Puma.h | 2 +- src/rl/kin/Revolute.h | 2 +- src/rl/kin/Rhino.h | 2 +- src/rl/kin/Transform.h | 2 +- src/rl/mdl/AnalyticalInverseKinematics.h | 2 +- src/rl/mdl/Body.h | 2 +- src/rl/mdl/CMakeLists.txt | 9 +++++++++ src/rl/mdl/Compound.h | 2 +- src/rl/mdl/Cylindrical.h | 2 +- src/rl/mdl/Dynamic.h | 2 +- src/rl/mdl/Element.h | 4 +++- src/rl/mdl/EulerCauchyIntegrator.h | 2 +- src/rl/mdl/Exception.h | 3 ++- src/rl/mdl/Factory.h | 3 ++- src/rl/mdl/Fixed.h | 2 +- src/rl/mdl/Frame.h | 2 +- src/rl/mdl/Helical.h | 2 +- src/rl/mdl/Integrator.h | 3 ++- src/rl/mdl/InverseKinematics.h | 3 ++- src/rl/mdl/IterativeInverseKinematics.h | 2 +- src/rl/mdl/JacobianInverseKinematics.h | 2 +- src/rl/mdl/Joint.h | 2 +- src/rl/mdl/Kinematic.h | 2 +- src/rl/mdl/Metric.h | 2 +- src/rl/mdl/Model.h | 2 +- src/rl/mdl/NloptInverseKinematics.h | 2 +- src/rl/mdl/Prismatic.h | 2 +- src/rl/mdl/Revolute.h | 2 +- src/rl/mdl/RungeKuttaNystromIntegrator.h | 2 +- src/rl/mdl/SixDof.h | 2 +- src/rl/mdl/Spherical.h | 2 +- src/rl/mdl/Transform.h | 2 +- src/rl/mdl/UrdfFactory.h | 2 +- src/rl/mdl/World.h | 2 +- src/rl/mdl/XmlFactory.h | 2 +- src/rl/plan/AddRrtConCon.h | 2 +- src/rl/plan/AdvancedOptimizer.h | 2 +- src/rl/plan/BridgeSampler.h | 2 +- src/rl/plan/CMakeLists.txt | 9 +++++++++ src/rl/plan/DistanceModel.h | 2 +- src/rl/plan/Eet.h | 2 +- src/rl/plan/Exception.h | 3 ++- src/rl/plan/GaussianSampler.h | 2 +- src/rl/plan/GnatNearestNeighbors.h | 2 +- src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h | 2 +- src/rl/plan/KdtreeNearestNeighbors.h | 2 +- src/rl/plan/LinearNearestNeighbors.h | 2 +- src/rl/plan/Metric.h | 3 ++- src/rl/plan/Model.h | 3 ++- src/rl/plan/NearestNeighbors.h | 2 +- src/rl/plan/Optimizer.h | 4 +++- src/rl/plan/Planner.h | 3 ++- src/rl/plan/Prm.h | 2 +- src/rl/plan/PrmUtilityGuided.h | 2 +- src/rl/plan/RecursiveVerifier.h | 2 +- src/rl/plan/Rrt.h | 2 +- src/rl/plan/RrtCon.h | 2 +- src/rl/plan/RrtConCon.h | 2 +- src/rl/plan/RrtDual.h | 2 +- src/rl/plan/RrtExtCon.h | 2 +- src/rl/plan/RrtExtExt.h | 2 +- src/rl/plan/RrtGoalBias.h | 2 +- src/rl/plan/Sampler.h | 3 ++- src/rl/plan/SequentialVerifier.h | 2 +- src/rl/plan/SimpleModel.h | 2 +- src/rl/plan/SimpleOptimizer.h | 2 +- src/rl/plan/UniformSampler.h | 2 +- src/rl/plan/Verifier.h | 3 ++- src/rl/plan/Viewer.h | 3 ++- src/rl/plan/WorkspaceMetric.h | 3 ++- src/rl/plan/WorkspaceSphere.h | 3 ++- src/rl/plan/WorkspaceSphereExplorer.h | 2 +- src/rl/sg/Base.h | 4 +++- src/rl/sg/Body.h | 2 +- src/rl/sg/CMakeLists.txt | 9 +++++++++ src/rl/sg/DepthScene.h | 2 +- src/rl/sg/DistanceScene.h | 2 +- src/rl/sg/Exception.h | 3 ++- src/rl/sg/Factory.h | 3 ++- src/rl/sg/Model.h | 2 +- src/rl/sg/RaycastScene.h | 2 +- src/rl/sg/Scene.h | 2 +- src/rl/sg/Shape.h | 2 +- src/rl/sg/SimpleScene.h | 2 +- src/rl/sg/UrdfFactory.h | 2 +- src/rl/sg/XmlFactory.h | 2 +- src/rl/sg/bullet/Body.h | 2 +- src/rl/sg/bullet/Model.h | 2 +- src/rl/sg/bullet/Scene.h | 2 +- src/rl/sg/bullet/Shape.h | 2 +- src/rl/sg/fcl/Body.h | 2 +- src/rl/sg/fcl/Model.h | 2 +- src/rl/sg/fcl/Scene.h | 2 +- src/rl/sg/fcl/Shape.h | 2 +- src/rl/sg/ode/Body.h | 2 +- src/rl/sg/ode/Model.h | 2 +- src/rl/sg/ode/Scene.h | 2 +- src/rl/sg/ode/Shape.h | 2 +- src/rl/sg/pqp/Body.h | 2 +- src/rl/sg/pqp/Model.h | 2 +- src/rl/sg/pqp/Scene.h | 2 +- src/rl/sg/pqp/Shape.h | 2 +- src/rl/sg/so/Body.h | 2 +- src/rl/sg/so/Model.h | 2 +- src/rl/sg/so/Scene.h | 2 +- src/rl/sg/so/Shape.h | 2 +- src/rl/sg/solid/Body.h | 2 +- src/rl/sg/solid/Model.h | 2 +- src/rl/sg/solid/Scene.h | 2 +- src/rl/sg/solid/Shape.h | 2 +- 184 files changed, 264 insertions(+), 182 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4102b5e2..649b83ae 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,6 +12,7 @@ list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake) include(CheckCXXCompilerFlag) include(CMakeDependentOption) include(CMakePackageConfigHelpers) +include(GenerateExportHeader) include(GNUInstallDirs) if(NOT CMAKE_VERSION VERSION_LESS 3.1) @@ -28,6 +29,16 @@ else() endif() endif() +if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) + set(CMAKE_C_VISIBILITY_PRESET hidden) + set(CMAKE_CXX_VISIBILITY_PRESET hidden) + set(CMAKE_VISIBILITY_INLINES_HIDDEN ON) +endif() + +set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) +set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) +set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) + if(WIN32) add_definitions( -D_ENABLE_EXTENDED_ALIGNED_STORAGE @@ -57,11 +68,8 @@ cmake_dependent_option(BUILD_RL_SG "Build scene graph abstraction component" ON cmake_dependent_option(BUILD_RL_PLAN "Build path planning component" ON "BUILD_RL_KIN;BUILD_RL_MATH;BUILD_RL_MDL;BUILD_RL_SG;BUILD_RL_UTIL;BUILD_RL_XML" OFF) -if(WIN32 AND CMAKE_VERSION VERSION_LESS 3.4) - set(BUILD_SHARED_LIBS OFF) -elseif(WIN32 AND NOT CMAKE_VERSION VERSION_LESS 3.4) +if(WIN32) option(BUILD_SHARED_LIBS "Build shared libraries" OFF) - set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS ${BUILD_SHARED_LIBS}) else() option(BUILD_SHARED_LIBS "Build shared libraries" ON) endif() diff --git a/src/rl/hal/AnalogInput.h b/src/rl/hal/AnalogInput.h index deb3815b..6c711ab3 100644 --- a/src/rl/hal/AnalogInput.h +++ b/src/rl/hal/AnalogInput.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class AnalogInput : public virtual Device + class RL_HAL_EXPORT AnalogInput : public virtual Device { public: AnalogInput(); diff --git a/src/rl/hal/AnalogInputReader.h b/src/rl/hal/AnalogInputReader.h index 6002ce78..84cf52a4 100644 --- a/src/rl/hal/AnalogInputReader.h +++ b/src/rl/hal/AnalogInputReader.h @@ -36,7 +36,7 @@ namespace rl { namespace hal { - class AnalogInputReader : public virtual AnalogInput + class RL_HAL_EXPORT AnalogInputReader : public virtual AnalogInput { public: AnalogInputReader(); diff --git a/src/rl/hal/AnalogInputWriter.h b/src/rl/hal/AnalogInputWriter.h index fc2648c6..a6a0aee3 100644 --- a/src/rl/hal/AnalogInputWriter.h +++ b/src/rl/hal/AnalogInputWriter.h @@ -36,7 +36,7 @@ namespace rl { namespace hal { - class AnalogInputWriter : public virtual AnalogInput + class RL_HAL_EXPORT AnalogInputWriter : public virtual AnalogInput { public: AnalogInputWriter(); diff --git a/src/rl/hal/AnalogOutput.h b/src/rl/hal/AnalogOutput.h index 6c093723..63a3445a 100644 --- a/src/rl/hal/AnalogOutput.h +++ b/src/rl/hal/AnalogOutput.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class AnalogOutput : public virtual Device + class RL_HAL_EXPORT AnalogOutput : public virtual Device { public: AnalogOutput(); diff --git a/src/rl/hal/AnalogOutputReader.h b/src/rl/hal/AnalogOutputReader.h index cf494a0d..d6f6470c 100644 --- a/src/rl/hal/AnalogOutputReader.h +++ b/src/rl/hal/AnalogOutputReader.h @@ -36,7 +36,7 @@ namespace rl { namespace hal { - class AnalogOutputReader : public virtual AnalogOutput + class RL_HAL_EXPORT AnalogOutputReader : public virtual AnalogOutput { public: AnalogOutputReader(); diff --git a/src/rl/hal/AnalogOutputWriter.h b/src/rl/hal/AnalogOutputWriter.h index 016d386f..f471860a 100644 --- a/src/rl/hal/AnalogOutputWriter.h +++ b/src/rl/hal/AnalogOutputWriter.h @@ -36,7 +36,7 @@ namespace rl { namespace hal { - class AnalogOutputWriter : public virtual AnalogOutput + class RL_HAL_EXPORT AnalogOutputWriter : public virtual AnalogOutput { public: AnalogOutputWriter(); diff --git a/src/rl/hal/Ati.h b/src/rl/hal/Ati.h index 0ddd43d1..5e8a722c 100644 --- a/src/rl/hal/Ati.h +++ b/src/rl/hal/Ati.h @@ -41,7 +41,7 @@ namespace rl /** * ATI Industrial Automation force-torque sensor. */ - class Ati : public CyclicDevice, public SixAxisForceTorqueSensor + class RL_HAL_EXPORT Ati : public CyclicDevice, public SixAxisForceTorqueSensor { public: Ati( diff --git a/src/rl/hal/AxisController.h b/src/rl/hal/AxisController.h index 2ef38bab..e43600f2 100644 --- a/src/rl/hal/AxisController.h +++ b/src/rl/hal/AxisController.h @@ -36,7 +36,7 @@ namespace rl { namespace hal { - class AxisController : public virtual Device + class RL_HAL_EXPORT AxisController : public virtual Device { public: AxisController(const ::std::size_t& dof); diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 527eb094..b2c3755a 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -207,6 +207,7 @@ endif() target_include_directories( hal PUBLIC + $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> ${Boost_INCLUDE_DIR} @@ -289,3 +290,11 @@ endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() + +generate_export_header( + hal + EXPORT_FILE_NAME export.h + PREFIX_NAME RL_ +) + +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/hal COMPONENT development) diff --git a/src/rl/hal/Camera.h b/src/rl/hal/Camera.h index 8f4d2f96..416ea47f 100644 --- a/src/rl/hal/Camera.h +++ b/src/rl/hal/Camera.h @@ -33,7 +33,7 @@ namespace rl { namespace hal { - class Camera : public virtual Device + class RL_HAL_EXPORT Camera : public virtual Device { public: Camera(); diff --git a/src/rl/hal/CartesianForceSensor.h b/src/rl/hal/CartesianForceSensor.h index 84c9bf1b..5a275f21 100644 --- a/src/rl/hal/CartesianForceSensor.h +++ b/src/rl/hal/CartesianForceSensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class CartesianForceSensor : public virtual AxisController + class RL_HAL_EXPORT CartesianForceSensor : public virtual AxisController { public: CartesianForceSensor(const ::std::size_t& dof); diff --git a/src/rl/hal/CartesianPositionActuator.h b/src/rl/hal/CartesianPositionActuator.h index 22759901..b62f629b 100644 --- a/src/rl/hal/CartesianPositionActuator.h +++ b/src/rl/hal/CartesianPositionActuator.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class CartesianPositionActuator : public virtual AxisController + class RL_HAL_EXPORT CartesianPositionActuator : public virtual AxisController { public: CartesianPositionActuator(const ::std::size_t& dof); diff --git a/src/rl/hal/CartesianPositionSensor.h b/src/rl/hal/CartesianPositionSensor.h index 17a5521b..42ecfe3f 100644 --- a/src/rl/hal/CartesianPositionSensor.h +++ b/src/rl/hal/CartesianPositionSensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class CartesianPositionSensor : public virtual AxisController + class RL_HAL_EXPORT CartesianPositionSensor : public virtual AxisController { public: CartesianPositionSensor(const ::std::size_t& dof); diff --git a/src/rl/hal/CartesianVelocitySensor.h b/src/rl/hal/CartesianVelocitySensor.h index c92245b9..17464a3e 100644 --- a/src/rl/hal/CartesianVelocitySensor.h +++ b/src/rl/hal/CartesianVelocitySensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class CartesianVelocitySensor : public virtual AxisController + class RL_HAL_EXPORT CartesianVelocitySensor : public virtual AxisController { public: CartesianVelocitySensor(const ::std::size_t& dof); diff --git a/src/rl/hal/Coach.h b/src/rl/hal/Coach.h index baf97e24..21e0325f 100644 --- a/src/rl/hal/Coach.h +++ b/src/rl/hal/Coach.h @@ -42,7 +42,7 @@ namespace rl { namespace hal { - class Coach : public CyclicDevice, public JointPositionActuator, public JointPositionSensor, public JointTorqueActuator, public JointVelocityActuator + class RL_HAL_EXPORT Coach : public CyclicDevice, public JointPositionActuator, public JointPositionSensor, public JointTorqueActuator, public JointVelocityActuator { public: Coach( diff --git a/src/rl/hal/Com.h b/src/rl/hal/Com.h index 7090fe10..54287db7 100644 --- a/src/rl/hal/Com.h +++ b/src/rl/hal/Com.h @@ -27,11 +27,13 @@ #ifndef RL_HAL_COM_H #define RL_HAL_COM_H +#include + namespace rl { namespace hal { - class Com + class RL_HAL_EXPORT Com { public: Com(); diff --git a/src/rl/hal/ComException.h b/src/rl/hal/ComException.h index 16b7df3e..3065caf1 100644 --- a/src/rl/hal/ComException.h +++ b/src/rl/hal/ComException.h @@ -33,7 +33,7 @@ namespace rl { namespace hal { - class ComException : public Exception + class RL_HAL_EXPORT ComException : public Exception { public: ComException(const ::std::string& what_arg); diff --git a/src/rl/hal/Comedi.h b/src/rl/hal/Comedi.h index ce29b81e..c01d5441 100644 --- a/src/rl/hal/Comedi.h +++ b/src/rl/hal/Comedi.h @@ -36,7 +36,7 @@ namespace rl { namespace hal { - class Comedi : public Com + class RL_HAL_EXPORT Comedi : public Com { public: Comedi(const ::std::string& filename = "/dev/comedi0"); diff --git a/src/rl/hal/CyclicDevice.h b/src/rl/hal/CyclicDevice.h index 976fb19e..1a85d3ab 100644 --- a/src/rl/hal/CyclicDevice.h +++ b/src/rl/hal/CyclicDevice.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class CyclicDevice : public virtual Device + class RL_HAL_EXPORT CyclicDevice : public virtual Device { public: CyclicDevice(const ::std::chrono::nanoseconds& updateRate); diff --git a/src/rl/hal/Dc1394Camera.h b/src/rl/hal/Dc1394Camera.h index 9bc1d784..2f6f4016 100644 --- a/src/rl/hal/Dc1394Camera.h +++ b/src/rl/hal/Dc1394Camera.h @@ -47,7 +47,7 @@ namespace rl /** * IEEE 1394 based cameras. */ - class Dc1394Camera : public Camera, public CyclicDevice + class RL_HAL_EXPORT Dc1394Camera : public Camera, public CyclicDevice { public: enum ColorCoding diff --git a/src/rl/hal/Device.h b/src/rl/hal/Device.h index ee9fc9a0..66353631 100644 --- a/src/rl/hal/Device.h +++ b/src/rl/hal/Device.h @@ -29,6 +29,7 @@ #include #include +#include namespace rl { @@ -37,7 +38,7 @@ namespace rl */ namespace hal { - class Device + class RL_HAL_EXPORT Device { public: Device(); diff --git a/src/rl/hal/DeviceException.h b/src/rl/hal/DeviceException.h index 03687786..1351d6d8 100644 --- a/src/rl/hal/DeviceException.h +++ b/src/rl/hal/DeviceException.h @@ -33,7 +33,7 @@ namespace rl { namespace hal { - class DeviceException : public Exception + class RL_HAL_EXPORT DeviceException : public Exception { public: DeviceException(const ::std::string& what_arg); diff --git a/src/rl/hal/DigitalInput.h b/src/rl/hal/DigitalInput.h index 7339a559..9a98be44 100644 --- a/src/rl/hal/DigitalInput.h +++ b/src/rl/hal/DigitalInput.h @@ -33,7 +33,7 @@ namespace rl { namespace hal { - class DigitalInput : public virtual Device + class RL_HAL_EXPORT DigitalInput : public virtual Device { public: DigitalInput(); diff --git a/src/rl/hal/DigitalInputReader.h b/src/rl/hal/DigitalInputReader.h index ee3efe33..fadf8d5e 100644 --- a/src/rl/hal/DigitalInputReader.h +++ b/src/rl/hal/DigitalInputReader.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class DigitalInputReader : public virtual DigitalInput + class RL_HAL_EXPORT DigitalInputReader : public virtual DigitalInput { public: DigitalInputReader(); diff --git a/src/rl/hal/DigitalInputWriter.h b/src/rl/hal/DigitalInputWriter.h index d4ac4c38..c3d65624 100644 --- a/src/rl/hal/DigitalInputWriter.h +++ b/src/rl/hal/DigitalInputWriter.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class DigitalInputWriter : public virtual DigitalInput + class RL_HAL_EXPORT DigitalInputWriter : public virtual DigitalInput { public: DigitalInputWriter(); diff --git a/src/rl/hal/DigitalOutput.h b/src/rl/hal/DigitalOutput.h index 4e72ce94..6ebc4a24 100644 --- a/src/rl/hal/DigitalOutput.h +++ b/src/rl/hal/DigitalOutput.h @@ -33,7 +33,7 @@ namespace rl { namespace hal { - class DigitalOutput : public virtual Device + class RL_HAL_EXPORT DigitalOutput : public virtual Device { public: DigitalOutput(); diff --git a/src/rl/hal/DigitalOutputReader.h b/src/rl/hal/DigitalOutputReader.h index c885c350..bf179549 100644 --- a/src/rl/hal/DigitalOutputReader.h +++ b/src/rl/hal/DigitalOutputReader.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class DigitalOutputReader : public virtual DigitalOutput + class RL_HAL_EXPORT DigitalOutputReader : public virtual DigitalOutput { public: DigitalOutputReader(); diff --git a/src/rl/hal/DigitalOutputWriter.h b/src/rl/hal/DigitalOutputWriter.h index 3a592f00..507a7659 100644 --- a/src/rl/hal/DigitalOutputWriter.h +++ b/src/rl/hal/DigitalOutputWriter.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class DigitalOutputWriter : public virtual DigitalOutput + class RL_HAL_EXPORT DigitalOutputWriter : public virtual DigitalOutput { public: DigitalOutputWriter(); diff --git a/src/rl/hal/Endian.h b/src/rl/hal/Endian.h index 12f23399..b15d8912 100644 --- a/src/rl/hal/Endian.h +++ b/src/rl/hal/Endian.h @@ -28,12 +28,13 @@ #define RL_HAL_ENDIAN_H #include +#include namespace rl { namespace hal { - class Endian + class RL_HAL_EXPORT Endian { public: static ::std::uint32_t bigDoubleWord(const ::std::uint16_t& highWord, const ::std::uint16_t& lowWord); diff --git a/src/rl/hal/Exception.h b/src/rl/hal/Exception.h index 1858b628..b324c240 100644 --- a/src/rl/hal/Exception.h +++ b/src/rl/hal/Exception.h @@ -29,6 +29,7 @@ #include #include +#include namespace rl { diff --git a/src/rl/hal/Fieldbus.h b/src/rl/hal/Fieldbus.h index fb669bac..21e63998 100644 --- a/src/rl/hal/Fieldbus.h +++ b/src/rl/hal/Fieldbus.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class Fieldbus : public Com + class RL_HAL_EXPORT Fieldbus : public Com { public: Fieldbus(); diff --git a/src/rl/hal/ForceSensor.h b/src/rl/hal/ForceSensor.h index c77ba5bd..d2a58cf8 100644 --- a/src/rl/hal/ForceSensor.h +++ b/src/rl/hal/ForceSensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class ForceSensor : public virtual Device + class RL_HAL_EXPORT ForceSensor : public virtual Device { public: ForceSensor(); diff --git a/src/rl/hal/Gnuplot.h b/src/rl/hal/Gnuplot.h index 100ed378..37207851 100644 --- a/src/rl/hal/Gnuplot.h +++ b/src/rl/hal/Gnuplot.h @@ -36,7 +36,7 @@ namespace rl { namespace hal { - class Gnuplot : public CyclicDevice, public JointPositionActuator + class RL_HAL_EXPORT Gnuplot : public CyclicDevice, public JointPositionActuator { public: Gnuplot( diff --git a/src/rl/hal/Gripper.h b/src/rl/hal/Gripper.h index 1207e1a4..dbead85b 100644 --- a/src/rl/hal/Gripper.h +++ b/src/rl/hal/Gripper.h @@ -33,7 +33,7 @@ namespace rl { namespace hal { - class Gripper : public virtual Device + class RL_HAL_EXPORT Gripper : public virtual Device { public: Gripper(); diff --git a/src/rl/hal/HilscherCifx.h b/src/rl/hal/HilscherCifx.h index f99d96b1..8c7d3cdc 100644 --- a/src/rl/hal/HilscherCifx.h +++ b/src/rl/hal/HilscherCifx.h @@ -39,7 +39,7 @@ namespace rl { namespace hal { - class HilscherCifx : public Fieldbus + class RL_HAL_EXPORT HilscherCifx : public Fieldbus { public: class Exception : public ComException diff --git a/src/rl/hal/JointAccelerationActuator.h b/src/rl/hal/JointAccelerationActuator.h index fb6295df..93123663 100644 --- a/src/rl/hal/JointAccelerationActuator.h +++ b/src/rl/hal/JointAccelerationActuator.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class JointAccelerationActuator : public virtual AxisController + class RL_HAL_EXPORT JointAccelerationActuator : public virtual AxisController { public: JointAccelerationActuator(const ::std::size_t& dof); diff --git a/src/rl/hal/JointCurrentSensor.h b/src/rl/hal/JointCurrentSensor.h index 3569c70a..07faf5bc 100644 --- a/src/rl/hal/JointCurrentSensor.h +++ b/src/rl/hal/JointCurrentSensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class JointCurrentSensor : public virtual AxisController + class RL_HAL_EXPORT JointCurrentSensor : public virtual AxisController { public: JointCurrentSensor(const ::std::size_t& dof); diff --git a/src/rl/hal/JointPositionActuator.h b/src/rl/hal/JointPositionActuator.h index 426aa075..54cbc0f8 100644 --- a/src/rl/hal/JointPositionActuator.h +++ b/src/rl/hal/JointPositionActuator.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class JointPositionActuator : public virtual AxisController + class RL_HAL_EXPORT JointPositionActuator : public virtual AxisController { public: JointPositionActuator(const ::std::size_t& dof); diff --git a/src/rl/hal/JointPositionSensor.h b/src/rl/hal/JointPositionSensor.h index ba2cef28..bfb41065 100644 --- a/src/rl/hal/JointPositionSensor.h +++ b/src/rl/hal/JointPositionSensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class JointPositionSensor : public virtual AxisController + class RL_HAL_EXPORT JointPositionSensor : public virtual AxisController { public: JointPositionSensor(const ::std::size_t& dof); diff --git a/src/rl/hal/JointTorqueActuator.h b/src/rl/hal/JointTorqueActuator.h index 1bdc8753..275a30b8 100644 --- a/src/rl/hal/JointTorqueActuator.h +++ b/src/rl/hal/JointTorqueActuator.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class JointTorqueActuator : public virtual AxisController + class RL_HAL_EXPORT JointTorqueActuator : public virtual AxisController { public: JointTorqueActuator(const ::std::size_t& dof); diff --git a/src/rl/hal/JointTorqueSensor.h b/src/rl/hal/JointTorqueSensor.h index b7842d4f..e8c52bf2 100644 --- a/src/rl/hal/JointTorqueSensor.h +++ b/src/rl/hal/JointTorqueSensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class JointTorqueSensor : public virtual AxisController + class RL_HAL_EXPORT JointTorqueSensor : public virtual AxisController { public: JointTorqueSensor(const ::std::size_t& dof); diff --git a/src/rl/hal/JointVelocityActuator.h b/src/rl/hal/JointVelocityActuator.h index e046d96e..4a60f664 100644 --- a/src/rl/hal/JointVelocityActuator.h +++ b/src/rl/hal/JointVelocityActuator.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class JointVelocityActuator : public virtual AxisController + class RL_HAL_EXPORT JointVelocityActuator : public virtual AxisController { public: JointVelocityActuator(const ::std::size_t& dof); diff --git a/src/rl/hal/JointVelocitySensor.h b/src/rl/hal/JointVelocitySensor.h index 66317570..c6473d94 100644 --- a/src/rl/hal/JointVelocitySensor.h +++ b/src/rl/hal/JointVelocitySensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class JointVelocitySensor : public virtual AxisController + class RL_HAL_EXPORT JointVelocitySensor : public virtual AxisController { public: JointVelocitySensor(const ::std::size_t& dof); diff --git a/src/rl/hal/Jr3.h b/src/rl/hal/Jr3.h index 4ef1342f..eda6b2ae 100644 --- a/src/rl/hal/Jr3.h +++ b/src/rl/hal/Jr3.h @@ -40,7 +40,7 @@ namespace rl /** * JR3 force-torque sensor. */ - class Jr3 : public CyclicDevice, public SixAxisForceTorqueSensor + class RL_HAL_EXPORT Jr3 : public CyclicDevice, public SixAxisForceTorqueSensor { public: Jr3(const ::std::string& filename = "/dev/comedi0", const ::std::chrono::nanoseconds& updateRate = ::std::chrono::milliseconds(1)); diff --git a/src/rl/hal/LeuzeRs4.h b/src/rl/hal/LeuzeRs4.h index f3b47458..693288cf 100644 --- a/src/rl/hal/LeuzeRs4.h +++ b/src/rl/hal/LeuzeRs4.h @@ -42,7 +42,7 @@ namespace rl /** * Leuze RS4 safety laser scanner. */ - class LeuzeRs4 : public CyclicDevice, public Lidar + class RL_HAL_EXPORT LeuzeRs4 : public CyclicDevice, public Lidar { public: enum BaudRate diff --git a/src/rl/hal/Lidar.h b/src/rl/hal/Lidar.h index 904b41ad..d7942472 100644 --- a/src/rl/hal/Lidar.h +++ b/src/rl/hal/Lidar.h @@ -33,7 +33,7 @@ namespace rl { namespace hal { - class Lidar : public virtual RangeSensor + class RL_HAL_EXPORT Lidar : public virtual RangeSensor { public: Lidar(); diff --git a/src/rl/hal/MitsubishiH7.h b/src/rl/hal/MitsubishiH7.h index 4368a74f..21d63f4f 100644 --- a/src/rl/hal/MitsubishiH7.h +++ b/src/rl/hal/MitsubishiH7.h @@ -46,7 +46,7 @@ namespace rl /** * Mitsubishi Electric MELFA Ethernet interface (software version H7 or later). */ - class MitsubishiH7 : + class RL_HAL_EXPORT MitsubishiH7 : public CartesianPositionActuator, public CartesianPositionSensor, public CyclicDevice, diff --git a/src/rl/hal/MitsubishiR3.h b/src/rl/hal/MitsubishiR3.h index ff285d4e..c669adab 100644 --- a/src/rl/hal/MitsubishiR3.h +++ b/src/rl/hal/MitsubishiR3.h @@ -42,7 +42,7 @@ namespace rl /** * Mitsubishi Electric R3 protocol. */ - class MitsubishiR3 : public Com + class RL_HAL_EXPORT MitsubishiR3 : public Com { public: enum HandSts diff --git a/src/rl/hal/RangeSensor.h b/src/rl/hal/RangeSensor.h index 1ce25b19..1002921d 100644 --- a/src/rl/hal/RangeSensor.h +++ b/src/rl/hal/RangeSensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class RangeSensor : public virtual Device + class RL_HAL_EXPORT RangeSensor : public virtual Device { public: RangeSensor(); diff --git a/src/rl/hal/RobotiqModelC.h b/src/rl/hal/RobotiqModelC.h index 40a64c2c..cc28403f 100644 --- a/src/rl/hal/RobotiqModelC.h +++ b/src/rl/hal/RobotiqModelC.h @@ -39,7 +39,7 @@ namespace rl { namespace hal { - class RobotiqModelC : public CyclicDevice, public Gripper + class RL_HAL_EXPORT RobotiqModelC : public CyclicDevice, public Gripper { public: enum ActionStatus diff --git a/src/rl/hal/SchmersalLss300.h b/src/rl/hal/SchmersalLss300.h index 21a0c71e..288699fe 100644 --- a/src/rl/hal/SchmersalLss300.h +++ b/src/rl/hal/SchmersalLss300.h @@ -42,7 +42,7 @@ namespace rl /** * Schmersal LSS 300 safety laser scanner. */ - class SchmersalLss300 : public CyclicDevice, public Lidar + class RL_HAL_EXPORT SchmersalLss300 : public CyclicDevice, public Lidar { public: enum BaudRate diff --git a/src/rl/hal/SchunkFpsF5.h b/src/rl/hal/SchunkFpsF5.h index ca28d7e4..a2f4b9e1 100644 --- a/src/rl/hal/SchunkFpsF5.h +++ b/src/rl/hal/SchunkFpsF5.h @@ -41,7 +41,7 @@ namespace rl /** * Schunk FPS-F5 flexible position sensor. */ - class SchunkFpsF5 : public CyclicDevice, public RangeSensor + class RL_HAL_EXPORT SchunkFpsF5 : public CyclicDevice, public RangeSensor { public: SchunkFpsF5(const ::std::string& device = "/dev/ttyS0"); diff --git a/src/rl/hal/Serial.h b/src/rl/hal/Serial.h index 43dd7dbe..26485593 100644 --- a/src/rl/hal/Serial.h +++ b/src/rl/hal/Serial.h @@ -44,7 +44,7 @@ namespace rl { namespace hal { - class Serial : public Com + class RL_HAL_EXPORT Serial : public Com { public: enum BaudRate diff --git a/src/rl/hal/SickLms200.h b/src/rl/hal/SickLms200.h index 13378f21..c707b5df 100644 --- a/src/rl/hal/SickLms200.h +++ b/src/rl/hal/SickLms200.h @@ -42,7 +42,7 @@ namespace rl /** * Sick LMS 200 laser measurement system. */ - class SickLms200 : public CyclicDevice, public Lidar + class RL_HAL_EXPORT SickLms200 : public CyclicDevice, public Lidar { public: enum BaudRate diff --git a/src/rl/hal/SickS300.h b/src/rl/hal/SickS300.h index b479008c..8ebfe37a 100644 --- a/src/rl/hal/SickS300.h +++ b/src/rl/hal/SickS300.h @@ -42,7 +42,7 @@ namespace rl /** * Sick S300 safety laser scanner. */ - class SickS300 : public CyclicDevice, public Lidar + class RL_HAL_EXPORT SickS300 : public CyclicDevice, public Lidar { public: SickS300( diff --git a/src/rl/hal/SixAxisForceTorqueSensor.h b/src/rl/hal/SixAxisForceTorqueSensor.h index 0acff6ad..480f1df1 100644 --- a/src/rl/hal/SixAxisForceTorqueSensor.h +++ b/src/rl/hal/SixAxisForceTorqueSensor.h @@ -36,7 +36,7 @@ namespace rl { namespace hal { - class SixAxisForceTorqueSensor : public virtual ForceSensor, public virtual TorqueSensor + class RL_HAL_EXPORT SixAxisForceTorqueSensor : public virtual ForceSensor, public virtual TorqueSensor { public: SixAxisForceTorqueSensor(); diff --git a/src/rl/hal/Socket.h b/src/rl/hal/Socket.h index b20129db..643efd35 100644 --- a/src/rl/hal/Socket.h +++ b/src/rl/hal/Socket.h @@ -44,10 +44,10 @@ namespace rl { namespace hal { - class Socket : public Com + class RL_HAL_EXPORT Socket : public Com { public: - class Address + class RL_HAL_EXPORT Address { public: Address(); diff --git a/src/rl/hal/TimeoutException.h b/src/rl/hal/TimeoutException.h index 4d1d4400..26feb5aa 100644 --- a/src/rl/hal/TimeoutException.h +++ b/src/rl/hal/TimeoutException.h @@ -33,7 +33,7 @@ namespace rl { namespace hal { - class TimeoutException : public ComException + class RL_HAL_EXPORT TimeoutException : public ComException { public: TimeoutException(); diff --git a/src/rl/hal/TorqueSensor.h b/src/rl/hal/TorqueSensor.h index 2afbb97b..32604f13 100644 --- a/src/rl/hal/TorqueSensor.h +++ b/src/rl/hal/TorqueSensor.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class TorqueSensor : public virtual Device + class RL_HAL_EXPORT TorqueSensor : public virtual Device { public: TorqueSensor(); diff --git a/src/rl/hal/UniversalRobotsDashboard.h b/src/rl/hal/UniversalRobotsDashboard.h index e33182a2..48457c7e 100644 --- a/src/rl/hal/UniversalRobotsDashboard.h +++ b/src/rl/hal/UniversalRobotsDashboard.h @@ -40,7 +40,7 @@ namespace rl /** * Universal Robots dashboard server. */ - class UniversalRobotsDashboard : public Com + class RL_HAL_EXPORT UniversalRobotsDashboard : public Com { public: enum ProgramState diff --git a/src/rl/hal/UniversalRobotsRealtime.h b/src/rl/hal/UniversalRobotsRealtime.h index d0980d69..4088f499 100644 --- a/src/rl/hal/UniversalRobotsRealtime.h +++ b/src/rl/hal/UniversalRobotsRealtime.h @@ -48,7 +48,7 @@ namespace rl /** * Universal Robots realtime interface (pre-3.0, 3.0, 3.1, 3.2, 3.3, 3.4, 3.5). */ - class UniversalRobotsRealtime : + class RL_HAL_EXPORT UniversalRobotsRealtime : public CartesianForceSensor, public CartesianPositionSensor, public CartesianVelocitySensor, diff --git a/src/rl/hal/UniversalRobotsRtde.h b/src/rl/hal/UniversalRobotsRtde.h index a8292fa9..ede3a9e6 100644 --- a/src/rl/hal/UniversalRobotsRtde.h +++ b/src/rl/hal/UniversalRobotsRtde.h @@ -56,7 +56,7 @@ namespace rl /** * Universal Robots RTDE interface (3.3). */ - class UniversalRobotsRtde : + class RL_HAL_EXPORT UniversalRobotsRtde : public CyclicDevice, public AnalogInputReader, public AnalogOutputReader, diff --git a/src/rl/hal/WeissException.h b/src/rl/hal/WeissException.h index 9f1cb50d..23ab6e7e 100644 --- a/src/rl/hal/WeissException.h +++ b/src/rl/hal/WeissException.h @@ -33,7 +33,7 @@ namespace rl { namespace hal { - class WeissException : public DeviceException + class RL_HAL_EXPORT WeissException : public DeviceException { public: enum Code diff --git a/src/rl/hal/WeissKms40.h b/src/rl/hal/WeissKms40.h index 6ab5deae..a0d49dbd 100644 --- a/src/rl/hal/WeissKms40.h +++ b/src/rl/hal/WeissKms40.h @@ -47,7 +47,7 @@ namespace rl * See "KMS Command Set Reference Manual": * */ - class WeissKms40 : public CyclicDevice, public SixAxisForceTorqueSensor + class RL_HAL_EXPORT WeissKms40 : public CyclicDevice, public SixAxisForceTorqueSensor { public: enum SystemState diff --git a/src/rl/hal/WeissWsg50.h b/src/rl/hal/WeissWsg50.h index 8dd5b990..38ec9a8d 100644 --- a/src/rl/hal/WeissWsg50.h +++ b/src/rl/hal/WeissWsg50.h @@ -50,7 +50,7 @@ namespace rl * Otherwise, the gripper will not grasp if object width is different * from the given value. */ - class WeissWsg50 : public CyclicDevice, public Gripper + class RL_HAL_EXPORT WeissWsg50 : public CyclicDevice, public Gripper { public: enum GraspingState diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index 079cb3e2..d904e21f 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -43,6 +43,7 @@ endif() target_include_directories( kin PUBLIC + $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> ${Boost_INCLUDE_DIR} @@ -102,3 +103,11 @@ endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() + +generate_export_header( + kin + EXPORT_FILE_NAME export.h + PREFIX_NAME RL_ +) + +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/kin COMPONENT development) diff --git a/src/rl/kin/Element.h b/src/rl/kin/Element.h index c4dcfac4..8cc95e5c 100644 --- a/src/rl/kin/Element.h +++ b/src/rl/kin/Element.h @@ -28,12 +28,13 @@ #define RL_KIN_ELEMENT_H #include +#include namespace rl { namespace kin { - class Element + class RL_KIN_EXPORT Element { public: Element(); diff --git a/src/rl/kin/Exception.h b/src/rl/kin/Exception.h index e51e1b24..0cd9c8a0 100644 --- a/src/rl/kin/Exception.h +++ b/src/rl/kin/Exception.h @@ -28,12 +28,13 @@ #define RL_KIN_EXCEPTION_H #include +#include namespace rl { namespace kin { - class Exception : public ::std::runtime_error + class RL_KIN_EXPORT Exception : public ::std::runtime_error { public: Exception(const ::std::string& what_arg); diff --git a/src/rl/kin/Frame.h b/src/rl/kin/Frame.h index ef151814..b3968995 100644 --- a/src/rl/kin/Frame.h +++ b/src/rl/kin/Frame.h @@ -35,7 +35,7 @@ namespace rl { namespace kin { - class Frame : public Element + class RL_KIN_EXPORT Frame : public Element { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/kin/Joint.h b/src/rl/kin/Joint.h index a1273679..d48e5691 100644 --- a/src/rl/kin/Joint.h +++ b/src/rl/kin/Joint.h @@ -36,7 +36,7 @@ namespace rl { namespace kin { - class Joint : public Transform + class RL_KIN_EXPORT Joint : public Transform { public: Joint(); diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 18ed9567..0bd78ab9 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -33,6 +33,7 @@ #include #include #include +#include #include #include #include @@ -50,7 +51,7 @@ namespace rl class Joint; class Transform; - class Kinematics + class RL_KIN_EXPORT Kinematics { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/kin/Link.h b/src/rl/kin/Link.h index ff83f644..33dde257 100644 --- a/src/rl/kin/Link.h +++ b/src/rl/kin/Link.h @@ -36,7 +36,7 @@ namespace rl { namespace kin { - class Link : public Frame + class RL_KIN_EXPORT Link : public Frame { public: Link(); diff --git a/src/rl/kin/Prismatic.h b/src/rl/kin/Prismatic.h index 366c9791..2f2da4bb 100644 --- a/src/rl/kin/Prismatic.h +++ b/src/rl/kin/Prismatic.h @@ -33,7 +33,7 @@ namespace rl { namespace kin { - class Prismatic : public Joint + class RL_KIN_EXPORT Prismatic : public Joint { public: Prismatic(); diff --git a/src/rl/kin/Puma.h b/src/rl/kin/Puma.h index d48e2636..1feae8bc 100644 --- a/src/rl/kin/Puma.h +++ b/src/rl/kin/Puma.h @@ -36,7 +36,7 @@ namespace rl /** * TRR base and TRT wrist. */ - class Puma : public Kinematics + class RL_KIN_EXPORT Puma : public Kinematics { public: enum Arm diff --git a/src/rl/kin/Revolute.h b/src/rl/kin/Revolute.h index fe31baeb..84a66048 100644 --- a/src/rl/kin/Revolute.h +++ b/src/rl/kin/Revolute.h @@ -33,7 +33,7 @@ namespace rl { namespace kin { - class Revolute : public Joint + class RL_KIN_EXPORT Revolute : public Joint { public: Revolute(); diff --git a/src/rl/kin/Rhino.h b/src/rl/kin/Rhino.h index 3bf4482c..c5eef4c5 100644 --- a/src/rl/kin/Rhino.h +++ b/src/rl/kin/Rhino.h @@ -36,7 +36,7 @@ namespace rl /** * TRR base and RT wrist. */ - class Rhino : public Kinematics + class RL_KIN_EXPORT Rhino : public Kinematics { public: enum Arm diff --git a/src/rl/kin/Transform.h b/src/rl/kin/Transform.h index fb3be142..fa310500 100644 --- a/src/rl/kin/Transform.h +++ b/src/rl/kin/Transform.h @@ -37,7 +37,7 @@ namespace rl { class Frame; - class Transform : public Element + class RL_KIN_EXPORT Transform : public Element { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/mdl/AnalyticalInverseKinematics.h b/src/rl/mdl/AnalyticalInverseKinematics.h index 7bb404ab..594ab407 100644 --- a/src/rl/mdl/AnalyticalInverseKinematics.h +++ b/src/rl/mdl/AnalyticalInverseKinematics.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class AnalyticalInverseKinematics : public InverseKinematics + class RL_MDL_EXPORT AnalyticalInverseKinematics : public InverseKinematics { public: AnalyticalInverseKinematics(Kinematic* kinematic); diff --git a/src/rl/mdl/Body.h b/src/rl/mdl/Body.h index 23906f4c..1ee10c79 100644 --- a/src/rl/mdl/Body.h +++ b/src/rl/mdl/Body.h @@ -35,7 +35,7 @@ namespace rl { namespace mdl { - class Body : public Frame + class RL_MDL_EXPORT Body : public Frame { public: Body(); diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 89aca169..10053a6f 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -96,6 +96,7 @@ endif() target_include_directories( mdl PUBLIC + $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> ${Boost_INCLUDE_DIR} @@ -161,3 +162,11 @@ endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() + +generate_export_header( + mdl + EXPORT_FILE_NAME export.h + PREFIX_NAME RL_ +) + +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/mdl COMPONENT development) diff --git a/src/rl/mdl/Compound.h b/src/rl/mdl/Compound.h index b465e0b6..e27cca39 100644 --- a/src/rl/mdl/Compound.h +++ b/src/rl/mdl/Compound.h @@ -38,7 +38,7 @@ namespace rl class Frame; class Transform; - class Compound + class RL_MDL_EXPORT Compound { public: Compound(Model* model); diff --git a/src/rl/mdl/Cylindrical.h b/src/rl/mdl/Cylindrical.h index 2e39caef..e6023e7c 100644 --- a/src/rl/mdl/Cylindrical.h +++ b/src/rl/mdl/Cylindrical.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class Cylindrical : public Joint + class RL_MDL_EXPORT Cylindrical : public Joint { public: Cylindrical(); diff --git a/src/rl/mdl/Dynamic.h b/src/rl/mdl/Dynamic.h index 0d5255ec..ac3cb70d 100644 --- a/src/rl/mdl/Dynamic.h +++ b/src/rl/mdl/Dynamic.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class Dynamic : public Kinematic + class RL_MDL_EXPORT Dynamic : public Kinematic { public: Dynamic(); diff --git a/src/rl/mdl/Element.h b/src/rl/mdl/Element.h index 7cbdcbce..b9f8c80d 100644 --- a/src/rl/mdl/Element.h +++ b/src/rl/mdl/Element.h @@ -30,13 +30,15 @@ #include #include +#include + namespace rl { namespace mdl { class Compound; - class Element + class RL_MDL_EXPORT Element { public: Element(); diff --git a/src/rl/mdl/EulerCauchyIntegrator.h b/src/rl/mdl/EulerCauchyIntegrator.h index 8680853a..85d97d3a 100644 --- a/src/rl/mdl/EulerCauchyIntegrator.h +++ b/src/rl/mdl/EulerCauchyIntegrator.h @@ -50,7 +50,7 @@ namespace rl * * @see Dynamic::forwardDynamics() */ - class EulerCauchyIntegrator : public Integrator + class RL_MDL_EXPORT EulerCauchyIntegrator : public Integrator { public: EulerCauchyIntegrator(Dynamic* dynamic); diff --git a/src/rl/mdl/Exception.h b/src/rl/mdl/Exception.h index 4d92efe5..3f7cd29c 100644 --- a/src/rl/mdl/Exception.h +++ b/src/rl/mdl/Exception.h @@ -28,12 +28,13 @@ #define RL_MDL_EXCEPTION_H #include +#include namespace rl { namespace mdl { - class Exception : public ::std::runtime_error + class RL_MDL_EXPORT Exception : public ::std::runtime_error { public: Exception(const ::std::string& what_arg); diff --git a/src/rl/mdl/Factory.h b/src/rl/mdl/Factory.h index 2e5872f6..dc342a03 100644 --- a/src/rl/mdl/Factory.h +++ b/src/rl/mdl/Factory.h @@ -28,6 +28,7 @@ #define RL_MDL_FACTORY_H #include +#include namespace rl { @@ -35,7 +36,7 @@ namespace rl { class Model; - class Factory + class RL_MDL_EXPORT Factory { public: Factory(); diff --git a/src/rl/mdl/Fixed.h b/src/rl/mdl/Fixed.h index 614468f0..9a08c81c 100644 --- a/src/rl/mdl/Fixed.h +++ b/src/rl/mdl/Fixed.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class Fixed : public Transform + class RL_MDL_EXPORT Fixed : public Transform { public: Fixed(); diff --git a/src/rl/mdl/Frame.h b/src/rl/mdl/Frame.h index 0786e0b5..2dcf34a2 100644 --- a/src/rl/mdl/Frame.h +++ b/src/rl/mdl/Frame.h @@ -38,7 +38,7 @@ namespace rl { namespace mdl { - class Frame : public Element + class RL_MDL_EXPORT Frame : public Element { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/mdl/Helical.h b/src/rl/mdl/Helical.h index b3f196b6..180e50c9 100644 --- a/src/rl/mdl/Helical.h +++ b/src/rl/mdl/Helical.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class Helical : public Joint + class RL_MDL_EXPORT Helical : public Joint { public: Helical(); diff --git a/src/rl/mdl/Integrator.h b/src/rl/mdl/Integrator.h index 3aa9c49e..b5fa1388 100644 --- a/src/rl/mdl/Integrator.h +++ b/src/rl/mdl/Integrator.h @@ -28,6 +28,7 @@ #define RL_MDL_INTEGRATOR_H #include +#include namespace rl { @@ -35,7 +36,7 @@ namespace rl { class Dynamic; - class Integrator + class RL_MDL_EXPORT Integrator { public: Integrator(Dynamic* dynamic); diff --git a/src/rl/mdl/InverseKinematics.h b/src/rl/mdl/InverseKinematics.h index c3987cf7..1c768e19 100644 --- a/src/rl/mdl/InverseKinematics.h +++ b/src/rl/mdl/InverseKinematics.h @@ -29,6 +29,7 @@ #include #include +#include namespace rl { @@ -36,7 +37,7 @@ namespace rl { class Kinematic; - class InverseKinematics + class RL_MDL_EXPORT InverseKinematics { public: typedef ::std::pair< ::rl::math::Transform, ::std::size_t> Goal; diff --git a/src/rl/mdl/IterativeInverseKinematics.h b/src/rl/mdl/IterativeInverseKinematics.h index 0dccc59f..b1147cb3 100644 --- a/src/rl/mdl/IterativeInverseKinematics.h +++ b/src/rl/mdl/IterativeInverseKinematics.h @@ -35,7 +35,7 @@ namespace rl { namespace mdl { - class IterativeInverseKinematics : public InverseKinematics + class RL_MDL_EXPORT IterativeInverseKinematics : public InverseKinematics { public: IterativeInverseKinematics(Kinematic* kinematic); diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index 4e81553c..24dc794a 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -45,7 +45,7 @@ namespace rl * * https://www.math.ucsd.edu/~sbuss/ResearchWeb/ikmethods/iksurvey.pdf */ - class JacobianInverseKinematics : public IterativeInverseKinematics + class RL_MDL_EXPORT JacobianInverseKinematics : public IterativeInverseKinematics { public: enum Method diff --git a/src/rl/mdl/Joint.h b/src/rl/mdl/Joint.h index 1fcb4a34..5c0b8dd5 100644 --- a/src/rl/mdl/Joint.h +++ b/src/rl/mdl/Joint.h @@ -36,7 +36,7 @@ namespace rl { namespace mdl { - class Joint : public Transform + class RL_MDL_EXPORT Joint : public Transform { public: Joint(const ::std::size_t& dofPosition, const ::std::size_t& dofVelocity); diff --git a/src/rl/mdl/Kinematic.h b/src/rl/mdl/Kinematic.h index 96820396..810a0fe1 100644 --- a/src/rl/mdl/Kinematic.h +++ b/src/rl/mdl/Kinematic.h @@ -35,7 +35,7 @@ namespace rl { namespace mdl { - class Kinematic : public Metric + class RL_MDL_EXPORT Kinematic : public Metric { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/mdl/Metric.h b/src/rl/mdl/Metric.h index 9c83eda2..6ac2462f 100644 --- a/src/rl/mdl/Metric.h +++ b/src/rl/mdl/Metric.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class Metric : public Model + class RL_MDL_EXPORT Metric : public Model { public: Metric(); diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 5c2a7ecc..16a25032 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -54,7 +54,7 @@ namespace rl class Joint; class World; - class Model + class RL_MDL_EXPORT Model { public: Model(); diff --git a/src/rl/mdl/NloptInverseKinematics.h b/src/rl/mdl/NloptInverseKinematics.h index b04fa5c8..9d0cb194 100644 --- a/src/rl/mdl/NloptInverseKinematics.h +++ b/src/rl/mdl/NloptInverseKinematics.h @@ -38,7 +38,7 @@ namespace rl { namespace mdl { - class NloptInverseKinematics : public IterativeInverseKinematics + class RL_MDL_EXPORT NloptInverseKinematics : public IterativeInverseKinematics { public: NloptInverseKinematics(Kinematic* kinematic); diff --git a/src/rl/mdl/Prismatic.h b/src/rl/mdl/Prismatic.h index c2cb043e..015761ed 100644 --- a/src/rl/mdl/Prismatic.h +++ b/src/rl/mdl/Prismatic.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class Prismatic : public Joint + class RL_MDL_EXPORT Prismatic : public Joint { public: Prismatic(); diff --git a/src/rl/mdl/Revolute.h b/src/rl/mdl/Revolute.h index 338f47aa..21f990aa 100644 --- a/src/rl/mdl/Revolute.h +++ b/src/rl/mdl/Revolute.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class Revolute : public Joint + class RL_MDL_EXPORT Revolute : public Joint { public: Revolute(); diff --git a/src/rl/mdl/RungeKuttaNystromIntegrator.h b/src/rl/mdl/RungeKuttaNystromIntegrator.h index e24e3c5a..906c06f9 100644 --- a/src/rl/mdl/RungeKuttaNystromIntegrator.h +++ b/src/rl/mdl/RungeKuttaNystromIntegrator.h @@ -54,7 +54,7 @@ namespace rl * * @see Dynamic::forwardDynamics() */ - class RungeKuttaNystromIntegrator : public Integrator + class RL_MDL_EXPORT RungeKuttaNystromIntegrator : public Integrator { public: RungeKuttaNystromIntegrator(Dynamic* dynamic); diff --git a/src/rl/mdl/SixDof.h b/src/rl/mdl/SixDof.h index 450c960e..99cb3b83 100644 --- a/src/rl/mdl/SixDof.h +++ b/src/rl/mdl/SixDof.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class SixDof : public Joint + class RL_MDL_EXPORT SixDof : public Joint { public: SixDof(); diff --git a/src/rl/mdl/Spherical.h b/src/rl/mdl/Spherical.h index 6b6f699f..2553fb57 100644 --- a/src/rl/mdl/Spherical.h +++ b/src/rl/mdl/Spherical.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class Spherical : public Joint + class RL_MDL_EXPORT Spherical : public Joint { public: Spherical(); diff --git a/src/rl/mdl/Transform.h b/src/rl/mdl/Transform.h index 04f12e29..1e659398 100644 --- a/src/rl/mdl/Transform.h +++ b/src/rl/mdl/Transform.h @@ -39,7 +39,7 @@ namespace rl { class Frame; - class Transform : public Element + class RL_MDL_EXPORT Transform : public Element { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/mdl/UrdfFactory.h b/src/rl/mdl/UrdfFactory.h index 49e727f7..3a751433 100644 --- a/src/rl/mdl/UrdfFactory.h +++ b/src/rl/mdl/UrdfFactory.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class UrdfFactory : public Factory + class RL_MDL_EXPORT UrdfFactory : public Factory { public: UrdfFactory(); diff --git a/src/rl/mdl/World.h b/src/rl/mdl/World.h index 1ab05495..5f519fb3 100644 --- a/src/rl/mdl/World.h +++ b/src/rl/mdl/World.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class World : public Frame + class RL_MDL_EXPORT World : public Frame { public: World(); diff --git a/src/rl/mdl/XmlFactory.h b/src/rl/mdl/XmlFactory.h index b2223a9a..6f512e33 100644 --- a/src/rl/mdl/XmlFactory.h +++ b/src/rl/mdl/XmlFactory.h @@ -33,7 +33,7 @@ namespace rl { namespace mdl { - class XmlFactory : public Factory + class RL_MDL_EXPORT XmlFactory : public Factory { public: XmlFactory(); diff --git a/src/rl/plan/AddRrtConCon.h b/src/rl/plan/AddRrtConCon.h index 56409040..eb7f9440 100644 --- a/src/rl/plan/AddRrtConCon.h +++ b/src/rl/plan/AddRrtConCon.h @@ -43,7 +43,7 @@ namespace rl * * http://dx.doi.org/10.1109/IROS.2005.1545607 */ - class AddRrtConCon : public RrtConCon + class RL_PLAN_EXPORT AddRrtConCon : public RrtConCon { public: AddRrtConCon(); diff --git a/src/rl/plan/AdvancedOptimizer.h b/src/rl/plan/AdvancedOptimizer.h index 801bda5c..e91cb2b6 100644 --- a/src/rl/plan/AdvancedOptimizer.h +++ b/src/rl/plan/AdvancedOptimizer.h @@ -33,7 +33,7 @@ namespace rl { namespace plan { - class AdvancedOptimizer : public SimpleOptimizer + class RL_PLAN_EXPORT AdvancedOptimizer : public SimpleOptimizer { public: AdvancedOptimizer(); diff --git a/src/rl/plan/BridgeSampler.h b/src/rl/plan/BridgeSampler.h index 8a4a9827..ef51b45f 100644 --- a/src/rl/plan/BridgeSampler.h +++ b/src/rl/plan/BridgeSampler.h @@ -43,7 +43,7 @@ namespace rl * * http://dx.doi.org/10.1109/ROBOT.2003.1242285 */ - class BridgeSampler : public GaussianSampler + class RL_PLAN_EXPORT BridgeSampler : public GaussianSampler { public: BridgeSampler(); diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index 14ac3efa..d45884ff 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -112,6 +112,7 @@ endif() target_include_directories( plan PUBLIC + $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> ${Boost_INCLUDE_DIR} @@ -175,3 +176,11 @@ endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() + +generate_export_header( + plan + EXPORT_FILE_NAME export.h + PREFIX_NAME RL_ +) + +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/plan COMPONENT development) diff --git a/src/rl/plan/DistanceModel.h b/src/rl/plan/DistanceModel.h index c423e088..f042a512 100644 --- a/src/rl/plan/DistanceModel.h +++ b/src/rl/plan/DistanceModel.h @@ -37,7 +37,7 @@ namespace rl { namespace plan { - class DistanceModel : public SimpleModel + class RL_PLAN_EXPORT DistanceModel : public SimpleModel { public: DistanceModel(); diff --git a/src/rl/plan/Eet.h b/src/rl/plan/Eet.h index b0d7771b..8526c87b 100644 --- a/src/rl/plan/Eet.h +++ b/src/rl/plan/Eet.h @@ -49,7 +49,7 @@ namespace rl * * http://dx.doi.org/10.1109/TRO.2014.2340191 */ - class Eet : public RrtCon + class RL_PLAN_EXPORT Eet : public RrtCon { public: struct ExplorerSetup diff --git a/src/rl/plan/Exception.h b/src/rl/plan/Exception.h index 83d1d764..5ac785c4 100644 --- a/src/rl/plan/Exception.h +++ b/src/rl/plan/Exception.h @@ -28,12 +28,13 @@ #define RL_PLAN_EXCEPTION_H #include +#include namespace rl { namespace plan { - class Exception : public ::std::runtime_error + class RL_PLAN_EXPORT Exception : public ::std::runtime_error { public: Exception(const ::std::string& what_arg); diff --git a/src/rl/plan/GaussianSampler.h b/src/rl/plan/GaussianSampler.h index f1839e26..b71e2b65 100644 --- a/src/rl/plan/GaussianSampler.h +++ b/src/rl/plan/GaussianSampler.h @@ -43,7 +43,7 @@ namespace rl * * http://dx.doi.org/10.1109/ROBOT.1999.772447 */ - class GaussianSampler : public UniformSampler + class RL_PLAN_EXPORT GaussianSampler : public UniformSampler { public: GaussianSampler(); diff --git a/src/rl/plan/GnatNearestNeighbors.h b/src/rl/plan/GnatNearestNeighbors.h index d4c54146..1f49a7e4 100644 --- a/src/rl/plan/GnatNearestNeighbors.h +++ b/src/rl/plan/GnatNearestNeighbors.h @@ -37,7 +37,7 @@ namespace rl { class Model; - class GnatNearestNeighbors : public NearestNeighbors + class RL_PLAN_EXPORT GnatNearestNeighbors : public NearestNeighbors { public: GnatNearestNeighbors(Model* model); diff --git a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h index abdad1ca..87d065a2 100644 --- a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h @@ -37,7 +37,7 @@ namespace rl { class Model; - class KdtreeBoundingBoxNearestNeighbors : public NearestNeighbors + class RL_PLAN_EXPORT KdtreeBoundingBoxNearestNeighbors : public NearestNeighbors { public: KdtreeBoundingBoxNearestNeighbors(Model* model); diff --git a/src/rl/plan/KdtreeNearestNeighbors.h b/src/rl/plan/KdtreeNearestNeighbors.h index efc8eef2..cf28c5ef 100644 --- a/src/rl/plan/KdtreeNearestNeighbors.h +++ b/src/rl/plan/KdtreeNearestNeighbors.h @@ -37,7 +37,7 @@ namespace rl { class Model; - class KdtreeNearestNeighbors : public NearestNeighbors + class RL_PLAN_EXPORT KdtreeNearestNeighbors : public NearestNeighbors { public: KdtreeNearestNeighbors(Model* model); diff --git a/src/rl/plan/LinearNearestNeighbors.h b/src/rl/plan/LinearNearestNeighbors.h index 7d2c9833..a67aea62 100644 --- a/src/rl/plan/LinearNearestNeighbors.h +++ b/src/rl/plan/LinearNearestNeighbors.h @@ -37,7 +37,7 @@ namespace rl { class Model; - class LinearNearestNeighbors : public NearestNeighbors + class RL_PLAN_EXPORT LinearNearestNeighbors : public NearestNeighbors { public: LinearNearestNeighbors(Model* model); diff --git a/src/rl/plan/Metric.h b/src/rl/plan/Metric.h index 1201b0ca..d033b81e 100644 --- a/src/rl/plan/Metric.h +++ b/src/rl/plan/Metric.h @@ -29,6 +29,7 @@ #include #include +#include namespace rl { @@ -36,7 +37,7 @@ namespace rl { class Model; - class Metric + class RL_PLAN_EXPORT Metric { public: typedef ::rl::math::Real Distance; diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 7bdb7466..950310e5 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -31,6 +31,7 @@ #include #include #include +#include #include #include @@ -38,7 +39,7 @@ namespace rl { namespace plan { - class Model + class RL_PLAN_EXPORT Model { public: Model(); diff --git a/src/rl/plan/NearestNeighbors.h b/src/rl/plan/NearestNeighbors.h index dfac3bd5..de3063f9 100644 --- a/src/rl/plan/NearestNeighbors.h +++ b/src/rl/plan/NearestNeighbors.h @@ -38,7 +38,7 @@ namespace rl { class Planner; - class NearestNeighbors + class RL_PLAN_EXPORT NearestNeighbors { public: typedef Metric::Distance Distance; diff --git a/src/rl/plan/Optimizer.h b/src/rl/plan/Optimizer.h index a975dc40..7ff2eb87 100644 --- a/src/rl/plan/Optimizer.h +++ b/src/rl/plan/Optimizer.h @@ -27,6 +27,8 @@ #ifndef RL_PLAN_OPTIMIZER_H #define RL_PLAN_OPTIMIZER_H +#include + #include "VectorList.h" namespace rl @@ -37,7 +39,7 @@ namespace rl class Verifier; class Viewer; - class Optimizer + class RL_PLAN_EXPORT Optimizer { public: Optimizer(); diff --git a/src/rl/plan/Planner.h b/src/rl/plan/Planner.h index 809c6e3a..63b530d3 100644 --- a/src/rl/plan/Planner.h +++ b/src/rl/plan/Planner.h @@ -30,6 +30,7 @@ #include #include #include +#include #include "VectorList.h" @@ -43,7 +44,7 @@ namespace rl class SimpleModel; class Viewer; - class Planner + class RL_PLAN_EXPORT Planner { public: Planner(); diff --git a/src/rl/plan/Prm.h b/src/rl/plan/Prm.h index e1dd4484..35bc10ca 100644 --- a/src/rl/plan/Prm.h +++ b/src/rl/plan/Prm.h @@ -61,7 +61,7 @@ namespace rl * * http://dx.doi.org/10.1109/70.508439 */ - class Prm : public Planner + class RL_PLAN_EXPORT Prm : public Planner { public: Prm(); diff --git a/src/rl/plan/PrmUtilityGuided.h b/src/rl/plan/PrmUtilityGuided.h index 70d6576e..e4efb32d 100644 --- a/src/rl/plan/PrmUtilityGuided.h +++ b/src/rl/plan/PrmUtilityGuided.h @@ -47,7 +47,7 @@ namespace rl * * http://www.roboticsproceedings.org/rss01/p15.pdf */ - class PrmUtilityGuided : public Prm + class RL_PLAN_EXPORT PrmUtilityGuided : public Prm { public: PrmUtilityGuided(); diff --git a/src/rl/plan/RecursiveVerifier.h b/src/rl/plan/RecursiveVerifier.h index c558ad65..1d590c6a 100644 --- a/src/rl/plan/RecursiveVerifier.h +++ b/src/rl/plan/RecursiveVerifier.h @@ -33,7 +33,7 @@ namespace rl { namespace plan { - class RecursiveVerifier : public Verifier + class RL_PLAN_EXPORT RecursiveVerifier : public Verifier { public: RecursiveVerifier(); diff --git a/src/rl/plan/Rrt.h b/src/rl/plan/Rrt.h index b6a15024..4a0df4f1 100644 --- a/src/rl/plan/Rrt.h +++ b/src/rl/plan/Rrt.h @@ -51,7 +51,7 @@ namespace rl * * http://msl.cs.uiuc.edu/~lavalle/papers/Lav98c.pdf */ - class Rrt : public Planner + class RL_PLAN_EXPORT Rrt : public Planner { public: Rrt(const ::std::size_t& trees = 1); diff --git a/src/rl/plan/RrtCon.h b/src/rl/plan/RrtCon.h index d70545eb..364eb866 100644 --- a/src/rl/plan/RrtCon.h +++ b/src/rl/plan/RrtCon.h @@ -43,7 +43,7 @@ namespace rl * * http://dx.doi.org/10.1109/ROBOT.2000.844730 */ - class RrtCon : public RrtGoalBias + class RL_PLAN_EXPORT RrtCon : public RrtGoalBias { public: RrtCon(); diff --git a/src/rl/plan/RrtConCon.h b/src/rl/plan/RrtConCon.h index ed7d8c65..afe94c97 100644 --- a/src/rl/plan/RrtConCon.h +++ b/src/rl/plan/RrtConCon.h @@ -43,7 +43,7 @@ namespace rl * * http://dx.doi.org/10.1109/ROBOT.2000.844730 */ - class RrtConCon : public RrtDual + class RL_PLAN_EXPORT RrtConCon : public RrtDual { public: RrtConCon(); diff --git a/src/rl/plan/RrtDual.h b/src/rl/plan/RrtDual.h index 8c350217..cc7fc90a 100644 --- a/src/rl/plan/RrtDual.h +++ b/src/rl/plan/RrtDual.h @@ -33,7 +33,7 @@ namespace rl { namespace plan { - class RrtDual : public Rrt + class RL_PLAN_EXPORT RrtDual : public Rrt { public: RrtDual(); diff --git a/src/rl/plan/RrtExtCon.h b/src/rl/plan/RrtExtCon.h index 913a6989..ddb72236 100644 --- a/src/rl/plan/RrtExtCon.h +++ b/src/rl/plan/RrtExtCon.h @@ -33,7 +33,7 @@ namespace rl { namespace plan { - class RrtExtCon : public RrtDual + class RL_PLAN_EXPORT RrtExtCon : public RrtDual { public: RrtExtCon(); diff --git a/src/rl/plan/RrtExtExt.h b/src/rl/plan/RrtExtExt.h index 91d8e0ce..9e4309cf 100644 --- a/src/rl/plan/RrtExtExt.h +++ b/src/rl/plan/RrtExtExt.h @@ -33,7 +33,7 @@ namespace rl { namespace plan { - class RrtExtExt : public RrtDual + class RL_PLAN_EXPORT RrtExtExt : public RrtDual { public: RrtExtExt(); diff --git a/src/rl/plan/RrtGoalBias.h b/src/rl/plan/RrtGoalBias.h index 0a4718f1..e974be12 100644 --- a/src/rl/plan/RrtGoalBias.h +++ b/src/rl/plan/RrtGoalBias.h @@ -35,7 +35,7 @@ namespace rl { namespace plan { - class RrtGoalBias : public Rrt + class RL_PLAN_EXPORT RrtGoalBias : public Rrt { public: RrtGoalBias(); diff --git a/src/rl/plan/Sampler.h b/src/rl/plan/Sampler.h index 881cb069..94696e1a 100644 --- a/src/rl/plan/Sampler.h +++ b/src/rl/plan/Sampler.h @@ -28,6 +28,7 @@ #define RL_PLAN_SAMPLER_H #include +#include namespace rl { @@ -35,7 +36,7 @@ namespace rl { class SimpleModel; - class Sampler + class RL_PLAN_EXPORT Sampler { public: Sampler(); diff --git a/src/rl/plan/SequentialVerifier.h b/src/rl/plan/SequentialVerifier.h index 38ceb039..9eaf14a4 100644 --- a/src/rl/plan/SequentialVerifier.h +++ b/src/rl/plan/SequentialVerifier.h @@ -33,7 +33,7 @@ namespace rl { namespace plan { - class SequentialVerifier : public Verifier + class RL_PLAN_EXPORT SequentialVerifier : public Verifier { public: SequentialVerifier(); diff --git a/src/rl/plan/SimpleModel.h b/src/rl/plan/SimpleModel.h index 0fed72c0..52d7e425 100644 --- a/src/rl/plan/SimpleModel.h +++ b/src/rl/plan/SimpleModel.h @@ -33,7 +33,7 @@ namespace rl { namespace plan { - class SimpleModel : public Model + class RL_PLAN_EXPORT SimpleModel : public Model { public: SimpleModel(); diff --git a/src/rl/plan/SimpleOptimizer.h b/src/rl/plan/SimpleOptimizer.h index dfd1fe14..570f27cf 100644 --- a/src/rl/plan/SimpleOptimizer.h +++ b/src/rl/plan/SimpleOptimizer.h @@ -33,7 +33,7 @@ namespace rl { namespace plan { - class SimpleOptimizer : public Optimizer + class RL_PLAN_EXPORT SimpleOptimizer : public Optimizer { public: SimpleOptimizer(); diff --git a/src/rl/plan/UniformSampler.h b/src/rl/plan/UniformSampler.h index 19ee52f0..58f0da24 100644 --- a/src/rl/plan/UniformSampler.h +++ b/src/rl/plan/UniformSampler.h @@ -38,7 +38,7 @@ namespace rl /** * Uniform random sampling strategy. */ - class UniformSampler : public Sampler + class RL_PLAN_EXPORT UniformSampler : public Sampler { public: UniformSampler(); diff --git a/src/rl/plan/Verifier.h b/src/rl/plan/Verifier.h index 191c4bef..e7d00f09 100644 --- a/src/rl/plan/Verifier.h +++ b/src/rl/plan/Verifier.h @@ -28,6 +28,7 @@ #define RL_PLAN_VERIFIER_H #include +#include namespace rl { @@ -35,7 +36,7 @@ namespace rl { class SimpleModel; - class Verifier + class RL_PLAN_EXPORT Verifier { public: Verifier(); diff --git a/src/rl/plan/Viewer.h b/src/rl/plan/Viewer.h index 11942918..24962932 100644 --- a/src/rl/plan/Viewer.h +++ b/src/rl/plan/Viewer.h @@ -29,6 +29,7 @@ #include #include +#include #include "VectorList.h" @@ -36,7 +37,7 @@ namespace rl { namespace plan { - class Viewer + class RL_PLAN_EXPORT Viewer { public: Viewer(); diff --git a/src/rl/plan/WorkspaceMetric.h b/src/rl/plan/WorkspaceMetric.h index b663431b..098a4bdd 100644 --- a/src/rl/plan/WorkspaceMetric.h +++ b/src/rl/plan/WorkspaceMetric.h @@ -29,12 +29,13 @@ #include #include +#include namespace rl { namespace plan { - class WorkspaceMetric + class RL_PLAN_EXPORT WorkspaceMetric { public: typedef ::rl::math::Real Distance; diff --git a/src/rl/plan/WorkspaceSphere.h b/src/rl/plan/WorkspaceSphere.h index 2e7822e1..e3db388e 100644 --- a/src/rl/plan/WorkspaceSphere.h +++ b/src/rl/plan/WorkspaceSphere.h @@ -29,6 +29,7 @@ #include #include +#include #include "Vector3Ptr.h" @@ -36,7 +37,7 @@ namespace rl { namespace plan { - struct WorkspaceSphere + struct RL_PLAN_EXPORT WorkspaceSphere { typedef ::boost::adjacency_list_traits< ::boost::listS, diff --git a/src/rl/plan/WorkspaceSphereExplorer.h b/src/rl/plan/WorkspaceSphereExplorer.h index 6ecb068f..abe275cf 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.h +++ b/src/rl/plan/WorkspaceSphereExplorer.h @@ -53,7 +53,7 @@ namespace rl * * http://dx.doi.org/10.1109/ROBOT.2001.932817 */ - class WorkspaceSphereExplorer + class RL_PLAN_EXPORT WorkspaceSphereExplorer { public: enum Greedy diff --git a/src/rl/sg/Base.h b/src/rl/sg/Base.h index f573130b..fa36fed1 100644 --- a/src/rl/sg/Base.h +++ b/src/rl/sg/Base.h @@ -27,11 +27,13 @@ #ifndef RL_SG_BASE_H #define RL_SG_BASE_H +#include + namespace rl { namespace sg { - class Base + class RL_SG_EXPORT Base { public: virtual ~Base(); diff --git a/src/rl/sg/Body.h b/src/rl/sg/Body.h index 45b63a33..3db9b9f6 100644 --- a/src/rl/sg/Body.h +++ b/src/rl/sg/Body.h @@ -43,7 +43,7 @@ namespace rl class Model; class Shape; - class Body : public Base + class RL_SG_EXPORT Body : public Base { public: typedef ::std::vector::iterator Iterator; diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 08864814..57af5757 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -181,6 +181,7 @@ install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION} target_include_directories( sg PUBLIC + $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> ) @@ -297,3 +298,11 @@ endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() + +generate_export_header( + sg + EXPORT_FILE_NAME export.h + PREFIX_NAME RL_ +) + +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg COMPONENT development) diff --git a/src/rl/sg/DepthScene.h b/src/rl/sg/DepthScene.h index f7bfdb71..d37dd0da 100644 --- a/src/rl/sg/DepthScene.h +++ b/src/rl/sg/DepthScene.h @@ -38,7 +38,7 @@ namespace rl class Body; class Shape; - class DepthScene : public virtual Scene + class RL_SG_EXPORT DepthScene : public virtual Scene { public: DepthScene(); diff --git a/src/rl/sg/DistanceScene.h b/src/rl/sg/DistanceScene.h index 3981c9a9..dbb16370 100644 --- a/src/rl/sg/DistanceScene.h +++ b/src/rl/sg/DistanceScene.h @@ -40,7 +40,7 @@ namespace rl class Scene; class Shape; - class DistanceScene : public virtual Scene + class RL_SG_EXPORT DistanceScene : public virtual Scene { public: DistanceScene(); diff --git a/src/rl/sg/Exception.h b/src/rl/sg/Exception.h index 5f175478..33bcf215 100644 --- a/src/rl/sg/Exception.h +++ b/src/rl/sg/Exception.h @@ -28,12 +28,13 @@ #define RL_SG_EXCEPTION_H #include +#include namespace rl { namespace sg { - class Exception : public ::std::runtime_error + class RL_SG_EXPORT Exception : public ::std::runtime_error { public: Exception(const ::std::string& what_arg); diff --git a/src/rl/sg/Factory.h b/src/rl/sg/Factory.h index 0664967e..029c3dba 100644 --- a/src/rl/sg/Factory.h +++ b/src/rl/sg/Factory.h @@ -28,6 +28,7 @@ #define RL_SG_FACTORY_H #include +#include namespace rl { @@ -35,7 +36,7 @@ namespace rl { class Scene; - class Factory + class RL_SG_EXPORT Factory { public: Factory(); diff --git a/src/rl/sg/Model.h b/src/rl/sg/Model.h index df24a388..0e3acd04 100644 --- a/src/rl/sg/Model.h +++ b/src/rl/sg/Model.h @@ -41,7 +41,7 @@ namespace rl class Body; class Scene; - class Model : public Base + class RL_SG_EXPORT Model : public Base { public: typedef ::std::vector::iterator Iterator; diff --git a/src/rl/sg/RaycastScene.h b/src/rl/sg/RaycastScene.h index 90043dcc..bd4f74ae 100644 --- a/src/rl/sg/RaycastScene.h +++ b/src/rl/sg/RaycastScene.h @@ -37,7 +37,7 @@ namespace rl { class Shape; - class RaycastScene : public virtual Scene + class RL_SG_EXPORT RaycastScene : public virtual Scene { public: RaycastScene(); diff --git a/src/rl/sg/Scene.h b/src/rl/sg/Scene.h index 2ef7401e..c8247a9b 100644 --- a/src/rl/sg/Scene.h +++ b/src/rl/sg/Scene.h @@ -41,7 +41,7 @@ namespace rl { class Model; - class Scene : public Base + class RL_SG_EXPORT Scene : public Base { public: typedef ::std::vector::iterator Iterator; diff --git a/src/rl/sg/Shape.h b/src/rl/sg/Shape.h index bab5ae02..20de433e 100644 --- a/src/rl/sg/Shape.h +++ b/src/rl/sg/Shape.h @@ -39,7 +39,7 @@ namespace rl { class Body; - class Shape : public Base + class RL_SG_EXPORT Shape : public Base { public: Shape(::SoVRMLShape* shape, Body* body); diff --git a/src/rl/sg/SimpleScene.h b/src/rl/sg/SimpleScene.h index 8563ffd7..7082fe51 100644 --- a/src/rl/sg/SimpleScene.h +++ b/src/rl/sg/SimpleScene.h @@ -37,7 +37,7 @@ namespace rl class Model; class Shape; - class SimpleScene : public virtual Scene + class RL_SG_EXPORT SimpleScene : public virtual Scene { public: SimpleScene(); diff --git a/src/rl/sg/UrdfFactory.h b/src/rl/sg/UrdfFactory.h index f546aa93..c76eabd7 100644 --- a/src/rl/sg/UrdfFactory.h +++ b/src/rl/sg/UrdfFactory.h @@ -33,7 +33,7 @@ namespace rl { namespace sg { - class UrdfFactory : public Factory + class RL_SG_EXPORT UrdfFactory : public Factory { public: UrdfFactory(); diff --git a/src/rl/sg/XmlFactory.h b/src/rl/sg/XmlFactory.h index ab71bd7c..7f38d38c 100644 --- a/src/rl/sg/XmlFactory.h +++ b/src/rl/sg/XmlFactory.h @@ -35,7 +35,7 @@ namespace rl { namespace sg { - class XmlFactory : public Factory + class RL_SG_EXPORT XmlFactory : public Factory { public: XmlFactory(); diff --git a/src/rl/sg/bullet/Body.h b/src/rl/sg/bullet/Body.h index c35996c7..dedcc3b9 100644 --- a/src/rl/sg/bullet/Body.h +++ b/src/rl/sg/bullet/Body.h @@ -39,7 +39,7 @@ namespace rl { class Model; - class Body : public ::rl::sg::Body + class RL_SG_EXPORT Body : public ::rl::sg::Body { public: Body(Model* model); diff --git a/src/rl/sg/bullet/Model.h b/src/rl/sg/bullet/Model.h index 3052818b..ec04f440 100644 --- a/src/rl/sg/bullet/Model.h +++ b/src/rl/sg/bullet/Model.h @@ -39,7 +39,7 @@ namespace rl { class Scene; - class Model : public ::rl::sg::Model + class RL_SG_EXPORT Model : public ::rl::sg::Model { public: Model(Scene* scene); diff --git a/src/rl/sg/bullet/Scene.h b/src/rl/sg/bullet/Scene.h index 8a7823c4..8cb40690 100644 --- a/src/rl/sg/bullet/Scene.h +++ b/src/rl/sg/bullet/Scene.h @@ -45,7 +45,7 @@ namespace rl */ namespace bullet { - class Scene : public ::rl::sg::DepthScene, public ::rl::sg::DistanceScene, public ::rl::sg::RaycastScene, public ::rl::sg::SimpleScene + class RL_SG_EXPORT Scene : public ::rl::sg::DepthScene, public ::rl::sg::DistanceScene, public ::rl::sg::RaycastScene, public ::rl::sg::SimpleScene { public: Scene(); diff --git a/src/rl/sg/bullet/Shape.h b/src/rl/sg/bullet/Shape.h index 6336e5a3..bb0faf81 100644 --- a/src/rl/sg/bullet/Shape.h +++ b/src/rl/sg/bullet/Shape.h @@ -38,7 +38,7 @@ namespace rl { namespace bullet { - class Shape : public ::rl::sg::Shape + class RL_SG_EXPORT Shape : public ::rl::sg::Shape { public: Shape(::SoVRMLShape* shape, Body* body); diff --git a/src/rl/sg/fcl/Body.h b/src/rl/sg/fcl/Body.h index fc3af355..dd8358cf 100644 --- a/src/rl/sg/fcl/Body.h +++ b/src/rl/sg/fcl/Body.h @@ -40,7 +40,7 @@ namespace rl { class Model; - class Body : public ::rl::sg::Body + class RL_SG_EXPORT Body : public ::rl::sg::Body { public: Body(Model* model); diff --git a/src/rl/sg/fcl/Model.h b/src/rl/sg/fcl/Model.h index 806cc798..9fd66c3b 100644 --- a/src/rl/sg/fcl/Model.h +++ b/src/rl/sg/fcl/Model.h @@ -39,7 +39,7 @@ namespace rl { class Scene; - class Model : public ::rl::sg::Model + class RL_SG_EXPORT Model : public ::rl::sg::Model { public: Model(Scene* scene); diff --git a/src/rl/sg/fcl/Scene.h b/src/rl/sg/fcl/Scene.h index 60f465e3..31b1eef5 100644 --- a/src/rl/sg/fcl/Scene.h +++ b/src/rl/sg/fcl/Scene.h @@ -46,7 +46,7 @@ namespace rl */ namespace fcl { - class Scene : public ::rl::sg::DepthScene, public ::rl::sg::DistanceScene, public ::rl::sg::SimpleScene + class RL_SG_EXPORT Scene : public ::rl::sg::DepthScene, public ::rl::sg::DistanceScene, public ::rl::sg::SimpleScene { public: Scene(); diff --git a/src/rl/sg/fcl/Shape.h b/src/rl/sg/fcl/Shape.h index f53b61ab..ec8d9a88 100644 --- a/src/rl/sg/fcl/Shape.h +++ b/src/rl/sg/fcl/Shape.h @@ -39,7 +39,7 @@ namespace rl { namespace fcl { - class Shape : public ::rl::sg::Shape + class RL_SG_EXPORT Shape : public ::rl::sg::Shape { public: Shape(SoVRMLShape* shape, ::rl::sg::Body* body); diff --git a/src/rl/sg/ode/Body.h b/src/rl/sg/ode/Body.h index a5b43b03..fd16243d 100644 --- a/src/rl/sg/ode/Body.h +++ b/src/rl/sg/ode/Body.h @@ -39,7 +39,7 @@ namespace rl { class Model; - class Body : public ::rl::sg::Body + class RL_SG_EXPORT Body : public ::rl::sg::Body { public: Body(Model* model); diff --git a/src/rl/sg/ode/Model.h b/src/rl/sg/ode/Model.h index 528f3815..8012c542 100644 --- a/src/rl/sg/ode/Model.h +++ b/src/rl/sg/ode/Model.h @@ -39,7 +39,7 @@ namespace rl { class Scene; - class Model : public ::rl::sg::Model + class RL_SG_EXPORT Model : public ::rl::sg::Model { public: Model(Scene* scene); diff --git a/src/rl/sg/ode/Scene.h b/src/rl/sg/ode/Scene.h index b966d2fc..6e7462e9 100644 --- a/src/rl/sg/ode/Scene.h +++ b/src/rl/sg/ode/Scene.h @@ -44,7 +44,7 @@ namespace rl */ namespace ode { - class Scene : public ::rl::sg::DepthScene, public ::rl::sg::RaycastScene, public ::rl::sg::SimpleScene + class RL_SG_EXPORT Scene : public ::rl::sg::DepthScene, public ::rl::sg::RaycastScene, public ::rl::sg::SimpleScene { public: Scene(); diff --git a/src/rl/sg/ode/Shape.h b/src/rl/sg/ode/Shape.h index a70a1d29..945e16ce 100644 --- a/src/rl/sg/ode/Shape.h +++ b/src/rl/sg/ode/Shape.h @@ -38,7 +38,7 @@ namespace rl { namespace ode { - class Shape : public ::rl::sg::Shape + class RL_SG_EXPORT Shape : public ::rl::sg::Shape { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/sg/pqp/Body.h b/src/rl/sg/pqp/Body.h index af73bd3e..5b47abce 100644 --- a/src/rl/sg/pqp/Body.h +++ b/src/rl/sg/pqp/Body.h @@ -37,7 +37,7 @@ namespace rl { class Model; - class Body : public ::rl::sg::Body + class RL_SG_EXPORT Body : public ::rl::sg::Body { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/sg/pqp/Model.h b/src/rl/sg/pqp/Model.h index 312cf859..cb5a29c3 100644 --- a/src/rl/sg/pqp/Model.h +++ b/src/rl/sg/pqp/Model.h @@ -37,7 +37,7 @@ namespace rl { class Scene; - class Model : public ::rl::sg::Model + class RL_SG_EXPORT Model : public ::rl::sg::Model { public: Model(Scene* scene); diff --git a/src/rl/sg/pqp/Scene.h b/src/rl/sg/pqp/Scene.h index 8a6c52fc..b7bd4295 100644 --- a/src/rl/sg/pqp/Scene.h +++ b/src/rl/sg/pqp/Scene.h @@ -44,7 +44,7 @@ namespace rl */ namespace pqp { - class Scene : public ::rl::sg::DistanceScene, public ::rl::sg::SimpleScene + class RL_SG_EXPORT Scene : public ::rl::sg::DistanceScene, public ::rl::sg::SimpleScene { public: Scene(); diff --git a/src/rl/sg/pqp/Shape.h b/src/rl/sg/pqp/Shape.h index 18fb7b7b..372e5577 100644 --- a/src/rl/sg/pqp/Shape.h +++ b/src/rl/sg/pqp/Shape.h @@ -41,7 +41,7 @@ namespace rl { namespace pqp { - class Shape : public ::rl::sg::Shape + class RL_SG_EXPORT Shape : public ::rl::sg::Shape { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/sg/so/Body.h b/src/rl/sg/so/Body.h index 08f1b06f..764eeb8f 100644 --- a/src/rl/sg/so/Body.h +++ b/src/rl/sg/so/Body.h @@ -39,7 +39,7 @@ namespace rl { class Model; - class Body : public ::rl::sg::Body + class RL_SG_EXPORT Body : public ::rl::sg::Body { public: Body(Model* model); diff --git a/src/rl/sg/so/Model.h b/src/rl/sg/so/Model.h index 7571c4c3..81064b27 100644 --- a/src/rl/sg/so/Model.h +++ b/src/rl/sg/so/Model.h @@ -37,7 +37,7 @@ namespace rl { class Scene; - class Model : public ::rl::sg::Model + class RL_SG_EXPORT Model : public ::rl::sg::Model { public: Model(Scene* scene); diff --git a/src/rl/sg/so/Scene.h b/src/rl/sg/so/Scene.h index 7f5197c0..cafae3f6 100644 --- a/src/rl/sg/so/Scene.h +++ b/src/rl/sg/so/Scene.h @@ -40,7 +40,7 @@ namespace rl */ namespace so { - class Scene : public ::rl::sg::Scene + class RL_SG_EXPORT Scene : public ::rl::sg::Scene { public: Scene(); diff --git a/src/rl/sg/so/Shape.h b/src/rl/sg/so/Shape.h index eed34513..6fb06e3a 100644 --- a/src/rl/sg/so/Shape.h +++ b/src/rl/sg/so/Shape.h @@ -39,7 +39,7 @@ namespace rl { class Body; - class Shape : public ::rl::sg::Shape + class RL_SG_EXPORT Shape : public ::rl::sg::Shape { public: Shape(::SoVRMLShape* shape, Body* body); diff --git a/src/rl/sg/solid/Body.h b/src/rl/sg/solid/Body.h index 19a9c19b..46480660 100644 --- a/src/rl/sg/solid/Body.h +++ b/src/rl/sg/solid/Body.h @@ -37,7 +37,7 @@ namespace rl { class Model; - class Body : public ::rl::sg::Body + class RL_SG_EXPORT Body : public ::rl::sg::Body { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/src/rl/sg/solid/Model.h b/src/rl/sg/solid/Model.h index f6c65cd9..f055046c 100644 --- a/src/rl/sg/solid/Model.h +++ b/src/rl/sg/solid/Model.h @@ -37,7 +37,7 @@ namespace rl { class Scene; - class Model : public ::rl::sg::Model + class RL_SG_EXPORT Model : public ::rl::sg::Model { public: Model(Scene* scene); diff --git a/src/rl/sg/solid/Scene.h b/src/rl/sg/solid/Scene.h index a48cbd48..f6cd7bab 100644 --- a/src/rl/sg/solid/Scene.h +++ b/src/rl/sg/solid/Scene.h @@ -48,7 +48,7 @@ namespace rl { class Shape; - class Scene : public ::rl::sg::DepthScene, public ::rl::sg::DistanceScene, public ::rl::sg::RaycastScene, public ::rl::sg::SimpleScene + class RL_SG_EXPORT Scene : public ::rl::sg::DepthScene, public ::rl::sg::DistanceScene, public ::rl::sg::RaycastScene, public ::rl::sg::SimpleScene { public: Scene(); diff --git a/src/rl/sg/solid/Shape.h b/src/rl/sg/solid/Shape.h index a22a9d74..33d7a97b 100644 --- a/src/rl/sg/solid/Shape.h +++ b/src/rl/sg/solid/Shape.h @@ -43,7 +43,7 @@ namespace rl { class Body; - class Shape : public ::rl::sg::Shape + class RL_SG_EXPORT Shape : public ::rl::sg::Shape { public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW From cbc5a4c1739b9e8da55a0e15abf25967eac99333 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 14 Apr 2019 01:08:01 +0200 Subject: [PATCH 205/546] Use Scalar for default value in Transform::distance --- src/rl/math/TransformAddons.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index 28a19d26..890e96e6 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -31,10 +31,10 @@ namespace Eigen { template class Transform { #endif -template +template inline Scalar -distance(const Transform& other, const OtherScalar2& weight = 1) const +distance(const Transform& other, const Scalar& weight = 1) const { using ::std::pow; using ::std::sqrt; From 51a3d3d58f57cb9726adc9c937496eff280d1ea9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 14 Apr 2019 14:07:18 +0200 Subject: [PATCH 206/546] Use target properties for symbol visibility --- CMakeLists.txt | 6 ------ src/rl/hal/CMakeLists.txt | 10 ++++++++++ src/rl/kin/CMakeLists.txt | 10 ++++++++++ src/rl/mdl/CMakeLists.txt | 10 ++++++++++ src/rl/plan/CMakeLists.txt | 10 ++++++++++ src/rl/sg/CMakeLists.txt | 10 ++++++++++ 6 files changed, 50 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 649b83ae..e5d078aa 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -29,12 +29,6 @@ else() endif() endif() -if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) - set(CMAKE_C_VISIBILITY_PRESET hidden) - set(CMAKE_CXX_VISIBILITY_PRESET hidden) - set(CMAKE_VISIBILITY_INLINES_HIDDEN ON) -endif() - set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index b2c3755a..231702d0 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -250,6 +250,16 @@ set_target_properties( VERSION ${VERSION} ) +if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) + set_target_properties( + hal + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON + ) +endif() + if(WIN32) if(BUILD_SHARED_LIBS) set_target_properties( diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index d904e21f..f5eb406f 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -63,6 +63,16 @@ set_target_properties( VERSION ${VERSION} ) +if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) + set_target_properties( + kin + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON + ) +endif() + if(WIN32) if(BUILD_SHARED_LIBS) set_target_properties( diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 10053a6f..cba344bd 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -122,6 +122,16 @@ set_target_properties( VERSION ${VERSION} ) +if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) + set_target_properties( + mdl + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON + ) +endif() + if(WIN32) if(BUILD_SHARED_LIBS) set_target_properties( diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index d45884ff..4ab9f028 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -136,6 +136,16 @@ set_target_properties( VERSION ${VERSION} ) +if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) + set_target_properties( + plan + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON + ) +endif() + if(WIN32) if(BUILD_SHARED_LIBS) set_target_properties( diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 57af5757..94a982ea 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -260,6 +260,16 @@ set_target_properties( VERSION ${VERSION} ) +if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) + set_target_properties( + sg + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON + ) +endif() + if(WIN32) if(BUILD_SHARED_LIBS) set_target_properties( From cf9b6b6f539754ed453bb3a5e30eec002601db9a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 14 Apr 2019 15:42:10 +0200 Subject: [PATCH 207/546] Add RL prefix to CMake options --- CMakeLists.txt | 37 ++++++++++---------- demos/CMakeLists.txt | 18 +++++----- demos/rlCoachKin/CMakeLists.txt | 2 +- demos/rlCoachMdl/CMakeLists.txt | 2 +- demos/rlCollisionDemo/CMakeLists.txt | 2 +- demos/rlPlanDemo/CMakeLists.txt | 2 +- demos/rlRotationConverterDemo/CMakeLists.txt | 2 +- demos/rlSimulator/CMakeLists.txt | 2 +- demos/rlViewDemo/CMakeLists.txt | 2 +- extras/wrlview/CMakeLists.txt | 2 +- rl-config.cmake.in | 16 ++++----- src/CMakeLists.txt | 16 ++++----- tests/CMakeLists.txt | 12 +++---- 13 files changed, 57 insertions(+), 58 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e5d078aa..c2c003d4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -47,28 +47,27 @@ set(Boost_ADDITIONAL_VERSIONS "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1 include(Qt4AutomocMocOptionsBoost) -option(BUILD_DEMOS "Build demos" ON) -option(BUILD_DOCUMENTATION "Build documentation" OFF) -option(BUILD_EXTRAS "Build extras" ON) -option(BUILD_RL_MATH "Build mathematics component" ON) -option(BUILD_RL_UTIL "Build utility component" ON) -option(BUILD_RL_XML "Build XML abstraction layer component" ON) -option(BUILD_TESTS "Build tests" ON) - -cmake_dependent_option(BUILD_RL_HAL "Build hardware abstraction layer component" ON "BUILD_RL_MATH;BUILD_RL_UTIL" OFF) -cmake_dependent_option(BUILD_RL_KIN "Build Denavit-Hartenberg kinematics component" ON "BUILD_RL_MATH;BUILD_RL_XML" OFF) -cmake_dependent_option(BUILD_RL_MDL "Build rigid body kinematics and dynamics component" ON "BUILD_RL_MATH;BUILD_RL_XML" OFF) -cmake_dependent_option(BUILD_RL_SG "Build scene graph abstraction component" ON "BUILD_RL_MATH;BUILD_RL_UTIL;BUILD_RL_XML" OFF) - -cmake_dependent_option(BUILD_RL_PLAN "Build path planning component" ON "BUILD_RL_KIN;BUILD_RL_MATH;BUILD_RL_MDL;BUILD_RL_SG;BUILD_RL_UTIL;BUILD_RL_XML" OFF) - if(WIN32) option(BUILD_SHARED_LIBS "Build shared libraries" OFF) else() option(BUILD_SHARED_LIBS "Build shared libraries" ON) endif() -option(USE_QT5 "Prefer Qt5 over Qt4 if available" ON) +option(RL_BUILD_DEMOS "Build demos" ON) +option(RL_BUILD_DOCUMENTATION "Build documentation" OFF) +option(RL_BUILD_EXTRAS "Build extras" ON) +option(RL_BUILD_MATH "Build mathematics component" ON) +option(RL_BUILD_TESTS "Build tests" ON) +option(RL_BUILD_UTIL "Build utility component" ON) +option(RL_BUILD_XML "Build XML abstraction layer component" ON) +option(RL_USE_QT5 "Prefer Qt5 over Qt4 if available" ON) + +cmake_dependent_option(RL_BUILD_HAL "Build hardware abstraction layer component" ON "RL_BUILD_MATH;RL_BUILD_UTIL" OFF) +cmake_dependent_option(RL_BUILD_KIN "Build Denavit-Hartenberg kinematics component" ON "RL_BUILD_MATH;RL_BUILD_XML" OFF) +cmake_dependent_option(RL_BUILD_MDL "Build rigid body kinematics and dynamics component" ON "RL_BUILD_MATH;RL_BUILD_XML" OFF) +cmake_dependent_option(RL_BUILD_SG "Build scene graph abstraction component" ON "RL_BUILD_MATH;RL_BUILD_UTIL;RL_BUILD_XML" OFF) + +cmake_dependent_option(RL_BUILD_PLAN "Build path planning component" ON "RL_BUILD_KIN;RL_BUILD_MATH;RL_BUILD_MDL;RL_BUILD_SG;RL_BUILD_UTIL;RL_BUILD_XML" OFF) include_directories(BEFORE src/rl/std) @@ -76,11 +75,11 @@ add_subdirectory(src/rl/std) add_subdirectory(src) add_subdirectory(examples) -if(BUILD_DEMOS) +if(RL_BUILD_DEMOS) add_subdirectory(demos) endif() -if(BUILD_TESTS) +if(RL_BUILD_TESTS) enable_testing() add_subdirectory(tests) endif() @@ -140,7 +139,7 @@ if(DEFINED TARGETS) ) endif() -if(BUILD_EXTRAS) +if(RL_BUILD_EXTRAS) add_subdirectory(extras) endif() diff --git a/demos/CMakeLists.txt b/demos/CMakeLists.txt index c51ef1c5..76e36dc1 100644 --- a/demos/CMakeLists.txt +++ b/demos/CMakeLists.txt @@ -1,4 +1,4 @@ -if(BUILD_RL_MATH) +if(RL_BUILD_MATH) add_subdirectory(rlDenavitHartenbergDemo) add_subdirectory(rlEulerAnglesDemo) add_subdirectory(rlFilterDemo) @@ -10,27 +10,27 @@ if(BUILD_RL_MATH) add_subdirectory(rlTrapezoidalVelocityDemo) endif() -if(BUILD_RL_UTIL) +if(RL_BUILD_UTIL) add_subdirectory(rlThreadsDemo) add_subdirectory(rlTimerDemo) endif() -if(BUILD_RL_XML) +if(RL_BUILD_XML) add_subdirectory(rlLoadXmlDemo) endif() -if(BUILD_RL_KIN) +if(RL_BUILD_KIN) add_subdirectory(rlJacobianDemo) add_subdirectory(rlPumaDemo) endif() -if(BUILD_RL_MDL) +if(RL_BUILD_MDL) add_subdirectory(rlDynamics1Demo) add_subdirectory(rlDynamics2Demo) add_subdirectory(rlInversePositionDemo) endif() -if(BUILD_RL_HAL) +if(RL_BUILD_HAL) add_subdirectory(rlAxisControllerDemo) add_subdirectory(rlCameraDemo) add_subdirectory(rlGripperDemo) @@ -40,16 +40,16 @@ if(BUILD_RL_HAL) add_subdirectory(rlSocketDemo) endif() -if(BUILD_RL_SG) +if(RL_BUILD_SG) add_subdirectory(rlCollisionDemo) add_subdirectory(rlViewDemo) endif() -if(BUILD_RL_KIN AND BUILD_RL_SG) +if(RL_BUILD_KIN AND RL_BUILD_SG) add_subdirectory(rlCoachKin) endif() -if(BUILD_RL_MDL AND BUILD_RL_SG) +if(RL_BUILD_MDL AND RL_BUILD_SG) add_subdirectory(rlCoachMdl) add_subdirectory(rlSimulator) endif() diff --git a/demos/rlCoachKin/CMakeLists.txt b/demos/rlCoachKin/CMakeLists.txt index ef933677..92c4252f 100644 --- a/demos/rlCoachKin/CMakeLists.txt +++ b/demos/rlCoachKin/CMakeLists.txt @@ -1,7 +1,7 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt5_FOUND) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) endif() diff --git a/demos/rlCoachMdl/CMakeLists.txt b/demos/rlCoachMdl/CMakeLists.txt index 65b41f33..dd4b79f6 100644 --- a/demos/rlCoachMdl/CMakeLists.txt +++ b/demos/rlCoachMdl/CMakeLists.txt @@ -1,7 +1,7 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt5_FOUND) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) endif() diff --git a/demos/rlCollisionDemo/CMakeLists.txt b/demos/rlCollisionDemo/CMakeLists.txt index 11edbdd3..cfc44a46 100644 --- a/demos/rlCollisionDemo/CMakeLists.txt +++ b/demos/rlCollisionDemo/CMakeLists.txt @@ -1,7 +1,7 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt5_FOUND) find_package(Qt5 COMPONENTS Core Gui OpenGL Widgets QUIET) endif() diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index 2728638b..9e6b97b2 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -2,7 +2,7 @@ find_package(Boost REQUIRED) find_package(OpenGL REQUIRED) find_package(SoQt) -if(USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt5_FOUND) find_package(Qt5 COMPONENTS Core Gui OpenGL PrintSupport Widgets QUIET) endif() diff --git a/demos/rlRotationConverterDemo/CMakeLists.txt b/demos/rlRotationConverterDemo/CMakeLists.txt index 1f8bdb25..25323eb8 100644 --- a/demos/rlRotationConverterDemo/CMakeLists.txt +++ b/demos/rlRotationConverterDemo/CMakeLists.txt @@ -1,4 +1,4 @@ -if(USE_QT5) +if(RL_USE_QT5) find_package(Qt5 COMPONENTS Core Gui Widgets QUIET) endif() diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index 0aeef929..e492b6e3 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -5,7 +5,7 @@ endif() find_package(OpenGL REQUIRED) find_package(SoQt) -if(USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt5_FOUND) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) endif() diff --git a/demos/rlViewDemo/CMakeLists.txt b/demos/rlViewDemo/CMakeLists.txt index a4754da5..52943525 100644 --- a/demos/rlViewDemo/CMakeLists.txt +++ b/demos/rlViewDemo/CMakeLists.txt @@ -1,6 +1,6 @@ find_package(SoQt) -if(USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt5_FOUND) find_package(Qt5 COMPONENTS Core Gui OpenGL Widgets QUIET) endif() diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 24044385..7ea148d6 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -2,7 +2,7 @@ project(wrlview) find_package(SoQt) -if(USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt5_FOUND) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) endif() diff --git a/rl-config.cmake.in b/rl-config.cmake.in index 0dcc4acb..75f5b297 100644 --- a/rl-config.cmake.in +++ b/rl-config.cmake.in @@ -3,14 +3,14 @@ set(RL_VERSION_MAJOR "@VERSION_MAJOR@") set(RL_VERSION_MINOR "@VERSION_MINOR@") set(RL_VERSION_PATCH "@VERSION_PATCH@") -set(RL_HAL_FOUND @BUILD_RL_HAL@) -set(RL_KIN_FOUND @BUILD_RL_KIN@) -set(RL_MATH_FOUND @BUILD_RL_MATH@) -set(RL_MDL_FOUND @BUILD_RL_MDL@) -set(RL_PLAN_FOUND @BUILD_RL_PLAN@) -set(RL_SG_FOUND @BUILD_RL_SG@) -set(RL_UTIL_FOUND @BUILD_RL_UTIL@) -set(RL_XML_FOUND @BUILD_RL_XML@) +set(RL_HAL_FOUND @RL_BUILD_HAL@) +set(RL_KIN_FOUND @RL_BUILD_KIN@) +set(RL_MATH_FOUND @RL_BUILD_MATH@) +set(RL_MDL_FOUND @RL_BUILD_MDL@) +set(RL_PLAN_FOUND @RL_BUILD_PLAN@) +set(RL_SG_FOUND @RL_BUILD_SG@) +set(RL_UTIL_FOUND @RL_BUILD_UTIL@) +set(RL_XML_FOUND @RL_BUILD_XML@) @PACKAGE_INIT@ diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index e1e0243a..aadfd290 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -1,39 +1,39 @@ -if(BUILD_RL_MATH) +if(RL_BUILD_MATH) add_subdirectory(rl/math) list(APPEND TARGETS math) endif() -if(BUILD_RL_UTIL) +if(RL_BUILD_UTIL) add_subdirectory(rl/util) list(APPEND TARGETS util) endif() -if(BUILD_RL_XML) +if(RL_BUILD_XML) add_subdirectory(rl/xml) list(APPEND TARGETS xml) endif() -if(BUILD_RL_KIN) +if(RL_BUILD_KIN) add_subdirectory(rl/kin) list(APPEND TARGETS kin) endif() -if(BUILD_RL_MDL) +if(RL_BUILD_MDL) add_subdirectory(rl/mdl) list(APPEND TARGETS mdl) endif() -if(BUILD_RL_HAL) +if(RL_BUILD_HAL) add_subdirectory(rl/hal) list(APPEND TARGETS hal) endif() -if(BUILD_RL_SG) +if(RL_BUILD_SG) add_subdirectory(rl/sg) list(APPEND TARGETS sg) endif() -if(BUILD_RL_PLAN) +if(RL_BUILD_PLAN) add_subdirectory(rl/plan) list(APPEND TARGETS plan) endif() diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index fdf8f712..af2ee738 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -1,4 +1,4 @@ -if(BUILD_RL_MATH) +if(RL_BUILD_MATH) add_subdirectory(rlCircularTest) add_subdirectory(rlMathDeltaTest) add_subdirectory(rlNearestNeighborsTest) @@ -6,26 +6,26 @@ if(BUILD_RL_MATH) add_subdirectory(rlSplineTest) endif() -if(BUILD_RL_KIN) +if(RL_BUILD_KIN) add_subdirectory(rlInverseKinematicsKinTest) add_subdirectory(rlJacobianKinTest) endif() -if(BUILD_RL_MDL) +if(RL_BUILD_MDL) add_subdirectory(rlDynamicsTest) add_subdirectory(rlInverseKinematicsMdlTest) add_subdirectory(rlJacobianMdlTest) endif() -if(BUILD_RL_HAL) +if(RL_BUILD_HAL) add_subdirectory(rlHalEndianTest) endif() -if(BUILD_RL_MDL AND BUILD_RL_SG) +if(RL_BUILD_MDL AND RL_BUILD_SG) add_subdirectory(rlCollisionTest) endif() -if(BUILD_RL_PLAN) +if(RL_BUILD_PLAN) add_subdirectory(rlEetTest) add_subdirectory(rlPrmTest) endif() From e52190b5dfe4ee23c39da4c81a16df47afc6adfc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 15 Apr 2019 00:15:06 +0200 Subject: [PATCH 208/546] Minor update --- CMakeLists.txt | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c2c003d4..4cb98d6c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,6 +14,12 @@ include(CMakeDependentOption) include(CMakePackageConfigHelpers) include(GenerateExportHeader) include(GNUInstallDirs) +include(Qt4AutomocMocOptionsBoost) + +set(Boost_ADDITIONAL_VERSIONS "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") +set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) +set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) +set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) if(NOT CMAKE_VERSION VERSION_LESS 3.1) set(CMAKE_CXX_STANDARD 11) @@ -29,10 +35,6 @@ else() endif() endif() -set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) -set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) -set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) - if(WIN32) add_definitions( -D_ENABLE_EXTENDED_ALIGNED_STORAGE @@ -43,10 +45,6 @@ if(WIN32) ) endif() -set(Boost_ADDITIONAL_VERSIONS "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") - -include(Qt4AutomocMocOptionsBoost) - if(WIN32) option(BUILD_SHARED_LIBS "Build shared libraries" OFF) else() From 6fcd429184a4034be2544357b47aeac81ddefe77 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 20:01:40 +0200 Subject: [PATCH 209/546] Minor fix --- demos/rlSimulator/MainWindow.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index ed2b620d..e89ba9c5 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -120,7 +120,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->geometryModels = this->scene->getModel(0); this->kinematicModels.reset(kinematicFactory.create(QApplication::arguments()[2].toStdString())); - this->simulationResetQ = rl::math::Vector::Zero(kinematicModels->getDof()); + this->simulationResetQ = rl::math::Vector::Zero(kinematicModels->getDofPosition()); this->simulationResetQd = rl::math::Vector::Zero(kinematicModels->getDof()); this->simulationResetQdd = rl::math::Vector::Zero(kinematicModels->getDof()); @@ -232,7 +232,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SLOT(operationalChanged(const QModelIndex&, const QModelIndex&)) ); - rl::math::Vector q(this->kinematicModels->getDof()); + rl::math::Vector q(this->kinematicModels->getDofPosition()); q.setZero(); positionModel->setData(q); //TODO? @@ -441,7 +441,7 @@ MainWindow::timerEvent(QTimerEvent *event) dynamic->setWorldGravity(g); std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); - rl::math::Vector q(dynamic->getDof()); + rl::math::Vector q(dynamic->getDofPosition()); rl::math::Vector qd(dynamic->getDof()); rl::math::Vector qdd(dynamic->getDof()); rl::math::Vector torque(dynamic->getDof()); From a7396c533cdbf3694eef5d7a8482aaa5df9db60f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Apr 2019 22:05:24 +0200 Subject: [PATCH 210/546] Add CMake options to disable optional components --- src/rl/hal/CMakeLists.txt | 21 +++++++++++++-------- src/rl/mdl/CMakeLists.txt | 6 ++++-- src/rl/sg/CMakeLists.txt | 28 +++++++++++++++++----------- src/rl/util/CMakeLists.txt | 11 +++++++---- 4 files changed, 41 insertions(+), 25 deletions(-) diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 231702d0..1b745356 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -9,6 +9,11 @@ find_package(cifX) find_package(Comedi) find_package(libdc1394) +cmake_dependent_option(RL_BUILD_HAL_ATIDAQ "Build ATIDAQ support" ON "RL_BUILD_HAL;ATIDAQ_FOUND;Comedi_FOUND" OFF) +cmake_dependent_option(RL_BUILD_HAL_CIFX "Build cifX support" ON "RL_BUILD_HAL;cifX_FOUND" OFF) +cmake_dependent_option(RL_BUILD_HAL_COMEDI "Build Comedi support" ON "RL_BUILD_HAL;Comedi_FOUND" OFF) +cmake_dependent_option(RL_BUILD_HAL_LIBDC1394 "Build libdc1394 support" ON "RL_BUILD_HAL;libdc1394_FOUND" OFF) + include(TestBigEndian) test_big_endian(BIG_ENDIAN) @@ -139,24 +144,24 @@ set( WeissWsg50.cpp ) -if(ATIDAQ_FOUND AND Comedi_FOUND) +if(RL_BUILD_HAL_ATIDAQ) list(APPEND HDRS Ati.h) list(APPEND SRCS Ati.cpp) endif() -if(cifX_FOUND) +if(RL_BUILD_HAL_CIFX) list(APPEND HDRS HilscherCifx.h) list(APPEND SRCS HilscherCifx.cpp) endif() -if(Comedi_FOUND) +if(RL_BUILD_HAL_COMEDI) list(APPEND HDRS Comedi.h) list(APPEND HDRS Jr3.h) list(APPEND SRCS Comedi.cpp) list(APPEND SRCS Jr3.cpp) endif() -if(libdc1394_FOUND) +if(RL_BUILD_HAL_LIBDC1394) list(APPEND HDRS Dc1394Camera.h) list(APPEND SRCS Dc1394Camera.cpp) endif() @@ -213,22 +218,22 @@ target_include_directories( ${Boost_INCLUDE_DIR} ) -if(ATIDAQ_FOUND AND Comedi_FOUND) +if(RL_BUILD_HAL_ATIDAQ) target_include_directories(hal PUBLIC ${ATIDAQ_INCLUDE_DIRS}) target_link_libraries(hal ${ATIDAQ_LIBRARIES}) endif() -if(cifX_FOUND) +if(RL_BUILD_HAL_CIFX) target_include_directories(hal PUBLIC ${cifX_INCLUDE_DIRS}) target_link_libraries(hal ${cifX_LIBRARIES}) endif() -if(Comedi_FOUND) +if(RL_BUILD_HAL_COMEDI) target_include_directories(hal PUBLIC ${Comedi_INCLUDE_DIRS}) target_link_libraries(hal ${Comedi_LIBRARIES}) endif() -if(libdc1394_FOUND) +if(RL_BUILD_HAL_LIBDC1394) target_compile_definitions(hal PUBLIC ${libdc1394_DEFINITIONS}) target_include_directories(hal PUBLIC ${libdc1394_INCLUDE_DIRS}) target_link_libraries(hal ${libdc1394_LIBRARIES}) diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index cba344bd..3b1f7d83 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -1,6 +1,8 @@ find_package(Boost REQUIRED) find_package(NLopt) +cmake_dependent_option(RL_BUILD_MDL_NLOPT "Build NLopt support" ON "RL_BUILD_MDL;NLOPT_FOUND" OFF) + set( HDRS AnalyticalInverseKinematics.h @@ -67,7 +69,7 @@ set( XmlFactory.cpp ) -if(NLOPT_FOUND) +if(RL_BUILD_MDL_NLOPT) list(APPEND HDRS NloptInverseKinematics.h) list(APPEND SRCS NloptInverseKinematics.cpp) endif() @@ -108,7 +110,7 @@ target_link_libraries( xml ) -if(NLOPT_FOUND) +if(RL_BUILD_MDL_NLOPT) target_compile_definitions(mdl INTERFACE -DRL_MDL_NLOPT) target_include_directories(mdl PUBLIC ${NLOPT_INCLUDE_DIRS}) target_link_libraries(mdl ${NLOPT_LIBRARY}) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 94a982ea..09b7e862 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -9,6 +9,12 @@ find_package(ODE) find_package(PQP) find_package(SOLID3) +cmake_dependent_option(RL_BUILD_SG_BULLET "Build Bullet support" ON "RL_BUILD_SG;BULLET_FOUND" OFF) +cmake_dependent_option(RL_BUILD_SG_FCL "Build FCL support" ON "RL_BUILD_SG;CCD_FOUND;FCL_FOUND" OFF) +cmake_dependent_option(RL_BUILD_SG_ODE "Build ODE support" ON "RL_BUILD_SG;ODE_FOUND" OFF) +cmake_dependent_option(RL_BUILD_SG_PQP "Build PQP support" ON "RL_BUILD_SG;PQP_FOUND" OFF) +cmake_dependent_option(RL_BUILD_SG_SOLID "Build SOLID support" ON "RL_BUILD_SG;SOLID3_FOUND" OFF) + set( BASE_HDRS Base.h @@ -45,7 +51,7 @@ set( ) list(APPEND SRCS ${BASE_SRCS}) -if(BULLET_FOUND) +if(RL_BUILD_SG_BULLET) set( BULLET_HDRS bullet/Body.h @@ -83,7 +89,7 @@ if(Coin_FOUND) list(APPEND SRCS ${COIN_SRCS}) endif() -if(CCD_FOUND AND FCL_FOUND) +if(RL_BUILD_SG_FCL) set( FCL_HDRS fcl/Body.h @@ -102,7 +108,7 @@ if(CCD_FOUND AND FCL_FOUND) list(APPEND SRCS ${FCL_SRCS}) endif() -if(ODE_FOUND) +if(RL_BUILD_SG_ODE) set( ODE_HDRS ode/Body.h @@ -121,7 +127,7 @@ if(ODE_FOUND) list(APPEND SRCS ${ODE_SRCS}) endif() -if(PQP_FOUND) +if(RL_BUILD_SG_PQP) set( PQP_HDRS pqp/Body.h @@ -140,7 +146,7 @@ if(PQP_FOUND) list(APPEND SRCS ${PQP_SRCS}) endif() -if(SOLID3_FOUND) +if(RL_BUILD_SG_SOLID) set( SOLID_HDRS solid/Body.h @@ -186,14 +192,14 @@ target_include_directories( $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> ) -if(BULLET_FOUND) +if(RL_BUILD_SG_BULLET) target_compile_definitions(sg INTERFACE -DRL_SG_BULLET) target_include_directories(sg PUBLIC ${BULLET_INCLUDE_DIRS}) target_link_libraries(sg ${BULLET_LIBRARIES}) install(FILES ${BULLET_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/bullet COMPONENT development) endif() -if(CCD_FOUND AND (FCL_FOUND OR ODE_FOUND)) +if(CCD_FOUND AND (RL_BUILD_SG_FCL OR RL_BUILD_SG_ODE)) target_include_directories(sg PUBLIC ${CCD_INCLUDE_DIRS}) target_link_libraries(sg ${CCD_LIBRARIES}) endif() @@ -222,7 +228,7 @@ if(Coin_FOUND) install(FILES ${COIN_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/so COMPONENT development) endif() -if(FCL_FOUND AND CCD_FOUND) +if(RL_BUILD_SG_FCL) target_compile_definitions(sg INTERFACE -DRL_SG_FCL) target_compile_definitions(sg PUBLIC ${FCL_DEFINITIONS}) target_include_directories(sg PUBLIC ${FCL_INCLUDE_DIRS}) @@ -230,7 +236,7 @@ if(FCL_FOUND AND CCD_FOUND) install(FILES ${FCL_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/fcl COMPONENT development) endif() -if(ODE_FOUND) +if(RL_BUILD_SG_ODE) target_compile_definitions(sg INTERFACE -DRL_SG_ODE) target_compile_definitions(sg PUBLIC ${ODE_DEFINITIONS}) target_include_directories(sg PUBLIC ${ODE_INCLUDE_DIRS}) @@ -238,14 +244,14 @@ if(ODE_FOUND) install(FILES ${ODE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/ode COMPONENT development) endif() -if(PQP_FOUND) +if(RL_BUILD_SG_PQP) target_compile_definitions(sg INTERFACE -DRL_SG_PQP) target_include_directories(sg PUBLIC ${PQP_INCLUDE_DIRS}) target_link_libraries(sg ${PQP_LIBRARIES}) install(FILES ${PQP_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/pqp COMPONENT development) endif() -if(SOLID3_FOUND) +if(RL_BUILD_SG_SOLID) target_compile_definitions(sg INTERFACE -DRL_SG_SOLID) target_include_directories(sg PUBLIC ${SOLID3_INCLUDE_DIRS}) target_link_libraries(sg ${SOLID3_LIBRARIES}) diff --git a/src/rl/util/CMakeLists.txt b/src/rl/util/CMakeLists.txt index 9d8e7f08..3c3c4642 100644 --- a/src/rl/util/CMakeLists.txt +++ b/src/rl/util/CMakeLists.txt @@ -2,6 +2,9 @@ find_package(RTAI) find_package(Threads REQUIRED) find_package(Xenomai) +cmake_dependent_option(RL_BUILD_UTIL_RTAI "Build RTAI support" ON "RL_BUILD_UTIL;RTAI_FOUND" OFF) +cmake_dependent_option(RL_BUILD_UTIL_XENOMAI "Build Xenomai support" ON "RL_BUILD_UTIL;Xenomai_FOUND" OFF) + set( BASE_HDRS process.h @@ -9,7 +12,7 @@ set( ) list(APPEND HDRS ${BASE_HDRS}) -if(RTAI_FOUND) +if(RL_BUILD_UTIL_RTAI) set( RTAI_HDRS rtai/chrono.h @@ -18,7 +21,7 @@ if(RTAI_FOUND) list(APPEND HDRS ${RTAI_HDRS}) endif() -if(Xenomai_FOUND) +if(RL_BUILD_UTIL_XENOMAI) set( XENOMAI_HDRS xenomai/chrono.h @@ -55,7 +58,7 @@ target_include_directories( install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/util COMPONENT development) -if(RTAI_FOUND) +if(RL_BUILD_UTIL_RTAI) target_include_directories(util INTERFACE ${RTAI_INCLUDE_DIRS}) if(NOT CMAKE_VERSION VERSION_LESS 3.0) target_link_libraries(util INTERFACE ${RTAI_LIBRARIES}) @@ -65,7 +68,7 @@ if(RTAI_FOUND) install(FILES ${RTAI_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/util/rtai COMPONENT development) endif() -if(Xenomai_FOUND) +if(RL_BUILD_UTIL_XENOMAI) target_compile_definitions(util INTERFACE ${Xenomai_DEFINITIONS}) target_include_directories(util INTERFACE ${Xenomai_INCLUDE_DIRS}) if(NOT CMAKE_VERSION VERSION_LESS 3.0) From 14db6ac7fa709d70761d3b3817e85b3f32111f0e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Apr 2019 22:45:40 +0200 Subject: [PATCH 211/546] Update copyright header --- tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp | 2 +- tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp index da159f7e..bc80b7a8 100644 --- a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp +++ b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2012, Andre Gaschler +// Copyright (c) 2019, Markus Rickert // All rights reserved. // // Redistribution and use in source and binary forms, with or without diff --git a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp index 9a3c7d7b..58d87de9 100644 --- a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp +++ b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2014, Andre Gaschler +// Copyright (c) 2019, Markus Rickert // All rights reserved. // // Redistribution and use in source and binary forms, with or without From 7c83e2c7b3bbbc76a9641e3dadf73c14d81aa385 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Apr 2019 22:53:26 +0200 Subject: [PATCH 212/546] Minor fixes --- demos/rlSimulator/ConfigurationDelegate.cpp | 2 + demos/rlSimulator/ConfigurationDelegate.h | 36 +++- demos/rlSimulator/ConfigurationModel.cpp | 4 +- demos/rlSimulator/ConfigurationModel.h | 36 +++- demos/rlSimulator/MainWindow.cpp | 189 ++++++++++---------- demos/rlSimulator/MainWindow.h | 8 +- demos/rlSimulator/Socket.cpp | 8 +- 7 files changed, 161 insertions(+), 122 deletions(-) diff --git a/demos/rlSimulator/ConfigurationDelegate.cpp b/demos/rlSimulator/ConfigurationDelegate.cpp index d39778e1..3a15349c 100644 --- a/demos/rlSimulator/ConfigurationDelegate.cpp +++ b/demos/rlSimulator/ConfigurationDelegate.cpp @@ -108,6 +108,7 @@ VelocityDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& opti Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels->getVelocityUnits(); editor->setRange(-10000, 10000); //TODO? + if (rl::math::UNIT_RADIAN == qUnits(index.row())) { editor->setSingleStep(1.0); @@ -130,6 +131,7 @@ AccelerationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels->getVelocityUnits(); editor->setRange(-10000, 10000); + if (rl::math::UNIT_RADIAN == qUnits(index.row())) { editor->setSingleStep(10.0); diff --git a/demos/rlSimulator/ConfigurationDelegate.h b/demos/rlSimulator/ConfigurationDelegate.h index 7d53ad99..e878b4cc 100644 --- a/demos/rlSimulator/ConfigurationDelegate.h +++ b/demos/rlSimulator/ConfigurationDelegate.h @@ -60,8 +60,8 @@ public slots: class PositionDelegate : public ConfigurationDelegate { public: - PositionDelegate(QObject* parent = nullptr) - : ConfigurationDelegate(parent) + PositionDelegate(QObject* parent = nullptr) : + ConfigurationDelegate(parent) { } @@ -72,13 +72,18 @@ class PositionDelegate : public ConfigurationDelegate } QWidget* createEditor(QWidget* parent, const QStyleOptionViewItem& option, const QModelIndex& index) const; + +protected: + +private: + }; class VelocityDelegate : public ConfigurationDelegate { public: - VelocityDelegate(QObject* parent = nullptr) - : ConfigurationDelegate(parent) + VelocityDelegate(QObject* parent = nullptr) : + ConfigurationDelegate(parent) { } @@ -89,13 +94,18 @@ class VelocityDelegate : public ConfigurationDelegate } QWidget* createEditor(QWidget* parent, const QStyleOptionViewItem& option, const QModelIndex& index) const; + +protected: + +private: + }; class AccelerationDelegate : public ConfigurationDelegate { public: - AccelerationDelegate(QObject* parent = nullptr) - : ConfigurationDelegate(parent) + AccelerationDelegate(QObject* parent = nullptr) : + ConfigurationDelegate(parent) { } @@ -106,13 +116,18 @@ class AccelerationDelegate : public ConfigurationDelegate } QWidget* createEditor(QWidget* parent, const QStyleOptionViewItem& option, const QModelIndex& index) const; + +protected: + +private: + }; class TorqueDelegate : public ConfigurationDelegate { public: - TorqueDelegate(QObject* parent = nullptr) - : ConfigurationDelegate(parent) + TorqueDelegate(QObject* parent = nullptr) : + ConfigurationDelegate(parent) { } @@ -123,6 +138,11 @@ class TorqueDelegate : public ConfigurationDelegate } QWidget* createEditor(QWidget* parent, const QStyleOptionViewItem& option, const QModelIndex& index) const; + +protected: + +private: + }; #endif // CONFIGURATIONDELEGATE_H diff --git a/demos/rlSimulator/ConfigurationModel.cpp b/demos/rlSimulator/ConfigurationModel.cpp index 5495e39f..b25c1489 100644 --- a/demos/rlSimulator/ConfigurationModel.cpp +++ b/demos/rlSimulator/ConfigurationModel.cpp @@ -404,9 +404,7 @@ TorqueModel::data(const QModelIndex& index, int role) const { case Qt::DisplayRole: case Qt::EditRole: - { - return MainWindow::instance()->externalTorque(index.row()); - } + return MainWindow::instance()->externalTorque(index.row()); break; case Qt::TextAlignmentRole: return Qt::AlignRight; diff --git a/demos/rlSimulator/ConfigurationModel.h b/demos/rlSimulator/ConfigurationModel.h index c6e38c68..076ca5db 100644 --- a/demos/rlSimulator/ConfigurationModel.h +++ b/demos/rlSimulator/ConfigurationModel.h @@ -65,8 +65,8 @@ public slots: class PositionModel : public ConfigurationModel { public: - PositionModel(QObject* parent = nullptr) - : ConfigurationModel(parent) + PositionModel(QObject* parent = nullptr) : + ConfigurationModel(parent) { } @@ -77,13 +77,18 @@ class PositionModel : public ConfigurationModel int rowCount(const QModelIndex& parent = QModelIndex()) const; QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + +protected: + +private: + }; class VelocityModel : public ConfigurationModel { public: - VelocityModel(QObject* parent = nullptr) - : ConfigurationModel(parent) + VelocityModel(QObject* parent = nullptr) : + ConfigurationModel(parent) { } @@ -94,13 +99,18 @@ class VelocityModel : public ConfigurationModel int rowCount(const QModelIndex& parent = QModelIndex()) const; QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + +protected: + +private: + }; class AccelerationModel : public ConfigurationModel { public: - AccelerationModel(QObject* parent = nullptr) - : ConfigurationModel(parent) + AccelerationModel(QObject* parent = nullptr) : + ConfigurationModel(parent) { } @@ -111,13 +121,18 @@ class AccelerationModel : public ConfigurationModel int rowCount(const QModelIndex& parent = QModelIndex()) const; QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + +protected: + +private: + }; class TorqueModel : public ConfigurationModel { public: - TorqueModel(QObject* parent = nullptr) - : ConfigurationModel(parent) + TorqueModel(QObject* parent = nullptr) : + ConfigurationModel(parent) { } @@ -128,6 +143,11 @@ class TorqueModel : public ConfigurationModel int rowCount(const QModelIndex& parent = QModelIndex()) const; QVariant data(const QModelIndex& index, int role = Qt::DisplayRole) const; + +protected: + +private: + }; #endif // CONFIGURATIONMODEL_H diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index e89ba9c5..123c1bb4 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include #include #include @@ -78,7 +79,6 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : saveImageAction(new QAction(this)), saveSceneAction(new QAction(this)), server(new Server(this)), - serverConnectionStatus(nullptr), simulationDampingFactor(nullptr), simulationDampingValue(static_cast(0.001)), simulationDockWidget(new QDockWidget(this)), @@ -120,9 +120,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->geometryModels = this->scene->getModel(0); this->kinematicModels.reset(kinematicFactory.create(QApplication::arguments()[2].toStdString())); - this->simulationResetQ = rl::math::Vector::Zero(kinematicModels->getDofPosition()); - this->simulationResetQd = rl::math::Vector::Zero(kinematicModels->getDof()); - this->simulationResetQdd = rl::math::Vector::Zero(kinematicModels->getDof()); + this->simulationResetQ = rl::math::Vector::Zero(this->kinematicModels->getDofPosition()); + this->simulationResetQd = rl::math::Vector::Zero(this->kinematicModels->getDof()); + this->simulationResetQdd = rl::math::Vector::Zero(this->kinematicModels->getDof()); this->positionDelegate = new PositionDelegate(this); this->positionModel = new PositionModel(this); @@ -134,8 +134,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : #endif // QT_VERSION this->positionView->horizontalHeader()->hide(); this->positionView->setAlternatingRowColors(true); - this->positionView->setItemDelegate(positionDelegate); - this->positionView->setModel(positionModel); + this->positionView->setItemDelegate(this->positionDelegate); + this->positionView->setModel(this->positionModel); #if QT_VERSION >= 0x050000 this->positionView->verticalHeader()->setSectionResizeMode(QHeaderView::ResizeToContents); #else // QT_VERSION @@ -152,8 +152,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : #endif // QT_VERSION this->velocityView->horizontalHeader()->hide(); this->velocityView->setAlternatingRowColors(true); - this->velocityView->setItemDelegate(velocityDelegate); - this->velocityView->setModel(velocityModel); + this->velocityView->setItemDelegate(this->velocityDelegate); + this->velocityView->setModel(this->velocityModel); #if QT_VERSION >= 0x050000 this->velocityView->verticalHeader()->setSectionResizeMode(QHeaderView::ResizeToContents); #else // QT_VERSION @@ -170,8 +170,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : #endif // QT_VERSION this->accelerationView->horizontalHeader()->hide(); this->accelerationView->setAlternatingRowColors(true); - this->accelerationView->setItemDelegate(accelerationDelegate); - this->accelerationView->setModel(accelerationModel); + this->accelerationView->setItemDelegate(this->accelerationDelegate); + this->accelerationView->setModel(this->accelerationModel); #if QT_VERSION >= 0x050000 this->accelerationView->verticalHeader()->setSectionResizeMode(QHeaderView::ResizeToContents); #else // QT_VERSION @@ -188,8 +188,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : #endif // QT_VERSION this->torqueView->horizontalHeader()->hide(); this->torqueView->setAlternatingRowColors(true); - this->torqueView->setItemDelegate(torqueDelegate); - this->torqueView->setModel(torqueModel); + this->torqueView->setItemDelegate(this->torqueDelegate); + this->torqueView->setModel(this->torqueModel); #if QT_VERSION >= 0x050000 this->torqueView->verticalHeader()->setSectionResizeMode(QHeaderView::ResizeToContents); #else // QT_VERSION @@ -219,7 +219,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->operationalViews = operationalView; QObject::connect( - positionModel, + this->positionModel, SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), operationalModel, SLOT(configurationChanged(const QModelIndex&, const QModelIndex&)) @@ -228,60 +228,61 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QObject::connect( operationalModel, SIGNAL(dataChanged(const QModelIndex&, const QModelIndex&)), - positionModel, + this->positionModel, SLOT(operationalChanged(const QModelIndex&, const QModelIndex&)) ); rl::math::Vector q(this->kinematicModels->getDofPosition()); q.setZero(); - positionModel->setData(q); //TODO? + this->positionModel->setData(q); //TODO? rl::math::Vector externalTorque = rl::math::Vector::Zero(this->kinematicModels->getDof()); this->externalTorque = externalTorque; - torqueModel->setData(externalTorque); + this->torqueModel->setData(externalTorque); - QWidget* simulationDockWidgetContent = new QWidget(simulationDockWidget); + QWidget* simulationDockWidgetContent = new QWidget(this->simulationDockWidget); QGroupBox* simulationGroup = new QGroupBox("Simulation", simulationDockWidgetContent); QVBoxLayout* simulationVerticalLayout = new QVBoxLayout(); QHBoxLayout* simulationHorizontalLayout = new QHBoxLayout(); - this->addDockWidget(Qt::LeftDockWidgetArea, simulationDockWidget); + this->addDockWidget(Qt::LeftDockWidgetArea, this->simulationDockWidget); this->simulationDockWidget->setWindowTitle("Control"); - simulationDockWidget->setWidget(simulationDockWidgetContent); + this->simulationDockWidget->setWidget(simulationDockWidgetContent); simulationDockWidgetContent->setLayout(simulationVerticalLayout); simulationVerticalLayout->addWidget(simulationGroup); simulationGroup->setLayout(simulationHorizontalLayout); - simulationStart = new QPushButton("&Start", simulationGroup); - simulationPause = new QPushButton("&Pause", simulationGroup); - simulationReset = new QPushButton("&Reset", simulationGroup); - QObject::connect(simulationStart, SIGNAL(clicked()), this, SLOT(clickSimulationStart())); - QObject::connect(simulationPause, SIGNAL(clicked()), this, SLOT(clickSimulationPause())); - QObject::connect(simulationReset, SIGNAL(clicked()), this, SLOT(clickSimulationReset())); - simulationHorizontalLayout->addWidget(simulationStart); - simulationHorizontalLayout->addWidget(simulationPause); - simulationHorizontalLayout->addWidget(simulationReset); + this->simulationStart = new QPushButton("&Start", simulationGroup); + this->simulationStart->setEnabled(false); + this->simulationPause = new QPushButton("&Pause", simulationGroup); + this->simulationReset = new QPushButton("&Reset", simulationGroup); + QObject::connect(this->simulationStart, SIGNAL(clicked()), this, SLOT(clickSimulationStart())); + QObject::connect(this->simulationPause, SIGNAL(clicked()), this, SLOT(clickSimulationPause())); + QObject::connect(this->simulationReset, SIGNAL(clicked()), this, SLOT(clickSimulationReset())); + simulationHorizontalLayout->addWidget(this->simulationStart); + simulationHorizontalLayout->addWidget(this->simulationPause); + simulationHorizontalLayout->addWidget(this->simulationReset); QGridLayout* simulationSettingsLayout = new QGridLayout(); QGroupBox* simulationSettings = new QGroupBox("Settings", simulationDockWidgetContent); simulationVerticalLayout->addWidget(simulationSettings); simulationSettings->setLayout(simulationSettingsLayout); - simulationGravity = new QDoubleSpinBox(simulationSettings); + this->simulationGravity = new QDoubleSpinBox(simulationSettings); simulationSettingsLayout->addWidget(new QLabel("Gravity [m/s^2]", simulationSettings), 0, 0); - simulationSettingsLayout->addWidget(simulationGravity, 0, 1); - simulationGravity->setRange(0, 100); - simulationGravity->setSingleStep(0.1); - simulationGravity->setDecimals(2); - simulationGravity->setValue(simulationGravityValue); - QObject::connect(simulationGravity, SIGNAL(valueChanged(double)), this, SLOT(changeSimulationGravity(double))); - simulationDampingFactor = new QDoubleSpinBox(simulationSettings); + simulationSettingsLayout->addWidget(this->simulationGravity, 0, 1); + this->simulationGravity->setRange(0, 100); + this->simulationGravity->setSingleStep(0.1); + this->simulationGravity->setDecimals(2); + this->simulationGravity->setValue(this->simulationGravityValue); + QObject::connect(this->simulationGravity, SIGNAL(valueChanged(double)), this, SLOT(changeSimulationGravity(double))); + this->simulationDampingFactor = new QDoubleSpinBox(simulationSettings); simulationSettingsLayout->addWidget(new QLabel("Damping Factor", simulationSettings), 1, 0); - simulationSettingsLayout->addWidget(simulationDampingFactor, 1, 1); - simulationDampingFactor->setRange(0, 1.5); - simulationDampingFactor->setSingleStep(0.0001); - simulationDampingFactor->setDecimals(5); - simulationDampingFactor->setValue(simulationDampingValue); - simulationDampingFactor->setToolTip(QString("0.0 gives a frictionless system, 1.0 damps almost all motion; try 0.001--0.005 for typical viscous friction")); - QObject::connect(simulationDampingFactor, SIGNAL(valueChanged(double)), this, SLOT(changeSimulationDampingFactor(double))); + simulationSettingsLayout->addWidget(this->simulationDampingFactor, 1, 1); + this->simulationDampingFactor->setRange(0, 1.5); + this->simulationDampingFactor->setSingleStep(0.0001); + this->simulationDampingFactor->setDecimals(5); + this->simulationDampingFactor->setValue(this->simulationDampingValue); + this->simulationDampingFactor->setToolTip(QString("0.0 gives a frictionless system, 1.0 damps almost all motion; try 0.001--0.005 for typical viscous friction")); + QObject::connect(this->simulationDampingFactor, SIGNAL(valueChanged(double)), this, SLOT(changeSimulationDampingFactor(double))); QGroupBox* simulationResults = new QGroupBox("Results", simulationDockWidgetContent); QGridLayout* simulationResultsLayout = new QGridLayout(); @@ -291,70 +292,70 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->simulationResultsEnergy = new QLineEdit(simulationResults); this->simulationResultsTime = new QLineEdit(simulationResults); simulationResultsLayout->addWidget(new QLabel("Simulated Time [s]", simulationResults), 0, 0); - simulationResultsLayout->addWidget(simulationTime, 0, 1); - simulationTime->setReadOnly(true); + simulationResultsLayout->addWidget(this->simulationTime, 0, 1); + this->simulationTime->setReadOnly(true); simulationResultsLayout->addWidget(new QLabel("Frame Computation Time [s]", simulationResults), 1, 0); - simulationResultsLayout->addWidget(simulationResultsTime, 1, 1); - simulationResultsTime->setToolTip(QString("should be under 0.05 s for good interactive results")); - simulationResultsTime->setReadOnly(true); + simulationResultsLayout->addWidget(this->simulationResultsTime, 1, 1); + this->simulationResultsTime->setToolTip(QString("should be under 0.05 s for good interactive results")); + this->simulationResultsTime->setReadOnly(true); simulationResultsLayout->addWidget(new QLabel("Kinetic Energy [kJ]", simulationResults), 2, 0); - simulationResultsLayout->addWidget(simulationResultsEnergy, 2, 1); - simulationResultsEnergy->setReadOnly(true); - - QGroupBox* serverBox = new QGroupBox("rlCoach Server", simulationDockWidgetContent); - QGridLayout* serverBoxLayout = new QGridLayout(); - serverBox->setLayout(serverBoxLayout); - simulationVerticalLayout->addWidget(serverBox); - this->serverConnectionStatus = new QLineEdit(serverBox); - serverBoxLayout->addWidget(new QLabel("Connection Status", serverBox), 0, 0); - serverBoxLayout->addWidget(serverConnectionStatus, 0, 1); - serverConnectionStatus->setReadOnly(true); - //simulationVerticalLayout->addItem(new QSpacerItem(20, 10, QSizePolicy::Minimum, QSizePolicy::Expanding)); - - this->addDockWidget(Qt::RightDockWidgetArea, positionDockWidget); + simulationResultsLayout->addWidget(this->simulationResultsEnergy, 2, 1); + this->simulationResultsEnergy->setReadOnly(true); + + this->addDockWidget(Qt::RightDockWidgetArea, this->positionDockWidget); this->positionDockWidget->setWidget(this->positionView); this->positionDockWidget->setWindowTitle("Position"); - this->addDockWidget(Qt::RightDockWidgetArea, velocityDockWidget); + this->addDockWidget(Qt::RightDockWidgetArea, this->velocityDockWidget); this->velocityDockWidget->setWidget(this->velocityView); this->velocityDockWidget->setWindowTitle("Velocity"); - this->addDockWidget(Qt::RightDockWidgetArea, accelerationDockWidget); + this->addDockWidget(Qt::RightDockWidgetArea, this->accelerationDockWidget); this->accelerationDockWidget->setWidget(this->accelerationView); this->accelerationDockWidget->setWindowTitle("Acceleration"); - this->addDockWidget(Qt::LeftDockWidgetArea, torqueDockWidget); + this->addDockWidget(Qt::LeftDockWidgetArea, this->torqueDockWidget); this->torqueDockWidget->setWidget(this->torqueView); - this->torqueDockWidget->setWindowTitle("Motor Torque"); + this->torqueDockWidget->setWindowTitle("Torque"); - this->addDockWidget(Qt::BottomDockWidgetArea, operationalDockWidget); + this->addDockWidget(Qt::BottomDockWidgetArea, this->operationalDockWidget); this->operationalDockWidget->setWidget(this->operationalViews); this->operationalDockWidget->setWindowTitle("Operational Position"); +#if QT_VERSION >= 0x050600 + QList resizeDocksWidgets; + resizeDocksWidgets.append(this->operationalDockWidget); + resizeDocksWidgets.append(this->simulationDockWidget); + QList resizeDocksSizes; + resizeDocksSizes.append(0); + resizeDocksSizes.append(0); + this->resizeDocks(resizeDocksWidgets, resizeDocksSizes, Qt::Vertical); +#endif // QT_VERSION + + this->statusBar(); + this->gradientBackground = new SoGradientBackground(); this->gradientBackground->ref(); this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); this->scene->root->insertChild(this->gradientBackground, 0); - QWidget* viewerContainer = new QWidget(this); - this->viewer = new SoQtExaminerViewer(viewerContainer, nullptr, true, SoQtFullViewer::BUILD_POPUP); + this->viewer = new SoQtExaminerViewer(this, nullptr, true, SoQtFullViewer::BUILD_POPUP); this->viewer->setSceneGraph(this->scene->root); this->viewer->setTransparencyType(SoGLRenderAction::SORTED_OBJECT_BLEND); this->viewer->viewAll(); - this->setCentralWidget(viewerContainer); - //this->viewer->getWidget()->resize(400, 300); - this->resize(1000, 750); + this->resize(1024, 768); + this->setCentralWidget(this->viewer->getWidget()); this->setWindowIconText("rlSimulator"); this->setWindowTitle("rlSimulator"); this->init(); this->server->listen(QHostAddress::Any, 11235); - this->setServerConnectionStatus("Listening on port 11235"); + this->statusBar()->showMessage("Listening on port 11235"); - this->timer.start(simulationTimeStep * simulationStepsPerFrame * 1000.f, this); + this->timer.start(this->simulationTimeStep * this->simulationStepsPerFrame * 1000, this); } MainWindow::~MainWindow() @@ -379,12 +380,16 @@ void MainWindow::clickSimulationStart() { this->simulationIsRunning = true; + this->simulationStart->setEnabled(false); + this->simulationPause->setEnabled(true); } void MainWindow::clickSimulationPause() { this->simulationIsRunning = false; + this->simulationStart->setEnabled(true); + this->simulationPause->setEnabled(false); } void @@ -395,10 +400,12 @@ MainWindow::clickSimulationReset() this->simulationTime->setText(QString::number(this->simulationTimeElapsed)); this->simulationResultsTime->setText(""); this->simulationResultsEnergy->setText(""); - kinematicModels->setPosition(simulationResetQ); - kinematicModels->setVelocity(simulationResetQd); - kinematicModels->setAcceleration(simulationResetQdd); - positionModel->setData(simulationResetQ); + this->kinematicModels->setPosition(this->simulationResetQ); + this->kinematicModels->setVelocity(this->simulationResetQd); + this->kinematicModels->setAcceleration(this->simulationResetQdd); + this->positionModel->setData(this->simulationResetQ); + this->simulationStart->setEnabled(true); + this->simulationPause->setEnabled(false); } MainWindow* @@ -430,7 +437,7 @@ MainWindow::init() void MainWindow::timerEvent(QTimerEvent *event) { - if (!simulationIsRunning) + if (!this->simulationIsRunning) { return; } @@ -448,18 +455,18 @@ MainWindow::timerEvent(QTimerEvent *event) rl::math::Matrix M(dynamic->getDof(), dynamic->getDof()); #if 1 - for (int i = 0; i < simulationStepsPerFrame; ++i) + for (int i = 0; i < this->simulationStepsPerFrame; ++i) { - dynamic->setTorque(externalTorque); + dynamic->setTorque(this->externalTorque); dynamic->forwardDynamics(); #if 1 q = dynamic->getPosition(); qd = dynamic->getVelocity(); qdd = dynamic->getAcceleration(); - qdd -= simulationDampingValue * qd / simulationTimeStep; + qdd -= this->simulationDampingValue * qd / this->simulationTimeStep; // TODO: this is a very simple integration, slightly better than Euler, could be replaced by a *functional-style* Runge-Kutta - q += simulationTimeStep * (qd + qdd * simulationTimeStep / 2); - qd += simulationTimeStep * qdd; + q += this->simulationTimeStep * (qd + qdd * this->simulationTimeStep / 2); + qd += this->simulationTimeStep * qdd; dynamic->setPosition(q); dynamic->setVelocity(qd); dynamic->setAcceleration(qdd); @@ -517,10 +524,10 @@ MainWindow::timerEvent(QTimerEvent *event) dynamic->forwardPosition(); std::chrono::steady_clock::time_point stopTime = std::chrono::steady_clock::now(); - this->simulationTimeElapsed += simulationStepsPerFrame * simulationTimeStep; + this->simulationTimeElapsed += this->simulationStepsPerFrame * this->simulationTimeStep; this->simulationTime->setText(QString::number(this->simulationTimeElapsed)); this->simulationResultsTime->setText(QString::number(std::chrono::duration_cast>(stopTime - startTime).count())); - rl::math::Real energy = 0.5 * qd.transpose() * M * qd; + rl::math::Real energy = static_cast(0.5) * qd.transpose() * M * qd; this->simulationResultsEnergy->setText(QString::number(energy)); this->positionModel->setData(q); this->velocityModel->setData(qd); @@ -531,7 +538,7 @@ void MainWindow::saveImage() { QImage image = static_cast(this->viewer->getGLWidget())->grabFrameBuffer(true); - image.save("coach-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".png", "PNG"); + image.save("rlSimulator-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".png", "PNG"); } void @@ -539,7 +546,7 @@ MainWindow::saveScene() { SoOutput output; - if (!output.openFile(QString("coach-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".wrl").toStdString().c_str())) + if (!output.openFile(QString("rlSimulator-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".wrl").toStdString().c_str())) { return; } @@ -551,9 +558,3 @@ MainWindow::saveScene() output.closeFile(); } - -void -MainWindow::setServerConnectionStatus(QString str) -{ - this->serverConnectionStatus->setText(str); -} diff --git a/demos/rlSimulator/MainWindow.h b/demos/rlSimulator/MainWindow.h index 72b3065f..26c5e234 100644 --- a/demos/rlSimulator/MainWindow.h +++ b/demos/rlSimulator/MainWindow.h @@ -30,13 +30,13 @@ #include #include #include +#include +#include #include #include #include #include #include -#include -#include #include #include #include @@ -100,8 +100,6 @@ public slots: void saveScene(); - void setServerConnectionStatus(QString str); - protected: MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); @@ -136,8 +134,6 @@ public slots: Server* server; - QLineEdit* serverConnectionStatus; - QDoubleSpinBox* simulationDampingFactor; rl::math::Real simulationDampingValue; diff --git a/demos/rlSimulator/Socket.cpp b/demos/rlSimulator/Socket.cpp index 3ac3e772..7b4b7ea6 100644 --- a/demos/rlSimulator/Socket.cpp +++ b/demos/rlSimulator/Socket.cpp @@ -24,6 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include +#include #include #include #include @@ -38,22 +40,22 @@ Socket::Socket(QObject* parent) : { QObject::connect(this, SIGNAL(disconnected()), this, SLOT(deleteLater())); QObject::connect(this, SIGNAL(readyRead()), this, SLOT(readClient())); - MainWindow::instance()->setServerConnectionStatus("Connected"); } Socket::~Socket() { - MainWindow::instance()->setServerConnectionStatus("Disconnected"); + MainWindow::instance()->statusBar()->showMessage("Listening on port 11235"); } void Socket::readClient() { + MainWindow::instance()->statusBar()->showMessage("Received data from " + this->peerAddress().toString() + ":" + QString::number(this->peerPort()), 1000); + QTextStream textStream(this); while (this->canReadLine()) { - MainWindow::instance()->setServerConnectionStatus("Received command"); std::size_t cmd = 0; textStream >> cmd; From f623ad9387bf827f3e2c716eaec6ea658f5d2727 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Apr 2019 23:14:57 +0200 Subject: [PATCH 213/546] Remove unused header --- demos/rlSimulator/MainWindow.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index 123c1bb4..3c4a61db 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -25,7 +25,6 @@ // #include -#include #include #include #include From 4717908f868dd0ae67b73b80746bcf94d23cc9a3 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Apr 2019 23:16:02 +0200 Subject: [PATCH 214/546] Call viewAll after drop event --- extras/wrlview/MainWindow.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 1e328030..89727524 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -227,6 +227,7 @@ MainWindow::dropEvent(QDropEvent* event) { QString filename = event->mimeData()->urls()[0].toLocalFile(); this->load(filename); + this->viewer->viewAll(); event->acceptProposedAction(); } } From b509a87437259f94afd167746724049e31357d76 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Apr 2019 23:16:51 +0200 Subject: [PATCH 215/546] Use extra separator for scene data --- extras/wrlview/MainWindow.cpp | 36 ++++++++++++++--------------------- extras/wrlview/MainWindow.h | 2 ++ 2 files changed, 16 insertions(+), 22 deletions(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 89727524..a41b0290 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -65,6 +65,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : origin1Switch(nullptr), origin1000Switch(nullptr), root(nullptr), + scene(nullptr), viewer(nullptr), widget(new QWidget(this)) { @@ -84,8 +85,12 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->setAcceptDrops(true); + this->root = new SoSeparator(); + this->root->ref(); + this->viewer = new SoQtExaminerViewer(this->widget); this->viewer->setDecoration(false); + this->viewer->setSceneGraph(this->root); this->viewer->setTransparencyType(SoGLRenderAction::SORTED_OBJECT_BLEND); this->gradientBackground = new SoGradientBackground(); @@ -94,8 +99,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->backgroundSwitch = new SoSwitch(); this->backgroundSwitch->whichChild = SO_SWITCH_ALL; - this->backgroundSwitch->ref(); this->backgroundSwitch->addChild(this->gradientBackground); + this->root->addChild(this->backgroundSwitch); SoCoordinate3* originCoordinate3 = new SoCoordinate3(); originCoordinate3->point.set1Value(0, SbVec3f(0, 0, 0)); @@ -133,8 +138,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->origin1Switch = new SoSwitch(); this->origin1Switch->whichChild = SO_SWITCH_NONE; - this->origin1Switch->ref(); this->origin1Switch->addChild(origin1Separator); + this->root->addChild(this->origin1Switch); SoScale* origin1000Scale = new SoScale(); origin1000Scale->scaleFactor.setValue(1000, 1000, 1000); @@ -148,8 +153,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->origin1000Switch = new SoSwitch(); this->origin1000Switch->whichChild = SO_SWITCH_NONE; - this->origin1000Switch->ref(); this->origin1000Switch->addChild(origin1000Separator); + this->root->addChild(this->origin1000Switch); this->offscreenRenderer = new SoOffscreenRenderer(this->viewer->getViewportRegion()); @@ -175,14 +180,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : MainWindow::~MainWindow() { - this->backgroundSwitch->unref(); - this->origin1Switch->unref(); - this->origin1000Switch->unref(); - - if (nullptr != this->root) - { - this->root->unref(); - } + this->root->unref(); if (nullptr != this->offscreenRenderer) { @@ -548,30 +546,24 @@ MainWindow::load(const QString filename) return; } - if (nullptr != this->root) + if (nullptr != this->scene) { - this->root->unref(); - this->root = nullptr; - this->viewer->setSceneGraph(nullptr); + this->root->removeChild(this->scene); this->filename.clear(); this->setWindowTitle("wrlview"); } - this->root = SoDB::readAll(&this->input); + this->scene = SoDB::readAll(&this->input); this->input.closeFile(); - if (nullptr == this->root) + if (nullptr == this->scene) { QMessageBox::critical(this, "Error", "Error reading file."); return; } - this->root->ref(); - this->root->insertChild(this->origin1Switch, 0); - this->root->insertChild(this->origin1000Switch, 0); - this->root->insertChild(this->backgroundSwitch, 0); - this->viewer->setSceneGraph(this->root); + this->root->addChild(this->scene); this->filename = filename; this->setWindowTitle(filename + " - wrlview"); } diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index 71d7f3d0..03fb1c9c 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -137,6 +137,8 @@ class MainWindow : public QMainWindow SoSeparator* root; + SoSeparator* scene; + SoQtExaminerViewer* viewer; QMenu* viewMenu; From 195c756a28dbfe1abc6fc20c0efb4f77612a3d69 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Apr 2019 23:32:48 +0200 Subject: [PATCH 216/546] Fix CMake option --- demos/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/CMakeLists.txt b/demos/CMakeLists.txt index 76e36dc1..b4d4130e 100644 --- a/demos/CMakeLists.txt +++ b/demos/CMakeLists.txt @@ -54,7 +54,7 @@ if(RL_BUILD_MDL AND RL_BUILD_SG) add_subdirectory(rlSimulator) endif() -if(BUILD_RL_PLAN) +if(RL_BUILD_PLAN) add_subdirectory(rlPlanDemo) add_subdirectory(rlPrmDemo) endif() From 3a15f51ba5040c5251ad0313c4810c2a8d396024 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 18 Apr 2019 20:00:34 +0200 Subject: [PATCH 217/546] Add missing export --- src/rl/hal/Exception.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/hal/Exception.h b/src/rl/hal/Exception.h index b324c240..b56f0181 100644 --- a/src/rl/hal/Exception.h +++ b/src/rl/hal/Exception.h @@ -35,7 +35,7 @@ namespace rl { namespace hal { - class Exception : public ::std::runtime_error + class RL_HAL_EXPORT Exception : public ::std::runtime_error { public: Exception(const ::std::string& what_arg); From 31b8f923d572ae2de8f5872997a7f507b289b402 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 16:33:41 +0200 Subject: [PATCH 218/546] Add additional engines and convert input angles to degrees --- demos/rlPrmDemo/CMakeLists.txt | 4 +++- demos/rlPrmDemo/rlPrmDemo.cpp | 23 ++++++++++++++++++++--- 2 files changed, 23 insertions(+), 4 deletions(-) diff --git a/demos/rlPrmDemo/CMakeLists.txt b/demos/rlPrmDemo/CMakeLists.txt index b148d08e..60a57c2d 100644 --- a/demos/rlPrmDemo/CMakeLists.txt +++ b/demos/rlPrmDemo/CMakeLists.txt @@ -1,8 +1,10 @@ find_package(Boost REQUIRED) +find_package(Bullet) +find_package(ODE) find_package(SOLID3) -if(SOLID3_FOUND) +if(Bullet_FOUND OR ODE_FOUND OR SOLID3_FOUND) add_executable( rlPrmDemo rlPrmDemo.cpp diff --git a/demos/rlPrmDemo/rlPrmDemo.cpp b/demos/rlPrmDemo/rlPrmDemo.cpp index 1469ff42..64c8137e 100644 --- a/demos/rlPrmDemo/rlPrmDemo.cpp +++ b/demos/rlPrmDemo/rlPrmDemo.cpp @@ -34,11 +34,19 @@ #include #include #include -#include #include #include + +#if defined(RL_SG_SOLID) #include #include +#elif defined(RL_SG_BULLET) +#include +#include +#elif defined(RL_SG_ODE) +#include +#include +#endif int main(int argc, char** argv) @@ -52,7 +60,13 @@ main(int argc, char** argv) try { rl::sg::XmlFactory factory; +#if defined(RL_SG_SOLID) rl::sg::solid::Scene scene; +#elif defined(RL_SG_BULLET) + rl::sg::bullet::Scene scene; +#elif defined(RL_SG_ODE) + rl::sg::ode::Scene scene; +#endif factory.load(argv[1], &scene); std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[2])); @@ -81,7 +95,7 @@ main(int argc, char** argv) for (std::size_t i = 0; i < kinematics->getDof(); ++i) { - start(i) = boost::lexical_cast(argv[i + 3]); + start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::DEG2RAD; } planner.start = &start; @@ -90,11 +104,14 @@ main(int argc, char** argv) for (std::size_t i = 0; i < kinematics->getDof(); ++i) { - goal(i) = boost::lexical_cast(argv[kinematics->getDof() + i + 3]); + goal(i) = boost::lexical_cast(argv[kinematics->getDof() + i + 3]) * rl::math::DEG2RAD; } planner.goal = &goal; + std::cout << "start: " << start.transpose() * rl::math::RAD2DEG << std::endl;; + std::cout << "goal: " << goal.transpose() * rl::math::RAD2DEG << std::endl;; + std::cout << "construct() ... " << std::endl;; std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); planner.construct(15); From 4d72a0ae9f78acdd74c3420b6b08f3471cf50873 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 16:34:10 +0200 Subject: [PATCH 219/546] Add demo for path planning using RRT --- demos/CMakeLists.txt | 1 + demos/rlRrtDemo/CMakeLists.txt | 25 +++++++ demos/rlRrtDemo/rlRrtDemo.cpp | 126 +++++++++++++++++++++++++++++++++ 3 files changed, 152 insertions(+) create mode 100644 demos/rlRrtDemo/CMakeLists.txt create mode 100644 demos/rlRrtDemo/rlRrtDemo.cpp diff --git a/demos/CMakeLists.txt b/demos/CMakeLists.txt index b4d4130e..900d68fe 100644 --- a/demos/CMakeLists.txt +++ b/demos/CMakeLists.txt @@ -57,6 +57,7 @@ endif() if(RL_BUILD_PLAN) add_subdirectory(rlPlanDemo) add_subdirectory(rlPrmDemo) + add_subdirectory(rlRrtDemo) endif() set(CPACK_NSIS_CREATE_ICONS_EXTRA ${CPACK_NSIS_CREATE_ICONS_EXTRA} PARENT_SCOPE) diff --git a/demos/rlRrtDemo/CMakeLists.txt b/demos/rlRrtDemo/CMakeLists.txt new file mode 100644 index 00000000..5b2f0975 --- /dev/null +++ b/demos/rlRrtDemo/CMakeLists.txt @@ -0,0 +1,25 @@ +find_package(Boost REQUIRED) + +find_package(Bullet) +find_package(ODE) +find_package(SOLID3) + +if(Bullet_FOUND OR ODE_FOUND OR SOLID3_FOUND) + add_executable( + rlRrtDemo + rlRrtDemo.cpp + ) + + target_include_directories( + rlRrtDemo + PUBLIC + ${Boost_INCLUDE_DIR} + ) + + target_link_libraries( + rlRrtDemo + plan + kin + sg + ) +endif() diff --git a/demos/rlRrtDemo/rlRrtDemo.cpp b/demos/rlRrtDemo/rlRrtDemo.cpp new file mode 100644 index 00000000..a91d336a --- /dev/null +++ b/demos/rlRrtDemo/rlRrtDemo.cpp @@ -0,0 +1,126 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(RL_SG_SOLID) +#include +#include +#elif defined(RL_SG_BULLET) +#include +#include +#elif defined(RL_SG_ODE) +#include +#include +#endif + +int +main(int argc, char** argv) +{ + if (argc < 3) + { + std::cout << "Usage: rlRrtDemo SCENEFILE KINEMATICSFILE START1 ... STARTn GOAL1 ... GOALn" << std::endl; + return EXIT_FAILURE; + } + + try + { + rl::sg::XmlFactory factory; +#if defined(RL_SG_SOLID) + rl::sg::solid::Scene scene; +#elif defined(RL_SG_BULLET) + rl::sg::bullet::Scene scene; +#elif defined(RL_SG_ODE) + rl::sg::ode::Scene scene; +#endif + factory.load(argv[1], &scene); + + std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[2])); + + rl::plan::SimpleModel model; + model.kin = kinematics.get(); + model.model = scene.getModel(0); + model.scene = &scene; + + rl::plan::KdtreeNearestNeighbors nearestNeighbors0(&model); + rl::plan::KdtreeNearestNeighbors nearestNeighbors1(&model); + rl::plan::RrtConCon planner; + rl::plan::UniformSampler sampler; + + planner.model = &model; + planner.setNearestNeighbors(&nearestNeighbors0, 0); + planner.setNearestNeighbors(&nearestNeighbors1, 1); + planner.sampler = &sampler; + + sampler.model = &model; + + planner.delta = 1 * rl::math::DEG2RAD; + + rl::math::Vector start(kinematics->getDof()); + + for (std::size_t i = 0; i < kinematics->getDof(); ++i) + { + start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::DEG2RAD; + } + + planner.start = &start; + + rl::math::Vector goal(kinematics->getDof()); + + for (std::size_t i = 0; i < kinematics->getDof(); ++i) + { + goal(i) = boost::lexical_cast(argv[kinematics->getDof() + i + 3]) * rl::math::DEG2RAD; + } + + planner.goal = &goal; + + std::cout << "start: " << start.transpose() * rl::math::RAD2DEG << std::endl;; + std::cout << "goal: " << goal.transpose() * rl::math::RAD2DEG << std::endl;; + + std::cout << "solve() ... " << std::endl;; + std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); + bool solved = planner.solve(); + std::chrono::steady_clock::time_point stopTime = std::chrono::steady_clock::now(); + std::cout << "solve() " << (solved ? "true" : "false") << " " << std::chrono::duration_cast>(stopTime - startTime).count() * 1000 << " ms" << std::endl; + + return EXIT_SUCCESS; + } + catch (const std::exception& e) + { + std::cerr << e.what() << std::endl; + return EXIT_FAILURE; + } +} From 8296c4f9068a36961662fc415ba12366457bfd4b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 18:02:02 +0200 Subject: [PATCH 220/546] Use Markdown for license file --- LICENSE | 23 ----------------------- LICENSE.md | 11 +++++++++++ cmake/CPackConfig.cmake | 5 ++--- 3 files changed, 13 insertions(+), 26 deletions(-) delete mode 100644 LICENSE create mode 100644 LICENSE.md diff --git a/LICENSE b/LICENSE deleted file mode 100644 index 6821a79e..00000000 --- a/LICENSE +++ /dev/null @@ -1,23 +0,0 @@ -Copyright (c) 2009, Markus Rickert -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -* Redistributions of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. -* Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - -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. diff --git a/LICENSE.md b/LICENSE.md new file mode 100644 index 00000000..3fe0d455 --- /dev/null +++ b/LICENSE.md @@ -0,0 +1,11 @@ +# BSD 2-Clause License + +Copyright (c) 2009, Markus Rickert +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. +* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +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. diff --git a/cmake/CPackConfig.cmake b/cmake/CPackConfig.cmake index 8e12fa3a..4e92434d 100644 --- a/cmake/CPackConfig.cmake +++ b/cmake/CPackConfig.cmake @@ -89,7 +89,7 @@ set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) set(CPACK_PACKAGE_VERSION_MINOR ${VERSION_MINOR}) set(CPACK_PACKAGE_VERSION_PATCH ${VERSION_PATCH}) set(CPACK_PROJECT_CONFIG_FILE ${CMAKE_CURRENT_SOURCE_DIR}/cmake/CPackProjectConfig.cmake) -set(CPACK_RESOURCE_FILE_LICENSE ${CMAKE_CURRENT_SOURCE_DIR}/LICENSE) +set(CPACK_RESOURCE_FILE_LICENSE ${CMAKE_CURRENT_SOURCE_DIR}/LICENSE.md) set(CPACK_RPM_COMPONENT_INSTALL ON) set(CPACK_RPM_DEMOS_FILE_NAME "RPM-DEFAULT") set(CPACK_RPM_demos_PACKAGE_REQUIRES "rl-examples = ${VERSION}") @@ -127,7 +127,7 @@ set( ${CMAKE_CURRENT_BINARY_DIR}/WixExtra.wxs ${CMAKE_CURRENT_SOURCE_DIR}/cmake/WixUI_FeatureTreeNoLicense.wxs ) -set(CPACK_WIX_LICENSE_RTF ${CMAKE_CURRENT_BINARY_DIR}/LICENSE.txt) +set(CPACK_WIX_LICENSE_RTF ${CMAKE_CURRENT_SOURCE_DIR}/LICENSE.md) set(CPACK_WIX_PATCH_FILE ${CMAKE_CURRENT_BINARY_DIR}/WixPatch.xml) set(CPACK_WIX_PRODUCT_ICON ${CMAKE_CURRENT_SOURCE_DIR}/robotics-library.ico) set(CPACK_WIX_PROGRAM_MENU_FOLDER ${CPACK_PACKAGE_NAME}) @@ -254,6 +254,5 @@ string(REPLACE ";" "\r\n" CPACK_NSIS_CREATE_ICONS_EXTRA "${CPACK_NSIS_CREATE_ICO string(REPLACE ";" "\r\n" CPACK_NSIS_DELETE_ICONS_EXTRA "${CPACK_NSIS_DELETE_ICONS_EXTRA}") string(REPLACE "/>;\r\n Date: Sat, 20 Apr 2019 18:02:07 +0200 Subject: [PATCH 221/546] Add README file --- README.md | 53 +++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 53 insertions(+) create mode 100644 README.md diff --git a/README.md b/README.md new file mode 100644 index 00000000..835743d3 --- /dev/null +++ b/README.md @@ -0,0 +1,53 @@ +# Robotics Library + +The [Robotics Library](https://www.roboticslibrary.org/) (RL) is a self-contained C++ library for rigid body kinematics and dynamics, motion planning, and control. It covers spatial vector algebra, multibody systems, hardware abstraction, path planning, collision detection, and visualization. It is being used in research projects and in education, available under a BSD license, and free for use in commercial applications. RL runs on many different systems, including Linux, macOS, and Windows. It uses CMake as a build system and can be compiled with Clang, GCC, and Visual Studio. + +## Getting Started + +We offer precompiled Ubuntu packages on [Launchpad](https://launchpad.net/~roblib/+archive/ubuntu/ppa) as well as Windows binaries on [GitHub](https://github.com/roboticslibrary/rl/releases) for the latest release version, while [Homebrew](https://brew.sh/) can be used on macOS to build corresponding packages. Tutorials on our website provide further information on how to develop applications using RL. + +These tutorials include instructions on how to + +* install the latest release on [Ubuntu](https://www.roboticslibrary.org/tutorials/install-ubuntu), [Windows](https://www.roboticslibrary.org/tutorials/install-windows), or [macOS](https://www.roboticslibrary.org/tutorials/install-macos), +* create your first program using RL on [Linux](https://www.roboticslibrary.org/tutorials/first-steps-linux) or [Windows](https://www.roboticslibrary.org/tutorials/first-steps-windows), +* have a look at our short API [overview](https://www.roboticslibrary.org/api) and our [documentation](http://doc.roboticslibrary.org/), +* create your [robot model](https://www.roboticslibrary.org/tutorials/create-a-robot-model) with a kinematics and geometry definition, +* plan a collision-free path in your [path planning scenario](https://www.roboticslibrary.org/tutorials/specify-a-path-planning-scenario), +* build RL from source on [Ubuntu](https://www.roboticslibrary.org/tutorials/build-ubuntu), [Windows](https://www.roboticslibrary.org/tutorials/build-windows), or [macOS](https://www.roboticslibrary.org/tutorials/build-macos). + +## Next Steps + +RL includes a number of demo [applications](demos) and a selection of [kinematics](examples/rlmdl), [geometry](examples/rlsg), and [path planning](examples/rlplan) examples that demonstrate how to use it for more advanced applications. Due to their size, a larger set of examples can be found in a [separate repository](https://github.com/roboticslibrary/rl-examples). + +Among several others, these demo applications include + +* a tool for [converting](demos/rlRotationConverterDemo) between rotation matrices, angle axis, quaternions, and Euler angles, +* the visualization of [collision detection](demos/rlCollisionDemo) queries that can highlight intersections, minimum distance, and penetration depth, +* a [kinematics simulator](demos/rlCoachMdl) that uses a TCP port for joint position updates, +* a [dynamics simulator](demos/rlSimulator) that listens for joint torque updates, +* the calculation of a collision-free path using a [Probabilistic Roadmap](demos/rlPrmDemo) or a [Rapidly-Exploring Random Tree](demos/rlRrtDemo), +* the visualization of [path planning](demos/rlPlanDemo) queries based on scenario definitions from an XML file, +* robot [forward and inverse dynamics](demos/rlDynamics1Demo) using the Recursive Newton-Euler and Articulated-Body Algorithm methods, +* the calculation of [dynamics properties](demos/rlDynamics2Demo) such as mass matrix, centrifugal and Coriolis forces, or gravity compensation, +* the calculation and sending of a [trajectory](demos/rlAxisControllerDemo) to a robot controller based on a cubic or quintic polynomial. + +## Publications + +For more detailed information on the design of the Robotics Library, please have a look at our IROS paper. The reference is + +Markus Rickert and Andre Gaschler. [Robotics Library: An object-oriented approach to robot applications](https://www.roboticslibrary.org/Rickert2017a.pdf). In *Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)*, pages 733–740, Vancouver, BC, Canada, September 2017. + + @InProceedings{Rickert2017a, + author = {Markus Rickert and Andre Gaschler}, + title = {{R}obotics {L}ibrary: An Object-Oriented Approach to Robot Applications}, + booktitle = {Proceedings of the {IEEE}/{RSJ} International Conference on Intelligent Robots and Systems}, + year = {2017}, + pages = {733--740}, + address = {Vancouver, BC, Canada}, + month = sep, + doi = {10.1109/IROS.2017.8202232}, + } + +## License + +All source code files of RL are licensed under the permissive [BSD 2-clause license](LICENSE.md). For the licenses of third-party dependencies, please refer to the respective projects. From f5d63ddb8d0b181ed2969e019a53b163d277582d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 21:22:19 +0200 Subject: [PATCH 222/546] Use shared_ptr for kinematics factories --- demos/rlCoachKin/MainWindow.cpp | 4 +- demos/rlCoachMdl/MainWindow.cpp | 4 +- demos/rlCoachMdl/MainWindow.h | 4 +- demos/rlDynamics1Demo/rlDynamics1Demo.cpp | 7 +- demos/rlDynamics2Demo/rlDynamics2Demo.cpp | 5 +- .../rlInversePositionDemo.cpp | 14 +-- demos/rlPlanDemo/MainWindow.cpp | 16 +-- demos/rlPlanDemo/MainWindow.h | 6 +- demos/rlSimulator/ConfigurationDelegate.cpp | 10 +- demos/rlSimulator/ConfigurationModel.cpp | 48 ++++---- demos/rlSimulator/MainWindow.cpp | 104 +++++++++--------- demos/rlSimulator/MainWindow.h | 6 +- demos/rlSimulator/OperationalModel.cpp | 16 +-- demos/rlSimulator/Socket.cpp | 4 +- src/rl/kin/Kinematics.cpp | 20 ++-- src/rl/kin/Kinematics.h | 2 +- src/rl/mdl/Factory.cpp | 6 +- src/rl/mdl/Factory.h | 3 +- src/rl/plan/Model.h | 4 +- tests/rlCollisionTest/rlCollisionTest.cpp | 7 +- tests/rlDynamicsTest/rlDynamicsTest.cpp | 11 +- .../rlInverseKinematicsMdlTest.cpp | 11 +- tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp | 3 +- 23 files changed, 145 insertions(+), 170 deletions(-) diff --git a/demos/rlCoachKin/MainWindow.cpp b/demos/rlCoachKin/MainWindow.cpp index a166821b..d83ac486 100644 --- a/demos/rlCoachKin/MainWindow.cpp +++ b/demos/rlCoachKin/MainWindow.cpp @@ -77,9 +77,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : for (int i = 2; i < QApplication::arguments().size(); ++i) { this->geometryModels.push_back(this->scene->getModel(i - 2)); - std::shared_ptr kinematicModel; - kinematicModel.reset(rl::kin::Kinematics::create(QApplication::arguments()[i].toStdString())); - this->kinematicModels.push_back(kinematicModel); + this->kinematicModels.push_back(rl::kin::Kinematics::create(QApplication::arguments()[i].toStdString())); } for (std::size_t i = 0; i < this->kinematicModels.size(); ++i) diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index d8926372..f0cec44b 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -106,9 +106,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : } this->geometryModels.push_back(this->scene->getModel(i - 2)); - std::shared_ptr kinematicModel; - kinematicModel.reset(kinematicFactory->create(kinematicFilename)); - this->kinematicModels.push_back(kinematicModel); + this->kinematicModels.push_back(std::dynamic_pointer_cast(kinematicFactory->create(kinematicFilename))); } for (std::size_t i = 0; i < this->kinematicModels.size(); ++i) diff --git a/demos/rlCoachMdl/MainWindow.h b/demos/rlCoachMdl/MainWindow.h index 797285c0..99f212a2 100644 --- a/demos/rlCoachMdl/MainWindow.h +++ b/demos/rlCoachMdl/MainWindow.h @@ -37,7 +37,7 @@ #include #include #include -#include +#include #include #include @@ -69,7 +69,7 @@ class MainWindow : public QMainWindow QComboBox* ikJacobianInverseComboBox; - std::vector> kinematicModels; + std::vector> kinematicModels; std::vector operationalModels; diff --git a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp index 6df7d719..43b76e58 100644 --- a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp +++ b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp @@ -29,7 +29,6 @@ #include #include #include -#include #include #include @@ -45,9 +44,7 @@ main(int argc, char** argv) try { rl::mdl::XmlFactory factory; - std::shared_ptr model(factory.create(argv[1])); - - rl::mdl::Dynamic* dynamic = dynamic_cast(model.get()); + std::shared_ptr dynamic = std::dynamic_pointer_cast(factory.create(argv[1])); rl::math::Vector q(dynamic->getDofPosition()); rl::math::Vector qd(dynamic->getDof()); @@ -74,7 +71,7 @@ main(int argc, char** argv) dynamic->forwardDynamics(); std::cout << "qdd = " << dynamic->getAcceleration().transpose() << std::endl; - rl::mdl::RungeKuttaNystromIntegrator integrator(dynamic); + rl::mdl::RungeKuttaNystromIntegrator integrator(dynamic.get()); integrator.integrate(1); std::cout << "q = " << dynamic->getPosition().transpose() << std::endl; std::cout << "qd = " << dynamic->getVelocity().transpose() << std::endl; diff --git a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp index 29e47bc3..56192075 100644 --- a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp +++ b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp @@ -30,7 +30,6 @@ #include #include #include -#include #include int @@ -45,9 +44,7 @@ main(int argc, char** argv) try { rl::mdl::XmlFactory factory; - std::shared_ptr model(factory.create(argv[1])); - - rl::mdl::Dynamic* dynamic = dynamic_cast(model.get()); + std::shared_ptr dynamic = std::dynamic_pointer_cast(factory.create(argv[1])); rl::math::Vector q(dynamic->getDofPosition()); rl::math::Vector qd(dynamic->getDof()); diff --git a/demos/rlInversePositionDemo/rlInversePositionDemo.cpp b/demos/rlInversePositionDemo/rlInversePositionDemo.cpp index 89e38209..fa53edb7 100644 --- a/demos/rlInversePositionDemo/rlInversePositionDemo.cpp +++ b/demos/rlInversePositionDemo/rlInversePositionDemo.cpp @@ -32,8 +32,8 @@ #include #include #include -#include #include +#include #include #include #include @@ -61,21 +61,19 @@ main(int argc, char** argv) ); std::string filename(argv[1]); - std::shared_ptr model; + std::shared_ptr kinematic; if ("urdf" == filename.substr(filename.length() - 4, 4)) { rl::mdl::UrdfFactory factory; - model.reset(factory.create(filename)); + kinematic = std::dynamic_pointer_cast(factory.create(filename)); } else { rl::mdl::XmlFactory factory; - model.reset(factory.create(filename)); + kinematic = std::dynamic_pointer_cast(factory.create(filename)); } - rl::mdl::Kinematic* kinematic = dynamic_cast(model.get()); - rl::math::Vector q(kinematic->getDof()); for (std::ptrdiff_t i = 0; i < q.size(); ++i) @@ -91,10 +89,10 @@ main(int argc, char** argv) std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::RAD2DEG << " deg, b: " << orientation.y() * rl::math::RAD2DEG << " deg, c: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; #ifdef RL_MDL_NLOPT - rl::mdl::NloptInverseKinematics ik(kinematic); + rl::mdl::NloptInverseKinematics ik(kinematic.get()); std::cout << "IK using rl::mdl::NloptInverseKinematics"; #else - rl::mdl::JacobianInverseKinematics ik(kinematic); + rl::mdl::JacobianInverseKinematics ik(kinematic.get()); std::cout << "IK using rl::mdl::JacobianInverseKinematics"; #endif ik.setDuration(std::chrono::seconds(1)); diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index b3cbb707..5757c519 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -949,9 +949,9 @@ MainWindow::load(const QString& filename) if ("mdl" == path.eval("string((/rl/plan|/rlplan)//model/kinematics/@type)").getValue()) { rl::xml::NodeSet mdl = path.eval("(/rl/plan|/rlplan)//model/kinematics").getValue(); - this->mdl.reset(dynamic_cast(modelFactory.create( + this->mdl = std::dynamic_pointer_cast(modelFactory.create( mdl[0].getUri(mdl[0].getProperty("href")) - ))); + )); if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/world) > 0").getValue()) { @@ -974,9 +974,9 @@ MainWindow::load(const QString& filename) else { rl::xml::NodeSet kin = path.eval("(/rl/plan|/rlplan)//model/kinematics").getValue(); - this->kin.reset(rl::kin::Kinematics::create( + this->kin = rl::kin::Kinematics::create( kin[0].getUri(kin[0].getProperty("href")) - )); + ); if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/world) > 0").getValue()) { @@ -1040,9 +1040,9 @@ MainWindow::load(const QString& filename) if ("mdl" == path.eval("string((/rl/plan|/rlplan)//viewer/model/kinematics/@type)").getValue()) { rl::xml::NodeSet mdl2 = path.eval("(/rl/plan|/rlplan)//viewer/model/kinematics").getValue(); - this->mdl2.reset(dynamic_cast(modelFactory.create( + this->mdl2 = std::dynamic_pointer_cast(modelFactory.create( mdl2[0].getUri(mdl2[0].getProperty("href")) - ))); + )); if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/world) > 0").getValue()) { @@ -1065,9 +1065,9 @@ MainWindow::load(const QString& filename) else { rl::xml::NodeSet kin2 = path.eval("(/rl/plan|/rlplan)//viewer/model/kinematics").getValue(); - this->kin2.reset(rl::kin::Kinematics::create( + this->kin2 = rl::kin::Kinematics::create( kin2[0].getUri(kin2[0].getProperty("href")) - )); + ); if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/world) > 0").getValue()) { diff --git a/demos/rlPlanDemo/MainWindow.h b/demos/rlPlanDemo/MainWindow.h index 335e6047..6c955523 100644 --- a/demos/rlPlanDemo/MainWindow.h +++ b/demos/rlPlanDemo/MainWindow.h @@ -35,7 +35,7 @@ #include #include #include -#include +#include #include #include #include @@ -84,9 +84,9 @@ class MainWindow : public QMainWindow std::shared_ptr kin2; - std::shared_ptr mdl; + std::shared_ptr mdl; - std::shared_ptr mdl2; + std::shared_ptr mdl2; std::shared_ptr model; diff --git a/demos/rlSimulator/ConfigurationDelegate.cpp b/demos/rlSimulator/ConfigurationDelegate.cpp index 3a15349c..48c156f1 100644 --- a/demos/rlSimulator/ConfigurationDelegate.cpp +++ b/demos/rlSimulator/ConfigurationDelegate.cpp @@ -78,9 +78,9 @@ PositionDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& opti { QDoubleSpinBox* editor = new QDoubleSpinBox(parent); - rl::math::Vector maximum = MainWindow::instance()->kinematicModels->getMaximum(); - rl::math::Vector minimum = MainWindow::instance()->kinematicModels->getMinimum(); - Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels->getPositionUnits(); + rl::math::Vector maximum = MainWindow::instance()->dynamicModel->getMaximum(); + rl::math::Vector minimum = MainWindow::instance()->dynamicModel->getMinimum(); + Eigen::Matrix qUnits = MainWindow::instance()->dynamicModel->getPositionUnits(); if (rl::math::UNIT_RADIAN == qUnits(index.row())) { @@ -105,7 +105,7 @@ VelocityDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& opti { QDoubleSpinBox* editor = new QDoubleSpinBox(parent); - Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels->getVelocityUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->dynamicModel->getVelocityUnits(); editor->setRange(-10000, 10000); //TODO? @@ -128,7 +128,7 @@ AccelerationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& { QDoubleSpinBox* editor = new QDoubleSpinBox(parent); - Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels->getVelocityUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->dynamicModel->getVelocityUnits(); editor->setRange(-10000, 10000); diff --git a/demos/rlSimulator/ConfigurationModel.cpp b/demos/rlSimulator/ConfigurationModel.cpp index b25c1489..e031039b 100644 --- a/demos/rlSimulator/ConfigurationModel.cpp +++ b/demos/rlSimulator/ConfigurationModel.cpp @@ -61,14 +61,14 @@ ConfigurationModel::flags(const QModelIndex &index) const QVariant ConfigurationModel::headerData(int section, Qt::Orientation orientation, int role) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return QVariant(); } if (Qt::DisplayRole == role && Qt::Vertical == orientation) { - if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->kinematicModels.get())) + if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->dynamicModel.get())) { for (std::size_t i = 0, j = 0; i < kinematic->getJoints(); ++i) { @@ -98,14 +98,14 @@ ConfigurationModel::operationalChanged(const QModelIndex& topLeft, const QModelI bool ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int role) { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return false; } if (index.isValid() && Qt::EditRole == role) { - if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->kinematicModels.get())) + if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->dynamicModel.get())) { if (dynamic_cast(this)) { @@ -178,12 +178,12 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int bool ConfigurationModel::setData(const rl::math::Vector& values) { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return false; } - if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->kinematicModels.get())) + if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->dynamicModel.get())) { if (dynamic_cast(this)) { @@ -220,53 +220,53 @@ ConfigurationModel::setData(const rl::math::Vector& values) int PositionModel::rowCount(const QModelIndex& parent) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return 0; } - return MainWindow::instance()->kinematicModels->getDofPosition(); + return MainWindow::instance()->dynamicModel->getDofPosition(); } int VelocityModel::rowCount(const QModelIndex& parent) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return 0; } - return MainWindow::instance()->kinematicModels->getDof(); + return MainWindow::instance()->dynamicModel->getDof(); } int AccelerationModel::rowCount(const QModelIndex& parent) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return 0; } - return MainWindow::instance()->kinematicModels->getDof(); + return MainWindow::instance()->dynamicModel->getDof(); } int TorqueModel::rowCount(const QModelIndex& parent) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return 0; } - return MainWindow::instance()->kinematicModels->getDof(); + return MainWindow::instance()->dynamicModel->getDof(); } QVariant PositionModel::data(const QModelIndex& index, int role) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return QVariant(); } @@ -281,8 +281,8 @@ PositionModel::data(const QModelIndex& index, int role) const case Qt::DisplayRole: case Qt::EditRole: { - rl::math::Vector values = MainWindow::instance()->kinematicModels->getPosition(); - Eigen::Matrix units = MainWindow::instance()->kinematicModels->getPositionUnits(); + rl::math::Vector values = MainWindow::instance()->dynamicModel->getPosition(); + Eigen::Matrix units = MainWindow::instance()->dynamicModel->getPositionUnits(); if (rl::math::UNIT_RADIAN == units(index.row())) { @@ -307,7 +307,7 @@ PositionModel::data(const QModelIndex& index, int role) const QVariant VelocityModel::data(const QModelIndex& index, int role) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return QVariant(); } @@ -322,8 +322,8 @@ VelocityModel::data(const QModelIndex& index, int role) const case Qt::DisplayRole: case Qt::EditRole: { - rl::math::Vector values = MainWindow::instance()->kinematicModels->getVelocity(); - Eigen::Matrix units = MainWindow::instance()->kinematicModels->getVelocityUnits(); + rl::math::Vector values = MainWindow::instance()->dynamicModel->getVelocity(); + Eigen::Matrix units = MainWindow::instance()->dynamicModel->getVelocityUnits(); if (rl::math::UNIT_RADIAN == units(index.row())) { @@ -348,7 +348,7 @@ VelocityModel::data(const QModelIndex& index, int role) const QVariant AccelerationModel::data(const QModelIndex& index, int role) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return QVariant(); } @@ -363,8 +363,8 @@ AccelerationModel::data(const QModelIndex& index, int role) const case Qt::DisplayRole: case Qt::EditRole: { - rl::math::Vector values = MainWindow::instance()->kinematicModels->getAcceleration(); - Eigen::Matrix units = MainWindow::instance()->kinematicModels->getAccelerationUnits(); + rl::math::Vector values = MainWindow::instance()->dynamicModel->getAcceleration(); + Eigen::Matrix units = MainWindow::instance()->dynamicModel->getAccelerationUnits(); if (rl::math::UNIT_RADIAN == units(index.row())) { @@ -390,7 +390,7 @@ AccelerationModel::data(const QModelIndex& index, int role) const QVariant TorqueModel::data(const QModelIndex& index, int role) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return QVariant(); } diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index 3c4a61db..dc2709d1 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -57,9 +57,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QMainWindow(parent, f), accelerationModel(nullptr), + dynamicModel(), externalTorque(), geometryModels(nullptr), - kinematicModels(), operationalModel(nullptr), positionModel(nullptr), scene(), @@ -118,10 +118,10 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : rl::mdl::XmlFactory kinematicFactory; this->geometryModels = this->scene->getModel(0); - this->kinematicModels.reset(kinematicFactory.create(QApplication::arguments()[2].toStdString())); - this->simulationResetQ = rl::math::Vector::Zero(this->kinematicModels->getDofPosition()); - this->simulationResetQd = rl::math::Vector::Zero(this->kinematicModels->getDof()); - this->simulationResetQdd = rl::math::Vector::Zero(this->kinematicModels->getDof()); + this->dynamicModel = std::dynamic_pointer_cast(kinematicFactory.create(QApplication::arguments()[2].toStdString())); + this->simulationResetQ = rl::math::Vector::Zero(this->dynamicModel->getDofPosition()); + this->simulationResetQd = rl::math::Vector::Zero(this->dynamicModel->getDof()); + this->simulationResetQdd = rl::math::Vector::Zero(this->dynamicModel->getDof()); this->positionDelegate = new PositionDelegate(this); this->positionModel = new PositionModel(this); @@ -231,11 +231,11 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SLOT(operationalChanged(const QModelIndex&, const QModelIndex&)) ); - rl::math::Vector q(this->kinematicModels->getDofPosition()); + rl::math::Vector q(this->dynamicModel->getDofPosition()); q.setZero(); this->positionModel->setData(q); //TODO? - rl::math::Vector externalTorque = rl::math::Vector::Zero(this->kinematicModels->getDof()); + rl::math::Vector externalTorque = rl::math::Vector::Zero(this->dynamicModel->getDof()); this->externalTorque = externalTorque; this->torqueModel->setData(externalTorque); @@ -399,9 +399,9 @@ MainWindow::clickSimulationReset() this->simulationTime->setText(QString::number(this->simulationTimeElapsed)); this->simulationResultsTime->setText(""); this->simulationResultsEnergy->setText(""); - this->kinematicModels->setPosition(this->simulationResetQ); - this->kinematicModels->setVelocity(this->simulationResetQd); - this->kinematicModels->setAcceleration(this->simulationResetQdd); + this->dynamicModel->setPosition(this->simulationResetQ); + this->dynamicModel->setVelocity(this->simulationResetQd); + this->dynamicModel->setAcceleration(this->simulationResetQdd); this->positionModel->setData(this->simulationResetQ); this->simulationStart->setEnabled(true); this->simulationPause->setEnabled(false); @@ -441,70 +441,68 @@ MainWindow::timerEvent(QTimerEvent *event) return; } - rl::mdl::Dynamic* dynamic = dynamic_cast(this->kinematicModels.get()); - rl::math::Vector3 g(0, 0, this->simulationGravityValue); - dynamic->setWorldGravity(g); + this->dynamicModel->setWorldGravity(g); std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); - rl::math::Vector q(dynamic->getDofPosition()); - rl::math::Vector qd(dynamic->getDof()); - rl::math::Vector qdd(dynamic->getDof()); - rl::math::Vector torque(dynamic->getDof()); - rl::math::Matrix M(dynamic->getDof(), dynamic->getDof()); + rl::math::Vector q(this->dynamicModel->getDofPosition()); + rl::math::Vector qd(this->dynamicModel->getDof()); + rl::math::Vector qdd(this->dynamicModel->getDof()); + rl::math::Vector torque(this->dynamicModel->getDof()); + rl::math::Matrix M(this->dynamicModel->getDof(), this->dynamicModel->getDof()); #if 1 for (int i = 0; i < this->simulationStepsPerFrame; ++i) { - dynamic->setTorque(this->externalTorque); - dynamic->forwardDynamics(); + this->dynamicModel->setTorque(this->externalTorque); + this->dynamicModel->forwardDynamics(); #if 1 - q = dynamic->getPosition(); - qd = dynamic->getVelocity(); - qdd = dynamic->getAcceleration(); + q = this->dynamicModel->getPosition(); + qd = this->dynamicModel->getVelocity(); + qdd = this->dynamicModel->getAcceleration(); qdd -= this->simulationDampingValue * qd / this->simulationTimeStep; // TODO: this is a very simple integration, slightly better than Euler, could be replaced by a *functional-style* Runge-Kutta q += this->simulationTimeStep * (qd + qdd * this->simulationTimeStep / 2); qd += this->simulationTimeStep * qdd; - dynamic->setPosition(q); - dynamic->setVelocity(qd); - dynamic->setAcceleration(qdd); + this->dynamicModel->setPosition(q); + this->dynamicModel->setVelocity(qd); + this->dynamicModel->setAcceleration(qdd); #else - dynamic->rungeKuttaNystrom(simulationTimeStep); // its side effects do not work with damping + this->dynamicModel->rungeKuttaNystrom(simulationTimeStep); // its side effects do not work with damping #endif } - q = dynamic->getPosition(); - qd = dynamic->getVelocity(); - qdd = dynamic->getAcceleration(); - torque = dynamic->getTorque(); - dynamic->calculateMassMatrix(M); - dynamic->setPosition(q); - dynamic->setVelocity(qd); - dynamic->setAcceleration(qdd); - dynamic->setTorque(torque); + q = this->dynamicModel->getPosition(); + qd = this->dynamicModel->getVelocity(); + qdd = this->dynamicModel->getAcceleration(); + torque = this->dynamicModel->getTorque(); + this->dynamicModel->calculateMassMatrix(M); + this->dynamicModel->setPosition(q); + this->dynamicModel->setVelocity(qd); + this->dynamicModel->setAcceleration(qdd); + this->dynamicModel->setTorque(torque); #else for (int i = 0; i < simulationStepsPerFrame; ++i) { - dynamic->getPosition(q); - dynamic->getVelocity(qd); - dynamic->getAcceleration(qdd); - dynamic->getTorque(torque); + this->dynamicModel->getPosition(q); + this->dynamicModel->getVelocity(qd); + this->dynamicModel->getAcceleration(qdd); + this->dynamicModel->getTorque(torque); // V - rl::math::Vector V(dynamic->getDof()); - dynamic->setPosition(q); - dynamic->setVelocity(qd); - dynamic->calculateCentrifugalCoriolis(V); + rl::math::Vector V(this->dynamicModel->getDof()); + this->dynamicModel->setPosition(q); + this->dynamicModel->setVelocity(qd); + this->dynamicModel->calculateCentrifugalCoriolis(V); // G - rl::math::Vector G(dynamic->getDof()); - dynamic->setPosition(q); - dynamic->calculateGravity(G); + rl::math::Vector G(this->dynamicModel->getDof()); + this->dynamicModel->setPosition(q); + this->dynamicModel->calculateGravity(G); // M^{-1} - rl::math::Matrix invM(dynamic->getDof(), dynamic->getDof()); - dynamic->calculateMassMatrixInverse(invM); + rl::math::Matrix invM(this->dynamicModel->getDof(), this->dynamicModel->getDof()); + this->dynamicModel->calculateMassMatrixInverse(invM); // M^{-1} * ( tau - V - G ) //qdd = invM * (torque - V - G); @@ -513,15 +511,15 @@ MainWindow::timerEvent(QTimerEvent *event) qdd -= simulationDampingValue * qd / simulationTimeStep; // simple Euler-Cauchy integration - dynamic->setAcceleration(qdd); + this->dynamicModel->setAcceleration(qdd); q += simulationTimeStep * qd; qd += simulationTimeStep * qdd; - dynamic->setPosition(q); - dynamic->setVelocity(qd); + this->dynamicModel->setPosition(q); + this->dynamicModel->setVelocity(qd); } #endif - dynamic->forwardPosition(); + this->dynamicModel->forwardPosition(); std::chrono::steady_clock::time_point stopTime = std::chrono::steady_clock::now(); this->simulationTimeElapsed += this->simulationStepsPerFrame * this->simulationTimeStep; this->simulationTime->setText(QString::number(this->simulationTimeElapsed)); diff --git a/demos/rlSimulator/MainWindow.h b/demos/rlSimulator/MainWindow.h index 26c5e234..4500bc30 100644 --- a/demos/rlSimulator/MainWindow.h +++ b/demos/rlSimulator/MainWindow.h @@ -39,7 +39,7 @@ #include #include #include -#include +#include #include #include @@ -69,12 +69,12 @@ class MainWindow : public QMainWindow AccelerationModel* accelerationModel; + std::shared_ptr dynamicModel; + rl::math::Vector externalTorque; rl::sg::Model* geometryModels; - std::shared_ptr kinematicModels; - OperationalModel* operationalModel; PositionModel* positionModel; diff --git a/demos/rlSimulator/OperationalModel.cpp b/demos/rlSimulator/OperationalModel.cpp index 0884cfa7..ffaf460e 100644 --- a/demos/rlSimulator/OperationalModel.cpp +++ b/demos/rlSimulator/OperationalModel.cpp @@ -63,7 +63,7 @@ OperationalModel::configurationChanged(const QModelIndex& topLeft, const QModelI QVariant OperationalModel::data(const QModelIndex& index, int role) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return QVariant(); } @@ -78,8 +78,8 @@ OperationalModel::data(const QModelIndex& index, int role) const case Qt::DisplayRole: case Qt::EditRole: { - const rl::math::Transform::ConstTranslationPart& position = MainWindow::instance()->kinematicModels->getOperationalPosition(index.row()).translation(); - rl::math::Vector3 orientation = MainWindow::instance()->kinematicModels->getOperationalPosition(index.row()).rotation().eulerAngles(2, 1, 0).reverse(); + const rl::math::Transform::ConstTranslationPart& position = MainWindow::instance()->dynamicModel->getOperationalPosition(index.row()).translation(); + rl::math::Vector3 orientation = MainWindow::instance()->dynamicModel->getOperationalPosition(index.row()).rotation().eulerAngles(2, 1, 0).reverse(); switch (index.column()) { @@ -130,7 +130,7 @@ OperationalModel::flags(const QModelIndex &index) const QVariant OperationalModel::headerData(int section, Qt::Orientation orientation, int role) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return QVariant(); } @@ -173,25 +173,25 @@ OperationalModel::headerData(int section, Qt::Orientation orientation, int role) int OperationalModel::rowCount(const QModelIndex& parent) const { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return 0; } - return MainWindow::instance()->kinematicModels->getOperationalDof(); + return MainWindow::instance()->dynamicModel->getOperationalDof(); } bool OperationalModel::setData(const QModelIndex& index, const QVariant& value, int role) { - if (nullptr == MainWindow::instance()->kinematicModels) + if (nullptr == MainWindow::instance()->dynamicModel) { return false; } if (index.isValid() && Qt::EditRole == role) { - if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->kinematicModels.get())) + if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->dynamicModel.get())) { rl::math::Transform x = kinematic->getOperationalPosition(index.row()); diff --git a/demos/rlSimulator/Socket.cpp b/demos/rlSimulator/Socket.cpp index 7b4b7ea6..dc7693e0 100644 --- a/demos/rlSimulator/Socket.cpp +++ b/demos/rlSimulator/Socket.cpp @@ -160,7 +160,7 @@ Socket::readClient() if (i < 1) { - rl::math::Vector q(MainWindow::instance()->kinematicModels->getDof()); + rl::math::Vector q(MainWindow::instance()->dynamicModel->getDof()); q.setZero(); for (std::ptrdiff_t j = 0; j < q.size(); ++j) @@ -179,7 +179,7 @@ Socket::readClient() if (i < 1) { - rl::math::Vector torque(MainWindow::instance()->kinematicModels->getDof()); + rl::math::Vector torque(MainWindow::instance()->dynamicModel->getDof()); torque.setZero(); for (std::ptrdiff_t j = 0; j < torque.size(); ++j) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 5ea9cad6..0a7e2450 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -117,10 +117,10 @@ namespace rl } } - Kinematics* + ::std::shared_ptr Kinematics::create(const ::std::string& filename) { - Kinematics* kinematics = nullptr; + ::std::shared_ptr kinematics; ::rl::xml::DomParser parser; @@ -149,15 +149,15 @@ namespace rl if ("puma" == instances[i].getName()) { - kinematics = new Puma(); + kinematics = ::std::make_shared(); } else if ("rhino" == instances[i].getName()) { - kinematics = new Rhino(); + kinematics = ::std::make_shared(); } else if ("kinematics" == instances[i].getName()) { - kinematics = new Kinematics(); + kinematics = ::std::make_shared(); } else { @@ -404,13 +404,10 @@ namespace rl kinematics->update(); - if (dynamic_cast(kinematics)) + if (::std::dynamic_pointer_cast(kinematics)) { if (kinematics->joints.size() != 6 || kinematics->links.size() != 7 || kinematics->transforms.size() != 8 || kinematics->frames.size() != 9) { - delete kinematics; - kinematics = nullptr; - if (kinematics->joints.size() != 6) { throw Exception("Puma kinematics with incorrect number of joints"); @@ -432,13 +429,10 @@ namespace rl } } } - else if (dynamic_cast(kinematics)) + else if (::std::dynamic_pointer_cast(kinematics)) { if (kinematics->joints.size() != 5 || kinematics->links.size() != 6 || kinematics->transforms.size() != 7 || kinematics->frames.size() != 8) { - delete kinematics; - kinematics = nullptr; - if (kinematics->joints.size() != 5) { throw Exception("Rhino kinematics with incorrect number of joints"); diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 0bd78ab9..c23cb42a 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -72,7 +72,7 @@ namespace rl */ virtual void clamp(::rl::math::Vector& q) const; - static Kinematics* create(const ::std::string& filename); + static ::std::shared_ptr create(const ::std::string& filename); /** * Calculate distance measure between specified configuration. diff --git a/src/rl/mdl/Factory.cpp b/src/rl/mdl/Factory.cpp index 52f7e457..bedab96b 100644 --- a/src/rl/mdl/Factory.cpp +++ b/src/rl/mdl/Factory.cpp @@ -39,11 +39,11 @@ namespace rl { } - Model* + ::std::shared_ptr Factory::create(const ::std::string& filename) { - Model* model = new Dynamic(); - this->load(filename, model); + ::std::shared_ptr model = ::std::make_shared(); + this->load(filename, model.get()); return model; } } diff --git a/src/rl/mdl/Factory.h b/src/rl/mdl/Factory.h index dc342a03..a827fff6 100644 --- a/src/rl/mdl/Factory.h +++ b/src/rl/mdl/Factory.h @@ -27,6 +27,7 @@ #ifndef RL_MDL_FACTORY_H #define RL_MDL_FACTORY_H +#include #include #include @@ -43,7 +44,7 @@ namespace rl virtual ~Factory(); - virtual Model* create(const ::std::string& filename); + virtual ::std::shared_ptr create(const ::std::string& filename); virtual void load(const ::std::string& filename, Model* model) = 0; diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 950310e5..e5dd9591 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -30,7 +30,7 @@ #include #include #include -#include +#include #include #include #include @@ -126,7 +126,7 @@ namespace rl ::rl::kin::Kinematics* kin; - ::rl::mdl::Dynamic* mdl; + ::rl::mdl::Kinematic* mdl; ::rl::sg::Model* model; diff --git a/tests/rlCollisionTest/rlCollisionTest.cpp b/tests/rlCollisionTest/rlCollisionTest.cpp index 0223485c..2a4afb07 100644 --- a/tests/rlCollisionTest/rlCollisionTest.cpp +++ b/tests/rlCollisionTest/rlCollisionTest.cpp @@ -106,8 +106,7 @@ main(int argc, char** argv) } rl::mdl::XmlFactory modelFactory; - std::shared_ptr model(modelFactory.create(argv[2])); - rl::mdl::Kinematic* kinematics = dynamic_cast(model.get()); + std::shared_ptr kinematics = std::dynamic_pointer_cast(modelFactory.create(argv[2])); std::size_t dof = kinematics->getDof(); rl::math::Vector q(kinematics->getDof()); @@ -164,7 +163,7 @@ main(int argc, char** argv) for (std::size_t i = 0; i < scenes.size(); ++i) { std::cout << "Testing SimpleScene::isColliding() in " << sceneNames[i] << ": "; - std::cout << (collides(scenes[i], kinematics) ? "true" : "false") << std::endl; + std::cout << (collides(scenes[i], kinematics.get()) ? "true" : "false") << std::endl; } std::mt19937 randomGenerator(0); @@ -191,7 +190,7 @@ main(int argc, char** argv) { scenes[i]->getModel(0)->getBody(b)->setFrame(kinematics->getBodyFrame(b)); } - results[i] = collides(scenes[i], kinematics); + results[i] = collides(scenes[i], kinematics.get()); } if ((results.array() == false).any() && (results.array() == true).any()) diff --git a/tests/rlDynamicsTest/rlDynamicsTest.cpp b/tests/rlDynamicsTest/rlDynamicsTest.cpp index 1d188159..e117d3f4 100644 --- a/tests/rlDynamicsTest/rlDynamicsTest.cpp +++ b/tests/rlDynamicsTest/rlDynamicsTest.cpp @@ -29,7 +29,6 @@ #include #include #include -#include #include int @@ -46,13 +45,11 @@ main(int argc, char** argv) srand(std::random_device()()); rl::mdl::XmlFactory factory; - std::shared_ptr model(factory.create(argv[1])); + std::shared_ptr dynamic = std::dynamic_pointer_cast(factory.create(argv[1])); - rl::mdl::Dynamic* dynamic = dynamic_cast(model.get()); - - rl::math::Vector q0(model->getDofPosition()); - rl::math::Vector qd0(model->getDof()); - rl::math::Vector qdd0(model->getDof()); + rl::math::Vector q0(dynamic->getDofPosition()); + rl::math::Vector qd0(dynamic->getDof()); + rl::math::Vector qdd0(dynamic->getDof()); for (::std::size_t i = 0; i < atoi(argv[2]); ++i) { diff --git a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp index 58d87de9..2072e2cc 100644 --- a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp +++ b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp @@ -49,26 +49,25 @@ main(int argc, char** argv) std::string filename = argv[1]; rl::mdl::XmlFactory factory; - std::shared_ptr model(factory.create(filename)); - rl::mdl::Kinematic* kinematics = dynamic_cast(model.get()); + std::shared_ptr kinematics = std::dynamic_pointer_cast(factory.create(filename)); kinematics->seed(0); std::vector, std::string>> ik; - std::shared_ptr jacobianSvd = std::make_shared(kinematics); + std::shared_ptr jacobianSvd = std::make_shared(kinematics.get()); jacobianSvd->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_SVD); ik.push_back(std::make_pair(jacobianSvd, "rl::mdl::JacobianInverseKinematics::METHOD_SVD")); - std::shared_ptr jacobianDls = std::make_shared(kinematics); + std::shared_ptr jacobianDls = std::make_shared(kinematics.get()); jacobianDls->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_DLS); ik.push_back(std::make_pair(jacobianDls, "rl::mdl::JacobianInverseKinematics::METHOD_DLS")); - std::shared_ptr jacobianTranspose = std::make_shared(kinematics); + std::shared_ptr jacobianTranspose = std::make_shared(kinematics.get()); jacobianTranspose->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE); ik.push_back(std::make_pair(jacobianTranspose, "rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE")); #ifdef RL_MDL_NLOPT - std::shared_ptr nlopt = std::make_shared(kinematics); + std::shared_ptr nlopt = std::make_shared(kinematics.get()); ik.push_back(std::make_pair(nlopt, "rl::mdl::NloptInverseKinematics")); #endif diff --git a/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp b/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp index 0c99942d..3bad206b 100644 --- a/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp +++ b/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp @@ -43,8 +43,7 @@ main(int argc, char** argv) } rl::mdl::XmlFactory factory; - std::shared_ptr model(factory.create(argv[1])); - rl::mdl::Kinematic* kinematics = dynamic_cast(model.get()); + std::shared_ptr kinematics = std::dynamic_pointer_cast(factory.create(argv[1])); std::size_t dof = kinematics->getDof(); std::srand(0); // get reproducible results From 30cfa608da6cbb2f00a39e739eb40c12141a0c68 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 21:30:09 +0200 Subject: [PATCH 223/546] Remove unused member variable --- demos/rlSimulator/ConfigurationDelegate.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/demos/rlSimulator/ConfigurationDelegate.h b/demos/rlSimulator/ConfigurationDelegate.h index e878b4cc..71233193 100644 --- a/demos/rlSimulator/ConfigurationDelegate.h +++ b/demos/rlSimulator/ConfigurationDelegate.h @@ -46,8 +46,6 @@ class ConfigurationDelegate : public QItemDelegate void updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const; - std::size_t id; - public slots: void valueChanged(double d); From 3154ad264ae38c2d1c68fe7e2e22636cf7033d5a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 21:53:09 +0200 Subject: [PATCH 224/546] Reduce scope of variables --- src/rl/hal/WeissKms40.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/src/rl/hal/WeissKms40.cpp b/src/rl/hal/WeissKms40.cpp index 1bae86d8..0186f0bd 100644 --- a/src/rl/hal/WeissKms40.cpp +++ b/src/rl/hal/WeissKms40.cpp @@ -448,18 +448,15 @@ namespace rl ::std::string reply; ::std::array buffer; - char* ptr; - ::std::size_t sumbytes; - ::std::size_t numbytes; do { - ptr = buffer.data(); - sumbytes = 0; + char* ptr = buffer.data(); + ::std::size_t sumbytes = 0; do { - numbytes = this->socket.recv(ptr, 1); + ::std::size_t numbytes = this->socket.recv(ptr, 1); ptr += numbytes; sumbytes += numbytes; } From 5b788dda3e9881118bde0303239e1c326b7eb58d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 22:08:28 +0200 Subject: [PATCH 225/546] Minor update --- demos/rlPlanDemo/Thread.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index 49d5e2cf..03b20717 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -174,7 +174,7 @@ Thread::run() { emit statusChanged("Showing start configuration."); this->drawConfiguration(*MainWindow::instance()->planner->start); - usleep(static_cast(2.0 * 1000.0 * 1000.0)); + QThread::usleep(static_cast(2.0 * 1000.0 * 1000.0)); } if (!this->running) return; @@ -183,7 +183,7 @@ Thread::run() { emit statusChanged("Showing goal configuration."); this->drawConfiguration(*MainWindow::instance()->planner->goal); - usleep(static_cast(2.0 * 1000.0 * 1000.0)); + QThread::usleep(static_cast(2.0 * 1000.0 * 1000.0)); } if (!this->running) return; @@ -355,7 +355,7 @@ Thread::run() { if (nullptr != MainWindow::instance()->planner->viewer) { - usleep(static_cast(2.0 * 1000.0 * 1000.0)); + QThread::usleep(static_cast(2.0 * 1000.0 * 1000.0)); } emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration) + " ms. Optimizing..."); @@ -394,7 +394,7 @@ Thread::run() if (i != path.end() && j != path.end()) { this->drawConfiguration(*i); - usleep(static_cast(0.01 * 1000.0 * 1000.0)); + QThread::usleep(static_cast(0.01 * 1000.0 * 1000.0)); } rl::math::Real delta = MainWindow::instance()->viewer->delta; @@ -411,7 +411,7 @@ Thread::run() MainWindow::instance()->model->interpolate(*i, *j, k / steps, inter); this->drawConfiguration(inter); - usleep(static_cast(0.01 * 1000.0 * 1000.0)); + QThread::usleep(static_cast(0.01 * 1000.0 * 1000.0)); } } @@ -423,7 +423,7 @@ Thread::run() if (ri != path.rend() && rj != path.rend()) { this->drawConfiguration(*ri); - usleep(static_cast(0.01 * 1000.0 * 1000.0)); + QThread::usleep(static_cast(0.01 * 1000.0 * 1000.0)); } for (; ri != path.rend() && rj != path.rend(); ++ri, ++rj) @@ -438,7 +438,7 @@ Thread::run() MainWindow::instance()->model->interpolate(*ri, *rj, k / steps, inter); this->drawConfiguration(inter); - usleep(static_cast(0.01 * 1000.0 * 1000.0)); + QThread::usleep(static_cast(0.01 * 1000.0 * 1000.0)); } } } From 5992bf6f1f225b86e609daaab9fd98ca51d789d8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 22:30:29 +0200 Subject: [PATCH 226/546] Rethrow timeout exception --- src/rl/hal/MitsubishiH7.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/hal/MitsubishiH7.cpp b/src/rl/hal/MitsubishiH7.cpp index 2c9e0946..2e22754a 100644 --- a/src/rl/hal/MitsubishiH7.cpp +++ b/src/rl/hal/MitsubishiH7.cpp @@ -430,9 +430,9 @@ namespace rl { this->socket.select(true, false, this->filter * this->getUpdateRate() + 6 * this->getUpdateRate()); } - catch (const TimeoutException& e) + catch (const TimeoutException&) { - throw e; + throw; } this->socket.recv(&this->in, sizeof(Command)); From 817d49e010ec6af9e141137e4f9323540b14eb6f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 22:35:53 +0200 Subject: [PATCH 227/546] Clarify calculation precedence --- src/rl/hal/Serial.cpp | 8 ++++---- src/rl/hal/UniversalRobotsRealtime.cpp | 4 ++-- src/rl/hal/UniversalRobotsRtde.cpp | 4 ++-- src/rl/sg/Body.cpp | 2 +- 4 files changed, 9 insertions(+), 9 deletions(-) diff --git a/src/rl/hal/Serial.cpp b/src/rl/hal/Serial.cpp index 05fb1952..d289e77c 100644 --- a/src/rl/hal/Serial.cpp +++ b/src/rl/hal/Serial.cpp @@ -186,10 +186,10 @@ namespace rl throw ComException(::GetLastError()); } - ctsOn = status & MS_CTS_ON ? true : false; - dsrOn = status & MS_DSR_ON ? true : false; - riOn = status & MS_RING_ON ? true : false; - dcdOn = status & MS_RLSD_ON ? true : false; + ctsOn = (status & MS_CTS_ON) ? true : false; + dsrOn = (status & MS_DSR_ON) ? true : false; + riOn = (status & MS_RING_ON) ? true : false; + dcdOn = (status & MS_RLSD_ON) ? true : false; #else // WIN32 int status = 0; diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index d39490b1..520c93c8 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -139,7 +139,7 @@ namespace rl bool UniversalRobotsRealtime::getDigitalInput(const ::std::size_t& i) const { - return this->in.digitalInputBits & (1ULL << i) ? true : false; + return (this->in.digitalInputBits & (1ULL << i)) ? true : false; } ::std::size_t @@ -157,7 +157,7 @@ namespace rl bool UniversalRobotsRealtime::getDigitalOutput(const ::std::size_t& i) const { - return this->in.digitalOutputs & (1ULL << i) ? true : false; + return (this->in.digitalOutputs & (1ULL << i)) ? true : false; } ::std::size_t diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 66542686..98badc93 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -364,7 +364,7 @@ namespace rl bool UniversalRobotsRtde::getDigitalInput(const ::std::size_t& i) const { - return this->output.actualDigitalInputBits & (1ULL << i) ? true : false; + return (this->output.actualDigitalInputBits & (1ULL << i)) ? true : false; } ::std::size_t @@ -382,7 +382,7 @@ namespace rl bool UniversalRobotsRtde::getDigitalOutput(const ::std::size_t& i) const { - return this->output.actualDigitalOutputBits & (1ULL << i) ? true : false; + return (this->output.actualDigitalOutputBits & (1ULL << i)) ? true : false; } ::std::size_t diff --git a/src/rl/sg/Body.cpp b/src/rl/sg/Body.cpp index 1a858c13..a1e41727 100644 --- a/src/rl/sg/Body.cpp +++ b/src/rl/sg/Body.cpp @@ -82,7 +82,7 @@ namespace rl { for (::std::size_t j = 0, k = 1; j < 3; ++j, k *= 2) { - p[i](j) = i & k ? this->max(j) : this->min(j); + p[i](j) = (i & k) ? this->max(j) : this->min(j); } } From 208d8c849fa49b48991fb7019ad274d05947f4e1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Apr 2019 22:57:10 +0200 Subject: [PATCH 228/546] Use std::array --- src/rl/hal/Ati.cpp | 26 ++++++++++++-------------- src/rl/hal/Ati.h | 5 +++-- 2 files changed, 15 insertions(+), 16 deletions(-) diff --git a/src/rl/hal/Ati.cpp b/src/rl/hal/Ati.cpp index 800d82c2..eb7a01a4 100644 --- a/src/rl/hal/Ati.cpp +++ b/src/rl/hal/Ati.cpp @@ -57,11 +57,8 @@ namespace rl throw DeviceException("Could not load the desired calibration"); } - for (::std::size_t i = 0; i < 6; ++i) - { - this->values[i] = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); - this->voltages[i] = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); - } + this->values.fill(::std::numeric_limits< ::rl::math::Real>::quiet_NaN()); + this->voltages.fill(::std::numeric_limits< ::rl::math::Real>::quiet_NaN()); } Ati::~Ati() @@ -75,7 +72,7 @@ namespace rl void Ati::bias() { - Bias(this->cal, this->voltages); + Bias(this->cal, this->voltages.data()); } void @@ -98,7 +95,7 @@ namespace rl { ::rl::math::Vector forces(3); - for (::std::size_t i = 0; i < 3; ++i) + for (::std::size_t i = 0; i < forces.size(); ++i) { forces(i) = this->values[i]; } @@ -127,7 +124,7 @@ namespace rl { ::rl::math::Vector forcesTorques(6); - for (::std::size_t i = 0; i < 6; ++i) + for (::std::size_t i = 0; i < forcesTorques.size(); ++i) { forcesTorques(i) = this->values[i]; } @@ -156,9 +153,9 @@ namespace rl { ::rl::math::Vector torques(3); - for (::std::size_t i = 3; i < 6; ++i) + for (::std::size_t i = 0; i < torques.size(); ++i) { - torques(i) = this->values[i]; + torques(i) = this->values[3 + i]; } return torques; @@ -190,8 +187,9 @@ namespace rl void Ati::resetBias() { - float voltages[6] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; - Bias(this->cal, voltages); + std::array voltages; + voltages.fill(0.0f); + Bias(this->cal, voltages.data()); } void @@ -202,12 +200,12 @@ namespace rl void Ati::step() { - for (::std::size_t i = 0; i < 6; ++i) + for (::std::size_t i = 0; i < this->voltages.size(); ++i) { this->comedi.read(0, i, this->voltages[i]); } - ConvertToFT(this->cal, this->voltages, this->values); + ConvertToFT(this->cal, this->voltages.data(), this->values.data()); } void diff --git a/src/rl/hal/Ati.h b/src/rl/hal/Ati.h index 5e8a722c..e1316572 100644 --- a/src/rl/hal/Ati.h +++ b/src/rl/hal/Ati.h @@ -27,6 +27,7 @@ #ifndef RL_HAL_ATI_H #define RL_HAL_ATI_H +#include #include #include @@ -100,9 +101,9 @@ namespace rl /** The number of the calibration within the file (usually 1). */ unsigned short int index; - float values[6]; + std::array values; - float voltages[6]; + std::array voltages; }; } } From 4fc02a15de9542768268cde12705781a3d03a516 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 21 Apr 2019 01:12:22 +0200 Subject: [PATCH 229/546] Use std::array --- src/rl/hal/Jr3.cpp | 27 +++++++++------------------ src/rl/hal/Jr3.h | 5 +++-- 2 files changed, 12 insertions(+), 20 deletions(-) diff --git a/src/rl/hal/Jr3.cpp b/src/rl/hal/Jr3.cpp index 8af5fc59..3f183896 100644 --- a/src/rl/hal/Jr3.cpp +++ b/src/rl/hal/Jr3.cpp @@ -41,11 +41,8 @@ namespace rl values(), zeroes() { - for (::std::size_t i = 0; i < 6; ++i) - { - this->values[i] = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); - this->zeroes[i] = 0; - } + this->values.fill(::std::numeric_limits< ::rl::math::Real>::quiet_NaN()); + this->zeroes.fill(0); } Jr3::~Jr3() @@ -55,10 +52,7 @@ namespace rl void Jr3::bias() { - for (::std::size_t i = 0; i < 6; ++i) - { - this->zeroes[i] = this->values[i]; - } + this->zeroes = this->values; } void @@ -73,7 +67,7 @@ namespace rl { ::rl::math::Vector forces(3); - for (::std::size_t i = 0; i < 3; ++i) + for (::std::size_t i = 0; i < forces.size(); ++i) { forces(i) = (this->values[i] - this->zeroes[i]) * 1000; } @@ -102,7 +96,7 @@ namespace rl { ::rl::math::Vector forcesTorques(6); - for (::std::size_t i = 0; i < 6; ++i) + for (::std::size_t i = 0; i < forcesTorques.size(); ++i) { forcesTorques(i) = (this->values[i] - this->zeroes[i]) * 1000; } @@ -131,9 +125,9 @@ namespace rl { ::rl::math::Vector torques(3); - for (::std::size_t i = 3; i < 6; ++i) + for (::std::size_t i = 0; i < torques.size(); ++i) { - torques(i) = (this->values[i] - this->zeroes[i]) * 1000; + torques(i) = (this->values[3 + i] - this->zeroes[3 + i]) * 1000; } return torques; @@ -165,10 +159,7 @@ namespace rl void Jr3::resetBias() { - for (::std::size_t i = 0; i < 6; ++i) - { - this->zeroes[i] = 0; - } + this->zeroes.fill(0); } void @@ -179,7 +170,7 @@ namespace rl void Jr3::step() { - for (::std::size_t i = 0; i < 6; ++i) + for (::std::size_t i = 0; i < this->values.size(); ++i) { this->comedi.read(0, i, this->values[i]); } diff --git a/src/rl/hal/Jr3.h b/src/rl/hal/Jr3.h index eda6b2ae..6b6b7326 100644 --- a/src/rl/hal/Jr3.h +++ b/src/rl/hal/Jr3.h @@ -27,6 +27,7 @@ #ifndef RL_HAL_JR3_H #define RL_HAL_JR3_H +#include #include #include "Comedi.h" @@ -84,9 +85,9 @@ namespace rl private: Comedi comedi; - float values[6]; + std::array values; - float zeroes[6]; + std::array zeroes; }; } } From 1a34c5b4c63751d87a8c6acd0e9b95abc191dce2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 21 Apr 2019 17:05:34 +0200 Subject: [PATCH 230/546] Use fstream and boost string algorithms --- extras/tris2wrl/CMakeLists.txt | 2 + extras/tris2wrl/tris2wrl.cpp | 165 +++++++++++++++++++-------------- 2 files changed, 95 insertions(+), 72 deletions(-) diff --git a/extras/tris2wrl/CMakeLists.txt b/extras/tris2wrl/CMakeLists.txt index 27a0e4a7..a9e94ce2 100644 --- a/extras/tris2wrl/CMakeLists.txt +++ b/extras/tris2wrl/CMakeLists.txt @@ -1,5 +1,6 @@ project(tris2wrl) +find_package(Boost REQUIRED) find_package(Coin) if(Coin_FOUND) @@ -17,6 +18,7 @@ if(Coin_FOUND) target_include_directories( tris2wrl PUBLIC + ${Boost_INCLUDE_DIR} ${Coin_INCLUDE_DIRS} ) diff --git a/extras/tris2wrl/tris2wrl.cpp b/extras/tris2wrl/tris2wrl.cpp index 3b51aeb7..e46f318b 100644 --- a/extras/tris2wrl/tris2wrl.cpp +++ b/extras/tris2wrl/tris2wrl.cpp @@ -1,9 +1,13 @@ +#include #include +#include #include +#include #include #include #include #include +#include #include #include #include @@ -19,10 +23,22 @@ main(int argc, char** argv) return EXIT_FAILURE; } - FILE* f = fopen(argv[1], "r"); - SoDB::init(); + std::fstream file; + file.open(argv[1]); + + std::string line; + std::vector tokens; + + std::getline(file, line); + + if (!boost::starts_with(line, "#")) + { + file.close(); + return EXIT_FAILURE; + } + SoVRMLTransform* root = new SoVRMLTransform(); root->ref(); @@ -41,106 +57,113 @@ main(int argc, char** argv) SoVRMLCoordinate* coordinate = new SoVRMLCoordinate(); indexedFaceSet->coord = coordinate; - char line[256]; - char ign; - - fscanf(f, "%[^\n]%c", line, &ign); + SoVRMLColor* color = new SoVRMLColor(); + indexedFaceSet->color = color; - float pt[3]; - unsigned int points = 0; + indexedFaceSet->colorPerVertex.setValue(false); + indexedFaceSet->solid.setValue(false); - while (EOF != fscanf(f, "%[^\n]%c", line, &ign)) - { - if ('#' != line[0]) + while (-1 != file.peek()) + { + std::getline(file, line); + + if (line.empty()) { - // Not a comment - if (3 != sscanf(line, "%g %g %g", pt, pt + 1, pt + 2)) - { - fprintf(stderr, "Error couldn't parse a point (%s)\n", line); - } - else - { - coordinate->point.set1Value(points, pt[0], pt[1], pt[2]); - ++points; - } + continue; } - else + else if (boost::starts_with(line, "#")) { break; } + + boost::trim(line); + boost::split(tokens, line, boost::is_space(), boost::token_compress_on); + + coordinate->point.set1Value(coordinate->point.getNum(), std::stof(tokens[0]), std::stof(tokens[1]), std::stof(tokens[2])); } - int tri[3]; - unsigned int triangles = 0; - - while (EOF != fscanf(f, "%[^\n]%c", line, &ign)) + while (-1 != file.peek()) { - if ('#' != line[0]) + std::getline(file, line); + + if (line.empty()) { - // Not a comment - if (3 != sscanf(line, "%d %d %d", tri, tri + 1, tri + 2)) - { - fprintf(stderr, "Error couldn't parse a triangle (%s)\n", line); - } - else - { - indexedFaceSet->coordIndex.set1Value(triangles, tri[0]); - ++triangles; - indexedFaceSet->coordIndex.set1Value(triangles, tri[1]); - ++triangles; - indexedFaceSet->coordIndex.set1Value(triangles, tri[2]); - ++triangles; - indexedFaceSet->coordIndex.set1Value(triangles, -1); - ++triangles; - } + continue; } - else + else if (boost::starts_with(line, "#")) { break; } + + boost::trim(line); + boost::split(tokens, line, boost::is_space(), boost::token_compress_on); + + for (std::size_t i = 0; i < tokens.size(); ++i) + { + indexedFaceSet->coordIndex.set1Value(indexedFaceSet->coordIndex.getNum(), std::stoi(tokens[i])); + } + + indexedFaceSet->coordIndex.set1Value(indexedFaceSet->coordIndex.getNum(), -1); } - float nm[14]; - - while (EOF != fscanf(f, "%[^\n]%c", line, &ign)) - { - if ('#' != line[0]) + while (-1 != file.peek()) + { + std::getline(file, line); + + if (line.empty()) { - // Not a comment - if (14 != sscanf(line, "%f %f %f %g %g %g %g %g %g %g %g %g %g %g", &nm[0], &nm[1], &nm[2], &nm[3], &nm[4], &nm[5], &nm[6], &nm[7], &nm[8], &nm[9], &nm[10], &nm[11], &nm[12], &nm[13])) - { - fprintf(stderr, "Error couldn't parse a material (%s)\n", line); - } + continue; } - else + else if (boost::starts_with(line, "#")) { break; } + + boost::trim(line); + boost::split(tokens, line, boost::is_space(), boost::token_compress_on); + + if (tokens.size() > 5) + { + color->color.set1Value(color->color.getNum(), std::stof(tokens[3]), std::stof(tokens[4]), std::stof(tokens[5])); + } } - int index; - int i = 0; - char* pointer; - - while (EOF != fscanf(f, "%[^\n]%c", line, &ign)) + while (-1 != file.peek()) { - if ('#' != line[0]) + std::getline(file, line); + + if (line.empty()) { - // Not a comment - pointer = &line[0]; - - while (1 == sscanf(pointer, "%d, ", &index)) - { - i++; - pointer += 3; - } + continue; } - else + else if (boost::starts_with(line, "#")) { break; } + + boost::trim_if(line, boost::is_any_of(", \t\n\v\f\r")); + boost::split(tokens, line, boost::is_any_of(", "), boost::token_compress_on); + + for (std::size_t i = 0; i < tokens.size(); ++i) + { + indexedFaceSet->colorIndex.set1Value(indexedFaceSet->colorIndex.getNum(), std::stoi(tokens[i])); + } } + std::cout << "coordinates: " << coordinate->point.getNum() << std::endl; + std::cout << "faces: " << indexedFaceSet->coordIndex.getNum() / 4 << std::endl; + std::cout << "materials: " << color->color.getNum() << std::endl; + std::cout << "material indices: " << indexedFaceSet->colorIndex.getNum() << std::endl; + + if (0 == indexedFaceSet->colorIndex.getNum()) + { + color->ref(); + indexedFaceSet->color.setValue(nullptr); + color->unref(); + } + + file.close(); + SoOutput out; out.openFile(argv[2]); out.setHeaderString("#VRML V2.0 utf8"); @@ -150,7 +173,5 @@ main(int argc, char** argv) root->unref(); - fclose(f); - return EXIT_SUCCESS; } From cdce9c27a996c082352ddaaab90441db6f51e10c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 21 Apr 2019 17:55:56 +0200 Subject: [PATCH 231/546] Fix condition for baud rate sync exception --- src/rl/hal/SickLms200.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/hal/SickLms200.cpp b/src/rl/hal/SickLms200.cpp index 2155caa3..cdd0c8ed 100644 --- a/src/rl/hal/SickLms200.cpp +++ b/src/rl/hal/SickLms200.cpp @@ -669,9 +669,9 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; } #if defined(WIN32) || defined(__QNX__) - if (3 == i) + if (2 == i) #else // defined(WIN32) || defined(__QNX__) - if (4 == i) + if (3 == i) #endif // defined(WIN32) || defined(__QNX__) { throw DeviceException("could not sync baud rate."); From a6372c11cf3cedc8bbacb82a9157301841dfdc43 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 21 Apr 2019 23:32:49 +0200 Subject: [PATCH 232/546] Add helper functions for printing hex numbers and restoring ios state --- src/rl/util/CMakeLists.txt | 8 +++ src/rl/util/io/BasicIosRestorer.h | 94 +++++++++++++++++++++++++++++++ src/rl/util/io/Hex.h | 80 ++++++++++++++++++++++++++ 3 files changed, 182 insertions(+) create mode 100644 src/rl/util/io/BasicIosRestorer.h create mode 100644 src/rl/util/io/Hex.h diff --git a/src/rl/util/CMakeLists.txt b/src/rl/util/CMakeLists.txt index 3c3c4642..a5c1b325 100644 --- a/src/rl/util/CMakeLists.txt +++ b/src/rl/util/CMakeLists.txt @@ -12,6 +12,13 @@ set( ) list(APPEND HDRS ${BASE_HDRS}) +set( + IO_HDRS + io/BasicIosRestorer.h + io/Hex.h +) +list(APPEND HDRS ${IO_HDRS}) + if(RL_BUILD_UTIL_RTAI) set( RTAI_HDRS @@ -57,6 +64,7 @@ target_include_directories( ) install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/util COMPONENT development) +install(FILES ${IO_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/util/io COMPONENT development) if(RL_BUILD_UTIL_RTAI) target_include_directories(util INTERFACE ${RTAI_INCLUDE_DIRS}) diff --git a/src/rl/util/io/BasicIosRestorer.h b/src/rl/util/io/BasicIosRestorer.h new file mode 100644 index 00000000..5a8f7aed --- /dev/null +++ b/src/rl/util/io/BasicIosRestorer.h @@ -0,0 +1,94 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_UTIL_IO_BASICIOSRESTORER_H +#define RL_UTIL_IO_BASICIOSRESTORER_H + +#include + +namespace rl +{ + namespace util + { + namespace io + { + template> + class BasicIosRestorer + { + public: + typedef ::std::basic_ios value_type; + + explicit BasicIosRestorer(value_type& ios) : + exceptions(ios.exceptions()), + fill(ios.fill()), + flags(ios.flags()), + ios(ios), + precision(ios.precision()), + rdbuf(ios.rdbuf()), + rdstate(ios.rdstate()), + tie(ios.tie()), + width(ios.width()) + { + } + + ~BasicIosRestorer() + { + this->ios.exceptions(this->exceptions); + this->ios.fill(this->fill); + this->ios.flags(this->flags); + this->ios.precision(this->precision); + this->ios.rdbuf(this->rdbuf); + this->ios.clear(this->rdstate); + this->ios.tie(this->tie); + this->ios.width(this->width); + } + + protected: + + private: + const typename value_type::iostate exceptions; + + const typename value_type::char_type fill; + + const typename value_type::fmtflags flags; + + value_type& ios; + + const typename ::std::streamsize precision; + + ::std::basic_streambuf* rdbuf; + + const typename value_type::iostate rdstate; + + ::std::basic_ostream* tie; + + const typename ::std::streamsize width; + }; + } + } +} + +#endif // RL_UTIL_IO_BASICIOSRESTORER_H diff --git a/src/rl/util/io/Hex.h b/src/rl/util/io/Hex.h new file mode 100644 index 00000000..90ee2ff4 --- /dev/null +++ b/src/rl/util/io/Hex.h @@ -0,0 +1,80 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_UTIL_IO_HEX_H +#define RL_UTIL_IO_HEX_H + +#include +#include + +#include "BasicIosRestorer.h" + +namespace rl +{ + namespace util + { + namespace io + { + template + class Hex + { + public: + explicit Hex(const T& value) : + value(value) + { + } + + const T& operator()() const + { + return this->value; + } + + protected: + + private: + const T& value; + }; + + template + inline Hex hex(const T& value) + { + return Hex(value); + } + + template + inline ::std::ostream& operator<<(::std::ostream& stream, const Hex& value) + { + BasicIosRestorer restorer(stream); + stream.fill('0'); + stream.setf(::std::ios_base::hex, ::std::ios_base::basefield); + stream.width(::std::numeric_limits::digits / 4); + return stream << static_cast(value()); + } + } + } +} + +#endif // RL_UTIL_IO_HEX_H From 92310630a482b54a818b30823e5ff1ea77c21840 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 21 Apr 2019 23:51:10 +0200 Subject: [PATCH 233/546] Replace printf with std::cout --- src/rl/hal/SickLms200.cpp | 222 +++++++++++++++++++------------------- src/rl/hal/SickS300.cpp | 26 ++--- src/rl/hal/WeissWsg50.cpp | 27 +++-- 3 files changed, 141 insertions(+), 134 deletions(-) diff --git a/src/rl/hal/SickLms200.cpp b/src/rl/hal/SickLms200.cpp index cdd0c8ed..9d4593de 100644 --- a/src/rl/hal/SickLms200.cpp +++ b/src/rl/hal/SickLms200.cpp @@ -25,9 +25,9 @@ // #include -#include #include #include +#include #include "DeviceException.h" #include "Endian.h" @@ -128,6 +128,8 @@ namespace rl void SickLms200::dumpConfiguration() { + using namespace ::rl::util::io; + assert(this->isConnected()); ::std::array< ::std::uint8_t, 812> buf; @@ -142,9 +144,9 @@ namespace rl this->recv(buf.data(), 1 + 1 + 2 + 1 + 32 + 1 + 2, 0xF4); - printf("A: %i\n", Endian::hostWord(buf[6], buf[5])); - printf("B: %02x %02x\n", buf[8], buf[7]); - printf("C: %02x\n", buf[9]); + ::std::cout << "A: " << Endian::hostWord(buf[6], buf[5]) << ::std::endl; + ::std::cout << "B: H:" << hex(buf[8]) << " L:" << hex(buf[7]) << ::std::endl; + ::std::cout << "C: " << hex(buf[9]) << ::std::endl; if (buf[9] & 1) { @@ -161,38 +163,40 @@ namespace rl ::std::cout << "Availability level 2" << ::std::endl; } - printf("D: %02x\n", buf[10]); - printf("E: %02x\n", buf[11]); - printf("F: %02x\n", buf[12]); - printf("G: %02x\n", buf[13]); - printf("H: %02x\n", buf[14]); - printf("I: %02x\n", buf[15]); - printf("J: %02x\n", buf[16]); - printf("K: %02x\n", buf[17]); - printf("L: %02x\n", buf[18]); - printf("M: %02x\n", buf[19]); - printf("N: %02x\n", buf[20]); - printf("O: %02x\n", buf[21]); - printf("P: %02x\n", buf[22]); - printf("Q: %02x\n", buf[23]); - printf("R: %02x\n", buf[24]); - printf("S: %02x\n", buf[25]); - printf("T: %02x\n", buf[26]); - printf("U: %02x\n", buf[27]); - printf("V: %02x\n", buf[28]); - printf("W: %02x\n", buf[29]); - printf("X: %02x\n", buf[30]); - printf("Y: %02x\n", buf[31]); - printf("Z: %02x\n", buf[32]); - printf("A1: %02x\n", buf[33]); - printf("A2: %02x\n", buf[34]); - printf("A3: %02x %02x\n", buf[36], buf[35]); - printf("A4: %02x %02x\n", buf[38], buf[37]); + ::std::cout << "D: " << hex(buf[10]) << ::std::endl; + ::std::cout << "E: " << hex(buf[11]) << ::std::endl; + ::std::cout << "F: " << hex(buf[12]) << ::std::endl; + ::std::cout << "G: " << hex(buf[13]) << ::std::endl; + ::std::cout << "H: " << hex(buf[14]) << ::std::endl; + ::std::cout << "I: " << hex(buf[15]) << ::std::endl; + ::std::cout << "J: " << hex(buf[16]) << ::std::endl; + ::std::cout << "K: " << hex(buf[17]) << ::std::endl; + ::std::cout << "L: " << hex(buf[18]) << ::std::endl; + ::std::cout << "M: " << hex(buf[19]) << ::std::endl; + ::std::cout << "N: " << hex(buf[20]) << ::std::endl; + ::std::cout << "O: " << hex(buf[21]) << ::std::endl; + ::std::cout << "P: " << hex(buf[22]) << ::std::endl; + ::std::cout << "Q: " << hex(buf[23]) << ::std::endl; + ::std::cout << "R: " << hex(buf[24]) << ::std::endl; + ::std::cout << "S: " << hex(buf[25]) << ::std::endl; + ::std::cout << "T: " << hex(buf[26]) << ::std::endl; + ::std::cout << "U: " << hex(buf[27]) << ::std::endl; + ::std::cout << "V: " << hex(buf[28]) << ::std::endl; + ::std::cout << "W: " << hex(buf[29]) << ::std::endl; + ::std::cout << "X: " << hex(buf[30]) << ::std::endl; + ::std::cout << "Y: " << hex(buf[31]) << ::std::endl; + ::std::cout << "Z: " << hex(buf[32]) << ::std::endl; + ::std::cout << "A1: " << hex(buf[33]) << ::std::endl; + ::std::cout << "A2: " << hex(buf[34]) << ::std::endl; + ::std::cout << "A3: H:" << hex(buf[36]) << " L:" << hex(buf[35]) << ::std::endl; + ::std::cout << "A4: " << Endian::hostWord(buf[38], buf[37]) << ::std::endl; } void SickLms200::dumpStatus() { + using namespace ::rl::util::io; + assert(this->isConnected()); ::std::array< ::std::uint8_t, 812> buf; @@ -207,86 +211,82 @@ namespace rl this->recv(buf.data(), 1 + 1 + 2 + 1 + 152 + 1 + 2, 0xB1); - printf("A: %c %c %c %c %c %c %c\n", buf[5], buf[6], buf[7], buf[8], buf[9], buf[10], buf[11]); - printf("B: %02x\n", buf[12]); - printf("C: %02x\n", buf[13]); - printf("D: reserved\n"); - printf("?: %c %c %c %c %c %c\n", buf[16], buf[17], buf[18], buf[19], buf[20], buf[21]); - printf("E: %02x\n", buf[22]); - printf("F: %i %i %i %i %i %i %i %i\n", - Endian::hostWord(buf[24], buf[23]), - Endian::hostWord(buf[26], buf[25]), - Endian::hostWord(buf[28], buf[27]), - Endian::hostWord(buf[30], buf[29]), - Endian::hostWord(buf[32], buf[31]), - Endian::hostWord(buf[34], buf[33]), - Endian::hostWord(buf[36], buf[35]), - Endian::hostWord(buf[38], buf[37]) - ); - printf("G: %i %i %i %i\n", - Endian::hostWord(buf[40], buf[39]), - Endian::hostWord(buf[42], buf[41]), - Endian::hostWord(buf[44], buf[43]), - Endian::hostWord(buf[46], buf[45]) - ); - printf("H: %i %i %i %i %i %i %i %i\n", - Endian::hostWord(buf[48], buf[47]), - Endian::hostWord(buf[50], buf[49]), - Endian::hostWord(buf[52], buf[51]), - Endian::hostWord(buf[54], buf[53]), - Endian::hostWord(buf[56], buf[55]), - Endian::hostWord(buf[58], buf[57]), - Endian::hostWord(buf[60], buf[59]), - Endian::hostWord(buf[62], buf[61]) - ); - printf("I: %i %i %i %i\n", - Endian::hostWord(buf[64], buf[63]), - Endian::hostWord(buf[66], buf[65]), - Endian::hostWord(buf[68], buf[67]), - Endian::hostWord(buf[70], buf[69]) - ); - printf("J: %i\n", Endian::hostWord(buf[72], buf[71])); - printf("K: reserved\n"); - printf("L: %i\n", Endian::hostWord(buf[76], buf[75])); - printf("M: reserved\n"); - printf("N: %i\n", Endian::hostWord(buf[80], buf[79])); - printf("O: %i\n", Endian::hostWord(buf[82], buf[81])); - printf("P: reserved\n"); - printf("Q: %i\n", Endian::hostWord(buf[86], buf[85])); - printf("R: %i\n", Endian::hostWord(buf[88], buf[87])); - printf("S: %i\n", Endian::hostWord(buf[90], buf[89])); - printf("T: %i\n", Endian::hostWord(buf[92], buf[91])); - printf("U: %i\n", Endian::hostWord(buf[94], buf[93])); - printf("V: %i\n", Endian::hostWord(buf[96], buf[95])); - printf("W: %i\n", Endian::hostWord(buf[98], buf[97])); - printf("X: %i\n", Endian::hostWord(buf[100], buf[99])); - printf("Y: %i\n", Endian::hostWord(buf[102], buf[101])); - printf("Z: %i\n", Endian::hostWord(buf[104], buf[103])); - printf("A1: reserved\n"); - printf("A2: %02x\n", buf[106]); - printf("A3: H:%02x L:%02x\n", buf[108], buf[107]); - printf("A4: H:%02x L:%02x\n", buf[110], buf[109]); - printf("A5: %i\n", Endian::hostWord(buf[112], buf[111])); - printf("A6: %i\n", Endian::hostWord(buf[114], buf[113])); - printf("A7: %02x\n", buf[115]); - printf("A8: %i\n", Endian::hostWord(buf[117], buf[116])); - printf("A9: %c\n", buf[118]); - printf("B1: reserved\n"); - printf("B2: %04x\n", Endian::hostWord(buf[121], buf[120])); - printf("B3: %02x\n", buf[122]); - printf("B4: %02x\n", buf[123]); - printf("B5: %02x\n", buf[124]); - printf("B6: %02x\n", buf[125]); - printf("B7: %02x\n", buf[126]); - printf("B8: %02x\n", buf[127]); - printf("B9: %c %c %c %c %c %c %c\n", buf[128], buf[129], buf[130], buf[131], buf[132], buf[133], buf[134]); - printf("C1: %i\n", Endian::hostDoubleWord(Endian::hostWord(buf[138], buf[137]), Endian::hostWord(buf[136], buf[135]))); - printf("C2: %i\n", Endian::hostDoubleWord(Endian::hostWord(buf[142], buf[141]), Endian::hostWord(buf[140], buf[139]))); - printf("C3: %i\n", Endian::hostDoubleWord(Endian::hostWord(buf[146], buf[145]), Endian::hostWord(buf[144], buf[143]))); - printf("C4: %i\n", Endian::hostDoubleWord(Endian::hostWord(buf[150], buf[149]), Endian::hostWord(buf[148], buf[147]))); - printf("C5: %i\n", Endian::hostWord(buf[152], buf[151])); - printf("C6: %i\n", Endian::hostWord(buf[154], buf[153])); - printf("C7: %i\n", Endian::hostWord(buf[156], buf[155])); + ::std::cout << "A: " << buf[5] << " " << buf[6] << " " << buf[7] << " " << buf[8] << " " << buf[9] << " " << buf[10] << " " << buf[11] << ::std::endl; + ::std::cout << "B: " << hex(buf[12]) << ::std::endl; + ::std::cout << "C: " << hex(buf[13]) << ::std::endl; + ::std::cout << "D: reserved" << ::std::endl; + ::std::cout << "?: " << buf[16] << " " << buf[17] << " " << buf[18] << " " << buf[19] << " " << buf[20] << " " << buf[21] << ::std::endl; + ::std::cout << "E: " << hex(buf[22]) << ::std::endl; + ::std::cout << "F: " << + Endian::hostWord(buf[24], buf[23]) << " " << + Endian::hostWord(buf[26], buf[25]) << " " << + Endian::hostWord(buf[28], buf[27]) << " " << + Endian::hostWord(buf[30], buf[29]) << " " << + Endian::hostWord(buf[32], buf[31]) << " " << + Endian::hostWord(buf[34], buf[33]) << " " << + Endian::hostWord(buf[36], buf[35]) << " " << + Endian::hostWord(buf[38], buf[37]) << ::std::endl; + ::std::cout << "G: " << + Endian::hostWord(buf[40], buf[39]) << " " << + Endian::hostWord(buf[42], buf[41]) << " " << + Endian::hostWord(buf[44], buf[43]) << " " << + Endian::hostWord(buf[46], buf[45]) << ::std::endl; + ::std::cout << "H: " << + Endian::hostWord(buf[48], buf[47]) << " " << + Endian::hostWord(buf[50], buf[49]) << " " << + Endian::hostWord(buf[52], buf[51]) << " " << + Endian::hostWord(buf[54], buf[53]) << " " << + Endian::hostWord(buf[56], buf[55]) << " " << + Endian::hostWord(buf[58], buf[57]) << " " << + Endian::hostWord(buf[60], buf[59]) << " " << + Endian::hostWord(buf[62], buf[61]) << ::std::endl; + ::std::cout << "I: " << + Endian::hostWord(buf[64], buf[63]) << " " << + Endian::hostWord(buf[66], buf[65]) << " " << + Endian::hostWord(buf[68], buf[67]) << " " << + Endian::hostWord(buf[70], buf[69]) << ::std::endl; + ::std::cout << "J: " << Endian::hostWord(buf[72], buf[71]) << ::std::endl; + ::std::cout << "K: reserved" << ::std::endl; + ::std::cout << "L: " << Endian::hostWord(buf[76], buf[75]) << ::std::endl; + ::std::cout << "M: reserved" << ::std::endl; + ::std::cout << "N: " << Endian::hostWord(buf[80], buf[79]) << ::std::endl; + ::std::cout << "O: " << Endian::hostWord(buf[82], buf[81]) << ::std::endl; + ::std::cout << "P: reserved" << ::std::endl; + ::std::cout << "Q: " << Endian::hostWord(buf[86], buf[85]) << ::std::endl; + ::std::cout << "R: " << Endian::hostWord(buf[88], buf[87]) << ::std::endl; + ::std::cout << "S: " << Endian::hostWord(buf[90], buf[89]) << ::std::endl; + ::std::cout << "T: " << Endian::hostWord(buf[92], buf[91]) << ::std::endl; + ::std::cout << "U: " << Endian::hostWord(buf[94], buf[93]) << ::std::endl; + ::std::cout << "V: " << Endian::hostWord(buf[96], buf[95]) << ::std::endl; + ::std::cout << "W: " << Endian::hostWord(buf[98], buf[97]) << ::std::endl; + ::std::cout << "X: " << Endian::hostWord(buf[100], buf[99]) << ::std::endl; + ::std::cout << "Y: " << Endian::hostWord(buf[102], buf[101]) << ::std::endl; + ::std::cout << "Z: " << Endian::hostWord(buf[104], buf[103]) << ::std::endl; + ::std::cout << "A1: reserved" << ::std::endl; + ::std::cout << "A2: " << hex(buf[106]) << ::std::endl; + ::std::cout << "A3: H:" << hex(buf[108]) << " L:" << hex(buf[107]) << ::std::endl; + ::std::cout << "A4: H:" << hex(buf[110]) << " L:" << hex(buf[109]) << ::std::endl; + ::std::cout << "A5: " << Endian::hostWord(buf[112], buf[111]) << ::std::endl; + ::std::cout << "A6: " << Endian::hostWord(buf[114], buf[113]) << ::std::endl; + ::std::cout << "A7: " << hex(buf[115]) << ::std::endl; + ::std::cout << "A8: " << Endian::hostWord(buf[117], buf[116]) << ::std::endl; + ::std::cout << "A9: " << buf[118] << ::std::endl; + ::std::cout << "B1: reserved" << ::std::endl; + ::std::cout << "B2: " << hex(Endian::hostWord(buf[121], buf[120])) << ::std::endl; + ::std::cout << "B3: " << hex(buf[122]) << ::std::endl; + ::std::cout << "B4: " << hex(buf[123]) << ::std::endl; + ::std::cout << "B5: " << hex(buf[124]) << ::std::endl; + ::std::cout << "B6: " << hex(buf[125]) << ::std::endl; + ::std::cout << "B7: " << hex(buf[126]) << ::std::endl; + ::std::cout << "B8: " << hex(buf[127]) << ::std::endl; + ::std::cout << "B9: " << " " << buf[128] << " " << buf[129] << " " << buf[130] << " " << buf[131] << " " << buf[132] << " " << buf[133] << " " << buf[134] << ::std::endl; + ::std::cout << "C1: " << Endian::hostDoubleWord(Endian::hostWord(buf[138], buf[137]), Endian::hostWord(buf[136], buf[135])) << ::std::endl; + ::std::cout << "C2: " << Endian::hostDoubleWord(Endian::hostWord(buf[142], buf[141]), Endian::hostWord(buf[140], buf[139])) << ::std::endl; + ::std::cout << "C3: " << Endian::hostDoubleWord(Endian::hostWord(buf[146], buf[145]), Endian::hostWord(buf[144], buf[143])) << ::std::endl; + ::std::cout << "C4: " << Endian::hostDoubleWord(Endian::hostWord(buf[150], buf[149]), Endian::hostWord(buf[148], buf[147])) << ::std::endl; + ::std::cout << "C5: " << Endian::hostWord(buf[152], buf[151]) << ::std::endl; + ::std::cout << "C6: " << Endian::hostWord(buf[154], buf[153]) << ::std::endl; + ::std::cout << "C7: " << Endian::hostWord(buf[156], buf[155]) << ::std::endl; } SickLms200::BaudRate diff --git a/src/rl/hal/SickS300.cpp b/src/rl/hal/SickS300.cpp index 995675d5..900ca267 100644 --- a/src/rl/hal/SickS300.cpp +++ b/src/rl/hal/SickS300.cpp @@ -25,9 +25,9 @@ // #include -#include #include #include +#include #include "DeviceException.h" #include "Endian.h" @@ -225,6 +225,8 @@ ::std::cerr << "Glare (dazzling) detected" << ::std::endl; ::std::size_t SickS300::recv(::std::uint8_t* buf) { + using namespace ::rl::util::io; + ::std::uint8_t* ptr; ::std::size_t sumbytes; ::std::size_t numbytes; @@ -239,7 +241,7 @@ ::std::cerr << "Glare (dazzling) detected" << ::std::endl; do { numbytes = serial.read(ptr, 1); -printf("buf[0] %02x\n", buf[0]); +::std::cout << "buf[0] " << hex(buf[0]) << ::std::endl; } while (0x00 != buf[0]); // 0x00 @@ -247,7 +249,7 @@ printf("buf[0] %02x\n", buf[0]); sumbytes += numbytes; numbytes = serial.read(ptr, 1); -printf("buf[1] %02x\n", buf[1]); +::std::cout << "buf[1] " << hex(buf[1]) << ::std::endl; } while (0x00 != buf[1]); // 0x00 0x00 @@ -255,7 +257,7 @@ printf("buf[1] %02x\n", buf[1]); sumbytes += numbytes; numbytes = serial.read(ptr, 1); -printf("buf[2] %02x\n", buf[2]); +::std::cout << "buf[2] " << hex(buf[2]) << ::std::endl; } while (0x00 != buf[2]); // 0x00 0x00 0x00 @@ -263,7 +265,7 @@ printf("buf[2] %02x\n", buf[2]); sumbytes += numbytes; numbytes = serial.read(ptr, 1); -printf("buf[3] %02x\n", buf[3]); +::std::cout << "buf[3] " << hex(buf[3]) << ::std::endl; ptr += numbytes; sumbytes += numbytes; @@ -316,7 +318,7 @@ printf("buf[3] %02x\n", buf[3]); for (::std::size_t i = 0; i < 6; ++i) { numbytes = serial.read(ptr, 1); -printf("buf[%zi] %02x\n", i + 4, buf[i + 4]); +::std::cout << "buf[" << i + 4 << "] " << hex(buf[i + 4]) << ::std::endl; ptr += numbytes; sumbytes += numbytes; } @@ -328,8 +330,8 @@ std::cout << "length " << length << std::endl; { throw DeviceException("Data length mismatch"); } -printf("coordinationFlag %02x\n", buf[8]); -printf("deviceAddress %02x\n", buf[9]); +::std::cout << "coordinationFlag " << hex(buf[8]) << ::std::endl; +::std::cout << "deviceAddress " << hex(buf[9]) << ::std::endl; for (::std::size_t i = 0; i < 1094; ++i) { @@ -337,7 +339,7 @@ printf("deviceAddress %02x\n", buf[9]); ptr += numbytes; sumbytes += numbytes; } -printf("version %02x%02x\n", buf[11], buf[10]); +::std::cout << "version " << hex(buf[11]) << hex(buf[10]) << ::std::endl; if (0x01 != buf[11] || 0x02 != buf[10]) { @@ -353,10 +355,10 @@ printf("version %02x%02x\n", buf[11], buf[10]); Endian::hostWord(buf[17], buf[16]), Endian::hostWord(buf[15], buf[14]) ); -std::cout << "scanNumber " << scanNumber << std::endl; +::std::cout << "scanNumber " << scanNumber << std::endl; ::std::uint16_t telegramNumber = Endian::hostWord(buf[19], buf[18]); -std::cout << "telegramNumber " << telegramNumber << std::endl; +::std::cout << "telegramNumber " << telegramNumber << std::endl; for (::std::size_t i = 0; i < 2; ++i) { @@ -376,7 +378,7 @@ std::cout << "telegramNumber " << telegramNumber << std::endl; { throw DeviceException("Checksum error"); } -for (::std::size_t i = 0; i < sumbytes; ++i) { printf("%02x ", buf[i]); } printf("\n"); +for (::std::size_t i = 0; i < sumbytes; ++i) { ::std::cout << hex(buf[i]) << " "; } ::std::cout << ::std::endl; return sumbytes; } diff --git a/src/rl/hal/WeissWsg50.cpp b/src/rl/hal/WeissWsg50.cpp index ec752fe2..1e7fbabf 100644 --- a/src/rl/hal/WeissWsg50.cpp +++ b/src/rl/hal/WeissWsg50.cpp @@ -33,7 +33,7 @@ //#define DEBUG_TCP_DATA #ifdef DEBUG_TCP_DATA -#include +#include #endif #include "Endian.h" @@ -675,6 +675,10 @@ namespace rl ::std::size_t WeissWsg50::recv(::std::uint8_t* buf) { +#ifdef DEBUG_TCP_DATA + using namespace ::rl::util::io; +#endif + assert(this->isConnected()); ::std::uint8_t* ptr; @@ -723,12 +727,11 @@ namespace rl } #ifdef DEBUG_TCP_DATA - printf("Debug: recv header buf:"); + ::std::cout << "Debug: recv header buf:"; for (::std::size_t i = 0; i < sumbytes; ++i) { - printf(" %02X", buf[i]); + ::std::cout << " " << hex(buf[i]); } - fflush(stdout); #endif ::std::uint16_t length = Endian::hostWord(buf[5], buf[4]); @@ -762,10 +765,9 @@ namespace rl #ifdef DEBUG_TCP_DATA for (::std::size_t i = 8; i < sumbytes; ++i) { - printf(" %02X", buf[i]); + ::std::cout << " " << hex(buf[i]); } - printf("\n"); - fflush(stdout); + ::std::cout << ::std::endl;; #endif if (this->crc(buf, sumbytes - 2) != Endian::hostWord(buf[sumbytes - 1], buf[sumbytes - 2])) @@ -833,6 +835,10 @@ namespace rl void WeissWsg50::send(::std::uint8_t* buf, const ::std::size_t& len) { +#ifdef DEBUG_TCP_DATA + using namespace ::rl::util::io; +#endif + assert(this->isConnected()); assert(len > 6); @@ -856,13 +862,12 @@ namespace rl } #ifdef DEBUG_TCP_DATA - printf("Debug: send buf:"); + ::std::cout << "Debug: send buf:"; for (::std::size_t i = 0; i < len; ++i) { - printf(" %02X", buf[i]); + ::std::cout << " " << hex(buf[i]); } - printf("\n"); - fflush(stdout); + ::std::cout << ::std::endl;; #endif } From 0094a4f91d44a8c35142ae35353e81816db5bb7a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 22 Apr 2019 18:52:28 +0200 Subject: [PATCH 234/546] Skip normalize for prismatic joints --- src/rl/kin/Joint.cpp | 5 +++++ src/rl/kin/Joint.h | 2 ++ src/rl/kin/Kinematics.cpp | 11 +---------- src/rl/kin/Revolute.cpp | 15 +++++++++++++++ src/rl/kin/Revolute.h | 2 ++ 5 files changed, 25 insertions(+), 10 deletions(-) diff --git a/src/rl/kin/Joint.cpp b/src/rl/kin/Joint.cpp index fa0a098d..838fc721 100644 --- a/src/rl/kin/Joint.cpp +++ b/src/rl/kin/Joint.cpp @@ -56,6 +56,11 @@ namespace rl return this->q; } + void + Joint::normalize(::rl::math::Real& q) + { + } + void Joint::setPosition(const ::rl::math::Real& q) { diff --git a/src/rl/kin/Joint.h b/src/rl/kin/Joint.h index d48e5691..1d23af1e 100644 --- a/src/rl/kin/Joint.h +++ b/src/rl/kin/Joint.h @@ -51,6 +51,8 @@ namespace rl virtual void jacobian(const ::rl::math::Transform& tcp, ::rl::math::MatrixBlock& j) = 0; + virtual void normalize(::rl::math::Real& q); + virtual void setPosition(const ::rl::math::Real& q); ::rl::math::Real a; diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 0a7e2450..e9007d7a 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -863,16 +863,7 @@ namespace rl { for (::std::size_t i = 0; i < this->getDof(); ++i) { - q(i) = ::std::fmod(q(i), 2 * static_cast< ::rl::math::Real>(M_PI)); - - if (q(i) < this->joints[i]->min) - { - q(i) += 2 * static_cast< ::rl::math::Real>(M_PI); - } - else if (q(i) > this->joints[i]->max) - { - q(i) -= 2 * static_cast< ::rl::math::Real>(M_PI); - } + this->joints[i]->normalize(q(i)); } } diff --git a/src/rl/kin/Revolute.cpp b/src/rl/kin/Revolute.cpp index f8b29dab..f4c42b3c 100644 --- a/src/rl/kin/Revolute.cpp +++ b/src/rl/kin/Revolute.cpp @@ -76,6 +76,21 @@ namespace rl j(5, 0) = z(2); } + void + Revolute::normalize(::rl::math::Real& q) + { + q = ::std::fmod(q, 2 * static_cast< ::rl::math::Real>(M_PI)); + + if (q < this->min) + { + q += 2 * static_cast< ::rl::math::Real>(M_PI); + } + else if (q > this->max) + { + q -= 2 * static_cast< ::rl::math::Real>(M_PI); + } + } + void Revolute::setPosition(const ::rl::math::Real& q) { diff --git a/src/rl/kin/Revolute.h b/src/rl/kin/Revolute.h index 84a66048..961fa184 100644 --- a/src/rl/kin/Revolute.h +++ b/src/rl/kin/Revolute.h @@ -49,6 +49,8 @@ namespace rl */ void jacobian(const ::rl::math::Transform& tcp, ::rl::math::MatrixBlock& j); + void normalize(::rl::math::Real& q); + void setPosition(const ::rl::math::Real& q); protected: From f37594b3cb941920a2f2185092303c6a47825799 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 22 Apr 2019 18:52:59 +0200 Subject: [PATCH 235/546] Use std::remainder over std::fmod --- src/rl/kin/Revolute.cpp | 2 +- src/rl/mdl/Revolute.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/kin/Revolute.cpp b/src/rl/kin/Revolute.cpp index f4c42b3c..a15bf1e9 100644 --- a/src/rl/kin/Revolute.cpp +++ b/src/rl/kin/Revolute.cpp @@ -79,7 +79,7 @@ namespace rl void Revolute::normalize(::rl::math::Real& q) { - q = ::std::fmod(q, 2 * static_cast< ::rl::math::Real>(M_PI)); + q = ::std::remainder(q, 2 * static_cast< ::rl::math::Real>(M_PI)); if (q < this->min) { diff --git a/src/rl/mdl/Revolute.cpp b/src/rl/mdl/Revolute.cpp index 702defee..37adead4 100644 --- a/src/rl/mdl/Revolute.cpp +++ b/src/rl/mdl/Revolute.cpp @@ -106,7 +106,7 @@ namespace rl void Revolute::normalize(::rl::math::VectorRef q) const { - q(0) = ::std::fmod(q(0), 2 * static_cast< ::rl::math::Real>(M_PI)); + q(0) = ::std::remainder(q(0), 2 * static_cast< ::rl::math::Real>(M_PI)); if (q(0) < this->min(0)) { From d65931b54d5965d8e71a1ecdc194b46a745b2303 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 23 Apr 2019 17:29:02 +0200 Subject: [PATCH 236/546] Update formatting --- demos/rlPumaDemo/rlPumaDemo.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/demos/rlPumaDemo/rlPumaDemo.cpp b/demos/rlPumaDemo/rlPumaDemo.cpp index ecca7c58..71629ad1 100644 --- a/demos/rlPumaDemo/rlPumaDemo.cpp +++ b/demos/rlPumaDemo/rlPumaDemo.cpp @@ -75,16 +75,15 @@ main(int argc, char** argv) << ", Wrist: " << (wrist == rl::kin::Puma::WRIST_FLIP ? "FLIP" : "NONFLIP") << std::endl; - std::cout << "q=" << std::endl << q.transpose() * rl::math::RAD2DEG << std::endl; + std::cout << "q: " << q.transpose() * rl::math::RAD2DEG << std::endl; puma->setPosition(q); puma->updateFrames(); - const rl::math::Transform::ConstTranslationPart& position = puma->forwardPosition().translation(); - + rl::math::Vector3 position = puma->forwardPosition().translation(); rl::math::Vector3 orientation = puma->forwardPosition().rotation().eulerAngles(2, 1, 0).reverse(); - std::cout << "x=" << std::endl << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::RAD2DEG << " deg, b: " << orientation.y() * rl::math::RAD2DEG << " deg, c: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; + std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::RAD2DEG << " deg, b: " << orientation.y() * rl::math::RAD2DEG << " deg, c: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; rl::math::Vector q2(puma->getDof()); q2.setConstant(1.0 * rl::math::DEG2RAD); @@ -97,14 +96,15 @@ main(int argc, char** argv) return EXIT_FAILURE; } - std::cout << "q=" << std::endl << q2.transpose() * rl::math::RAD2DEG << std::endl; + std::cout << "q: " << q2.transpose() * rl::math::RAD2DEG << std::endl; puma->setPosition(q2); puma->updateFrames(); + position = puma->forwardPosition().translation(); orientation = puma->forwardPosition().rotation().eulerAngles(2, 1, 0).reverse(); - std::cout << "x=" << std::endl << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::RAD2DEG << " deg, b: " << orientation.y() * rl::math::RAD2DEG << " deg, c: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; + std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::RAD2DEG << " deg, b: " << orientation.y() * rl::math::RAD2DEG << " deg, c: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; } else { From c660d46214f8a8587f435a7c0c1735f87d68ba62 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 23 Apr 2019 17:51:25 +0200 Subject: [PATCH 237/546] Use nlopt_set_xtol_abs1 --- src/rl/mdl/NloptInverseKinematics.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 0f23c015..20e26d90 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -180,9 +180,7 @@ namespace rl ::nlopt_destroy ); - ::std::vector tolerance(this->kinematic->getDofPosition(), this->tolerance); - - if (::nlopt_set_xtol_abs(opt.get(), tolerance.data()) < 0) + if (::nlopt_set_xtol_abs1(opt.get(), this->tolerance) < 0) { return false; } From d934098ad02a49e2959ff7fd10b51cefbda27a7b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 26 Apr 2019 22:57:21 +0200 Subject: [PATCH 238/546] Update Boost_ADDITIONAL_VERSIONS to support 1.70 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4cb98d6c..9cf44e01 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,7 +16,7 @@ include(GenerateExportHeader) include(GNUInstallDirs) include(Qt4AutomocMocOptionsBoost) -set(Boost_ADDITIONAL_VERSIONS "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") +set(Boost_ADDITIONAL_VERSIONS "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) From 54c4320bb3e81b1b55d3a8e0a2497073043c9e02 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 26 Apr 2019 22:57:42 +0200 Subject: [PATCH 239/546] Update Boost to 1.70.0 --- 3rdparty/boost/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/boost/CMakeLists.txt b/3rdparty/boost/CMakeLists.txt index 0859acc1..2dacce9a 100644 --- a/3rdparty/boost/CMakeLists.txt +++ b/3rdparty/boost/CMakeLists.txt @@ -7,9 +7,9 @@ include(GNUInstallDirs) ExternalProject_Add( boost - URL https://dl.bintray.com/boostorg/release/1.69.0/source/boost_1_69_0.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_69_0.tar.bz2 - URL_MD5 a1332494397bf48332cb152abfefcec2 + URL https://dl.bintray.com/boostorg/release/1.70.0/source/boost_1_70_0.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_70_0.tar.bz2 + URL_MD5 242ecc63507711d6706b9b0c0d0c7d4f CONFIGURE_COMMAND "" BUILD_COMMAND "" BUILD_IN_SOURCE 1 From 8d0a724ecabc6523cbc74de08d851fdf943cfac8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Apr 2019 16:11:04 +0200 Subject: [PATCH 240/546] Update IK selection GUI elements --- demos/rlCoachMdl/MainWindow.cpp | 38 +++------------------------ demos/rlCoachMdl/MainWindow.h | 4 --- demos/rlCoachMdl/OperationalModel.cpp | 6 ++++- 3 files changed, 8 insertions(+), 40 deletions(-) diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index f0cec44b..363fcb82 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -51,7 +51,6 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : ikAlgorithmComboBox(new QComboBox(this)), ikDurationSpinBox(new QSpinBox(this)), ikJacobianComboBox(new QComboBox(this)), - ikJacobianInverseComboBox(new QComboBox(this)), kinematicModels(), operationalModels(), scene(), @@ -207,23 +206,19 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->ikDurationSpinBox->setToolTip("Max. IK Duration"); this->ikDurationSpinBox->setValue(500); - this->ikJacobianComboBox->addItem("Inverse"); + this->ikJacobianComboBox->addItem("DLS"); + this->ikJacobianComboBox->addItem("SVD"); this->ikJacobianComboBox->addItem("Transpose"); this->ikJacobianComboBox->setToolTip("Jacobian Method"); + this->ikJacobianComboBox->setCurrentIndex(this->ikJacobianComboBox->findText("SVD")); QObject::connect(this->ikJacobianComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(changeIkJacobian())); - this->ikJacobianInverseComboBox->addItem("SVD"); - this->ikJacobianInverseComboBox->addItem("DLS"); - this->ikJacobianInverseComboBox->setToolTip("Jacobian Inverse Method"); - this->statusBar()->addPermanentWidget(this->ikAlgorithmComboBox); this->statusBar()->addPermanentWidget(this->ikJacobianComboBox); - this->statusBar()->addPermanentWidget(this->ikJacobianInverseComboBox); this->statusBar()->addPermanentWidget(this->ikDurationSpinBox); this->changeIkAlgorithm(); - this->changeIkJacobian(); this->gradientBackground = new SoGradientBackground(); this->gradientBackground->ref(); @@ -258,42 +253,15 @@ MainWindow::changeIkAlgorithm() if ("JacobianInverseKinematics" == this->ikAlgorithmComboBox->currentText()) { this->ikDurationSpinBox->setVisible(true); - - if ("Inverse" != this->ikJacobianComboBox->currentText()) - { - this->ikJacobianInverseComboBox->setVisible(false); - } - else - { - this->ikJacobianInverseComboBox->setVisible(true); - } - this->ikJacobianComboBox->setVisible(true); } else if ("NloptInverseKinematics" == this->ikAlgorithmComboBox->currentText()) { this->ikDurationSpinBox->setVisible(true); - this->ikJacobianInverseComboBox->setVisible(false); this->ikJacobianComboBox->setVisible(false); } } -void -MainWindow::changeIkJacobian() -{ - if ("JacobianInverseKinematics" == this->ikAlgorithmComboBox->currentText()) - { - if ("Inverse" != this->ikJacobianComboBox->currentText()) - { - this->ikJacobianInverseComboBox->setVisible(false); - } - else - { - this->ikJacobianInverseComboBox->setVisible(true); - } - } -} - MainWindow* MainWindow::instance() { diff --git a/demos/rlCoachMdl/MainWindow.h b/demos/rlCoachMdl/MainWindow.h index 99f212a2..3f907fcf 100644 --- a/demos/rlCoachMdl/MainWindow.h +++ b/demos/rlCoachMdl/MainWindow.h @@ -67,8 +67,6 @@ class MainWindow : public QMainWindow QComboBox* ikJacobianComboBox; - QComboBox* ikJacobianInverseComboBox; - std::vector> kinematicModels; std::vector operationalModels; @@ -78,8 +76,6 @@ class MainWindow : public QMainWindow public slots: void changeIkAlgorithm(); - void changeIkJacobian(); - void saveImageWithAlpha(); void saveImageWithoutAlpha(); diff --git a/demos/rlCoachMdl/OperationalModel.cpp b/demos/rlCoachMdl/OperationalModel.cpp index d57869fb..558ed1b7 100644 --- a/demos/rlCoachMdl/OperationalModel.cpp +++ b/demos/rlCoachMdl/OperationalModel.cpp @@ -248,7 +248,11 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r rl::mdl::JacobianInverseKinematics* jacobianIk = static_cast(ik.get()); jacobianIk->setDuration(std::chrono::milliseconds(MainWindow::instance()->ikDurationSpinBox->cleanText().toUInt())); - if ("SVD" == MainWindow::instance()->ikJacobianInverseComboBox->currentText()) + if ("DLS" == MainWindow::instance()->ikJacobianComboBox->currentText()) + { + jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_DLS); + } + else if ("SVD" == MainWindow::instance()->ikJacobianComboBox->currentText()) { jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_SVD); } From c3ab8db548898cbb0d7401ffd67bb505c095c989 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Apr 2019 16:19:53 +0200 Subject: [PATCH 241/546] Refactor rl::mdl::IterativeInverseKinematics --- demos/rlCoachMdl/MainWindow.cpp | 9 + demos/rlCoachMdl/MainWindow.h | 2 + demos/rlCoachMdl/OperationalModel.cpp | 2 + src/rl/mdl/IterativeInverseKinematics.cpp | 28 ++- src/rl/mdl/IterativeInverseKinematics.h | 13 +- src/rl/mdl/JacobianInverseKinematics.cpp | 66 +++--- src/rl/mdl/JacobianInverseKinematics.h | 14 +- src/rl/mdl/NloptInverseKinematics.cpp | 211 ++++++++++++------ src/rl/mdl/NloptInverseKinematics.h | 57 ++++- .../rlInverseKinematicsMdlTest.cpp | 12 +- 10 files changed, 275 insertions(+), 139 deletions(-) diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index 363fcb82..4ec2bd97 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -50,6 +50,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : geometryModels(), ikAlgorithmComboBox(new QComboBox(this)), ikDurationSpinBox(new QSpinBox(this)), + ikIterationsSpinBox(new QSpinBox(this)), ikJacobianComboBox(new QComboBox(this)), kinematicModels(), operationalModels(), @@ -206,6 +207,11 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->ikDurationSpinBox->setToolTip("Max. IK Duration"); this->ikDurationSpinBox->setValue(500); + this->ikIterationsSpinBox->setMaximum(100000); + this->ikIterationsSpinBox->setMinimum(1); + this->ikIterationsSpinBox->setToolTip("Max. IK Iterations"); + this->ikIterationsSpinBox->setValue(10000); + this->ikJacobianComboBox->addItem("DLS"); this->ikJacobianComboBox->addItem("SVD"); this->ikJacobianComboBox->addItem("Transpose"); @@ -216,6 +222,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->statusBar()->addPermanentWidget(this->ikAlgorithmComboBox); this->statusBar()->addPermanentWidget(this->ikJacobianComboBox); + this->statusBar()->addPermanentWidget(this->ikIterationsSpinBox); this->statusBar()->addPermanentWidget(this->ikDurationSpinBox); this->changeIkAlgorithm(); @@ -253,11 +260,13 @@ MainWindow::changeIkAlgorithm() if ("JacobianInverseKinematics" == this->ikAlgorithmComboBox->currentText()) { this->ikDurationSpinBox->setVisible(true); + this->ikIterationsSpinBox->setVisible(true); this->ikJacobianComboBox->setVisible(true); } else if ("NloptInverseKinematics" == this->ikAlgorithmComboBox->currentText()) { this->ikDurationSpinBox->setVisible(true); + this->ikIterationsSpinBox->setVisible(true); this->ikJacobianComboBox->setVisible(false); } } diff --git a/demos/rlCoachMdl/MainWindow.h b/demos/rlCoachMdl/MainWindow.h index 3f907fcf..d0982046 100644 --- a/demos/rlCoachMdl/MainWindow.h +++ b/demos/rlCoachMdl/MainWindow.h @@ -65,6 +65,8 @@ class MainWindow : public QMainWindow QSpinBox* ikDurationSpinBox; + QSpinBox* ikIterationsSpinBox; + QComboBox* ikJacobianComboBox; std::vector> kinematicModels; diff --git a/demos/rlCoachMdl/OperationalModel.cpp b/demos/rlCoachMdl/OperationalModel.cpp index 558ed1b7..a829e81a 100644 --- a/demos/rlCoachMdl/OperationalModel.cpp +++ b/demos/rlCoachMdl/OperationalModel.cpp @@ -247,6 +247,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r ik = std::make_shared(kinematic); rl::mdl::JacobianInverseKinematics* jacobianIk = static_cast(ik.get()); jacobianIk->setDuration(std::chrono::milliseconds(MainWindow::instance()->ikDurationSpinBox->cleanText().toUInt())); + jacobianIk->setIterations(MainWindow::instance()->ikIterationsSpinBox->cleanText().toUInt()); if ("DLS" == MainWindow::instance()->ikJacobianComboBox->currentText()) { @@ -267,6 +268,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r ik = std::make_shared(kinematic); rl::mdl::NloptInverseKinematics* nloptIk = static_cast(ik.get()); nloptIk->setDuration(std::chrono::milliseconds(MainWindow::instance()->ikDurationSpinBox->cleanText().toUInt())); + nloptIk->setIterations(MainWindow::instance()->ikIterationsSpinBox->cleanText().toUInt()); } #endif diff --git a/src/rl/mdl/IterativeInverseKinematics.cpp b/src/rl/mdl/IterativeInverseKinematics.cpp index 5b663e6d..29cc2da6 100644 --- a/src/rl/mdl/IterativeInverseKinematics.cpp +++ b/src/rl/mdl/IterativeInverseKinematics.cpp @@ -32,7 +32,9 @@ namespace rl { IterativeInverseKinematics::IterativeInverseKinematics(Kinematic* kinematic) : InverseKinematics(kinematic), - duration(::std::chrono::milliseconds(100)) + duration(::std::chrono::milliseconds(1000)), + epsilon(static_cast< ::rl::math::Real>(1.0e-6)), + iterations(10000) { } @@ -46,10 +48,34 @@ namespace rl return this->duration; } + const ::rl::math::Real& + IterativeInverseKinematics::getEpsilon() const + { + return this->epsilon; + } + + const ::std::size_t& + IterativeInverseKinematics::getIterations() const + { + return this->iterations; + } + void IterativeInverseKinematics::setDuration(const ::std::chrono::nanoseconds& duration) { this->duration = duration; } + + void + IterativeInverseKinematics::setEpsilon(const::rl::math::Real& epsilon) + { + this->epsilon = epsilon; + } + + void + IterativeInverseKinematics::setIterations(const ::std::size_t& iterations) + { + this->iterations = iterations; + } } } diff --git a/src/rl/mdl/IterativeInverseKinematics.h b/src/rl/mdl/IterativeInverseKinematics.h index b1147cb3..aa1e8e2f 100644 --- a/src/rl/mdl/IterativeInverseKinematics.h +++ b/src/rl/mdl/IterativeInverseKinematics.h @@ -44,13 +44,24 @@ namespace rl const ::std::chrono::nanoseconds& getDuration() const; + const ::rl::math::Real& getEpsilon() const; + + const ::std::size_t& getIterations() const; + void setDuration(const ::std::chrono::nanoseconds& duration); + virtual void setEpsilon(const::rl::math::Real& epsilon); + + void setIterations(const ::std::size_t& iterations); + protected: - ::std::chrono::nanoseconds duration; private: + ::std::chrono::nanoseconds duration; + + ::rl::math::Real epsilon; + ::std::size_t iterations; }; } } diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index a8b632d2..142c37db 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -34,8 +34,6 @@ namespace rl JacobianInverseKinematics::JacobianInverseKinematics(Kinematic* kinematic) : IterativeInverseKinematics(kinematic), delta(::std::numeric_limits< ::rl::math::Real>::infinity()), - epsilon(static_cast< ::rl::math::Real>(1.0e-3)), - iterations(1000), method(METHOD_SVD), randDistribution(0, 1), randEngine(::std::random_device()()) @@ -52,18 +50,6 @@ namespace rl return this->delta; } - const ::rl::math::Real& - JacobianInverseKinematics::getEpsilon() const - { - return this->epsilon; - } - - const ::std::size_t& - JacobianInverseKinematics::getIterations() const - { - return this->iterations; - } - const JacobianInverseKinematics::Method& JacobianInverseKinematics::getMethod() const { @@ -71,21 +57,15 @@ namespace rl } void - JacobianInverseKinematics::setDelta(const::rl::math::Real& delta) + JacobianInverseKinematics::seed(const ::std::mt19937::result_type& value) { - this->delta = delta; - } - - void - JacobianInverseKinematics::setEpsilon(const::rl::math::Real& epsilon) - { - this->epsilon = epsilon; + this->randEngine.seed(value); } void - JacobianInverseKinematics::setIterations(const ::std::size_t& iterations) + JacobianInverseKinematics::setDelta(const::rl::math::Real& delta) { - this->iterations = iterations; + this->delta = delta; } void @@ -98,7 +78,8 @@ namespace rl JacobianInverseKinematics::solve() { ::std::chrono::steady_clock::time_point start = ::std::chrono::steady_clock::now(); - double remaining = ::std::chrono::duration(this->duration).count(); + double remaining = ::std::chrono::duration(this->getDuration()).count(); + ::std::size_t iteration = 0; ::rl::math::Vector q = this->kinematic->getPosition(); ::rl::math::Vector q2(this->kinematic->getDofPosition()); @@ -109,9 +90,7 @@ namespace rl do { - ::rl::math::Real delta = 1; - - for (::std::size_t i = 0; i < this->iterations && delta > this->epsilon; ++i) + do { this->kinematic->forwardPosition(); dx.setZero(); @@ -122,6 +101,17 @@ namespace rl dxi = this->kinematic->getOperationalPosition(this->goals[i].second).toDelta(this->goals[i].first); } + if (dx.squaredNorm() < ::std::pow(this->getEpsilon(), 2)) + { + this->kinematic->normalize(q); + this->kinematic->setPosition(q); + + if (this->kinematic->isValid(q)) + { + return true; + } + } + this->kinematic->calculateJacobian(); switch (this->method) @@ -146,27 +136,23 @@ namespace rl } this->kinematic->step(q, dq, q2); - delta = this->kinematic->distance(q, q2); - if (delta > this->delta) + if (this->kinematic->transformedDistance(q, q2) > ::std::pow(this->delta, 2)) { this->kinematic->interpolate(q, q2, this->delta, q2); } q = q2; this->kinematic->setPosition(q); - } - - if (dx.squaredNorm() < this->epsilon) - { - this->kinematic->normalize(q); - this->kinematic->setPosition(q); - if (this->kinematic->isValid(q)) + remaining = ::std::chrono::duration(this->getDuration() - (::std::chrono::steady_clock::now() - start)).count(); + + if (0 == ++iteration % 100) { - return true; + break; } } + while (remaining > 0 && iteration < this->getIterations()); for (::std::size_t i = 0; i < this->kinematic->getDof(); ++i) { @@ -176,9 +162,9 @@ namespace rl q = this->kinematic->generatePositionUniform(rand); this->kinematic->setPosition(q); - remaining = ::std::chrono::duration(this->duration - (::std::chrono::steady_clock::now() - start)).count(); + remaining = ::std::chrono::duration(this->getDuration() - (::std::chrono::steady_clock::now() - start)).count(); } - while (remaining > 0); + while (remaining > 0 && iteration < this->getIterations()); return false; } diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index 24dc794a..7bbb5aed 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -61,17 +61,11 @@ namespace rl const ::rl::math::Real& getDelta() const; - const ::rl::math::Real& getEpsilon() const; - - const ::std::size_t& getIterations() const; - const Method& getMethod() const; - void setDelta(const::rl::math::Real& delta); - - void setEpsilon(const::rl::math::Real& epsilon); + void seed(const ::std::mt19937::result_type& value); - void setIterations(const ::std::size_t& iterations); + void setDelta(const::rl::math::Real& delta); void setMethod(const Method& method); @@ -82,10 +76,6 @@ namespace rl private: ::rl::math::Real delta; - ::rl::math::Real epsilon; - - ::std::size_t iterations; - Method method; ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 20e26d90..e217b557 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -24,8 +24,6 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include - #include "Kinematic.h" #include "NloptInverseKinematics.h" @@ -36,14 +34,20 @@ namespace rl NloptInverseKinematics::NloptInverseKinematics(Kinematic* kinematic) : IterativeInverseKinematics(kinematic), delta(static_cast< ::rl::math::Real>(1.0e-8)), - epsilonRotation(static_cast< ::rl::math::Real>(1.0e-6)), - epsilonTranslation(static_cast< ::rl::math::Real>(1.0e-6)), + lb(this->kinematic->getMinimum()), + opt(::nlopt_create(::NLOPT_LD_SLSQP, kinematic->getDofPosition()), ::nlopt_destroy), randDistribution(0, 1), randEngine(::std::random_device()()), - tolerance(static_cast< ::rl::math::Real>(1.0e-8)) + ub(this->kinematic->getMaximum()) { - this->lb = this->kinematic->getMinimum(); - this->ub = this->kinematic->getMaximum(); + Exception::check(::nlopt_set_ftol_abs(opt.get(), ::std::numeric_limits::epsilon())); + Exception::check(::nlopt_set_ftol_rel(opt.get(), ::std::numeric_limits::epsilon())); + Exception::check(::nlopt_set_lower_bounds(opt.get(), this->lb.data())); + Exception::check(::nlopt_set_min_objective(opt.get(), &NloptInverseKinematics::f, this)); + Exception::check(::nlopt_set_stopval(opt.get(), ::std::pow(this->getEpsilon(), 2))); + Exception::check(::nlopt_set_upper_bounds(opt.get(), this->ub.data())); + Exception::check(::nlopt_set_xtol_abs1(opt.get(), ::std::numeric_limits::epsilon())); + Exception::check(::nlopt_set_xtol_rel(opt.get(), ::std::numeric_limits::epsilon())); } NloptInverseKinematics::~NloptInverseKinematics() @@ -62,39 +66,31 @@ namespace rl { ::rl::math::VectorBlock dxi = dx.segment(6 * this->goals[i].second, 6); dxi = this->kinematic->getOperationalPosition(this->goals[i].second).toDelta(this->goals[i].first); - - if (dxi.segment(0, 3).cwiseAbs().maxCoeff() < this->epsilonTranslation) - { - dxi.segment(0, 3).setZero(); - } - - if (dxi.segment(3, 3).cwiseAbs().maxCoeff() < this->epsilonRotation) - { - dxi.segment(3, 3).setZero(); - } } return dx.squaredNorm(); } - ::rl::math::Real + double NloptInverseKinematics::f(unsigned n, const double* x, double* grad, void* data) { NloptInverseKinematics* ik = static_cast(data); - ::Eigen::Map< const ::rl::math::Vector> q(x, n, 1); + ++ik->iteration; + + ::Eigen::Map< const ::Eigen::VectorXd> q(x, n, 1); if (!q.allFinite()) { - return ::std::numeric_limits< ::rl::math::Real>::infinity(); + return ::std::numeric_limits::infinity(); } ::rl::math::Real result = ik->error(q); - ::rl::math::Vector q2(q); - if (nullptr != grad) { + ::Eigen::VectorXd q2(q); + for (::std::ptrdiff_t i = 0; i < q.size(); ++i) { q2(i) = q(i) + ik->delta; @@ -112,27 +108,53 @@ namespace rl } const ::rl::math::Real& - NloptInverseKinematics::getEpsilonRotation() const + NloptInverseKinematics::getDelta() const { - return this->epsilonRotation; + return this->delta; } - const ::rl::math::Real& - NloptInverseKinematics::getEpsilonTranslation() const + ::rl::math::Real + NloptInverseKinematics::getFunctionToleranceAbsolute() const { - return this->epsilonTranslation; + return ::nlopt_get_ftol_abs(this->opt.get()); } - const ::rl::math::Real& - NloptInverseKinematics::getDelta() const + ::rl::math::Real + NloptInverseKinematics::getFunctionToleranceRelative() const { - return this->delta; + return ::nlopt_get_ftol_rel(this->opt.get()); + } + + const ::rl::math::Vector& + NloptInverseKinematics::getLowerBound() const + { + return this->lb; } - const double& - NloptInverseKinematics::getTolerance() const + ::rl::math::Vector + NloptInverseKinematics::getOptimizationToleranceAbsolute() const { - return this->tolerance; + ::rl::math::Vector tol; + Exception::check(::nlopt_get_xtol_abs(this->opt.get(), tol.data())); + return tol; + } + + ::rl::math::Real + NloptInverseKinematics::getOptimizationToleranceRelative() const + { + return ::nlopt_get_xtol_rel(this->opt.get()); + } + + const ::rl::math::Vector& + NloptInverseKinematics::getUpperBound() const + { + return this->ub; + } + + void + NloptInverseKinematics::seed(const ::std::mt19937::result_type& value) + { + this->randEngine.seed(value); } void @@ -141,31 +163,54 @@ namespace rl this->delta = delta; } - void NloptInverseKinematics::setEpsilonRotation(const::rl::math::Real& epsilonRotation) + void + NloptInverseKinematics::setEpsilon(const::rl::math::Real& epsilon) + { + Exception::check(::nlopt_set_stopval(opt.get(), ::std::pow(epsilon, 2))); + IterativeInverseKinematics::setEpsilon(epsilon); + } + + void + NloptInverseKinematics::setFunctionToleranceAbsolute(const ::rl::math::Real& functionToleranceAbsolute) { - this->epsilonRotation = epsilonRotation; + Exception::check(::nlopt_set_ftol_abs(opt.get(), functionToleranceAbsolute)); } - void NloptInverseKinematics::setEpsilonTranslation(const::rl::math::Real& epsilonTranslation) + void + NloptInverseKinematics::setFunctionToleranceRelative(const ::rl::math::Real& functionToleranceRelative) { - this->epsilonTranslation = epsilonTranslation; + Exception::check(::nlopt_set_ftol_rel(opt.get(), functionToleranceRelative)); } void NloptInverseKinematics::setLowerBound(const ::rl::math::Vector& lb) { + Exception::check(::nlopt_set_lower_bounds(opt.get(), lb.data())); this->lb = lb; } void - NloptInverseKinematics::setTolerance(const double& tolerance) + NloptInverseKinematics::setOptimizationToleranceAbsolute(const ::rl::math::Real& optimizationToleranceAbsolute) + { + Exception::check(::nlopt_set_xtol_abs1(opt.get(), optimizationToleranceAbsolute)); + } + + void + NloptInverseKinematics::setOptimizationToleranceAbsolute(const ::rl::math::Vector& optimizationToleranceAbsolute) { - this->tolerance = tolerance; + Exception::check(::nlopt_set_xtol_abs(opt.get(), optimizationToleranceAbsolute.data())); + } + + void + NloptInverseKinematics::setOptimizationToleranceRelative(const ::rl::math::Real& optimizationToleranceRelative) + { + Exception::check(::nlopt_set_xtol_rel(opt.get(), optimizationToleranceRelative)); } void NloptInverseKinematics::setUpperBound(const ::rl::math::Vector& ub) { + Exception::check(::nlopt_set_upper_bounds(opt.get(), ub.data())); this->ub = ub; } @@ -173,32 +218,8 @@ namespace rl NloptInverseKinematics::solve() { ::std::chrono::steady_clock::time_point start = ::std::chrono::steady_clock::now(); - double remaining = ::std::chrono::duration(this->duration).count(); - - ::std::unique_ptr< ::nlopt_opt_s, decltype(&::nlopt_destroy)> opt( - ::nlopt_create(::NLOPT_LD_SLSQP, this->kinematic->getDofPosition()), - ::nlopt_destroy - ); - - if (::nlopt_set_xtol_abs1(opt.get(), this->tolerance) < 0) - { - return false; - } - - if (::nlopt_set_min_objective(opt.get(), &NloptInverseKinematics::f, this) < 0) - { - return false; - } - - if (::nlopt_set_lower_bounds(opt.get(), this->lb.data()) < 0) - { - return false; - } - - if (::nlopt_set_upper_bounds(opt.get(), this->ub.data()) < 0) - { - return false; - } + double remaining = ::std::chrono::duration(this->getDuration()).count(); + this->iteration = 0; ::rl::math::Vector rand(this->kinematic->getDof()); ::rl::math::Vector q = this->kinematic->getPosition(); @@ -206,20 +227,26 @@ namespace rl do { - if (::nlopt_set_maxtime(opt.get(), remaining) < 0) + if (::nlopt_set_maxeval(opt.get(), this->getIterations() - this->iteration) < 0) { return false; } - if (::nlopt_optimize(opt.get(), q.data(), &optF) < -1) + if (::nlopt_set_maxtime(opt.get(), remaining) < 0) { return false; } - if (this->error(q) < ::std::numeric_limits< ::rl::math::Real>::epsilon()) + ::nlopt_result result = ::nlopt_optimize(opt.get(), q.data(), &optF); + + if (::NLOPT_STOPVAL_REACHED == result) { return true; } + else if (result < -1) + { + return false; + } for (::std::size_t i = 0; i < this->kinematic->getDof(); ++i) { @@ -228,11 +255,55 @@ namespace rl q = this->kinematic->generatePositionUniform(rand, this->lb, this->ub); - remaining = ::std::chrono::duration(this->duration - (::std::chrono::steady_clock::now() - start)).count(); + remaining = ::std::chrono::duration(this->getDuration() - (::std::chrono::steady_clock::now() - start)).count(); } - while (remaining > 0); + while (remaining > 0 && this->iteration < this->getIterations()); return false; } + + NloptInverseKinematics::Exception::Exception(const ::nlopt_result& result) : + ::rl::mdl::Exception(::std::string()), + result(result) + { + } + + NloptInverseKinematics::Exception::~Exception() throw() + { + } + + void + NloptInverseKinematics::Exception::check(const ::nlopt_result& result) + { + if (result < 0) + { + throw Exception(result); + } + } + + ::nlopt_result + NloptInverseKinematics::Exception::getResult() const + { + return this->result; + } + + const char* + NloptInverseKinematics::Exception::what() const throw() + { + switch (this->result) + { + case ::NLOPT_FAILURE: + return "Generic failure."; + break; + case ::NLOPT_INVALID_ARGS: + return "Invalid arguments."; + break; + case ::NLOPT_OUT_OF_MEMORY: + return "Out of memory."; + break; + default: + break; + } + } } } diff --git a/src/rl/mdl/NloptInverseKinematics.h b/src/rl/mdl/NloptInverseKinematics.h index 9d0cb194..6942a20e 100644 --- a/src/rl/mdl/NloptInverseKinematics.h +++ b/src/rl/mdl/NloptInverseKinematics.h @@ -28,10 +28,12 @@ #define RL_MDL_NLOPTINVERSEKINEMATICS_H #include +#include #include #include #include +#include "Exception.h" #include "IterativeInverseKinematics.h" namespace rl @@ -41,27 +43,60 @@ namespace rl class RL_MDL_EXPORT NloptInverseKinematics : public IterativeInverseKinematics { public: + class Exception : public ::rl::mdl::Exception + { + public: + Exception(const ::nlopt_result& result); + + virtual ~Exception() throw(); + + static void check(const ::nlopt_result& result); + + ::nlopt_result getResult() const; + + virtual const char* what() const throw(); + + protected: + + private: + ::nlopt_result result; + }; + NloptInverseKinematics(Kinematic* kinematic); virtual ~NloptInverseKinematics(); const ::rl::math::Real& getDelta() const; - const ::rl::math::Real& getEpsilonRotation() const; + ::rl::math::Real getFunctionToleranceAbsolute() const; + + ::rl::math::Real getFunctionToleranceRelative() const; + + const ::rl::math::Vector& getLowerBound() const; - const ::rl::math::Real& getEpsilonTranslation() const; + ::rl::math::Vector getOptimizationToleranceAbsolute() const; - const double& getTolerance() const; + ::rl::math::Real getOptimizationToleranceRelative() const; + + const ::rl::math::Vector& getUpperBound() const; + + void seed(const ::std::mt19937::result_type& value); void setDelta(const::rl::math::Real& delta); - void setEpsilonRotation(const::rl::math::Real& epsilonRotation); + void setEpsilon(const::rl::math::Real& epsilon); + + void setFunctionToleranceAbsolute(const ::rl::math::Real& functionToleranceAbsolute); - void setEpsilonTranslation(const::rl::math::Real& epsilonTranslation); + void setFunctionToleranceRelative(const ::rl::math::Real& functionToleranceRelative); void setLowerBound(const ::rl::math::Vector& lb); - void setTolerance(const double& tolerance); + void setOptimizationToleranceAbsolute(const ::rl::math::Real& optimizationToleranceAbsolute); + + void setOptimizationToleranceAbsolute(const ::rl::math::Vector& optimizationToleranceAbsolute); + + void setOptimizationToleranceRelative(const ::rl::math::Real& optimizationToleranceRelative); void setUpperBound(const ::rl::math::Vector& ub); @@ -72,22 +107,20 @@ namespace rl private: ::rl::math::Real error(const ::rl::math::Vector& q); - static ::rl::math::Real f(unsigned n, const double* x, double* grad, void* data); + static double f(unsigned n, const double* x, double* grad, void* data); ::rl::math::Real delta; - ::rl::math::Real epsilonRotation; - - ::rl::math::Real epsilonTranslation; + ::std::size_t iteration; ::rl::math::Vector lb; + ::std::unique_ptr< ::nlopt_opt_s, decltype(&::nlopt_destroy)> opt; + ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; ::std::mt19937 randEngine; - double tolerance; - ::rl::math::Vector ub; }; } diff --git a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp index 2072e2cc..90c6d7b6 100644 --- a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp +++ b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp @@ -55,25 +55,30 @@ main(int argc, char** argv) std::vector, std::string>> ik; std::shared_ptr jacobianSvd = std::make_shared(kinematics.get()); + jacobianSvd->seed(0); jacobianSvd->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_SVD); ik.push_back(std::make_pair(jacobianSvd, "rl::mdl::JacobianInverseKinematics::METHOD_SVD")); std::shared_ptr jacobianDls = std::make_shared(kinematics.get()); + jacobianDls->seed(0); jacobianDls->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_DLS); ik.push_back(std::make_pair(jacobianDls, "rl::mdl::JacobianInverseKinematics::METHOD_DLS")); std::shared_ptr jacobianTranspose = std::make_shared(kinematics.get()); + jacobianTranspose->seed(0); jacobianTranspose->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE); ik.push_back(std::make_pair(jacobianTranspose, "rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE")); #ifdef RL_MDL_NLOPT std::shared_ptr nlopt = std::make_shared(kinematics.get()); + nlopt->seed(0); ik.push_back(std::make_pair(nlopt, "rl::mdl::NloptInverseKinematics")); #endif for (std::size_t i = 0; i < ik.size(); ++i) { - ik[i].first->setDuration(std::chrono::seconds(10)); + ik[i].first->setDuration(std::chrono::nanoseconds::max()); + ik[i].first->setIterations(100000); for (std::size_t n = 0; n < 100; ++n) { @@ -100,10 +105,11 @@ main(int argc, char** argv) kinematics->forwardPosition(); rl::math::Transform t3 = kinematics->getOperationalPosition(0); - if (!t3.isApprox(t1, static_cast(1.03-6))) + if (t3.toDelta(t1).squaredNorm() > std::pow(ik[i].first->getEpsilon(), 2)) { std::cerr << ik[i].second << " on file " << filename << " with incorrect operational position." << std::endl; - std::cerr << "norm(t1 - t3) = " << (t1.matrix() - t3.matrix()).norm() << std::endl; + std::cerr << "t3.toDelta(t1).squaredNorm() = " << t3.toDelta(t1).squaredNorm() << std::endl; + std::cerr << "t3.toDelta(t1) = " << t3.toDelta(t1).transpose() << std::endl; std::cerr << "t1 = " << std::endl << t1.matrix() << std::endl; std::cerr << "t3 = " << std::endl << t3.matrix() << std::endl; std::cerr << "q1 = " << q1.transpose() << std::endl; From 4ee63c11ad056580f8a5e8a3540996d455c3cc4d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Apr 2019 16:21:23 +0200 Subject: [PATCH 242/546] Synchronize rl::kin::Kinematics::inversePosition and rl::mdl::JacobianInverseKinematics --- src/rl/kin/Kinematics.cpp | 37 +++++++++++-------- src/rl/kin/Kinematics.h | 4 +- .../rlInverseKinematicsKinTest.cpp | 16 ++++---- 3 files changed, 32 insertions(+), 25 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index e9007d7a..d0362acc 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -758,6 +758,7 @@ namespace rl ::std::chrono::steady_clock::time_point start = ::std::chrono::steady_clock::now(); double remaining = ::std::chrono::duration(duration).count(); + ::std::size_t iteration = 0; this->getPosition(q); ::rl::math::Vector q2(this->getDof()); @@ -766,9 +767,7 @@ namespace rl do { - ::rl::math::Real delta2 = 1; - - for (::std::size_t i = 0; i < iterations && delta2 > epsilon; ++i) + do { this->updateFrames(); dx.setZero(); @@ -776,42 +775,48 @@ namespace rl ::rl::math::VectorBlock dxi = dx.segment(6 * leaf, 6); dxi = this->forwardPosition(leaf).toDelta(x); + if (dx.squaredNorm() < ::std::pow(epsilon, 2)) + { + this->normalize(q); + this->setPosition(q); + + if (this->isValid(q)) + { + return true; + } + } + this->updateJacobian(); this->updateJacobianInverse(); this->inverseVelocity(dx, dq); this->step(q, dq, q2); - delta2 = this->distance(q, q2); - if (delta2 > delta) + if (this->transformedDistance(q, q2) > ::std::pow(delta, 2)) { this->interpolate(q, q2, delta, q2); } q = q2; this->setPosition(q); - } - - - if (dx.squaredNorm() < epsilon) - { - this->normalize(q); - this->setPosition(q); - if (this->isValid(q)) + remaining = ::std::chrono::duration(duration - (::std::chrono::steady_clock::now() - start)).count(); + + if (0 == ++iteration % 100) { - return true; + break; } } + while (remaining > 0 && iteration < iterations); q = this->generatePositionUniform(); this->setPosition(q); remaining = ::std::chrono::duration(duration - (::std::chrono::steady_clock::now() - start)).count(); } - while (remaining > 0); + while (remaining > 0 && iteration < iterations); - return true; + return false; } void diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index c23cb42a..c8699ece 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -221,8 +221,8 @@ namespace rl const ::std::size_t& leaf = 0, const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(), const ::rl::math::Real& epsilon = static_cast< ::rl::math::Real>(1.0e-3), - const ::std::size_t& iterations = 1000, - const ::std::chrono::nanoseconds& duration = ::std::chrono::milliseconds(100) + const ::std::size_t& iterations = 10000, + const ::std::chrono::nanoseconds& duration = ::std::chrono::milliseconds(1000) ); /** diff --git a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp index bc80b7a8..49bd917b 100644 --- a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp +++ b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp @@ -63,9 +63,9 @@ main(int argc, char** argv) q3, 0, std::numeric_limits< ::rl::math::Real>::infinity(), - static_cast(1.0e-3), - 1000, - std::chrono::seconds(10) + static_cast(1.0e-6), + 100000, + std::chrono::nanoseconds::max() ); if (!solved) @@ -81,10 +81,11 @@ main(int argc, char** argv) kinematics->updateFrames(); rl::math::Transform t3 = kinematics->forwardPosition(); - if (!t3.isApprox(t1, static_cast(1.03-6))) + if (t3.toDelta(t1).squaredNorm() > std::pow(static_cast(1.0e-6), 2)) { std::cerr << "rl::kin::Kinematics::inversePosition on file " << filename << " with incorrect operational position." << std::endl; - std::cerr << "norm(t1 - t3) = " << (t1.matrix() - t3.matrix()).norm() << std::endl; + std::cerr << "t3.toDelta(t1).squaredNorm() = " << t3.toDelta(t1).squaredNorm() << std::endl; + std::cerr << "t3.toDelta(t1) = " << t3.toDelta(t1).transpose() << std::endl; std::cerr << "t1 = " << std::endl << t1.matrix() << std::endl; std::cerr << "t3 = " << std::endl << t3.matrix() << std::endl; std::cerr << "q1 = " << q1.transpose() << std::endl; @@ -117,10 +118,11 @@ main(int argc, char** argv) puma->updateFrames(); rl::math::Transform t4 = puma->forwardPosition(); - if (!t4.isApprox(t1, static_cast(1.03-6))) + if (t4.toDelta(t1).squaredNorm() > std::pow(static_cast(1.0e-6), 2)) { std::cerr << "rl::kin::Puma::inversePosition on file " << filename << " with incorrect operational position." << std::endl; - std::cerr << "norm(t1 - t4) = " << (t1.matrix() - t4.matrix()).norm() << std::endl; + std::cerr << "t4.toDelta(t1).squaredNorm() = " << t4.toDelta(t1).squaredNorm() << std::endl; + std::cerr << "t4.toDelta(t1) = " << t4.toDelta(t1).transpose() << std::endl; std::cerr << "t1 = " << std::endl << t1.matrix() << std::endl; std::cerr << "t4 = " << std::endl << t4.matrix() << std::endl; std::cerr << "q1 = " << q1.transpose() << std::endl; From 6546cb1080d342101bb064a607d1542f00fe68a1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 29 Apr 2019 15:57:30 +0200 Subject: [PATCH 243/546] Add additional error cases --- src/rl/mdl/NloptInverseKinematics.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index e217b557..678a142b 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -301,7 +301,14 @@ namespace rl case ::NLOPT_OUT_OF_MEMORY: return "Out of memory."; break; + case ::NLOPT_ROUNDOFF_LIMITED: + return "Halted because roundoff errors limited progress."; + break; + case ::NLOPT_FORCED_STOP: + return "Halted because of a forced termination."; + break; default: + return "Unknown error."; break; } } From 00e00fe01d95134c1c64075957faaa6d3feba074 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 29 Apr 2019 20:02:41 +0200 Subject: [PATCH 244/546] Use Jacobian for gradient in rl::mdl::NloptInverseKinematics --- src/rl/mdl/NloptInverseKinematics.cpp | 64 +++++++-------------------- src/rl/mdl/NloptInverseKinematics.h | 10 +---- 2 files changed, 17 insertions(+), 57 deletions(-) diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 678a142b..79b599d5 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -33,7 +33,6 @@ namespace rl { NloptInverseKinematics::NloptInverseKinematics(Kinematic* kinematic) : IterativeInverseKinematics(kinematic), - delta(static_cast< ::rl::math::Real>(1.0e-8)), lb(this->kinematic->getMinimum()), opt(::nlopt_create(::NLOPT_LD_SLSQP, kinematic->getDofPosition()), ::nlopt_destroy), randDistribution(0, 1), @@ -54,63 +53,38 @@ namespace rl { } - ::rl::math::Real - NloptInverseKinematics::error(const ::rl::math::Vector& q) - { - this->kinematic->setPosition(q); - this->kinematic->forwardPosition(); - - ::rl::math::Vector dx = ::rl::math::Vector::Zero(6 * this->kinematic->getOperationalDof()); - - for (::std::size_t i = 0; i < this->goals.size(); ++i) - { - ::rl::math::VectorBlock dxi = dx.segment(6 * this->goals[i].second, 6); - dxi = this->kinematic->getOperationalPosition(this->goals[i].second).toDelta(this->goals[i].first); - } - - return dx.squaredNorm(); - } - double - NloptInverseKinematics::f(unsigned n, const double* x, double* grad, void* data) + NloptInverseKinematics::f(unsigned int n, const double* x, double* grad, void* data) { NloptInverseKinematics* ik = static_cast(data); - ++ik->iteration; - ::Eigen::Map< const ::Eigen::VectorXd> q(x, n, 1); + ::Eigen::Map q(x, n, 1); if (!q.allFinite()) { return ::std::numeric_limits::infinity(); } - ::rl::math::Real result = ik->error(q); + ik->kinematic->setPosition(q); + ik->kinematic->forwardPosition(); + + ::rl::math::Vector dx = ::rl::math::Vector::Zero(6 * ik->kinematic->getOperationalDof()); + + for (::std::size_t i = 0; i < ik->goals.size(); ++i) + { + ::rl::math::VectorBlock dxi = dx.segment(6 * ik->goals[i].second, 6); + dxi = ik->kinematic->getOperationalPosition(ik->goals[i].second).toDelta(ik->goals[i].first); + } if (nullptr != grad) { - ::Eigen::VectorXd q2(q); - - for (::std::ptrdiff_t i = 0; i < q.size(); ++i) - { - q2(i) = q(i) + ik->delta; - ::rl::math::Real dq1 = ik->error(q2); - - q2(i) = q(i) - ik->delta; - ::rl::math::Real dq2 = ik->error(q2); - - q2(i) = q(i); - grad[i] = (dq1 - dq2) / (2 * ik->delta); - } + ::Eigen::Map< ::Eigen::VectorXd> grad2(grad, n, 1); + ik->kinematic->calculateJacobian(); + grad2 = -2 * ik->kinematic->getJacobian().transpose() * dx; } - return result; - } - - const ::rl::math::Real& - NloptInverseKinematics::getDelta() const - { - return this->delta; + return dx.squaredNorm(); } ::rl::math::Real @@ -157,12 +131,6 @@ namespace rl this->randEngine.seed(value); } - void - NloptInverseKinematics::setDelta(const::rl::math::Real& delta) - { - this->delta = delta; - } - void NloptInverseKinematics::setEpsilon(const::rl::math::Real& epsilon) { diff --git a/src/rl/mdl/NloptInverseKinematics.h b/src/rl/mdl/NloptInverseKinematics.h index 6942a20e..0a25cf0b 100644 --- a/src/rl/mdl/NloptInverseKinematics.h +++ b/src/rl/mdl/NloptInverseKinematics.h @@ -66,8 +66,6 @@ namespace rl virtual ~NloptInverseKinematics(); - const ::rl::math::Real& getDelta() const; - ::rl::math::Real getFunctionToleranceAbsolute() const; ::rl::math::Real getFunctionToleranceRelative() const; @@ -82,8 +80,6 @@ namespace rl void seed(const ::std::mt19937::result_type& value); - void setDelta(const::rl::math::Real& delta); - void setEpsilon(const::rl::math::Real& epsilon); void setFunctionToleranceAbsolute(const ::rl::math::Real& functionToleranceAbsolute); @@ -105,11 +101,7 @@ namespace rl protected: private: - ::rl::math::Real error(const ::rl::math::Vector& q); - - static double f(unsigned n, const double* x, double* grad, void* data); - - ::rl::math::Real delta; + static double f(unsigned int n, const double* x, double* grad, void* data); ::std::size_t iteration; From c4984a8cab86088ebfd78d0805bffb2113aa2ecf Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 29 Apr 2019 20:05:28 +0200 Subject: [PATCH 245/546] Initialize vector length --- src/rl/mdl/NloptInverseKinematics.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 79b599d5..84dc1f75 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -108,7 +108,7 @@ namespace rl ::rl::math::Vector NloptInverseKinematics::getOptimizationToleranceAbsolute() const { - ::rl::math::Vector tol; + ::rl::math::Vector tol(this->kinematic->getDofPosition()); Exception::check(::nlopt_get_xtol_abs(this->opt.get(), tol.data())); return tol; } From cb95e957e2d14e4f8e7fc3124b85c38b6a529794 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 30 Apr 2019 15:38:23 +0200 Subject: [PATCH 246/546] Set working directory to path of file before SoInput::openFile --- extras/wrlview/CMakeLists.txt | 2 +- extras/wrlview/MainWindow.cpp | 4 ++++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 7ea148d6..0c1c6892 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -60,7 +60,7 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) set_target_properties( wrlview PROPERTIES - VERSION 0.1.12 + VERSION 0.1.13 ) install( diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index a41b0290..c4cfa702 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -33,6 +33,7 @@ #include #include #include +#include #include #include #include @@ -540,6 +541,9 @@ MainWindow::load(const QString filename) return; } + QFileInfo fileInfo(filename); + QDir::setCurrent(fileInfo.path()); + if (!this->input.openFile(filename.toStdString().c_str(), true)) { QMessageBox::critical(this, "Error", "File not found."); From a765a43c2f6d104160f333b9bf433887e010077b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 30 Apr 2019 17:45:14 +0200 Subject: [PATCH 247/546] Minor fixes --- demos/rlCoachMdl/MainWindow.cpp | 2 -- src/rl/mdl/IterativeInverseKinematics.cpp | 2 +- src/rl/mdl/IterativeInverseKinematics.h | 2 +- src/rl/mdl/JacobianInverseKinematics.cpp | 2 +- src/rl/mdl/JacobianInverseKinematics.h | 2 +- src/rl/mdl/NloptInverseKinematics.cpp | 2 +- src/rl/mdl/NloptInverseKinematics.h | 2 +- 7 files changed, 6 insertions(+), 8 deletions(-) diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index 4ec2bd97..562dbe2a 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -218,8 +218,6 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->ikJacobianComboBox->setToolTip("Jacobian Method"); this->ikJacobianComboBox->setCurrentIndex(this->ikJacobianComboBox->findText("SVD")); - QObject::connect(this->ikJacobianComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(changeIkJacobian())); - this->statusBar()->addPermanentWidget(this->ikAlgorithmComboBox); this->statusBar()->addPermanentWidget(this->ikJacobianComboBox); this->statusBar()->addPermanentWidget(this->ikIterationsSpinBox); diff --git a/src/rl/mdl/IterativeInverseKinematics.cpp b/src/rl/mdl/IterativeInverseKinematics.cpp index 29cc2da6..7b1fa18b 100644 --- a/src/rl/mdl/IterativeInverseKinematics.cpp +++ b/src/rl/mdl/IterativeInverseKinematics.cpp @@ -67,7 +67,7 @@ namespace rl } void - IterativeInverseKinematics::setEpsilon(const::rl::math::Real& epsilon) + IterativeInverseKinematics::setEpsilon(const ::rl::math::Real& epsilon) { this->epsilon = epsilon; } diff --git a/src/rl/mdl/IterativeInverseKinematics.h b/src/rl/mdl/IterativeInverseKinematics.h index aa1e8e2f..9efb9d9d 100644 --- a/src/rl/mdl/IterativeInverseKinematics.h +++ b/src/rl/mdl/IterativeInverseKinematics.h @@ -50,7 +50,7 @@ namespace rl void setDuration(const ::std::chrono::nanoseconds& duration); - virtual void setEpsilon(const::rl::math::Real& epsilon); + virtual void setEpsilon(const ::rl::math::Real& epsilon); void setIterations(const ::std::size_t& iterations); diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index 142c37db..478c60db 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -63,7 +63,7 @@ namespace rl } void - JacobianInverseKinematics::setDelta(const::rl::math::Real& delta) + JacobianInverseKinematics::setDelta(const ::rl::math::Real& delta) { this->delta = delta; } diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index 7bbb5aed..82745b78 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -65,7 +65,7 @@ namespace rl void seed(const ::std::mt19937::result_type& value); - void setDelta(const::rl::math::Real& delta); + void setDelta(const ::rl::math::Real& delta); void setMethod(const Method& method); diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 84dc1f75..5bdaafbb 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -132,7 +132,7 @@ namespace rl } void - NloptInverseKinematics::setEpsilon(const::rl::math::Real& epsilon) + NloptInverseKinematics::setEpsilon(const ::rl::math::Real& epsilon) { Exception::check(::nlopt_set_stopval(opt.get(), ::std::pow(epsilon, 2))); IterativeInverseKinematics::setEpsilon(epsilon); diff --git a/src/rl/mdl/NloptInverseKinematics.h b/src/rl/mdl/NloptInverseKinematics.h index 0a25cf0b..891215ee 100644 --- a/src/rl/mdl/NloptInverseKinematics.h +++ b/src/rl/mdl/NloptInverseKinematics.h @@ -80,7 +80,7 @@ namespace rl void seed(const ::std::mt19937::result_type& value); - void setEpsilon(const::rl::math::Real& epsilon); + void setEpsilon(const ::rl::math::Real& epsilon); void setFunctionToleranceAbsolute(const ::rl::math::Real& functionToleranceAbsolute); From 6d1a3457dd19902aaf2d42531e3a8f4aee8036b6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 30 Apr 2019 17:46:46 +0200 Subject: [PATCH 248/546] Set minimum dock sizes to 1 --- demos/rlCoachKin/MainWindow.cpp | 2 +- demos/rlCoachMdl/MainWindow.cpp | 2 +- demos/rlSimulator/MainWindow.cpp | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/demos/rlCoachKin/MainWindow.cpp b/demos/rlCoachKin/MainWindow.cpp index d83ac486..c9723706 100644 --- a/demos/rlCoachKin/MainWindow.cpp +++ b/demos/rlCoachKin/MainWindow.cpp @@ -158,7 +158,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QList resizeDocksWidgets; resizeDocksWidgets.append(this->operationalDockWidget); QList resizeDocksSizes; - resizeDocksSizes.append(0); + resizeDocksSizes.append(1); this->resizeDocks(resizeDocksWidgets, resizeDocksSizes, Qt::Vertical); #endif // QT_VERSION diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index 562dbe2a..b85d540c 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -185,7 +185,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QList resizeDocksWidgets; resizeDocksWidgets.append(this->operationalDockWidget); QList resizeDocksSizes; - resizeDocksSizes.append(0); + resizeDocksSizes.append(1); this->resizeDocks(resizeDocksWidgets, resizeDocksSizes, Qt::Vertical); #endif // QT_VERSION diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index dc2709d1..8138e593 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -326,8 +326,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : resizeDocksWidgets.append(this->operationalDockWidget); resizeDocksWidgets.append(this->simulationDockWidget); QList resizeDocksSizes; - resizeDocksSizes.append(0); - resizeDocksSizes.append(0); + resizeDocksSizes.append(1); + resizeDocksSizes.append(1); this->resizeDocks(resizeDocksWidgets, resizeDocksSizes, Qt::Vertical); #endif // QT_VERSION From 2335e14cdcb1d5fc10ef880a8e6eeda085aa1f87 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 4 May 2019 22:32:56 +0200 Subject: [PATCH 249/546] Update Debian package names --- debian/control | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/debian/control b/debian/control index 5edca03f..4538c7d0 100644 --- a/debian/control +++ b/debian/control @@ -7,17 +7,14 @@ Build-Depends: debhelper (>= 7.0.50~), graphviz, libboost-all-dev (>= 1.46), libbullet-dev, - libcoin60-dev | libcoin80-dev, libcomedi-dev, libdc1394-22-dev (>= 2.1), libeigen3-dev (>= 3.2.0), libnlopt-dev (>= 2.4.1), libode-dev (>= 2:0.11), - libqt4-dev, - libqt4-opengl-dev, libsimage-dev, libsolid3d-dev (>= 3.5.6), - libsoqt4-dev, + libsoqt-dev, libxml2-dev (>= 2.7), libxslt1-dev (>= 1.1.26) Standards-Version: 3.9.1 @@ -59,17 +56,14 @@ Architecture: any Depends: librl (= ${binary:Version}), libboost-all-dev (>= 1.46), libbullet-dev, - libcoin60-dev | libcoin80-dev, libcomedi-dev, libdc1394-22-dev (>= 2.1), libeigen3-dev (>= 3.2.0), libnlopt-dev (>= 2.4.1), libode-dev (>= 2:0.11), - libqt4-dev, - libqt4-opengl-dev, libsimage-dev, libsolid3d-dev (>= 3.5.6), - libsoqt4-dev, + libsoqt-dev, libxml2-dev (>= 2.7), libxslt1-dev (>= 1.1.26) Description: Development files for the Robotics Library From 102da905c85fd95597e38fd6ad966f33d3784a70 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 5 May 2019 15:00:23 +0200 Subject: [PATCH 250/546] Separate Debian packaging from source --- debian/changelog | 5 -- debian/compat | 1 - debian/control | 99 ----------------------------------- debian/copyright | 31 ----------- debian/librl-demos.install | 3 -- debian/librl-dev.install | 3 -- debian/librl-doc.install | 1 - debian/librl-examples.install | 2 - debian/librl-extras.install | 3 -- debian/librl.install | 1 - debian/rules | 16 ------ 11 files changed, 165 deletions(-) delete mode 100644 debian/changelog delete mode 100644 debian/compat delete mode 100644 debian/control delete mode 100644 debian/copyright delete mode 100644 debian/librl-demos.install delete mode 100644 debian/librl-dev.install delete mode 100644 debian/librl-doc.install delete mode 100644 debian/librl-examples.install delete mode 100644 debian/librl-extras.install delete mode 100644 debian/librl.install delete mode 100644 debian/rules diff --git a/debian/changelog b/debian/changelog deleted file mode 100644 index bf8e2722..00000000 --- a/debian/changelog +++ /dev/null @@ -1,5 +0,0 @@ -rl (0.7.0) UNRELEASED; urgency=low - - * Upstream build. - - -- Robotics Library Team Mon, 25 Sep 2017 12:00:00 +0100 diff --git a/debian/compat b/debian/compat deleted file mode 100644 index 7f8f011e..00000000 --- a/debian/compat +++ /dev/null @@ -1 +0,0 @@ -7 diff --git a/debian/control b/debian/control deleted file mode 100644 index 4538c7d0..00000000 --- a/debian/control +++ /dev/null @@ -1,99 +0,0 @@ -Source: rl -Priority: extra -Maintainer: Robotics Library Team -Build-Depends: debhelper (>= 7.0.50~), - cmake (>= 2.8.11), - doxygen, - graphviz, - libboost-all-dev (>= 1.46), - libbullet-dev, - libcomedi-dev, - libdc1394-22-dev (>= 2.1), - libeigen3-dev (>= 3.2.0), - libnlopt-dev (>= 2.4.1), - libode-dev (>= 2:0.11), - libsimage-dev, - libsolid3d-dev (>= 3.5.6), - libsoqt-dev, - libxml2-dev (>= 2.7), - libxslt1-dev (>= 1.1.26) -Standards-Version: 3.9.1 -Section: libs -Homepage: https://www.roboticslibrary.org/ - -Package: librl -Section: libs -Architecture: any -Depends: ${shlibs:Depends}, ${misc:Depends} -Description: Runtime files for the Robotics Library - The Robotics Library (RL) is a self-contained C++ library for robot - kinematics, visualization, motion planning, and control. - This package contains the runtime files for RL. - -Package: librl-dbg -Section: debug -Architecture: any -Priority: extra -Depends: librl (= ${binary:Version}), ${misc:Depends} -Description: Debugging symbols for the Robotics Library - The Robotics Library (RL) is a self-contained C++ library for robot - kinematics, visualization, motion planning, and control. - This package contains the debugging symbols for RL. - -Package: librl-demos -Section: misc -Architecture: any -Depends: librl (= ${binary:Version}), librl-examples (= ${binary:Version}), - ${shlibs:Depends}, ${misc:Depends} -Description: Demo programs for the Robotics Library - The Robotics Library (RL) is a self-contained C++ library for robot - kinematics, visualization, motion planning, and control. - This package contains the demo programs for RL. - -Package: librl-dev -Section: libdevel -Architecture: any -Depends: librl (= ${binary:Version}), - libboost-all-dev (>= 1.46), - libbullet-dev, - libcomedi-dev, - libdc1394-22-dev (>= 2.1), - libeigen3-dev (>= 3.2.0), - libnlopt-dev (>= 2.4.1), - libode-dev (>= 2:0.11), - libsimage-dev, - libsolid3d-dev (>= 3.5.6), - libsoqt-dev, - libxml2-dev (>= 2.7), - libxslt1-dev (>= 1.1.26) -Description: Development files for the Robotics Library - The Robotics Library (RL) is a self-contained C++ library for robot - kinematics, visualization, motion planning, and control. - This package contains the development files for RL. - -Package: librl-doc -Section: doc -Architecture: all -Priority: extra -Description: Documentation for the Robotics Library - The Robotics Library (RL) is a self-contained C++ library for robot - kinematics, visualization, motion planning, and control. - This package contains the documentation for RL. - -Package: librl-examples -Section: misc -Architecture: all -Description: Example files for the Robotics Library - The Robotics Library (RL) is a self-contained C++ library for robot - kinematics, visualization, motion planning, and control. - This package contains the example files for RL. - -Package: librl-extras -Section: misc -Architecture: any -Priority: extra -Depends: ${shlibs:Depends}, ${misc:Depends} -Description: Extra programs for the Robotics Library - The Robotics Library (RL) is a self-contained C++ library for robot - kinematics, visualization, motion planning, and control. - This package contains the extra programs for RL. diff --git a/debian/copyright b/debian/copyright deleted file mode 100644 index f0e46410..00000000 --- a/debian/copyright +++ /dev/null @@ -1,31 +0,0 @@ -Format: http://dep.debian.net/deps/dep5 -Upstream-Name: Robotics Library -Upstream-Contact: Robotics Library Team -Source: https://www.roboticslibrary.org/ - -Files: * -Copyright: Copyright 2009 Robotics Library Team -License: BSD-2-clause - Copyright (c) 2009 - All rights reserved. - - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - * Redistributions of source code must retain the above copyright notice, - this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - - 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. diff --git a/debian/librl-demos.install b/debian/librl-demos.install deleted file mode 100644 index 27104fb0..00000000 --- a/debian/librl-demos.install +++ /dev/null @@ -1,3 +0,0 @@ -usr/bin/rl* -usr/share/applications/rl*.desktop -usr/share/icons/hicolor/scalable/apps/robotics-library.svg diff --git a/debian/librl-dev.install b/debian/librl-dev.install deleted file mode 100644 index a8d6f39d..00000000 --- a/debian/librl-dev.install +++ /dev/null @@ -1,3 +0,0 @@ -usr/include/* -usr/lib/*/lib{*.a,*.so} -usr/lib/*/cmake/rl*/* diff --git a/debian/librl-doc.install b/debian/librl-doc.install deleted file mode 100644 index d9d4f6f8..00000000 --- a/debian/librl-doc.install +++ /dev/null @@ -1 +0,0 @@ -usr/share/doc/* diff --git a/debian/librl-examples.install b/debian/librl-examples.install deleted file mode 100644 index e32d7756..00000000 --- a/debian/librl-examples.install +++ /dev/null @@ -1,2 +0,0 @@ -usr/share/gtksourceview-3.0/* -usr/share/rl*/examples/* diff --git a/debian/librl-extras.install b/debian/librl-extras.install deleted file mode 100644 index eb82793c..00000000 --- a/debian/librl-extras.install +++ /dev/null @@ -1,3 +0,0 @@ -usr/bin/wrlview* -usr/share/applications/wrlview.desktop -usr/share/icons/hicolor/scalable/apps/wrlview.svg diff --git a/debian/librl.install b/debian/librl.install deleted file mode 100644 index 3ddde584..00000000 --- a/debian/librl.install +++ /dev/null @@ -1 +0,0 @@ -usr/lib/*/lib*.so.* diff --git a/debian/rules b/debian/rules deleted file mode 100644 index dbc87ef6..00000000 --- a/debian/rules +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/make -f - -export DH_VERBOSE=1 -export DEB_BUILD_OPTIONS=parallel=4 - -override_dh_auto_configure: - dh_auto_configure -- -DCMAKE_BUILD_TYPE=RelWithDebInfo -DBUILD_DOCUMENTATION=ON - -override_dh_auto_test: - dh_auto_test -- ARGS+=--output-on-failure - -override_dh_strip: - dh_strip --dbg-package=librl-dbg - -%: - dh $@ --buildsystem=cmake --parallel From 9243bac4b683ad2e61728a8453757edfc92d16dc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 8 May 2019 20:41:34 +0200 Subject: [PATCH 251/546] Remove unused leading -D from target_compile_definitions --- demos/rlGripperDemo/CMakeLists.txt | 8 ++++---- demos/rlInversePositionDemo/CMakeLists.txt | 8 ++++---- demos/rlSimulator/CMakeLists.txt | 8 ++++---- .../rlSixAxisForceTorqueSensorDemo/CMakeLists.txt | 8 ++++---- demos/rlThreadsDemo/CMakeLists.txt | 8 ++++---- demos/rlTimerDemo/CMakeLists.txt | 8 ++++---- src/rl/hal/CMakeLists.txt | 14 +++++++------- src/rl/math/CMakeLists.txt | 2 +- src/rl/mdl/CMakeLists.txt | 10 +++++----- src/rl/plan/CMakeLists.txt | 8 ++++---- src/rl/sg/CMakeLists.txt | 14 +++++++------- tests/rlNearestNeighborsTest/CMakeLists.txt | 8 ++++---- 12 files changed, 52 insertions(+), 52 deletions(-) diff --git a/demos/rlGripperDemo/CMakeLists.txt b/demos/rlGripperDemo/CMakeLists.txt index 66648623..f74743eb 100644 --- a/demos/rlGripperDemo/CMakeLists.txt +++ b/demos/rlGripperDemo/CMakeLists.txt @@ -11,10 +11,10 @@ if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_compile_definitions( rlGripperDemo PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) target_include_directories(rlGripperDemo PUBLIC ${Boost_INCLUDE_DIR}) diff --git a/demos/rlInversePositionDemo/CMakeLists.txt b/demos/rlInversePositionDemo/CMakeLists.txt index 36063c5b..41f6a8dd 100644 --- a/demos/rlInversePositionDemo/CMakeLists.txt +++ b/demos/rlInversePositionDemo/CMakeLists.txt @@ -9,10 +9,10 @@ if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_compile_definitions( rlInversePositionDemo PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) endif() diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index e492b6e3..2c28f38a 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -66,10 +66,10 @@ if(QT_FOUND AND SoQt_FOUND) target_compile_definitions( rlSimulator PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) endif() diff --git a/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt b/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt index 143ed562..89f0ac7f 100644 --- a/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt +++ b/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt @@ -11,10 +11,10 @@ if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_compile_definitions( rlSixAxisForceTorqueSensorDemo PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) endif() diff --git a/demos/rlThreadsDemo/CMakeLists.txt b/demos/rlThreadsDemo/CMakeLists.txt index df66b9c6..df03cc61 100644 --- a/demos/rlThreadsDemo/CMakeLists.txt +++ b/demos/rlThreadsDemo/CMakeLists.txt @@ -11,10 +11,10 @@ if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_compile_definitions( rlThreadsDemo PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) target_include_directories(rlThreadsDemo PUBLIC ${Boost_INCLUDE_DIR}) diff --git a/demos/rlTimerDemo/CMakeLists.txt b/demos/rlTimerDemo/CMakeLists.txt index 3f38e421..fc0e745e 100644 --- a/demos/rlTimerDemo/CMakeLists.txt +++ b/demos/rlTimerDemo/CMakeLists.txt @@ -13,10 +13,10 @@ if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_compile_definitions( rlTimerDemo PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) target_include_directories(rlTimerDemo PUBLIC ${Boost_INCLUDE_DIR}) diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 1b745356..79e10d53 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -175,24 +175,24 @@ add_library( target_compile_definitions( hal PUBLIC - -DBOOST_ALL_NO_LIB + BOOST_ALL_NO_LIB ) if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_compile_definitions( hal PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) endif() if(BIG_ENDIAN) - target_compile_definitions(hal PRIVATE -DHAVE_BIG_ENDIAN) + target_compile_definitions(hal PRIVATE HAVE_BIG_ENDIAN) else() - target_compile_definitions(hal PRIVATE -DHAVE_LITTLE_ENDIAN) + target_compile_definitions(hal PRIVATE HAVE_LITTLE_ENDIAN) endif() if(NOT CMAKE_VERSION VERSION_LESS 3.8) diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index 58f4db84..337872a2 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -67,7 +67,7 @@ else() endif() if(CMAKE_SIZEOF_VOID_P EQUAL 4) - target_compile_definitions(math INTERFACE -DEIGEN_DONT_ALIGN_STATICALLY) + target_compile_definitions(math INTERFACE EIGEN_DONT_ALIGN_STATICALLY) endif() if(NOT CMAKE_VERSION VERSION_LESS 3.8) diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 3b1f7d83..96e28129 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -84,10 +84,10 @@ if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_compile_definitions( mdl PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) endif() @@ -111,7 +111,7 @@ target_link_libraries( ) if(RL_BUILD_MDL_NLOPT) - target_compile_definitions(mdl INTERFACE -DRL_MDL_NLOPT) + target_compile_definitions(mdl INTERFACE RL_MDL_NLOPT) target_include_directories(mdl PUBLIC ${NLOPT_INCLUDE_DIRS}) target_link_libraries(mdl ${NLOPT_LIBRARY}) endif() diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index 4ab9f028..0f39e938 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -98,10 +98,10 @@ if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_compile_definitions( plan PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) endif() diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 09b7e862..36719428 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -193,7 +193,7 @@ target_include_directories( ) if(RL_BUILD_SG_BULLET) - target_compile_definitions(sg INTERFACE -DRL_SG_BULLET) + target_compile_definitions(sg INTERFACE RL_SG_BULLET) target_include_directories(sg PUBLIC ${BULLET_INCLUDE_DIRS}) target_link_libraries(sg ${BULLET_LIBRARIES}) install(FILES ${BULLET_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/bullet COMPONENT development) @@ -210,13 +210,13 @@ if(Coin_FOUND) set(CMAKE_REQUIRED_LIBRARIES ${Coin_LIBRARIES}) check_include_file_cxx(ForeignFiles/SoSTLFileKit.h HAVE_SOSTLFILEKIT_H) if(HAVE_SOSTLFILEKIT_H) - target_compile_definitions(sg PRIVATE -DHAVE_SOSTLFILEKIT_H) + target_compile_definitions(sg PRIVATE HAVE_SOSTLFILEKIT_H) check_cxx_source_compiles(" #include int main() { SoSTLFileKit* stlFileKit = new SoSTLFileKit(); stlFileKit->convert(); return 0; } " HAVE_SOSTLFILEKIT_CONVERT) if(HAVE_SOSTLFILEKIT_CONVERT) - target_compile_definitions(sg PRIVATE -DHAVE_SOSTLFILEKIT_CONVERT) + target_compile_definitions(sg PRIVATE HAVE_SOSTLFILEKIT_CONVERT) endif() endif() unset(CMAKE_REQUIRED_DEFINITIONS) @@ -229,7 +229,7 @@ if(Coin_FOUND) endif() if(RL_BUILD_SG_FCL) - target_compile_definitions(sg INTERFACE -DRL_SG_FCL) + target_compile_definitions(sg INTERFACE RL_SG_FCL) target_compile_definitions(sg PUBLIC ${FCL_DEFINITIONS}) target_include_directories(sg PUBLIC ${FCL_INCLUDE_DIRS}) target_link_libraries(sg ${FCL_LIBRARIES}) @@ -237,7 +237,7 @@ if(RL_BUILD_SG_FCL) endif() if(RL_BUILD_SG_ODE) - target_compile_definitions(sg INTERFACE -DRL_SG_ODE) + target_compile_definitions(sg INTERFACE RL_SG_ODE) target_compile_definitions(sg PUBLIC ${ODE_DEFINITIONS}) target_include_directories(sg PUBLIC ${ODE_INCLUDE_DIRS}) target_link_libraries(sg ${ODE_LIBRARIES}) @@ -245,14 +245,14 @@ if(RL_BUILD_SG_ODE) endif() if(RL_BUILD_SG_PQP) - target_compile_definitions(sg INTERFACE -DRL_SG_PQP) + target_compile_definitions(sg INTERFACE RL_SG_PQP) target_include_directories(sg PUBLIC ${PQP_INCLUDE_DIRS}) target_link_libraries(sg ${PQP_LIBRARIES}) install(FILES ${PQP_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/pqp COMPONENT development) endif() if(RL_BUILD_SG_SOLID) - target_compile_definitions(sg INTERFACE -DRL_SG_SOLID) + target_compile_definitions(sg INTERFACE RL_SG_SOLID) target_include_directories(sg PUBLIC ${SOLID3_INCLUDE_DIRS}) target_link_libraries(sg ${SOLID3_LIBRARIES}) install(FILES ${SOLID_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/solid COMPONENT development) diff --git a/tests/rlNearestNeighborsTest/CMakeLists.txt b/tests/rlNearestNeighborsTest/CMakeLists.txt index 764c26e6..e3e13fd3 100644 --- a/tests/rlNearestNeighborsTest/CMakeLists.txt +++ b/tests/rlNearestNeighborsTest/CMakeLists.txt @@ -10,10 +10,10 @@ if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) target_compile_definitions( rlNearestNeighborsTest PUBLIC - -DBOOST_ALL_NO_LIB - -DBOOST_CHRONO_HEADER_ONLY - -DBOOST_ERROR_CODE_HEADER_ONLY - -DBOOST_SYSTEM_NO_DEPRECATED + BOOST_ALL_NO_LIB + BOOST_CHRONO_HEADER_ONLY + BOOST_ERROR_CODE_HEADER_ONLY + BOOST_SYSTEM_NO_DEPRECATED ) endif() From c0f98752f60a3d66160f795585f87a6c0ccb6109 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 8 May 2019 20:50:21 +0200 Subject: [PATCH 252/546] Minor fix --- demos/rlSimulator/OperationalModel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/rlSimulator/OperationalModel.cpp b/demos/rlSimulator/OperationalModel.cpp index ffaf460e..b136ddbb 100644 --- a/demos/rlSimulator/OperationalModel.cpp +++ b/demos/rlSimulator/OperationalModel.cpp @@ -239,7 +239,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r rl::mdl::NloptInverseKinematics ik(kinematic); #else rl::mdl::JacobianInverseKinematics ik(kinematic); - ik.delta = 1; + ik.setDelta(1); #endif ik.addGoal(x, index.row()); From f4914320f4e12883c4dc771d94d100df1e5c3cb9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 12 May 2019 19:11:31 +0200 Subject: [PATCH 253/546] Match names and capitalization of CMake find modules --- cmake/{Findlibiconv.cmake => FindIconv.cmake} | 74 ++++----- cmake/FindLibLZMA.cmake | 150 ++++++++++++++++++ .../{Findlibxml2.cmake => FindLibXml2.cmake} | 24 +-- .../{Findlibxslt.cmake => FindLibXslt.cmake} | 22 +-- cmake/{Findzlib.cmake => FindZLIB.cmake} | 72 ++++----- src/rl/xml/CMakeLists.txt | 34 ++-- 6 files changed, 268 insertions(+), 108 deletions(-) rename cmake/{Findlibiconv.cmake => FindIconv.cmake} (50%) create mode 100644 cmake/FindLibLZMA.cmake rename cmake/{Findlibxml2.cmake => FindLibXml2.cmake} (83%) rename cmake/{Findlibxslt.cmake => FindLibXslt.cmake} (83%) rename cmake/{Findzlib.cmake => FindZLIB.cmake} (55%) diff --git a/cmake/Findlibiconv.cmake b/cmake/FindIconv.cmake similarity index 50% rename from cmake/Findlibiconv.cmake rename to cmake/FindIconv.cmake index 08537f05..fcf514be 100644 --- a/cmake/Findlibiconv.cmake +++ b/cmake/FindIconv.cmake @@ -9,13 +9,13 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} ${PATH}/libiconv*/${CMAKE_INSTALL_INCLUDEDIR} ) - list(APPEND libiconv_INCLUDE_HINTS ${HINTS}) + list(APPEND Iconv_INCLUDE_HINTS ${HINTS}) endforeach() list( APPEND - libiconv_INCLUDE_HINTS - $ENV{libiconv_DIR}/${CMAKE_INSTALL_INCLUDEDIR} + Iconv_INCLUDE_HINTS + $ENV{Iconv_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) foreach(PATH $ENV{CMAKE_PREFIX_PATH}) @@ -25,7 +25,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} ${PATH}/libiconv*/${CMAKE_INSTALL_INCLUDEDIR} ) - list(APPEND libiconv_INCLUDE_HINTS ${HINTS}) + list(APPEND Iconv_INCLUDE_HINTS ${HINTS}) endforeach() foreach(PATH $ENV{PATH}) @@ -34,12 +34,12 @@ foreach(PATH $ENV{PATH}) HINTS ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} ) - list(APPEND libiconv_INCLUDE_HINTS ${HINTS}) + list(APPEND Iconv_INCLUDE_HINTS ${HINTS}) endforeach() file( GLOB - libiconv_INCLUDE_PATHS + Iconv_INCLUDE_PATHS $ENV{HOME}/include /usr/local/include /opt/local/include @@ -50,16 +50,16 @@ file( ) find_path( - libiconv_INCLUDE_DIRS + Iconv_INCLUDE_DIRS NAMES iconv.h HINTS - ${libiconv_INCLUDE_HINTS} + ${Iconv_INCLUDE_HINTS} PATHS - ${libiconv_INCLUDE_PATHS} + ${Iconv_INCLUDE_PATHS} ) -mark_as_advanced(libiconv_INCLUDE_DIRS) +mark_as_advanced(Iconv_INCLUDE_DIRS) foreach(PATH ${CMAKE_PREFIX_PATH}) file( @@ -68,13 +68,13 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_LIBDIR} ${PATH}/libiconv*/${CMAKE_INSTALL_LIBDIR} ) - list(APPEND libiconv_LIBRARY_HINTS ${HINTS}) + list(APPEND Iconv_LIBRARY_HINTS ${HINTS}) endforeach() list( APPEND - libiconv_LIBRARY_HINTS - $ENV{libiconv_DIR}/${CMAKE_INSTALL_LIBDIR} + Iconv_LIBRARY_HINTS + $ENV{Iconv_DIR}/${CMAKE_INSTALL_LIBDIR} ) foreach(PATH $ENV{CMAKE_PREFIX_PATH}) @@ -84,7 +84,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_LIBDIR} ${PATH}/libiconv*/${CMAKE_INSTALL_LIBDIR} ) - list(APPEND libiconv_LIBRARY_HINTS ${HINTS}) + list(APPEND Iconv_LIBRARY_HINTS ${HINTS}) endforeach() foreach(PATH $ENV{PATH}) @@ -93,12 +93,12 @@ foreach(PATH $ENV{PATH}) HINTS ${PATH}/../${CMAKE_INSTALL_LIBDIR} ) - list(APPEND libiconv_LIBRARY_HINTS ${HINTS}) + list(APPEND Iconv_LIBRARY_HINTS ${HINTS}) endforeach() file( GLOB - libiconv_LIBRARY_PATHS + Iconv_LIBRARY_PATHS $ENV{HOME}/lib /usr/local/lib /opt/local/lib @@ -108,49 +108,49 @@ file( ) find_library( - libiconv_LIBRARY_DEBUG + Iconv_LIBRARY_DEBUG NAMES iconvd libiconvd libiconvd_a HINTS - ${libiconv_LIBRARY_HINTS} + ${Iconv_LIBRARY_HINTS} PATHS - ${libiconv_LIBRARY_PATHS} + ${Iconv_LIBRARY_PATHS} ) find_library( - libiconv_LIBRARY_RELEASE + Iconv_LIBRARY_RELEASE NAMES iconv libiconv liblibiconv_a HINTS - ${libiconv_LIBRARY_HINTS} + ${Iconv_LIBRARY_HINTS} PATHS - ${libiconv_LIBRARY_PATHS} + ${Iconv_LIBRARY_PATHS} ) -select_library_configurations(libiconv) +select_library_configurations(Iconv) find_package_handle_standard_args( - libiconv - FOUND_VAR libiconv_FOUND - REQUIRED_VARS libiconv_INCLUDE_DIRS libiconv_LIBRARIES + Iconv + FOUND_VAR Iconv_FOUND + REQUIRED_VARS Iconv_INCLUDE_DIRS Iconv_LIBRARIES ) -if(libiconv_FOUND AND NOT TARGET libiconv::libiconv) - add_library(libiconv::libiconv UNKNOWN IMPORTED) +if(Iconv_FOUND AND NOT TARGET Iconv::Iconv) + add_library(Iconv::Iconv UNKNOWN IMPORTED) - if(libiconv_LIBRARY_RELEASE) - set_property(TARGET libiconv::libiconv APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(libiconv::libiconv PROPERTIES IMPORTED_LOCATION_RELEASE "${libiconv_LIBRARY_RELEASE}") + if(Iconv_LIBRARY_RELEASE) + set_property(TARGET Iconv::Iconv APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(Iconv::Iconv PROPERTIES IMPORTED_LOCATION_RELEASE "${Iconv_LIBRARY_RELEASE}") endif() - if(libiconv_LIBRARY_DEBUG) - set_property(TARGET libiconv::libiconv APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(libiconv::libiconv PROPERTIES IMPORTED_LOCATION_DEBUG "${libiconv_LIBRARY_DEBUG}") + if(Iconv_LIBRARY_DEBUG) + set_property(TARGET Iconv::Iconv APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(Iconv::Iconv PROPERTIES IMPORTED_LOCATION_DEBUG "${Iconv_LIBRARY_DEBUG}") endif() set_target_properties( - libiconv::libiconv PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${libiconv_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${libiconv_INCLUDE_DIRS}" + Iconv::Iconv PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "${Iconv_DEFINITIONS}" + INTERFACE_INCLUDE_DIRECTORIES "${Iconv_INCLUDE_DIRS}" ) endif() diff --git a/cmake/FindLibLZMA.cmake b/cmake/FindLibLZMA.cmake new file mode 100644 index 00000000..7b209deb --- /dev/null +++ b/cmake/FindLibLZMA.cmake @@ -0,0 +1,150 @@ +include(FindPackageHandleStandardArgs) +include(GNUInstallDirs) +include(SelectLibraryConfigurations) + +foreach(PATH ${CMAKE_PREFIX_PATH}) + file( + GLOB + HINTS + ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} + ${PATH}/liblzma*/${CMAKE_INSTALL_INCLUDEDIR} + ) + list(APPEND LIBLZMA_INCLUDE_HINTS ${HINTS}) +endforeach() + +list( + APPEND + LIBLZMA_INCLUDE_HINTS + $ENV{LibLZMA_DIR}/${CMAKE_INSTALL_INCLUDEDIR} +) + +foreach(PATH $ENV{CMAKE_PREFIX_PATH}) + file( + GLOB + HINTS + ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} + ${PATH}/liblzma*/${CMAKE_INSTALL_INCLUDEDIR} + ) + list(APPEND LIBLZMA_INCLUDE_HINTS ${HINTS}) +endforeach() + +foreach(PATH $ENV{PATH}) + file( + GLOB + HINTS + ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} + ) + list(APPEND LIBLZMA_INCLUDE_HINTS ${HINTS}) +endforeach() + +file( + GLOB + LIBLZMA_INCLUDE_PATHS + $ENV{HOME}/include + /usr/local/include + /opt/local/include + /usr/include + ${CMAKE_OSX_SYSROOT}/usr/include +) + +find_path( + LIBLZMA_INCLUDE_DIRS + NAMES + lzma.h + HINTS + ${LIBLZMA_INCLUDE_HINTS} + PATHS + ${LIBLZMA_INCLUDE_PATHS} +) + +mark_as_advanced(LIBLZMA_INCLUDE_DIRS) + +foreach(PATH ${CMAKE_PREFIX_PATH}) + file( + GLOB + HINTS + ${PATH}/${CMAKE_INSTALL_LIBDIR} + ${PATH}/liblzma*/${CMAKE_INSTALL_LIBDIR} + ) + list(APPEND LIBLZMA_LIBRARY_HINTS ${HINTS}) +endforeach() + +list( + APPEND + LIBLZMA_LIBRARY_HINTS + $ENV{LibLZMA_DIR}/${CMAKE_INSTALL_LIBDIR} +) + +foreach(PATH $ENV{CMAKE_PREFIX_PATH}) + file( + GLOB + HINTS + ${PATH}/${CMAKE_INSTALL_LIBDIR} + ${PATH}/liblzma*/${CMAKE_INSTALL_LIBDIR} + ) + list(APPEND LIBLZMA_LIBRARY_HINTS ${HINTS}) +endforeach() + +foreach(PATH $ENV{PATH}) + file( + GLOB + HINTS + ${PATH}/../${CMAKE_INSTALL_LIBDIR} + ) + list(APPEND LIBLZMA_LIBRARY_HINTS ${HINTS}) +endforeach() + +file( + GLOB + LIBLZMA_LIBRARY_PATHS + $ENV{HOME}/lib + /usr/local/lib + /opt/local/lib + /usr/lib +) + +find_library( + LIBLZMA_LIBRARY_DEBUG + NAMES + liblzmad lzmad + HINTS + ${LIBLZMA_LIBRARY_HINTS} + PATHS + ${LIBLZMA_LIBRARY_PATHS} +) +find_library( + LIBLZMA_LIBRARY_RELEASE + NAMES + liblzma lzma + HINTS + ${LIBLZMA_LIBRARY_HINTS} + PATHS + ${LIBLZMA_LIBRARY_PATHS} +) + +select_library_configurations(LIBLZMA) + +find_package_handle_standard_args( + LibLZMA + FOUND_VAR LIBLZMA_FOUND + REQUIRED_VARS LIBLZMA_INCLUDE_DIRS LIBLZMA_LIBRARIES +) + +if(LIBLZMA_FOUND AND NOT TARGET LibLZMA::LibLZMA) + add_library(LibLZMA::LibLZMA UNKNOWN IMPORTED) + + if(LIBLZMA_LIBRARY_RELEASE) + set_property(TARGET LibLZMA::LibLZMA APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(LibLZMA::LibLZMA PROPERTIES IMPORTED_LOCATION_RELEASE "${LIBLZMA_LIBRARY_RELEASE}") + endif() + + if(LIBLZMA_LIBRARY_DEBUG) + set_property(TARGET LibLZMA::LibLZMA APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(LibLZMA::LibLZMA PROPERTIES IMPORTED_LOCATION_DEBUG "${LIBLZMA_LIBRARY_DEBUG}") + endif() + + set_target_properties( + LibLZMA::LibLZMA PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES "${LIBLZMA_INCLUDE_DIRS}" + ) +endif() diff --git a/cmake/Findlibxml2.cmake b/cmake/FindLibXml2.cmake similarity index 83% rename from cmake/Findlibxml2.cmake rename to cmake/FindLibXml2.cmake index b8c17d71..da70d4e3 100644 --- a/cmake/Findlibxml2.cmake +++ b/cmake/FindLibXml2.cmake @@ -17,8 +17,8 @@ endforeach() list( APPEND LIBXML2_INCLUDE_HINTS - $ENV{libxml2_DIR}/${CMAKE_INSTALL_INCLUDEDIR}/libxml2 - $ENV{libxml2_DIR}/${CMAKE_INSTALL_INCLUDEDIR} + $ENV{LibXml2_DIR}/${CMAKE_INSTALL_INCLUDEDIR}/libxml2 + $ENV{LibXml2_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) foreach(PATH $ENV{CMAKE_PREFIX_PATH}) @@ -83,7 +83,7 @@ endforeach() list( APPEND LIBXML2_LIBRARY_HINTS - $ENV{LIBXML2_DIR}/${CMAKE_INSTALL_LIBDIR} + $ENV{LibXml2_DIR}/${CMAKE_INSTALL_LIBDIR} ) foreach(PATH $ENV{CMAKE_PREFIX_PATH}) @@ -136,26 +136,26 @@ find_library( select_library_configurations(LIBXML2) find_package_handle_standard_args( - libxml2 - FOUND_VAR LIBXML2_FOUND + LibXml2 + FOUND_VAR LibXml2_FOUND REQUIRED_VARS LIBXML2_INCLUDE_DIRS LIBXML2_LIBRARIES ) -if(LIBXML2_FOUND AND NOT TARGET libxml2::libxml2) - add_library(libxml2::libxml2 UNKNOWN IMPORTED) +if(LibXml2_FOUND AND NOT TARGET LibXml2::LibXml2) + add_library(LibXml2::LibXml2 UNKNOWN IMPORTED) if(LIBXML2_LIBRARY_RELEASE) - set_property(TARGET libxml2::libxml2 APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(libxml2::libxml2 PROPERTIES IMPORTED_LOCATION_RELEASE "${LIBXML2_LIBRARY_RELEASE}") + set_property(TARGET LibXml2::LibXml2 APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(LibXml2::LibXml2 PROPERTIES IMPORTED_LOCATION_RELEASE "${LIBXML2_LIBRARY_RELEASE}") endif() if(LIBXML2_LIBRARY_DEBUG) - set_property(TARGET libxml2::libxml2 APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(libxml2::libxml2 PROPERTIES IMPORTED_LOCATION_DEBUG "${LIBXML2_LIBRARY_DEBUG}") + set_property(TARGET LibXml2::LibXml2 APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(LibXml2::LibXml2 PROPERTIES IMPORTED_LOCATION_DEBUG "${LIBXML2_LIBRARY_DEBUG}") endif() set_target_properties( - libxml2::libxml2 PROPERTIES + LibXml2::LibXml2 PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${LIBXML2_INCLUDE_DIRS}" ) endif() diff --git a/cmake/Findlibxslt.cmake b/cmake/FindLibXslt.cmake similarity index 83% rename from cmake/Findlibxslt.cmake rename to cmake/FindLibXslt.cmake index 88542b99..17722a86 100644 --- a/cmake/Findlibxslt.cmake +++ b/cmake/FindLibXslt.cmake @@ -17,8 +17,8 @@ endforeach() list( APPEND LIBXSLT_INCLUDE_HINTS - $ENV{LIBXSLT_DIR}/${CMAKE_INSTALL_INCLUDEDIR}/libxslt - $ENV{LIBXSLT_DIR}/${CMAKE_INSTALL_INCLUDEDIR} + $ENV{LibXslt_DIR}/${CMAKE_INSTALL_INCLUDEDIR}/libxslt + $ENV{LibXslt_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) foreach(PATH $ENV{CMAKE_PREFIX_PATH}) @@ -81,7 +81,7 @@ endforeach() list( APPEND LIBXSLT_LIBRARY_HINTS - $ENV{LIBXSLT_DIR}/${CMAKE_INSTALL_LIBDIR} + $ENV{LibXslt_DIR}/${CMAKE_INSTALL_LIBDIR} ) foreach(PATH $ENV{CMAKE_PREFIX_PATH}) @@ -130,26 +130,26 @@ find_library( select_library_configurations(LIBXSLT) find_package_handle_standard_args( - libxslt + LibXslt FOUND_VAR LIBXSLT_FOUND REQUIRED_VARS LIBXSLT_INCLUDE_DIRS LIBXSLT_LIBRARIES ) -if(LIBXSLT_FOUND AND NOT TARGET libxslt::libxslt) - add_library(libxslt::libxslt UNKNOWN IMPORTED) +if(LIBXSLT_FOUND AND NOT TARGET LibXslt::LibXslt) + add_library(LibXslt::LibXslt UNKNOWN IMPORTED) if(LIBXSLT_LIBRARY_RELEASE) - set_property(TARGET libxslt::libxslt APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(libxslt::libxslt PROPERTIES IMPORTED_LOCATION_RELEASE "${LIBXSLT_LIBRARY_RELEASE}") + set_property(TARGET LibXslt::LibXslt APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(LibXslt::LibXslt PROPERTIES IMPORTED_LOCATION_RELEASE "${LIBXSLT_LIBRARY_RELEASE}") endif() if(LIBXSLT_LIBRARY_DEBUG) - set_property(TARGET libxslt::libxslt APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(libxslt::libxslt PROPERTIES IMPORTED_LOCATION_DEBUG "${LIBXSLT_LIBRARY_DEBUG}") + set_property(TARGET LibXslt::LibXslt APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(LibXslt::LibXslt PROPERTIES IMPORTED_LOCATION_DEBUG "${LIBXSLT_LIBRARY_DEBUG}") endif() set_target_properties( - libxslt::libxslt PROPERTIES + LibXslt::LibXslt PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${LIBXSLT_INCLUDE_DIRS}" ) endif() diff --git a/cmake/Findzlib.cmake b/cmake/FindZLIB.cmake similarity index 55% rename from cmake/Findzlib.cmake rename to cmake/FindZLIB.cmake index d1666f5a..24557d14 100644 --- a/cmake/Findzlib.cmake +++ b/cmake/FindZLIB.cmake @@ -9,13 +9,13 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} ${PATH}/zlib*/${CMAKE_INSTALL_INCLUDEDIR} ) - list(APPEND zlib_INCLUDE_HINTS ${HINTS}) + list(APPEND ZLIB_INCLUDE_HINTS ${HINTS}) endforeach() list( APPEND - zlib_INCLUDE_HINTS - $ENV{zlib_DIR}/${CMAKE_INSTALL_INCLUDEDIR} + ZLIB_INCLUDE_HINTS + $ENV{ZLIB_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) foreach(PATH $ENV{CMAKE_PREFIX_PATH}) @@ -25,7 +25,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} ${PATH}/zlib*/${CMAKE_INSTALL_INCLUDEDIR} ) - list(APPEND zlib_INCLUDE_HINTS ${HINTS}) + list(APPEND ZLIB_INCLUDE_HINTS ${HINTS}) endforeach() foreach(PATH $ENV{PATH}) @@ -34,12 +34,12 @@ foreach(PATH $ENV{PATH}) HINTS ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} ) - list(APPEND zlib_INCLUDE_HINTS ${HINTS}) + list(APPEND ZLIB_INCLUDE_HINTS ${HINTS}) endforeach() file( GLOB - zlib_INCLUDE_PATHS + ZLIB_INCLUDE_PATHS $ENV{HOME}/include /usr/local/include /opt/local/include @@ -50,16 +50,16 @@ file( ) find_path( - zlib_INCLUDE_DIRS + ZLIB_INCLUDE_DIRS NAMES zlib.h HINTS - ${zlib_INCLUDE_HINTS} + ${ZLIB_INCLUDE_HINTS} PATHS - ${zlib_INCLUDE_PATHS} + ${ZLIB_INCLUDE_PATHS} ) -mark_as_advanced(zlib_INCLUDE_DIRS) +mark_as_advanced(ZLIB_INCLUDE_DIRS) foreach(PATH ${CMAKE_PREFIX_PATH}) file( @@ -68,13 +68,13 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_LIBDIR} ${PATH}/zlib*/${CMAKE_INSTALL_LIBDIR} ) - list(APPEND zlib_LIBRARY_HINTS ${HINTS}) + list(APPEND ZLIB_LIBRARY_HINTS ${HINTS}) endforeach() list( APPEND - zlib_LIBRARY_HINTS - $ENV{zlib_DIR}/${CMAKE_INSTALL_LIBDIR} + ZLIB_LIBRARY_HINTS + $ENV{ZLIB_DIR}/${CMAKE_INSTALL_LIBDIR} ) foreach(PATH $ENV{CMAKE_PREFIX_PATH}) @@ -84,7 +84,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) ${PATH}/${CMAKE_INSTALL_LIBDIR} ${PATH}/zlib*/${CMAKE_INSTALL_LIBDIR} ) - list(APPEND zlib_LIBRARY_HINTS ${HINTS}) + list(APPEND ZLIB_LIBRARY_HINTS ${HINTS}) endforeach() foreach(PATH $ENV{PATH}) @@ -93,12 +93,12 @@ foreach(PATH $ENV{PATH}) HINTS ${PATH}/../${CMAKE_INSTALL_LIBDIR} ) - list(APPEND zlib_LIBRARY_HINTS ${HINTS}) + list(APPEND ZLIB_LIBRARY_HINTS ${HINTS}) endforeach() file( GLOB - zlib_LIBRARY_PATHS + ZLIB_LIBRARY_PATHS $ENV{HOME}/lib /usr/local/lib /opt/local/lib @@ -108,48 +108,48 @@ file( ) find_library( - zlib_LIBRARY_DEBUG + ZLIB_LIBRARY_DEBUG NAMES zd zlibd zlib_ad zlibstaticd zlibwapid zdlld HINTS - ${zlib_LIBRARY_HINTS} + ${ZLIB_LIBRARY_HINTS} PATHS - ${zlib_LIBRARY_PATHS} + ${ZLIB_LIBRARY_PATHS} ) find_library( - zlib_LIBRARY_RELEASE + ZLIB_LIBRARY_RELEASE NAMES z zlib zlib_a zlibstatic zlibwapi zdll HINTS - ${zlib_LIBRARY_HINTS} + ${ZLIB_LIBRARY_HINTS} PATHS - ${zlib_LIBRARY_PATHS} + ${ZLIB_LIBRARY_PATHS} ) -select_library_configurations(zlib) +select_library_configurations(ZLIB) find_package_handle_standard_args( - zlib - FOUND_VAR zlib_FOUND - REQUIRED_VARS zlib_INCLUDE_DIRS zlib_LIBRARIES + ZLIB + FOUND_VAR ZLIB_FOUND + REQUIRED_VARS ZLIB_INCLUDE_DIRS ZLIB_LIBRARIES ) -if(zlib_FOUND AND NOT TARGET zlib::zlib) - add_library(zlib::zlib UNKNOWN IMPORTED) +if(ZLIB_FOUND AND NOT TARGET ZLIB::ZLIB) + add_library(ZLIB::ZLIB UNKNOWN IMPORTED) - if(zlib_LIBRARY_RELEASE) - set_property(TARGET zlib::zlib APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(zlib::zlib PROPERTIES IMPORTED_LOCATION_RELEASE "${zlib_LIBRARY_RELEASE}") + if(ZLIB_LIBRARY_RELEASE) + set_property(TARGET ZLIB::ZLIB APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(ZLIB::ZLIB PROPERTIES IMPORTED_LOCATION_RELEASE "${ZLIB_LIBRARY_RELEASE}") endif() - if(zlib_LIBRARY_DEBUG) - set_property(TARGET zlib::zlib APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(zlib::zlib PROPERTIES IMPORTED_LOCATION_DEBUG "${zlib_LIBRARY_DEBUG}") + if(ZLIB_LIBRARY_DEBUG) + set_property(TARGET ZLIB::ZLIB APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(ZLIB::ZLIB PROPERTIES IMPORTED_LOCATION_DEBUG "${ZLIB_LIBRARY_DEBUG}") endif() set_target_properties( - zlib::zlib PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${zlib_INCLUDE_DIRS}" + ZLIB::ZLIB PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES "${ZLIB_INCLUDE_DIRS}" ) endif() diff --git a/src/rl/xml/CMakeLists.txt b/src/rl/xml/CMakeLists.txt index ea529bdf..f6a4cf6d 100644 --- a/src/rl/xml/CMakeLists.txt +++ b/src/rl/xml/CMakeLists.txt @@ -1,9 +1,10 @@ find_package(Boost REQUIRED) -find_package(libiconv) -find_package(libxml2 REQUIRED) -find_package(libxslt REQUIRED) -find_package(zlib) +find_package(Iconv) +find_package(LibLZMA) +find_package(LibXml2 REQUIRED) +find_package(LibXslt REQUIRED) +find_package(ZLIB) set( HDRS @@ -47,21 +48,30 @@ else() target_link_libraries(xml ${LIBXML2_LIBRARIES} ${LIBXSLT_LIBRARIES}) endif() -if(libiconv_FOUND) - target_include_directories(xml INTERFACE ${libiconv_INCLUDE_DIRS}) +if(Iconv_FOUND) + target_include_directories(xml INTERFACE ${Iconv_INCLUDE_DIRS}) if(NOT CMAKE_VERSION VERSION_LESS 3.0) - target_link_libraries(xml INTERFACE ${libiconv_LIBRARIES}) + target_link_libraries(xml INTERFACE ${Iconv_LIBRARIES}) else() - target_link_libraries(xml ${libiconv_LIBRARIES}) + target_link_libraries(xml ${Iconv_LIBRARIES}) endif() endif() -if(zlib_FOUND) - target_include_directories(xml INTERFACE ${zlib_INCLUDE_DIRS}) +if(LIBLZMA_FOUND) + target_include_directories(xml INTERFACE ${LIBLZMA_INCLUDE_DIRS}) if(NOT CMAKE_VERSION VERSION_LESS 3.0) - target_link_libraries(xml INTERFACE ${zlib_LIBRARIES}) + target_link_libraries(xml INTERFACE ${LIBLZMA_LIBRARIES}) else() - target_link_libraries(xml ${zlib_LIBRARIES}) + target_link_libraries(xml ${LIBLZMA_LIBRARIES}) + endif() +endif() + +if(ZLIB_FOUND) + target_include_directories(xml INTERFACE ${ZLIB_INCLUDE_DIRS}) + if(NOT CMAKE_VERSION VERSION_LESS 3.0) + target_link_libraries(xml INTERFACE ${ZLIB_LIBRARIES}) + else() + target_link_libraries(xml ${ZLIB_LIBRARIES}) endif() endif() From b7f50193071c1ca85ea522c85574674302d9966c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 12 May 2019 23:14:15 +0200 Subject: [PATCH 254/546] Update libiconv CMake patch --- 3rdparty/libiconv/CMakeLists.txt | 2 +- 3rdparty/libiconv/CMakeLists.txt.in | 144 ++++++++++++++------- 3rdparty/libiconv/iconv-config.cmake.in | 38 ++++++ 3rdparty/libiconv/libiconv-config.cmake.in | 12 -- 4 files changed, 136 insertions(+), 60 deletions(-) create mode 100644 3rdparty/libiconv/iconv-config.cmake.in delete mode 100644 3rdparty/libiconv/libiconv-config.cmake.in diff --git a/3rdparty/libiconv/CMakeLists.txt b/3rdparty/libiconv/CMakeLists.txt index 569e9f82..bc696d90 100644 --- a/3rdparty/libiconv/CMakeLists.txt +++ b/3rdparty/libiconv/CMakeLists.txt @@ -15,7 +15,7 @@ ExternalProject_Add( PATCH_COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/CMakeLists.txt.in /CMakeLists.txt && ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/config.h.cmake.in /config.h.cmake.in && - ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/libiconv-config.cmake.in /libiconv-config.cmake.in && + ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/iconv-config.cmake.in /iconv-config.cmake.in && ${PATCH_EXECUTABLE} -p1 -t -N ${PATCH_BINARY} < ${CMAKE_CURRENT_SOURCE_DIR}/libiconv-1.15.patch CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} INSTALL_DIR ${CMAKE_INSTALL_PREFIX} diff --git a/3rdparty/libiconv/CMakeLists.txt.in b/3rdparty/libiconv/CMakeLists.txt.in index b1e8db48..589b2693 100644 --- a/3rdparty/libiconv/CMakeLists.txt.in +++ b/3rdparty/libiconv/CMakeLists.txt.in @@ -21,10 +21,6 @@ function(CHECK_RAW_SYMBOL_EXISTS SYMBOL FILES VARIABLE) check_c_source_compiles("${SOURCE}" "${VARIABLE}") endfunction() -set(CMAKE_IMPORT_LIBRARY_PREFIX "") -set(CMAKE_SHARED_LIBRARY_PREFIX "") -set(CMAKE_STATIC_LIBRARY_PREFIX "") - set(VERSION_MAJOR 1) set(VERSION_MINOR 15) set(VERSION ${VERSION_MAJOR}.${VERSION_MINOR}) @@ -546,13 +542,13 @@ configure_file(include/iconv.h.in include/iconv.h.inst @ONLY) configure_file(libcharset/include/libcharset.h.in include/libcharset.h @ONLY) add_library( - libcharset + Charset libcharset/lib/localcharset.c libcharset/lib/relocatable.c ) target_compile_definitions( - libcharset + Charset PRIVATE -DBUILDING_LIBCHARSET -DHAVE_CONFIG_H @@ -565,46 +561,73 @@ target_compile_definitions( ) if(BUILD_SHARED_LIBS) - target_compile_definitions(libcharset PRIVATE -D_DLL -DBUILDING_DLL) + target_compile_definitions(Charset PRIVATE -D_DLL -DBUILDING_DLL) endif() if(ENABLE_EXTRA) - target_compile_definitions(libcharset PRIVATE -DENABLE_EXTRA=1) + target_compile_definitions(Charset PRIVATE -DENABLE_EXTRA=1) else() - target_compile_definitions(libcharset PRIVATE -DENABLE_EXTRA=0) + target_compile_definitions(Charset PRIVATE -DENABLE_EXTRA=0) endif() if(ENABLE_NLS) - target_compile_definitions(libcharset PRIVATE -DENABLE_NLS=1) + target_compile_definitions(Charset PRIVATE -DENABLE_NLS=1) else() - target_compile_definitions(libcharset PRIVATE -DENABLE_NLS=0) + target_compile_definitions(Charset PRIVATE -DENABLE_NLS=0) endif() if(ENABLE_RELOCATABLE) - target_compile_definitions(libcharset PRIVATE -DENABLE_RELOCATABLE=1) + target_compile_definitions(Charset PRIVATE -DENABLE_RELOCATABLE=1) else() - target_compile_definitions(libcharset PRIVATE -DENABLE_RELOCATABLE=0) + target_compile_definitions(Charset PRIVATE -DENABLE_RELOCATABLE=0) endif() target_include_directories( - libcharset + Charset PUBLIC $ $ $/${CMAKE_INSTALL_INCLUDEDIR}> ) -set_target_properties(libcharset PROPERTIES DEBUG_POSTFIX d VERSION ${VERSION}) +set_target_properties( + Charset + PROPERTIES + IMPORT_PREFIX lib + OUTPUT_NAME charset + POSITION_INDEPENDENT_CODE ON + PREFIX lib + VERSION ${VERSION} +) + +if(WIN32) + if(BUILD_SHARED_LIBS) + set_target_properties( + Charset + PROPERTIES + DEBUG_POSTFIX d + ) + else() + set_target_properties( + Charset + PROPERTIES + DEBUG_POSTFIX sd + MINSIZEREL_POSTFIX s + RELEASE_POSTFIX s + RELWITHDEBINFO_POSTFIX s + ) + endif() +endif() add_library( - libiconv + Iconv lib/iconv.c lib/relocatable.c libcharset/lib/localcharset.c ) target_compile_definitions( - libiconv + Iconv PRIVATE -DBUILDING_LIBICONV -DHAVE_CONFIG_H @@ -617,44 +640,71 @@ target_compile_definitions( ) if(BUILD_SHARED_LIBS) - target_compile_definitions(libiconv PRIVATE -D_DLL -DBUILDING_DLL) + target_compile_definitions(Iconv PRIVATE -D_DLL -DBUILDING_DLL) endif() if(ENABLE_EXTRA) - target_compile_definitions(libiconv PRIVATE -DENABLE_EXTRA=1) + target_compile_definitions(Iconv PRIVATE -DENABLE_EXTRA=1) else() - target_compile_definitions(libiconv PRIVATE -DENABLE_EXTRA=0) + target_compile_definitions(Iconv PRIVATE -DENABLE_EXTRA=0) endif() if(ENABLE_NLS) - target_compile_definitions(libiconv PRIVATE -DENABLE_NLS=1) + target_compile_definitions(Iconv PRIVATE -DENABLE_NLS=1) else() - target_compile_definitions(libiconv PRIVATE -DENABLE_NLS=0) + target_compile_definitions(Iconv PRIVATE -DENABLE_NLS=0) endif() if(ENABLE_RELOCATABLE) - target_compile_definitions(libiconv PRIVATE -DENABLE_RELOCATABLE=1) + target_compile_definitions(Iconv PRIVATE -DENABLE_RELOCATABLE=1) else() - target_compile_definitions(libiconv PRIVATE -DENABLE_RELOCATABLE=0) + target_compile_definitions(Iconv PRIVATE -DENABLE_RELOCATABLE=0) endif() target_include_directories( - libiconv + Iconv PUBLIC $ $ $/${CMAKE_INSTALL_INCLUDEDIR}> ) -target_link_libraries(libiconv libcharset) +target_link_libraries(Iconv Charset) -set_target_properties(libiconv PROPERTIES DEBUG_POSTFIX d VERSION ${VERSION}) +set_target_properties( + Iconv + PROPERTIES + IMPORT_PREFIX lib + OUTPUT_NAME iconv + POSITION_INDEPENDENT_CODE ON + PREFIX lib + VERSION ${VERSION} +) + +if(WIN32) + if(BUILD_SHARED_LIBS) + set_target_properties( + Iconv + PROPERTIES + DEBUG_POSTFIX d + ) + else() + set_target_properties( + Iconv + PROPERTIES + DEBUG_POSTFIX sd + MINSIZEREL_POSTFIX s + RELEASE_POSTFIX s + RELWITHDEBINFO_POSTFIX s + ) + endif() +endif() install(FILES ${CMAKE_CURRENT_BINARY_DIR}/include/iconv.h.inst DESTINATION ${CMAKE_INSTALL_INCLUDEDIR} RENAME iconv.h COMPONENT development) install( - TARGETS libcharset libiconv - EXPORT libiconv + TARGETS Charset Iconv + EXPORT Iconv ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime @@ -662,15 +712,15 @@ install( if(BUILD_SHARED_LIBS) install( - TARGETS libcharset libiconv - EXPORT libiconv + TARGETS Charset Iconv + EXPORT Iconv LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY ) endif() -if(MSVC AND BUILD_SHARED_LIBS AND ${CMAKE_MAJOR_VERSION} GREATER 2 AND ${CMAKE_MINOR_VERSION} GREATER 0) - install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) - install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) +if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) + install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) + install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() #configure_file(srclib/stdbool.in.h include/stdbool.h @ONLY) @@ -745,10 +795,10 @@ endif() # $ #) # -#target_link_libraries(iconv libiconv) +#target_link_libraries(iconv Iconv) # #install( -# TARGETS iconv +# TARGETS iconv # COMPONENT programs # ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} # LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} @@ -770,32 +820,32 @@ install(FILES man/iconv_open_into.3.html DESTINATION ${CMAKE_INSTALL_DATADIR}/do install(FILES man/iconvctl.3.html DESTINATION ${CMAKE_INSTALL_DATADIR}/doc/libiconv COMPONENT documentation) configure_package_config_file( - libiconv-config.cmake.in libiconv-config.cmake - INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/libiconv-${VERSION} + iconv-config.cmake.in iconv-config.cmake + INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/iconv-${VERSION} ) install( - FILES ${CMAKE_CURRENT_BINARY_DIR}/libiconv-config.cmake - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/libiconv-${VERSION} + FILES ${CMAKE_CURRENT_BINARY_DIR}/iconv-config.cmake + DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/iconv-${VERSION} ) write_basic_package_version_file( - ${CMAKE_CURRENT_BINARY_DIR}/libiconv-config-version.cmake + ${CMAKE_CURRENT_BINARY_DIR}/iconv-config-version.cmake VERSION ${VERSION} COMPATIBILITY ExactVersion ) install( - FILES ${CMAKE_CURRENT_BINARY_DIR}/libiconv-config-version.cmake - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/libiconv-${VERSION} + FILES ${CMAKE_CURRENT_BINARY_DIR}/iconv-config-version.cmake + DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/iconv-${VERSION} COMPONENT development ) install( - EXPORT libiconv - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/libiconv-${VERSION} - NAMESPACE libiconv:: - FILE libiconv-export.cmake + EXPORT Iconv + DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/iconv-${VERSION} + NAMESPACE Iconv:: + FILE iconv-export.cmake COMPONENT development ) diff --git a/3rdparty/libiconv/iconv-config.cmake.in b/3rdparty/libiconv/iconv-config.cmake.in new file mode 100644 index 00000000..84023c6e --- /dev/null +++ b/3rdparty/libiconv/iconv-config.cmake.in @@ -0,0 +1,38 @@ +set(Iconv_VERSION "@VERSION@") +set(Iconv_VERSION_MAJOR "@VERSION_MAJOR@") +set(Iconv_VERSION_MINOR "@VERSION_MINOR@") + +@PACKAGE_INIT@ + +include("${CMAKE_CURRENT_LIST_DIR}/iconv-export.cmake") + +set(Iconv_DEFINITIONS "") +set(Iconv_INCLUDE_DIRS "${PACKAGE_PREFIX_DIR}/@CMAKE_INSTALL_INCLUDEDIR@") +set(Iconv_LIBRARY_DIRS "${PACKAGE_PREFIX_DIR}/@CMAKE_INSTALL_LIBDIR@") + +macro(select_library_location target basename) + foreach(property IN ITEMS IMPORTED_LOCATION IMPORTED_IMPLIB) + get_target_property(${basename}_${property}_DEBUG ${target} ${property}_DEBUG) + get_target_property(${basename}_${property}_MINSIZEREL ${target} ${property}_MINSIZEREL) + get_target_property(${basename}_${property}_RELEASE ${target} ${property}_RELEASE) + get_target_property(${basename}_${property}_RELWITHDEBINFO ${target} ${property}_RELWITHDEBINFO) + + if(${basename}_${property}_DEBUG AND ${basename}_${property}_RELEASE) + set(${basename}_LIBRARIES debug ${${basename}_${property}_DEBUG} optimized ${${basename}_${property}_RELEASE}) + elseif(${basename}_${property}_DEBUG AND ${basename}_${property}_RELWITHDEBINFO) + set(${basename}_LIBRARIES debug ${${basename}_${property}_DEBUG} optimized ${${basename}_${property}_RELWITHDEBINFO}) + elseif(${basename}_${property}_DEBUG AND ${basename}_${property}_MINSIZEREL) + set(${basename}_LIBRARIES debug ${${basename}_${property}_DEBUG} optimized ${${basename}_${property}_MINSIZEREL}) + elseif(${basename}_${property}_RELEASE) + set(${basename}_LIBRARIES ${${basename}_${property}_RELEASE}) + elseif(${basename}_${property}_RELWITHDEBINFO) + set(${basename}_LIBRARIES ${${basename}_${property}_RELWITHDEBINFO}) + elseif(${basename}_${property}_MINSIZEREL) + set(${basename}_LIBRARIES ${${basename}_${property}_MINSIZEREL}) + elseif(${basename}_${property}_DEBUG) + set(${basename}_LIBRARIES ${${basename}_${property}_DEBUG}) + endif() + endforeach() +endmacro() + +select_library_location(Iconv::Iconv Iconv) diff --git a/3rdparty/libiconv/libiconv-config.cmake.in b/3rdparty/libiconv/libiconv-config.cmake.in deleted file mode 100644 index 39eff3ae..00000000 --- a/3rdparty/libiconv/libiconv-config.cmake.in +++ /dev/null @@ -1,12 +0,0 @@ -set(libiconv_VERSION "@VERSION@") -set(libiconv_VERSION_MAJOR "@VERSION_MAJOR@") -set(libiconv_VERSION_MINOR "@VERSION_MINOR@") - -@PACKAGE_INIT@ - -include("${CMAKE_CURRENT_LIST_DIR}/libiconv-export.cmake") - -set(libiconv_DEFINITIONS "") -set(libiconv_INCLUDE_DIRS "") -set(libiconv_LIBRARY_DIRS "") -set(libiconv_LIBRARIES "libiconv::libiconv") From 25f186517c2fae6d179b0e72bff81473b5b09b90 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 12 May 2019 23:39:02 +0200 Subject: [PATCH 255/546] Update NLopt to 2.6.1 --- 3rdparty/nlopt/CMakeLists.txt | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/3rdparty/nlopt/CMakeLists.txt b/3rdparty/nlopt/CMakeLists.txt index 62916a00..dee075c1 100644 --- a/3rdparty/nlopt/CMakeLists.txt +++ b/3rdparty/nlopt/CMakeLists.txt @@ -7,10 +7,10 @@ include(ExternalProject) ExternalProject_Add( nlopt #GIT_REPOSITORY git://github.com/stevengj/nlopt.git - #GIT_TAG 2.5.0 - URL https://github.com/stevengj/nlopt/archive/v2.5.0.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/nlopt-2.5.0.zip - URL_MD5 229ac19157563c76b1b1c28ef3f3f7d0 - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_DEBUG_POSTFIX=d -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_SHARED_LIBS=ON -DNLOPT_GUILE=OFF -DNLOPT_MATLAB=OFF -DNLOPT_OCTAVE=OFF -DNLOPT_PYTHON=OFF -DNLOPT_SWIG=OFF + #GIT_TAG 2.6.1 + URL https://github.com/stevengj/nlopt/archive/v2.6.1.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/nlopt-2.6.1.zip + URL_MD5 66ddf7088aeeef969972bc7061779805 + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_DEBUG_POSTFIX=d -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_SHARED_LIBS=ON -DNLOPT_GUILE=OFF -DNLOPT_MATLAB=OFF -DNLOPT_OCTAVE=OFF -DNLOPT_PYTHON=OFF -DNLOPT_SWIG=OFF -DNLOPT_TESTS=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From 78919a42250c0ef381bfd4a00a1672659211443e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 17 May 2019 22:23:21 +0200 Subject: [PATCH 256/546] Update libiconv CMake patch --- 3rdparty/libiconv/CMakeLists.txt.in | 113 ++++++++++++++-------------- 1 file changed, 58 insertions(+), 55 deletions(-) diff --git a/3rdparty/libiconv/CMakeLists.txt.in b/3rdparty/libiconv/CMakeLists.txt.in index 589b2693..2b6736c7 100644 --- a/3rdparty/libiconv/CMakeLists.txt.in +++ b/3rdparty/libiconv/CMakeLists.txt.in @@ -26,6 +26,9 @@ set(VERSION_MINOR 15) set(VERSION ${VERSION_MAJOR}.${VERSION_MINOR}) option(BUILD_SHARED_LIBS "Build shared libraries" ON) +option(LIBICONV_ENABLE_EXTRA "Enable a few rarely used encodings" OFF) +option(LIBICONV_ENABLE_NLS "Translate program messages to user's native language" OFF) +option(LIBICONV_ENABLE_RELOCATABLE "Install a package that can be moved in the file system" ON) check_type_size("ptrdiff_t" BITSIZEOF_PTRDIFF_T) set(CMAKE_EXTRA_INCLUDE_FILES "signal.h") @@ -41,9 +44,9 @@ check_symbol_exists(EILSEQ "errno.h" HAVE_EILSEQ) if(NOT HAVE_EILSEQ) set(EILSEQ "ENOENT") endif() -option(ENABLE_EXTRA "Enable a few rarely used encodings" OFF) -option(ENABLE_NLS "Translate program messages to user's native language" OFF) -option(ENABLE_RELOCATABLE "Install a package that can be moved in the file system" ON) +set(ENABLE_EXTRA ${LIBICONV_ENABLE_EXTRA}) +set(ENABLE_NLS ${LIBICONV_ENABLE_NLS}) +set(ENABLE_RELOCATABLE ${LIBICONV_ENABLE_RELOCATABLE}) check_c_source_runs(" #include static void exception_handler(int sig) { exit (1); } @@ -550,36 +553,36 @@ add_library( target_compile_definitions( Charset PRIVATE - -DBUILDING_LIBCHARSET - -DHAVE_CONFIG_H - -DIN_LIBRARY - -DINSTALLDIR="${CMAKE_INSTALL_LIBDIR}" - -DLIBDIR="${CMAKE_INSTALL_LIBDIR}" - -DNO_XMALLOC - -Drelocate=libcharset_relocate - -Dset_relocation_prefix=libcharset_set_relocation_prefix + BUILDING_LIBCHARSET + HAVE_CONFIG_H + IN_LIBRARY + INSTALLDIR="${CMAKE_INSTALL_LIBDIR}" + LIBDIR="${CMAKE_INSTALL_LIBDIR}" + NO_XMALLOC + relocate=libcharset_relocate + set_relocation_prefix=libcharset_set_relocation_prefix ) if(BUILD_SHARED_LIBS) - target_compile_definitions(Charset PRIVATE -D_DLL -DBUILDING_DLL) + target_compile_definitions(Charset PRIVATE _DLL BUILDING_DLL) endif() -if(ENABLE_EXTRA) - target_compile_definitions(Charset PRIVATE -DENABLE_EXTRA=1) +if(LIBICONV_ENABLE_EXTRA) + target_compile_definitions(Charset PRIVATE ENABLE_EXTRA=1) else() - target_compile_definitions(Charset PRIVATE -DENABLE_EXTRA=0) + target_compile_definitions(Charset PRIVATE ENABLE_EXTRA=0) endif() -if(ENABLE_NLS) - target_compile_definitions(Charset PRIVATE -DENABLE_NLS=1) +if(LIBICONV_ENABLE_NLS) + target_compile_definitions(Charset PRIVATE ENABLE_NLS=1) else() - target_compile_definitions(Charset PRIVATE -DENABLE_NLS=0) + target_compile_definitions(Charset PRIVATE ENABLE_NLS=0) endif() -if(ENABLE_RELOCATABLE) - target_compile_definitions(Charset PRIVATE -DENABLE_RELOCATABLE=1) +if(LIBICONV_ENABLE_RELOCATABLE) + target_compile_definitions(Charset PRIVATE ENABLE_RELOCATABLE=1) else() - target_compile_definitions(Charset PRIVATE -DENABLE_RELOCATABLE=0) + target_compile_definitions(Charset PRIVATE ENABLE_RELOCATABLE=0) endif() target_include_directories( @@ -629,36 +632,36 @@ add_library( target_compile_definitions( Iconv PRIVATE - -DBUILDING_LIBICONV - -DHAVE_CONFIG_H - -DIN_LIBRARY - -DINSTALLDIR="${CMAKE_INSTALL_LIBDIR}" - -DLIBDIR="${CMAKE_INSTALL_LIBDIR}" - -DNO_XMALLOC - -Drelocate=libiconv_relocate - -Dset_relocation_prefix=libiconv_set_relocation_prefix + BUILDING_LIBICONV + HAVE_CONFIG_H + IN_LIBRARY + INSTALLDIR="${CMAKE_INSTALL_LIBDIR}" + LIBDIR="${CMAKE_INSTALL_LIBDIR}" + NO_XMALLOC + relocate=libiconv_relocate + set_relocation_prefix=libiconv_set_relocation_prefix ) if(BUILD_SHARED_LIBS) - target_compile_definitions(Iconv PRIVATE -D_DLL -DBUILDING_DLL) + target_compile_definitions(Iconv PRIVATE _DLL BUILDING_DLL) endif() -if(ENABLE_EXTRA) - target_compile_definitions(Iconv PRIVATE -DENABLE_EXTRA=1) +if(LIBICONV_ENABLE_EXTRA) + target_compile_definitions(Iconv PRIVATE ENABLE_EXTRA=1) else() - target_compile_definitions(Iconv PRIVATE -DENABLE_EXTRA=0) + target_compile_definitions(Iconv PRIVATE ENABLE_EXTRA=0) endif() -if(ENABLE_NLS) - target_compile_definitions(Iconv PRIVATE -DENABLE_NLS=1) +if(LIBICONV_ENABLE_NLS) + target_compile_definitions(Iconv PRIVATE ENABLE_NLS=1) else() - target_compile_definitions(Iconv PRIVATE -DENABLE_NLS=0) + target_compile_definitions(Iconv PRIVATE ENABLE_NLS=0) endif() -if(ENABLE_RELOCATABLE) - target_compile_definitions(Iconv PRIVATE -DENABLE_RELOCATABLE=1) +if(LIBICONV_ENABLE_RELOCATABLE) + target_compile_definitions(Iconv PRIVATE ENABLE_RELOCATABLE=1) else() - target_compile_definitions(Iconv PRIVATE -DENABLE_RELOCATABLE=0) + target_compile_definitions(Iconv PRIVATE ENABLE_RELOCATABLE=0) endif() target_include_directories( @@ -760,31 +763,31 @@ endif() #target_compile_definitions( # iconv # PRIVATE -# -DEXEEXT="${CMAKE_EXECUTABLE_SUFFIX}" -# -DINSTALLDIR="${CMAKE_INSTALL_BINDIR}" -# -DINSTALLPREFIX="${CMAKE_INSTALL_PREFIX}" -# -DLIBPATHVAR="" -# -DLIBDIRS="" -# -DLOCALEDIR="${CMAKE_INSTALL_LOCALEDIR}" -# -DNO_XMALLOC +# EXEEXT="${CMAKE_EXECUTABLE_SUFFIX}" +# INSTALLDIR="${CMAKE_INSTALL_BINDIR}" +# INSTALLPREFIX="${CMAKE_INSTALL_PREFIX}" +# LIBPATHVAR="" +# LIBDIRS="" +# LOCALEDIR="${CMAKE_INSTALL_LOCALEDIR}" +# NO_XMALLOC #) # -#if(ENABLE_EXTRA) -# target_compile_definitions(iconv PRIVATE -DENABLE_EXTRA=1) +#if(LIBICONV_ENABLE_EXTRA) +# target_compile_definitions(iconv PRIVATE ENABLE_EXTRA=1) #else() -# target_compile_definitions(iconv PRIVATE -DENABLE_EXTRA=0) +# target_compile_definitions(iconv PRIVATE ENABLE_EXTRA=0) #endif() # -#if(ENABLE_NLS) -# target_compile_definitions(iconv PRIVATE -DENABLE_NLS=1) +#if(LIBICONV_ENABLE_NLS) +# target_compile_definitions(iconv PRIVATE ENABLE_NLS=1) #else() -# target_compile_definitions(iconv PRIVATE -DENABLE_NLS=0) +# target_compile_definitions(iconv PRIVATE ENABLE_NLS=0) #endif() # -#if(ENABLE_RELOCATABLE) -# target_compile_definitions(iconv PRIVATE -DENABLE_RELOCATABLE=1) +#if(LIBICONV_ENABLE_RELOCATABLE) +# target_compile_definitions(iconv PRIVATE ENABLE_RELOCATABLE=1) #else() -# target_compile_definitions(iconv PRIVATE -DENABLE_RELOCATABLE=0) +# target_compile_definitions(iconv PRIVATE ENABLE_RELOCATABLE=0) #endif() # #target_include_directories( From 68401b94051733b6a6201546643737fc811e0cdd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 18 May 2019 00:14:01 +0200 Subject: [PATCH 257/546] Add CMake ExternalProject for xz --- 3rdparty/CMakeLists.txt | 2 ++ 3rdparty/libxml2/CMakeLists.txt | 2 +- 3rdparty/xz/CMakeLists.txt | 16 ++++++++++++++++ 3 files changed, 19 insertions(+), 1 deletion(-) create mode 100644 3rdparty/xz/CMakeLists.txt diff --git a/3rdparty/CMakeLists.txt b/3rdparty/CMakeLists.txt index 5da37e1b..454d65cd 100644 --- a/3rdparty/CMakeLists.txt +++ b/3rdparty/CMakeLists.txt @@ -42,6 +42,7 @@ add_subdirectory(ode) add_subdirectory(pqp) add_subdirectory(coin3d/simage) add_subdirectory(solid) +add_subdirectory(xz) add_subdirectory(zlib) add_subdirectory(libxml2) @@ -65,6 +66,7 @@ set( "${CMAKE_CURRENT_BINARY_DIR}/simage/simage-prefix/src/simage-build;simage;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/solid/solid-prefix/src/solid-build;solid;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/soqt/soqt-prefix/src/soqt-build;soqt;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/xz/xz-prefix/src/xz-build;xz;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/zlib/zlib-prefix/src/zlib-build;zlib;ALL;/" ) diff --git a/3rdparty/libxml2/CMakeLists.txt b/3rdparty/libxml2/CMakeLists.txt index 71c50e8a..b2e7b472 100644 --- a/3rdparty/libxml2/CMakeLists.txt +++ b/3rdparty/libxml2/CMakeLists.txt @@ -4,7 +4,7 @@ list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) ExternalProject_Add( libxml2 - DEPENDS libiconv zlib + DEPENDS libiconv xz zlib #GIT_REPOSITORY git://git.gnome.org/libxml2 #GIT_TAG v2.9.5 URL https://github.com/roboticslibrary/libxml2/archive/patch.zip diff --git a/3rdparty/xz/CMakeLists.txt b/3rdparty/xz/CMakeLists.txt new file mode 100644 index 00000000..eaa3338e --- /dev/null +++ b/3rdparty/xz/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 2.8.11) + +project(xz) + +include(ExternalProject) + +ExternalProject_Add( + xz + #GIT_REPOSITORY https://git.tukaani.org/xz.git + #GIT_TAG v5.2.3 + URL https://github.com/roboticslibrary/xz/archive/patch.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/xz-5.2.3.tar.gz + #URL_MD5 ef68674fb47a8b8e741b34e429d86e9d + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) From 1e41cb48892d3333bd58e9317d28bf7dd00024b6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 18 May 2019 00:18:07 +0200 Subject: [PATCH 258/546] Update 3rdparty CPACK_INSTALL_CMAKE_PROJECTS --- 3rdparty/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/CMakeLists.txt b/3rdparty/CMakeLists.txt index 454d65cd..39802d03 100644 --- a/3rdparty/CMakeLists.txt +++ b/3rdparty/CMakeLists.txt @@ -55,7 +55,9 @@ set( CPACK_INSTALL_CMAKE_PROJECTS "${CMAKE_CURRENT_BINARY_DIR}/atidaq/atidaq-prefix/src/atidaq-build;atidaq;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/bullet/bullet-prefix/src/bullet-build;bullet;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/coin/coin-prefix/src/coin-build;coin;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/coin3d/coin/coin-prefix/src/coin-build;coin;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/coin3d/simage/simage-prefix/src/simage-build;simage;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/coin3d/soqt/soqt-prefix/src/soqt-build;soqt;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/eigen/eigen-prefix/src/eigen-build;eigen;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/libiconv/libiconv-prefix/src/libiconv-build;libiconv;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/libxml2/libxml2-prefix/src/libxml2-build;libxml2;ALL;/" @@ -63,9 +65,7 @@ set( "${CMAKE_CURRENT_BINARY_DIR}/nlopt/nlopt-prefix/src/nlopt-build;nlopt;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/ode/ode-prefix/src/ode-build;ode;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/pqp/pqp-prefix/src/pqp-build;pqp;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/simage/simage-prefix/src/simage-build;simage;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/solid/solid-prefix/src/solid-build;solid;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/soqt/soqt-prefix/src/soqt-build;soqt;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/xz/xz-prefix/src/xz-build;xz;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/zlib/zlib-prefix/src/zlib-build;zlib;ALL;/" ) From 670c838fc9c91723fcb341111d2b69c992524bdf Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 18 May 2019 00:32:09 +0200 Subject: [PATCH 259/546] Add debug postfix on WIN32 --- extras/wrlview/CMakeLists.txt | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 0c1c6892..fdad220d 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -63,6 +63,14 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) VERSION 0.1.13 ) + if(WIN32) + set_target_properties( + wrlview + PROPERTIES + DEBUG_POSTFIX d + ) + endif() + install( TARGETS wrlview From 5888698804fed8cafa8abd5fab5e4b1fa7094757 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 18 May 2019 01:15:27 +0200 Subject: [PATCH 260/546] Update Debian and RPM packages --- cmake/CPackConfig.cmake | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/cmake/CPackConfig.cmake b/cmake/CPackConfig.cmake index 4e92434d..00552cc5 100644 --- a/cmake/CPackConfig.cmake +++ b/cmake/CPackConfig.cmake @@ -187,7 +187,7 @@ if(CCD_INCLUDE_DIRS AND CCD_LIBRARY_RELEASE) list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libccd-devel") endif() if(Coin_INCLUDE_DIRS AND Coin_LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libcoin60-dev | libcoin80-dev") + list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libcoin-dev | libcoin80-dev | libcoin60-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "Coin3-devel") endif() if(Comedi_INCLUDE_DIRS AND Comedi_LIBRARY_RELEASE) @@ -209,13 +209,17 @@ if(libdc1394_V2_INCLUDE_DIRS AND libdc1394_V2_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libdc1394-22-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libdc1394-devel") endif() +if(LIBLZMA_INCLUDE_DIRS AND LIBLZMA_LIBRARY_RELEASE) + list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "liblzma-dev") + list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "lzma-devel") +endif() if(LIBXML2_INCLUDE_DIRS AND LIBXML2_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libxml2-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libxml2-devel") endif() -if(LIBXSLT__INCLUDE_DIRS AND LIBXSLT__LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "LIBXSLT_1-dev") - list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "LIBXSLT_-devel") +if(LIBXSLT_INCLUDE_DIRS AND LIBXSLT_LIBRARY_RELEASE) + list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libxslt1-dev") + list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libxslt-devel") endif() if(NLopt_INCLUDE_DIRS AND NLopt_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libnlopt-dev") From fd5f77fe6453c417606c775271442fe6597191b7 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 19 May 2019 21:04:45 +0200 Subject: [PATCH 261/546] Fix parent of colliding vertices node --- demos/rlPlanDemo/Viewer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/rlPlanDemo/Viewer.cpp b/demos/rlPlanDemo/Viewer.cpp index 4754d394..434840d1 100644 --- a/demos/rlPlanDemo/Viewer.cpp +++ b/demos/rlPlanDemo/Viewer.cpp @@ -370,7 +370,7 @@ Viewer::Viewer(QWidget* parent, Qt::WindowFlags f) : this->verticesColliding->addChild(this->verticesCollidingShape); - this->root->addChild(this->verticesColliding); + this->vertices->addChild(this->verticesColliding); // verticesFree From 11bec7b5ea98cb7b39f1b829199112c717b96604 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 20 May 2019 12:05:11 +0200 Subject: [PATCH 262/546] Update CMake find_package modules --- cmake/FindBullet.cmake | 18 +++++++----------- cmake/FindEigen3.cmake | 16 ++-------------- cmake/FindLibXml2.cmake | 13 ++----------- cmake/FindLibXslt.cmake | 17 ++++++----------- cmake/FindcifX.cmake | 16 ++++++---------- 5 files changed, 23 insertions(+), 57 deletions(-) diff --git a/cmake/FindBullet.cmake b/cmake/FindBullet.cmake index 840b5200..cdb51f99 100644 --- a/cmake/FindBullet.cmake +++ b/cmake/FindBullet.cmake @@ -6,9 +6,7 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/bullet ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Bullet*/${CMAKE_INSTALL_INCLUDEDIR}/bullet ${PATH}/Bullet*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND BULLET_INCLUDE_HINTS ${HINTS}) @@ -17,7 +15,6 @@ endforeach() list( APPEND BULLET_INCLUDE_HINTS - $ENV{Bullet_DIR}/${CMAKE_INSTALL_INCLUDEDIR}/bullet $ENV{Bullet_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) @@ -25,9 +22,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/bullet ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Bullet*/${CMAKE_INSTALL_INCLUDEDIR}/bullet ${PATH}/Bullet*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND BULLET_INCLUDE_HINTS ${HINTS}) @@ -37,7 +32,6 @@ foreach(PATH $ENV{PATH}) file( GLOB HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR}/bullet ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND BULLET_INCLUDE_HINTS ${HINTS}) @@ -46,11 +40,11 @@ endforeach() file( GLOB BULLET_INCLUDE_PATHS - $ENV{BULLET_ROOT_DIR}/include/bullet - $ENV{HOME}/include/bullet - /usr/local/include/bullet - /opt/local/include/bullet - /usr/include/bullet + $ENV{BULLET_ROOT_DIR}/include + $ENV{HOME}/include + /usr/local/include + /opt/local/include + /usr/include ) find_path( @@ -61,6 +55,8 @@ find_path( ${BULLET_INCLUDE_HINTS} PATHS ${BULLET_INCLUDE_PATHS} + PATH_SUFFIXES + bullet ) mark_as_advanced(BULLET_INCLUDE_DIRS) diff --git a/cmake/FindEigen3.cmake b/cmake/FindEigen3.cmake index 8efb2abe..f33a828c 100644 --- a/cmake/FindEigen3.cmake +++ b/cmake/FindEigen3.cmake @@ -6,9 +6,7 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/eigen3 ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Eigen*/${CMAKE_INSTALL_INCLUDEDIR}/eigen3 ${PATH}/Eigen*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND EIGEN3_INCLUDE_HINTS ${HINTS}) @@ -17,7 +15,6 @@ endforeach() list( APPEND EIGEN3_INCLUDE_HINTS - $ENV{Eigen3_DIR}/${CMAKE_INSTALL_INCLUDEDIR}/eigen3 $ENV{Eigen3_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) @@ -25,9 +22,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/eigen3 ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Eigen*/${CMAKE_INSTALL_INCLUDEDIR}/eigen3 ${PATH}/Eigen*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND EIGEN3_INCLUDE_HINTS ${HINTS}) @@ -37,7 +32,6 @@ foreach(PATH $ENV{PATH}) file( GLOB HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR}/eigen3 ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND EIGEN3_INCLUDE_HINTS ${HINTS}) @@ -46,21 +40,13 @@ endforeach() file( GLOB EIGEN3_INCLUDE_PATHS - $ENV{EIGEN3_ROOT}/include/eigen3 $ENV{EIGEN3_ROOT}/include $ENV{EIGEN3_ROOT} - $ENV{EIGEN3_ROOT_DIR}/include/eigen3 $ENV{EIGEN3_ROOT_DIR}/include $ENV{EIGEN3_ROOT_DIR} $ENV{HOME}/include - /usr/local/include/eigen3 - /usr/local/include/eigen* /usr/local/include - /opt/local/include/eigen3 - /opt/local/include/eigen* /opt/local/include - /usr/include/eigen3 - /usr/include/eigen* /usr/include ) @@ -72,6 +58,8 @@ find_path( ${EIGEN3_INCLUDE_HINTS} PATHS ${EIGEN3_INCLUDE_PATHS} + PATH_SUFFIXES + eigen3 ) mark_as_advanced(EIGEN3_INCLUDE_DIRS) diff --git a/cmake/FindLibXml2.cmake b/cmake/FindLibXml2.cmake index da70d4e3..b73b4704 100644 --- a/cmake/FindLibXml2.cmake +++ b/cmake/FindLibXml2.cmake @@ -6,9 +6,7 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/libxml2 ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libxml2*/${CMAKE_INSTALL_INCLUDEDIR}/libxml2 ${PATH}/libxml2*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND LIBXML2_INCLUDE_HINTS ${HINTS}) @@ -17,7 +15,6 @@ endforeach() list( APPEND LIBXML2_INCLUDE_HINTS - $ENV{LibXml2_DIR}/${CMAKE_INSTALL_INCLUDEDIR}/libxml2 $ENV{LibXml2_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) @@ -25,9 +22,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/libxml2 ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libxml2*/${CMAKE_INSTALL_INCLUDEDIR}/libxml2 ${PATH}/libxml2*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND LIBXML2_INCLUDE_HINTS ${HINTS}) @@ -37,7 +32,6 @@ foreach(PATH $ENV{PATH}) file( GLOB HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR}/libxml2 ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND LIBXML2_INCLUDE_HINTS ${HINTS}) @@ -46,15 +40,10 @@ endforeach() file( GLOB LIBXML2_INCLUDE_PATHS - $ENV{HOME}/include/libxml2 $ENV{HOME}/include - /usr/local/include/libxml2 /usr/local/include - /opt/local/include/libxml2 /opt/local/include - /usr/include/libxml2 /usr/include - ${CMAKE_OSX_SYSROOT}/usr/include/libxml2 ${CMAKE_OSX_SYSROOT}/usr/include ) @@ -66,6 +55,8 @@ find_path( ${LIBXML2_INCLUDE_HINTS} PATHS ${LIBXML2_INCLUDE_PATHS} + PATH_SUFFIXES + libxml2 ) mark_as_advanced(LIBXML2_INCLUDE_DIRS) diff --git a/cmake/FindLibXslt.cmake b/cmake/FindLibXslt.cmake index 17722a86..17e0504e 100644 --- a/cmake/FindLibXslt.cmake +++ b/cmake/FindLibXslt.cmake @@ -6,9 +6,7 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/libxslt ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libxslt*/${CMAKE_INSTALL_INCLUDEDIR}/libxslt ${PATH}/libxslt*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND LIBXSLT_INCLUDE_HINTS ${HINTS}) @@ -17,7 +15,6 @@ endforeach() list( APPEND LIBXSLT_INCLUDE_HINTS - $ENV{LibXslt_DIR}/${CMAKE_INSTALL_INCLUDEDIR}/libxslt $ENV{LibXslt_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) @@ -25,9 +22,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/libxslt ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libxslt*/${CMAKE_INSTALL_INCLUDEDIR}/libxslt ${PATH}/libxslt*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND LIBXSLT_INCLUDE_HINTS ${HINTS}) @@ -37,7 +32,6 @@ foreach(PATH $ENV{PATH}) file( GLOB HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR}/libxslt ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND LIBXSLT_INCLUDE_HINTS ${HINTS}) @@ -46,15 +40,10 @@ endforeach() file( GLOB LIBXSLT_INCLUDE_PATHS - $ENV{HOME}/include/libxslt $ENV{HOME}/include - /usr/local/include/libxslt /usr/local/include - /opt/local/include/libxslt /opt/local/include - /usr/include/libxslt /usr/include - ${CMAKE_OSX_SYSROOT}/usr/include/libxslt ${CMAKE_OSX_SYSROOT}/usr/include ) @@ -63,6 +52,8 @@ find_path( NAMES libxslt/xslt.h HINTS + ${LIBXSLT_INCLUDE_HINTS} + PATHS ${LIBXSLT_INCLUDE_PATHS} ) @@ -117,6 +108,8 @@ find_library( NAMES libxsltd xsltd HINTS + ${LIBXSLT_LIBRARY_HINTS} + PATHS ${LIBXSLT_LIBRARY_PATHS} ) find_library( @@ -124,6 +117,8 @@ find_library( NAMES libxslt xslt HINTS + ${LIBXSLT_LIBRARY_HINTS} + PATHS ${LIBXSLT_LIBRARY_PATHS} ) diff --git a/cmake/FindcifX.cmake b/cmake/FindcifX.cmake index 25548430..3f416423 100644 --- a/cmake/FindcifX.cmake +++ b/cmake/FindcifX.cmake @@ -6,9 +6,7 @@ foreach(PATH ${CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/cifx ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/cifX*/${CMAKE_INSTALL_INCLUDEDIR}/cifx ${PATH}/cifX*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND cifX_INCLUDE_HINTS ${HINTS}) @@ -17,7 +15,6 @@ endforeach() list( APPEND cifX_INCLUDE_HINTS - $ENV{cifX_DIR}/${CMAKE_INSTALL_INCLUDEDIR}/cifx $ENV{cifX_DIR}/${CMAKE_INSTALL_INCLUDEDIR} ) @@ -25,9 +22,7 @@ foreach(PATH $ENV{CMAKE_PREFIX_PATH}) file( GLOB HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR}/cifx ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/cifX*/${CMAKE_INSTALL_INCLUDEDIR}/cifx ${PATH}/cifX*/${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND cifX_INCLUDE_HINTS ${HINTS}) @@ -37,7 +32,6 @@ foreach(PATH $ENV{PATH}) file( GLOB HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR}/cifx ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} ) list(APPEND cifX_INCLUDE_HINTS ${HINTS}) @@ -50,12 +44,14 @@ find_path( HINTS ${cifX_INCLUDE_HINTS} PATHS - $ENV{HOME}/include/cifx - /usr/local/include/cifx - /opt/local/include/cifx - /usr/include/cifx + $ENV{HOME}/include + /usr/local/include + /opt/local/include + /usr/include "$ENV{ProgramW6432}/cifX Device Driver/SDK/includes" "$ENV{ProgramFiles}/cifX Device Driver/SDK/includes" + PATH_SUFFIXES + cifx ) mark_as_advanced(cifX_INCLUDE_DIRS) From e872bd0624ddc613808d2ac896883593cb9b7879 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 22 May 2019 16:27:40 +0200 Subject: [PATCH 263/546] Update dynamics demos and tests --- demos/rlDynamics2Demo/rlDynamics2Demo.cpp | 51 +++++----- tests/rlDynamicsTest/rlDynamicsTest.cpp | 114 +++++++++++----------- 2 files changed, 86 insertions(+), 79 deletions(-) diff --git a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp index 56192075..30243b97 100644 --- a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp +++ b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp @@ -64,12 +64,9 @@ main(int argc, char** argv) rl::math::Vector g(3); dynamic->getWorldGravity(g); - rl::math::Vector tmp(dynamic->getDof()); - rl::math::Vector tmp2(6 * dynamic->getOperationalDof()); - std::cout << "===============================================================================" << std::endl; - // FP + // forward position dynamic->setPosition(q); dynamic->forwardPosition(); @@ -79,7 +76,7 @@ main(int argc, char** argv) std::cout << "===============================================================================" << std::endl; - // FV + // forward velocity dynamic->setPosition(q); dynamic->setVelocity(qd); @@ -91,23 +88,28 @@ main(int argc, char** argv) // J rl::math::Matrix J(6 * dynamic->getOperationalDof(), dynamic->getDof()); - dynamic->calculateJacobian(J); + dynamic->calculateJacobian(J, false); std::cout << "J = " << std::endl << J << std::endl; // J * qd - tmp2 = J * qd; - std::cout << "xd = " << tmp2.transpose() << std::endl; + rl::math::Vector Jqd = J * qd; + std::cout << "xd = J * qd = " << Jqd.transpose() << std::endl; - // invJ + // J^{-1} rl::math::Matrix invJ(dynamic->getDof(), 6 * dynamic->getOperationalDof()); dynamic->calculateJacobianInverse(J, invJ); std::cout << "J^{-1} = " << std::endl << invJ << std::endl; + // J^{-1} * xd + + rl::math::Vector invJxd = invJ * Jqd; + std::cout << "qd = J^{-1} * xd = " << invJxd.transpose() << std::endl; + std::cout << "===============================================================================" << std::endl; - // FA + // forward acceleration dynamic->setPosition(q); dynamic->setVelocity(qd); @@ -122,17 +124,22 @@ main(int argc, char** argv) // Jd * qd rl::math::Vector Jdqd(6 * dynamic->getOperationalDof()); - dynamic->calculateJacobianDerivative(Jdqd); - std::cout << "Jd*qd = " << Jdqd.transpose() << std::endl; + dynamic->calculateJacobianDerivative(Jdqd, false); + std::cout << "Jd * qd = " << Jdqd.transpose() << std::endl; + + // J * qdd + Jd * qd + + rl::math::Vector JqddJdqd = J * qdd + Jdqd; + std::cout << "xdd = J * qdd + Jd * qd = " << JqddJdqd.transpose() << std::endl; - // J * qdd + Jd * qd + // J^{-1} * (xdd - Jd * qd) - tmp2 = J * qdd + Jdqd; - std::cout << "xdd = " << tmp2.transpose() << std::endl; + rl::math::Vector invJxddJdqd = invJ * (JqddJdqd - Jdqd); + std::cout << "qdd = J^{-1} * (xdd - Jd * qd) = " << invJxddJdqd.transpose() << std::endl; std::cout << "===============================================================================" << std::endl; - // RNE + // inverse dynamics dynamic->setPosition(q); dynamic->setVelocity(qd); @@ -169,12 +176,12 @@ main(int argc, char** argv) // M * qdd + V + G - tmp = M * qdd + V + G; - std::cout << "tau = " << tmp.transpose() << std::endl; + rl::math::Vector MqddVG = M * qdd + V + G; + std::cout << "tau = M * qdd + V + G = " << MqddVG.transpose() << std::endl; std::cout << "===============================================================================" << std::endl; - // FD + // forward dynamics dynamic->setPosition(q); dynamic->setVelocity(qd); @@ -199,10 +206,10 @@ main(int argc, char** argv) std::cout << "G = " << G.transpose() << std::endl; - // M^{-1} * ( tau - V - G ) + // M^{-1} * (tau - V - G) - tmp = invM * (tau - V - G); - std::cout << "qdd = " << tmp.transpose() << std::endl; + rl::math::Vector invMtauVG = invM * (tau - V - G); + std::cout << "qdd = M^{-1} * (tau - V - G) = " << invMtauVG.transpose() << std::endl; std::cout << "===============================================================================" << std::endl; } diff --git a/tests/rlDynamicsTest/rlDynamicsTest.cpp b/tests/rlDynamicsTest/rlDynamicsTest.cpp index e117d3f4..da2c5447 100644 --- a/tests/rlDynamicsTest/rlDynamicsTest.cpp +++ b/tests/rlDynamicsTest/rlDynamicsTest.cpp @@ -47,29 +47,29 @@ main(int argc, char** argv) rl::mdl::XmlFactory factory; std::shared_ptr dynamic = std::dynamic_pointer_cast(factory.create(argv[1])); - rl::math::Vector q0(dynamic->getDofPosition()); - rl::math::Vector qd0(dynamic->getDof()); - rl::math::Vector qdd0(dynamic->getDof()); + rl::math::Vector q(dynamic->getDofPosition()); + rl::math::Vector qd(dynamic->getDof()); + rl::math::Vector qdd(dynamic->getDof()); for (::std::size_t i = 0; i < atoi(argv[2]); ++i) { if (0 == i) { - q0.setZero(); - qd0.setZero(); - qdd0.setOnes(); + q.setZero(); + qd.setOnes(); + qdd.setOnes(); } else { - q0.setRandom(); - qd0.setRandom(); - qdd0.setRandom(); + q.setRandom(); + qd.setRandom(); + qdd.setRandom(); } // forward velocity (recursive) - dynamic->setPosition(q0); - dynamic->setVelocity(qd0); + dynamic->setPosition(q); + dynamic->setVelocity(qd); dynamic->forwardVelocity(); rl::math::Vector xdRecursive(6 * dynamic->getOperationalDof()); @@ -82,15 +82,15 @@ main(int argc, char** argv) // forward velocity (matrices) - dynamic->setPosition(q0); - dynamic->calculateJacobian(); + dynamic->setPosition(q); + dynamic->calculateJacobian(false); - rl::math::Vector xdMatrices = dynamic->getJacobian() * qd0; + rl::math::Vector xdMatrices = dynamic->getJacobian() * qd; if (!xdMatrices.isApprox(xdRecursive)) { - std::cerr << "q0 = " << q0.transpose() << std::endl; - std::cerr << "qd0 = " << qd0.transpose() << std::endl; + std::cerr << "q = " << q.transpose() << std::endl; + std::cerr << "qd = " << qd.transpose() << std::endl; std::cerr << "xd (recursive) = " << xdRecursive.transpose() << std::endl; std::cerr << "xd (matrices) = " << xdMatrices.transpose() << std::endl; return EXIT_FAILURE; @@ -98,9 +98,9 @@ main(int argc, char** argv) // forward acceleration (recursive) - dynamic->setPosition(q0); - dynamic->setVelocity(qd0); - dynamic->setAcceleration(qdd0); + dynamic->setPosition(q); + dynamic->setVelocity(qd); + dynamic->setAcceleration(qdd); dynamic->forwardVelocity(); dynamic->forwardAcceleration(); @@ -114,18 +114,18 @@ main(int argc, char** argv) // forward acceleration (matrices) - dynamic->setPosition(q0); - dynamic->calculateJacobian(); - dynamic->setVelocity(qd0); - dynamic->calculateJacobianDerivative(); + dynamic->setPosition(q); + dynamic->calculateJacobian(false); + dynamic->setVelocity(qd); + dynamic->calculateJacobianDerivative(false); - rl::math::Vector xddMatrices = dynamic->getJacobian() * qdd0 + dynamic->getJacobianDerivative(); + rl::math::Vector xddMatrices = dynamic->getJacobian() * qdd + dynamic->getJacobianDerivative(); if (!xddMatrices.isApprox(xddRecursive)) { - std::cerr << "q0 = " << q0.transpose() << std::endl; - std::cerr << "qd0 = " << qd0.transpose() << std::endl; - std::cerr << "qdd0 = " << qdd0.transpose() << std::endl; + std::cerr << "q = " << q.transpose() << std::endl; + std::cerr << "qd = " << qd.transpose() << std::endl; + std::cerr << "qdd = " << qdd.transpose() << std::endl; std::cerr << "xdd (recursive) = " << xddRecursive.transpose() << std::endl; std::cerr << "xdd (matrices) = " << xddMatrices.transpose() << std::endl; return EXIT_FAILURE; @@ -133,30 +133,30 @@ main(int argc, char** argv) // inverse dynamics (recursive) - dynamic->setPosition(q0); - dynamic->setVelocity(qd0); - dynamic->setAcceleration(qdd0); + dynamic->setPosition(q); + dynamic->setVelocity(qd); + dynamic->setAcceleration(qdd); dynamic->inverseDynamics(); rl::math::Vector tauRecursive = dynamic->getTorque(); // inverse dynamics (matrices) - dynamic->setPosition(q0); + dynamic->setPosition(q); dynamic->calculateMassMatrix(); - dynamic->setPosition(q0); - dynamic->setVelocity(qd0); + dynamic->setPosition(q); + dynamic->setVelocity(qd); dynamic->calculateCentrifugalCoriolis(); - dynamic->setPosition(q0); + dynamic->setPosition(q); dynamic->calculateGravity(); - rl::math::Vector tauMatrices = dynamic->getMassMatrix() * qdd0 + dynamic->getCentrifugalCoriolis() + dynamic->getGravity(); + rl::math::Vector tauMatrices = dynamic->getMassMatrix() * qdd + dynamic->getCentrifugalCoriolis() + dynamic->getGravity(); if (!tauMatrices.isApprox(tauRecursive)) { - std::cerr << "q0 = " << q0.transpose() << std::endl; - std::cerr << "qd0 = " << qd0.transpose() << std::endl; - std::cerr << "qdd0 = " << qdd0.transpose() << std::endl; + std::cerr << "q = " << q.transpose() << std::endl; + std::cerr << "qd = " << qd.transpose() << std::endl; + std::cerr << "qdd = " << qdd.transpose() << std::endl; std::cerr << "tau (recursive) = " << tauRecursive.transpose() << std::endl; std::cerr << "tau (matrices) = " << tauMatrices.transpose() << std::endl; return EXIT_FAILURE; @@ -164,45 +164,45 @@ main(int argc, char** argv) // forward dynamics (recursive) - dynamic->setPosition(q0); - dynamic->setVelocity(qd0); + dynamic->setPosition(q); + dynamic->setVelocity(qd); dynamic->setTorque(tauRecursive); dynamic->forwardDynamics(); - rl::math::Vector qdd1Recursive = dynamic->getAcceleration(); + rl::math::Vector qddRecursive = dynamic->getAcceleration(); - if (!qdd1Recursive.isApprox(qdd0)) + if (!qddRecursive.isApprox(qdd)) { - std::cerr << "q0 = " << q0.transpose() << std::endl; - std::cerr << "qd0 = " << qd0.transpose() << std::endl; - std::cerr << "qdd0 = " << qdd0.transpose() << std::endl; + std::cerr << "q = " << q.transpose() << std::endl; + std::cerr << "qd = " << qd.transpose() << std::endl; + std::cerr << "qdd = " << qdd.transpose() << std::endl; std::cerr << "tau (recursive) = " << tauRecursive.transpose() << std::endl; std::cerr << "tau (matrices) = " << tauMatrices.transpose() << std::endl; - std::cerr << "qdd1 (recursive) = " << qdd1Recursive.transpose() << std::endl; + std::cerr << "qdd (recursive) = " << qddRecursive.transpose() << std::endl; return EXIT_FAILURE; } // forward dynamics (matrices) - dynamic->setPosition(q0); + dynamic->setPosition(q); dynamic->calculateMassMatrixInverse(); - dynamic->setPosition(q0); - dynamic->setVelocity(qd0); + dynamic->setPosition(q); + dynamic->setVelocity(qd); dynamic->calculateCentrifugalCoriolis(); - dynamic->setPosition(q0); + dynamic->setPosition(q); dynamic->calculateGravity(); - rl::math::Vector qdd1Matrices = dynamic->getMassMatrixInverse() * (tauMatrices - dynamic->getCentrifugalCoriolis() - dynamic->getGravity()); + rl::math::Vector qddMatrices = dynamic->getMassMatrixInverse() * (tauMatrices - dynamic->getCentrifugalCoriolis() - dynamic->getGravity()); - if (!qdd1Matrices.isApprox(qdd1Recursive)) + if (!qddMatrices.isApprox(qddRecursive)) { - std::cerr << "q0 = " << q0.transpose() << std::endl; - std::cerr << "qd0 = " << qd0.transpose() << std::endl; - std::cerr << "qdd0 = " << qdd0.transpose() << std::endl; + std::cerr << "q = " << q.transpose() << std::endl; + std::cerr << "qd = " << qd.transpose() << std::endl; + std::cerr << "qdd = " << qdd.transpose() << std::endl; std::cerr << "tau (recursive) = " << tauRecursive.transpose() << std::endl; std::cerr << "tau (matrices) = " << tauMatrices.transpose() << std::endl; - std::cerr << "qdd1 (recursive) = " << qdd1Recursive.transpose() << std::endl; - std::cerr << "qdd1 (matrices) = " << qdd1Matrices.transpose() << std::endl; + std::cerr << "qdd (recursive) = " << qddRecursive.transpose() << std::endl; + std::cerr << "qdd (matrices) = " << qddMatrices.transpose() << std::endl; return EXIT_FAILURE; } } From f256972fb169df5e6d2d819a9dabaa7746a1c1e4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 22 May 2019 16:31:01 +0200 Subject: [PATCH 264/546] Sort functions alphabetically --- src/rl/math/QuaternionBaseAddons.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 56f96c4e..bd72e30f 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -107,18 +107,18 @@ static Quaternion Random(const MatrixBase& rand) ); } -template +template Vector3 -angularVelocity(const QuaternionBase& qd) const +angularAcceleration(const QuaternionBase& qd, const QuaternionBase& qdd) const { - return ((qd * this->derived().conjugate()) * Scalar(2)).vec(); + return ((qdd * this->derived().conjugate() + qd * qd.conjugate()) * Scalar(2)).vec(); } -template +template Vector3 -angularAcceleration(const QuaternionBase& qd, const QuaternionBase& qdd) const +angularVelocity(const QuaternionBase& qd) const { - return ((qdd * this->derived().conjugate() + qd * qd.conjugate()) * Scalar(2)).vec(); + return ((qd * this->derived().conjugate()) * Scalar(2)).vec(); } Quaternion From 8cf0864a9d8963f0f041664efaa0d5e92ffe1328 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 23 May 2019 10:34:55 +0200 Subject: [PATCH 265/546] Add check for nullptr in rl::xml::NodeSet --- src/rl/xml/NodeSet.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rl/xml/NodeSet.h b/src/rl/xml/NodeSet.h index 193f2106..420d9519 100644 --- a/src/rl/xml/NodeSet.h +++ b/src/rl/xml/NodeSet.h @@ -66,7 +66,7 @@ namespace rl bool empty() const { - return 0 == this->size(); + return nullptr == this->nodeSet.get() || 0 == this->size(); } ::xmlNodeSetPtr get() const @@ -76,7 +76,7 @@ namespace rl int max_size() const { - return this->nodeSet->nodeMax; + return nullptr != this->nodeSet.get() ? this->nodeSet->nodeMax : 0; } ::xmlNodeSet& operator*() const @@ -91,7 +91,7 @@ namespace rl int size() const { - return this->nodeSet->nodeNr; + return nullptr != this->nodeSet.get() ? this->nodeSet->nodeNr : 0; } protected: From 71cf795fe8a2453e91a8717f38d2180bf25d8ad8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 23 May 2019 11:42:57 +0200 Subject: [PATCH 266/546] Add exceptions for invalid definition files --- src/rl/kin/Kinematics.cpp | 5 +++++ src/rl/mdl/XmlFactory.cpp | 5 +++++ src/rl/sg/XmlFactory.cpp | 5 +++++ 3 files changed, 15 insertions(+) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index d0362acc..f7e80502 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -143,6 +143,11 @@ namespace rl ::rl::xml::NodeSet instances = path.eval("(/rl/kin|/rlkin)/kinematics|(/rl/kin|/rlkin)/puma|(/rl/kin|/rlkin)/rhino").getValue< ::rl::xml::NodeSet>(); + if (instances.empty()) + { + throw Exception("rl::kin::Kinematics::create() - No models found in file " + filename); + } + for (int i = 0; i < ::std::min(1, instances.size()); ++i) { ::rl::xml::Path path(document, instances[i]); diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index aab01701..42b8ae16 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -89,6 +89,11 @@ namespace rl ::rl::xml::NodeSet models = path.eval("(/rl/mdl|/rlmdl)/model").getValue< ::rl::xml::NodeSet>(); + if (models.empty()) + { + throw Exception("rl::mdl::XmlFactory::load() - No models found in file " + filename); + } + for (int i = 0; i < ::std::min(1, models.size()); ++i) { ::rl::xml::Path path(document, models[i]); diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp index 52d3ae06..a872826b 100644 --- a/src/rl/sg/XmlFactory.cpp +++ b/src/rl/sg/XmlFactory.cpp @@ -75,6 +75,11 @@ namespace rl ::rl::xml::NodeSet scenes = path.eval("(/rl/sg|/rlsg)/scene").getValue< ::rl::xml::NodeSet>(); + if (scenes.empty()) + { + throw Exception("rl::sg::XmlFactory::load() - No scenes found in file " + filename); + } + for (int i = 0; i < ::std::min(1, scenes.size()); ++i) { ::SoInput input; From 87a0a7dde802ba0ccda9bce29d1a76d74793baf5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 23 May 2019 18:36:03 +0200 Subject: [PATCH 267/546] Fix whitespace --- src/rl/math/Spline.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 3eed1651..fe4853a0 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -1003,7 +1003,7 @@ namespace rl Real d = ::std::abs(q1(i) - q0(i)); Real tj; Real ta; - + // assume vmax is reached if (vmax(i) * jmax(i) >= amax(i) * amax(i)) { From f25eb2bb12d7bb4db7a1bb8b816f83332b8a3138 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 24 May 2019 11:30:23 +0200 Subject: [PATCH 268/546] Fix whitespace --- src/rl/math/SplineQuaternion.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/math/SplineQuaternion.h b/src/rl/math/SplineQuaternion.h index 7e42fa40..011d1f51 100644 --- a/src/rl/math/SplineQuaternion.h +++ b/src/rl/math/SplineQuaternion.h @@ -233,7 +233,7 @@ namespace rl Real x0 = this->lower(); ::std::size_t i = 0; - + for (; x > x0 + this->polynomials[i].duration() && i < this->polynomials.size(); ++i) { x0 += this->polynomials[i].duration(); From 863bd9cdecf0e2c6ccd8261a6ba8d68001aa4bfe Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 24 May 2019 18:45:25 +0200 Subject: [PATCH 269/546] Update slerp first derivative --- src/rl/math/QuaternionBaseAddons.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index bd72e30f..a127fa2c 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -257,7 +257,7 @@ template Quaternion slerpFirstDerivative(const Scalar& t, const QuaternionBase& other) const { - Quaternion tmp = this->derived().dot(other) < Scalar(0) ? this->derived().conjugate() * -other : this->derived().conjugate() * other; + Quaternion tmp = this->derived().conjugate() * other; return this->derived() * tmp.pow(t) * tmp.log(); } From caedc5c112f5622f8400842420e1d5c854dacfd8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 24 May 2019 18:50:58 +0200 Subject: [PATCH 270/546] Use world frame for velocity and acceleration in quaternion interpolation --- src/rl/math/PolynomialQuaternion.h | 59 +++++++++++++++--------------- src/rl/math/SplineQuaternion.h | 23 ++++++------ 2 files changed, 41 insertions(+), 41 deletions(-) diff --git a/src/rl/math/PolynomialQuaternion.h b/src/rl/math/PolynomialQuaternion.h index 2f34e94d..02704e58 100644 --- a/src/rl/math/PolynomialQuaternion.h +++ b/src/rl/math/PolynomialQuaternion.h @@ -64,16 +64,17 @@ namespace rl static Polynomial CubicFirst(const Quaternion& y0, const Quaternion& y1, const Vector3& yd0, const Vector3& yd1, const Real& x1 = 1) { - Real dtheta = y0.angularDistance(y1); - Vector3 e = (y0.inverse() * y1).vec(); + using ::std::abs; + using ::std::atan2; - if (e.norm() <= ::std::numeric_limits::epsilon()) - { - e.setZero(); - } - else + Quaternion dy = y0.conjugate() * y1; + Real norm = dy.vec().norm(); + Real dtheta = 2 * atan2(norm, abs(dy.w())); + Vector3 e = dy.vec(); + + if (norm > 0) { - e.normalize(); + e /= norm; } Polynomial f(3); @@ -90,16 +91,17 @@ namespace rl static Polynomial Linear(const Quaternion& y0, const Quaternion& y1, const Real& x1 = 1) { - Real dtheta = y0.angularDistance(y1); - Vector3 e = (y0.inverse() * y1).vec(); + using ::std::abs; + using ::std::atan2; - if (e.norm() <= ::std::numeric_limits::epsilon()) - { - e.setZero(); - } - else + Quaternion dy = y0.conjugate() * y1; + Real norm = dy.vec().norm(); + Real dtheta = 2 * atan2(norm, abs(dy.w())); + Vector3 e = dy.vec(); + + if (norm > 0) { - e.normalize(); + e /= norm; } Polynomial f(1); @@ -136,17 +138,12 @@ namespace rl { assert(derivative <= 2 && "Polynomial: higher derivatives not implemented"); - Vector3 axis = this->eval(x); - Real theta = axis.norm(); - Vector3 u; + Vector3 u = this->eval(x); + Real theta = u.norm(); - if (theta <= ::std::numeric_limits::epsilon()) - { - u.setZero(); - } - else + if (theta > 0) { - u = axis.normalized(); + u /= theta; } Quaternion y = this->y0 * AngleAxis(theta, u); @@ -162,7 +159,7 @@ namespace rl Vector3 w = u.cross(axisd) / theta; Vector3 omega; - if (theta > ::std::numeric_limits::epsilon()) + if (theta > 0) { omega = u * thetad + ::std::sin(theta) * w.cross(u) - (1 - ::std::cos(theta)) * w; } @@ -171,7 +168,8 @@ namespace rl omega = axisd; } - Quaternion yd = y.firstDerivative(omega); + Vector3 yomega = y._transformVector(omega); + Quaternion yd = y.firstDerivative(yomega); if (1 == derivative) { @@ -184,7 +182,7 @@ namespace rl Vector3 wd = (u.cross(axisdd) - 2 * thetad * w) / theta; Vector3 omegad; - if (theta > ::std::numeric_limits::epsilon()) + if (theta > 0) { omegad = u * thetadd + ::std::sin(theta) * wd.cross(u) - (1 - ::std::cos(theta)) * wd + thetad * w.cross(u) + omega.cross(u * thetad - w); } @@ -193,7 +191,8 @@ namespace rl omegad = axisdd; } - Quaternion ydd = y.secondDerivative(yd, omega, omegad); + Vector3 yomegad = y._transformVector(omegad); + Quaternion ydd = y.secondDerivative(yd, yomega, yomegad); if (2 == derivative) { @@ -249,7 +248,7 @@ namespace rl static Vector3 invB(const Vector3& e, const Real& dtheta, const Vector3& x) { - if (dtheta <= ::std::numeric_limits::epsilon()) + if (dtheta < ::std::numeric_limits::epsilon()) { return x; } diff --git a/src/rl/math/SplineQuaternion.h b/src/rl/math/SplineQuaternion.h index 011d1f51..06ae99f0 100644 --- a/src/rl/math/SplineQuaternion.h +++ b/src/rl/math/SplineQuaternion.h @@ -61,6 +61,9 @@ namespace rl static Spline CubicFirst(const ::std::vector& x, const ::std::vector& y, const Vector3& yd0, const Vector3& yd1) { + using ::std::abs; + using ::std::atan2; + assert(x.size() > 1); assert(x.size() == y.size()); @@ -75,16 +78,14 @@ namespace rl for (::std::size_t i = 0; i < n - 1; ++i) { dx[i] = x[i + 1] - x[i]; - dtheta[i] = y[i].angularDistance(y[i + 1]); - e[i] = (y[i].inverse() * y[i + 1]).vec(); + Quaternion dy = y[i].conjugate() * y[i + 1]; + Real norm = dy.vec().norm(); + dtheta[i] = 2 * atan2(norm, abs(dy.w())); + e[i] = dy.vec(); - if (e[i].norm() <= ::std::numeric_limits::epsilon()) - { - e[i].setZero(); - } - else + if (norm > 0) { - e[i].normalize(); + e[i] /= norm; } } @@ -308,7 +309,7 @@ namespace rl private: static Vector3 B(const Vector3& e, const Real& dtheta, const Vector3& x) { - if (dtheta <= ::std::numeric_limits::epsilon()) + if (dtheta < ::std::numeric_limits::epsilon()) { return x; } @@ -321,7 +322,7 @@ namespace rl static Vector3 invB(const Vector3& e, const Real& dtheta, const Vector3& x) { - if (dtheta <= ::std::numeric_limits::epsilon()) + if (dtheta < ::std::numeric_limits::epsilon()) { return x; } @@ -334,7 +335,7 @@ namespace rl static Vector3 R(const Vector3& e, const Real& dtheta, const Vector3& omega) { - if (dtheta <= ::std::numeric_limits::epsilon()) + if (dtheta < ::std::numeric_limits::epsilon()) { return Vector3::Zero(); } From c8cf1ac803e6f2b0aeff4f81da01b32e2bbd49df Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 25 May 2019 14:57:47 +0200 Subject: [PATCH 271/546] Use conjugate instead of inverse in squadFirstDerivative --- src/rl/math/QuaternionBaseAddons.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index a127fa2c..960c1b7e 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -281,7 +281,7 @@ squadFirstDerivative(const Scalar& t, const QuaternionBase& a, co { Quaternion u = this->derived().slerp(t, other); Quaternion v = a.slerp(t, b); - Quaternion w = u.inverse() * v; + Quaternion w = u.conjugate() * v; Quaternion ud = u * (this->derived().conjugate() * other).log(); Quaternion vd = v * (a.conjugate() * b).log(); Quaternion wd = u.conjugate() * vd - u.pow(Scalar(-2)) * ud * v; From 199157dfb8ed41f196173eb6fa56640332fb2978 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 25 May 2019 14:58:28 +0200 Subject: [PATCH 272/546] Add quaternion slerp second derivative --- src/rl/math/QuaternionBaseAddons.h | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 960c1b7e..161f61c2 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -261,6 +261,15 @@ slerpFirstDerivative(const Scalar& t, const QuaternionBase& other) return this->derived() * tmp.pow(t) * tmp.log(); } +template +Quaternion +slerpSecondDerivative(const Scalar& t, const QuaternionBase& other) const +{ + Quaternion tmp = this->derived().conjugate() * other; + Quaternion tmp2 = tmp.log(); + return this->derived() * tmp.pow(t) * tmp2 * tmp2; +} + template Quaternion squad(const Scalar& t, const QuaternionBase& a, const QuaternionBase& b, const QuaternionBase& other) const From 86596806c428c785c5fa80ee07d171059d06dfe1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 29 May 2019 21:50:40 +0200 Subject: [PATCH 273/546] Fix typo --- demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp | 4 ++-- src/rl/math/Spline.h | 4 ++-- tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp index 07abdac3..e08c2e52 100644 --- a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp +++ b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp @@ -272,7 +272,7 @@ main(int argc, char** argv) } { - rl::math::Spline f0 = rl::math::Spline::TrapeziodalAccelerationAtRest( + rl::math::Spline f0 = rl::math::Spline::TrapezoidalAccelerationAtRest( rl::math::Vector::Constant(1, 0), rl::math::Vector::Constant(1, 1), rl::math::Vector::Constant(1, 1), @@ -280,7 +280,7 @@ main(int argc, char** argv) rl::math::Vector::Constant(1, 1) ); eval(f0); - rl::math::Spline f1 = rl::math::Spline::TrapeziodalAccelerationAtRest( + rl::math::Spline f1 = rl::math::Spline::TrapezoidalAccelerationAtRest( rl::math::ArrayX::Constant(1, 0), rl::math::ArrayX::Constant(1, 1), rl::math::ArrayX::Constant(1, 1), diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index fe4853a0..f2407638 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -984,9 +984,9 @@ namespace rl * L. Biagiotti, C. Melchiorri (2008) "Trajectory Planning for Automatic * Machines and Robots", pp. 90ff. */ - static Spline TrapeziodalAccelerationAtRest(const T& q0, const T& q1, const T& vmax, const T& amax, const T& jmax) + static Spline TrapezoidalAccelerationAtRest(const T& q0, const T& q1, const T& vmax, const T& amax, const T& jmax) { -// assert((vmax > 0).all() && (amax > 0).all() && (jmax > 0).all() && "TrapeziodalAccelerationAtRest: velocity, acceleration and jerk limits must be positive."); +// assert((vmax > 0).all() && (amax > 0).all() && (jmax > 0).all() && "TrapezoidalAccelerationAtRest: velocity, acceleration and jerk limits must be positive."); ::std::size_t dim = TypeTraits::size(q0); diff --git a/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp b/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp index addb4042..49b57b56 100644 --- a/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp +++ b/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp @@ -40,7 +40,7 @@ main(int argc, char** argv) rl::math::Real vmax = (i % 2 == 0) ? 1 : 1000; rl::math::Real amax = 10; rl::math::Real jmax = (i / 2 == 0) ? 3 : 300; - rl::math::Spline f = rl::math::Spline::TrapeziodalAccelerationAtRest(q0, q1, vmax, amax, jmax); + rl::math::Spline f = rl::math::Spline::TrapezoidalAccelerationAtRest(q0, q1, vmax, amax, jmax); #if 0 // plot for [i=2:5] "interpolation.dat" using 1:i with lines @@ -110,7 +110,7 @@ main(int argc, char** argv) jmax << 100, 100, 100, 100; - rl::math::Spline f = rl::math::Spline::TrapeziodalAccelerationAtRest(q0, q1, vmax, amax, jmax); + rl::math::Spline f = rl::math::Spline::TrapezoidalAccelerationAtRest(q0, q1, vmax, amax, jmax); #if 0 // plot for [i=2:5] "interpolation.dat" using 1:i with lines From bb2683204d258c42bff47538cc5c98f919d0e210 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 31 May 2019 02:06:35 +0200 Subject: [PATCH 274/546] Reorder workspace explorer greedy element --- examples/rlplan/rlplan.xsd | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/rlplan/rlplan.xsd b/examples/rlplan/rlplan.xsd index 9dcb1ecc..8abed0d6 100644 --- a/examples/rlplan/rlplan.xsd +++ b/examples/rlplan/rlplan.xsd @@ -83,11 +83,6 @@ - - - - - @@ -110,6 +105,11 @@ + + + + + From 4f63e50826cae5b527b0afe08b41452923a5462f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 31 May 2019 02:13:06 +0200 Subject: [PATCH 275/546] Add bounding box to workspace sphere explorer --- demos/rlPlanDemo/MainWindow.cpp | 7 ++ examples/rlplan/rlplan.xsd | 24 +++++++ src/rl/math/AlignedBox.h | 86 +++++++++++++++++++++++++ src/rl/math/CMakeLists.txt | 1 + src/rl/plan/WorkspaceSphereExplorer.cpp | 16 ++++- src/rl/plan/WorkspaceSphereExplorer.h | 3 + 6 files changed, 134 insertions(+), 3 deletions(-) create mode 100644 src/rl/math/AlignedBox.h diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 5757c519..ab1cdb66 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -1452,6 +1452,13 @@ MainWindow::load(const QString& filename) explorerSetup.goalFrame = -1; } + explorer->boundingBox.max().x() = path.eval("number(boundingBox/max/x)").getValue(std::numeric_limits::max()); + explorer->boundingBox.max().y() = path.eval("number(boundingBox/max/y)").getValue(std::numeric_limits::max()); + explorer->boundingBox.max().z() = path.eval("number(boundingBox/max/z)").getValue(std::numeric_limits::max()); + explorer->boundingBox.min().x() = path.eval("number(boundingBox/min/x)").getValue(-std::numeric_limits::max()); + explorer->boundingBox.min().y() = path.eval("number(boundingBox/min/y)").getValue(-std::numeric_limits::max()); + explorer->boundingBox.min().z() = path.eval("number(boundingBox/min/z)").getValue(-std::numeric_limits::max()); + if (path.eval("count(distance) > 0").getValue()) { explorer->greedy = rl::plan::WorkspaceSphereExplorer::GREEDY_DISTANCE; diff --git a/examples/rlplan/rlplan.xsd b/examples/rlplan/rlplan.xsd index 8abed0d6..15b9dfac 100644 --- a/examples/rlplan/rlplan.xsd +++ b/examples/rlplan/rlplan.xsd @@ -83,6 +83,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/src/rl/math/AlignedBox.h b/src/rl/math/AlignedBox.h new file mode 100644 index 00000000..8bc62588 --- /dev/null +++ b/src/rl/math/AlignedBox.h @@ -0,0 +1,86 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MATH_ALIGNEDBOX_H +#define RL_MATH_ALIGNEDBOX_H + +#define EIGEN_MATRIXBASE_PLUGIN +#define EIGEN_QUATERNIONBASE_PLUGIN +#define EIGEN_TRANSFORM_PLUGIN + +#include + +#include "Real.h" + +namespace rl +{ + namespace math + { + template + class AlignedBox : public ::Eigen::AlignedBox + { + public: + using ::Eigen::AlignedBox::AlignedBox; + + template + inline NonInteger interiorDistance(const ::Eigen::MatrixBase& p) const + { + using ::std::max; + using ::std::min; + + Scalar dist(::Eigen::NumTraits::highest()); + + for (Index k = 0; k < this->dim(); ++k) + { + dist = min(dist, max(p[k] - m_min[k], Scalar(0))); + dist = min(dist, max(m_max[k] - p[k], Scalar(0))); + } + + return dist; + } + + template + inline Scalar squaredInteriorDistance(const ::Eigen::MatrixBase& p) const + { + using ::std::pow; + return pow(this->squaredInteriorDistance(p), 2); + } + + protected: + + private: + + }; + + typedef AlignedBox AlignedBoxX; + + typedef AlignedBox AlignedBox2; + + typedef AlignedBox AlignedBox3; + } +} + +#endif // RL_MATH_ALIGNEDBOX_H diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index 337872a2..14c01952 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -4,6 +4,7 @@ find_package(Eigen3 REQUIRED) set( BASE_HDRS algorithm.h + AlignedBox.h Array.h Circular.h CircularVector2.h diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index aefe6d97..d86df324 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -37,6 +37,10 @@ namespace rl namespace plan { WorkspaceSphereExplorer::WorkspaceSphereExplorer() : + boundingBox( + ::rl::math::Vector3::Constant(-std::numeric_limits< ::rl::math::Real>::max()), + ::rl::math::Vector3::Constant(std::numeric_limits< ::rl::math::Real>::max()) + ), goal(), greedy(GREEDY_SPACE), model(nullptr), @@ -93,7 +97,10 @@ namespace rl { WorkspaceSphere start; start.center = ::std::make_shared< ::rl::math::Vector3>(*this->start); - start.radius = this->model->distance(*start.center); + start.radius = ::std::min( + this->model->distance(*start.center), + this->boundingBox.interiorDistance(*start.center) + ); start.radiusSum = start.radius; start.parent = nullptr; @@ -168,11 +175,14 @@ namespace rl ); sphere.parent = vertex; - if ((*this->start - *sphere.center).norm() <= this->range) + if ((*this->start - *sphere.center).norm() <= this->range && this->boundingBox.contains(*sphere.center)) { if (!this->isCovered(top.parent, *sphere.center)) { - sphere.radius = this->model->distance(*sphere.center); + sphere.radius = ::std::min( + this->model->distance(*sphere.center), + this->boundingBox.interiorDistance(*sphere.center) + ); sphere.radiusSum = sphere.radius + top.radiusSum; if (sphere.radius >= this->radius) diff --git a/src/rl/plan/WorkspaceSphereExplorer.h b/src/rl/plan/WorkspaceSphereExplorer.h index abe275cf..8b85af71 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.h +++ b/src/rl/plan/WorkspaceSphereExplorer.h @@ -31,6 +31,7 @@ #include #include #include +#include #include #include "WorkspaceSphere.h" @@ -77,6 +78,8 @@ namespace rl void seed(const ::std::mt19937::result_type& value); + ::rl::math::AlignedBox3 boundingBox; + ::rl::math::Vector3* goal; Greedy greedy; From d355822073e58fd8ca77d4cc6827a21acf593cd3 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 30 May 2019 16:23:21 +0200 Subject: [PATCH 276/546] Fix rlPlanDemo duration output --- demos/rlPlanDemo/Thread.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index 03b20717..a13261b1 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -199,9 +199,9 @@ Thread::run() bool solved = MainWindow::instance()->planner->solve(); std::chrono::steady_clock::time_point stop = std::chrono::steady_clock::now(); - double plannerDuration = std::chrono::duration_cast>(stop - start).count() * 1000; + double plannerDuration = std::chrono::duration_cast>(stop - start).count(); - emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration) + " ms."); + emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration * 1000) + " ms."); std::fstream benchmark; benchmark.open("benchmark.csv", std::ios::app | std::ios::in | std::ios::out); From c402415c7d3791f915cac6f78f231d45de248019 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 31 May 2019 13:21:16 +0200 Subject: [PATCH 277/546] Add convenience function for collision checking in planners --- demos/rlPlanDemo/ConfigurationSpaceThread.cpp | 5 +---- src/rl/plan/BridgeSampler.cpp | 12 +++--------- src/rl/plan/Eet.cpp | 5 +---- src/rl/plan/GaussianSampler.cpp | 15 +++------------ src/rl/plan/Planner.cpp | 10 ++-------- src/rl/plan/PrmUtilityGuided.cpp | 7 ++----- src/rl/plan/RecursiveVerifier.cpp | 5 +---- src/rl/plan/Rrt.cpp | 15 +++------------ src/rl/plan/Sampler.cpp | 4 +--- src/rl/plan/SequentialVerifier.cpp | 5 +---- src/rl/plan/SimpleModel.cpp | 8 ++++++++ src/rl/plan/SimpleModel.h | 2 ++ 12 files changed, 28 insertions(+), 65 deletions(-) diff --git a/demos/rlPlanDemo/ConfigurationSpaceThread.cpp b/demos/rlPlanDemo/ConfigurationSpaceThread.cpp index 9488e7c0..48a93a59 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceThread.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceThread.cpp @@ -76,10 +76,7 @@ ConfigurationSpaceThread::run() { q(this->axis0) = minimum(this->axis0) + j * delta0; - model->setPosition(q); - model->updateFrames(); - - if (model->isColliding()) + if (model->isColliding(q)) { emit addCollision( q(this->axis0), diff --git a/src/rl/plan/BridgeSampler.cpp b/src/rl/plan/BridgeSampler.cpp index a50b738a..af327b87 100644 --- a/src/rl/plan/BridgeSampler.cpp +++ b/src/rl/plan/BridgeSampler.cpp @@ -57,10 +57,7 @@ namespace rl { ::rl::math::Vector q2 = this->generate(); - this->model->setPosition(q2); - this->model->updateFrames(); - - if (this->model->isColliding()) + if (this->model->isColliding(q2)) { for (::std::size_t i = 0; i < this->model->getDof(); ++i) { @@ -69,14 +66,11 @@ namespace rl ::rl::math::Vector q3 = this->model->generatePositionGaussian(gauss, q2, *this->sigma); - if (this->model->isColliding()) + if (this->model->isColliding(q3)) { this->model->interpolate(q2, q3, static_cast< ::rl::math::Real>(0.5), q); - this->model->setPosition(q); - this->model->updateFrames(); - - if (!this->model->isColliding()) + if (!this->model->isColliding(q)) { return q; } diff --git a/src/rl/plan/Eet.cpp b/src/rl/plan/Eet.cpp index 39672dc8..50727dc2 100644 --- a/src/rl/plan/Eet.cpp +++ b/src/rl/plan/Eet.cpp @@ -218,10 +218,7 @@ namespace rl this->viewer->drawConfiguration(*expanded.q); } - this->model->setPosition(*expanded.q); - this->model->updateFrames(); - - if (this->model->isColliding()) + if (this->model->isColliding(*expanded.q)) { return -1; } diff --git a/src/rl/plan/GaussianSampler.cpp b/src/rl/plan/GaussianSampler.cpp index f8147e6d..832bc36f 100644 --- a/src/rl/plan/GaussianSampler.cpp +++ b/src/rl/plan/GaussianSampler.cpp @@ -67,25 +67,16 @@ namespace rl ::rl::math::Vector q2 = this->model->generatePositionGaussian(gauss, q, *this->sigma); - this->model->setPosition(q); - this->model->updateFrames(); - - if (!this->model->isColliding()) + if (!this->model->isColliding(q)) { - this->model->setPosition(q2); - this->model->updateFrames(); - - if (this->model->isColliding()) + if (this->model->isColliding(q2)) { return q; } } else { - this->model->setPosition(q2); - this->model->updateFrames(); - - if (!this->model->isColliding()) + if (!this->model->isColliding(q2)) { return q2; } diff --git a/src/rl/plan/Planner.cpp b/src/rl/plan/Planner.cpp index c6b8d7ff..d3dd99a5 100644 --- a/src/rl/plan/Planner.cpp +++ b/src/rl/plan/Planner.cpp @@ -69,10 +69,7 @@ namespace rl return false; } - this->model->setPosition(*this->start); - this->model->updateFrames(); - - if (this->model->isColliding()) + if (this->model->isColliding(*this->start)) { if (nullptr != this->viewer) { @@ -82,10 +79,7 @@ namespace rl return false; } - this->model->setPosition(*this->goal); - this->model->updateFrames(); - - if (this->model->isColliding()) + if (this->model->isColliding(*this->goal)) { if (nullptr != this->viewer) { diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index 75795146..f8f0d8d4 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -75,7 +75,7 @@ namespace rl #ifdef ORIGINAL_VERSION // Used in the paper: take the samples with the least collision probability if (pFree > pBest) - { + { pBest = pFree; bestSample = sample; } @@ -90,10 +90,7 @@ namespace rl } // now do collision check - this->model->setPosition(bestSample.q); - this->model->updateFrames(); - - if (!this->model->isColliding()) + if (!this->model->isColliding(bestSample.q)) { // store the sample in the graph bestSample.isColliding = false; diff --git a/src/rl/plan/RecursiveVerifier.cpp b/src/rl/plan/RecursiveVerifier.cpp index 65f0f992..794ea28e 100644 --- a/src/rl/plan/RecursiveVerifier.cpp +++ b/src/rl/plan/RecursiveVerifier.cpp @@ -73,10 +73,7 @@ namespace rl return true; } - this->model->setPosition(inter); - this->model->updateFrames(); - - if (this->model->isColliding()) + if (this->model->isColliding(inter)) { return true; } diff --git a/src/rl/plan/Rrt.cpp b/src/rl/plan/Rrt.cpp index c57c007d..519f4bd8 100644 --- a/src/rl/plan/Rrt.cpp +++ b/src/rl/plan/Rrt.cpp @@ -126,10 +126,7 @@ namespace rl // this->viewer->drawConfiguration(*last); } - this->model->setPosition(*last); - this->model->updateFrames(); - - if (this->model->isColliding()) + if (this->model->isColliding(*last)) { return nullptr; } @@ -153,10 +150,7 @@ namespace rl // this->viewer->drawConfiguration(next); } - this->model->setPosition(next); - this->model->updateFrames(); - - if (this->model->isColliding()) + if (this->model->isColliding(next)) { break; } @@ -179,10 +173,7 @@ namespace rl this->model->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, *next); - this->model->setPosition(*next); - this->model->updateFrames(); - - if (!this->model->isColliding()) + if (!this->model->isColliding(*next)) { Vertex extended = this->addVertex(tree, next); this->addEdge(nearest.second, extended, tree); diff --git a/src/rl/plan/Sampler.cpp b/src/rl/plan/Sampler.cpp index a5f6bb9a..aa8f7419 100644 --- a/src/rl/plan/Sampler.cpp +++ b/src/rl/plan/Sampler.cpp @@ -48,10 +48,8 @@ namespace rl do { q = this->generate(); - this->model->setPosition(q); - this->model->updateFrames(); } - while (this->model->isColliding()); + while (this->model->isColliding(q)); return q; } diff --git a/src/rl/plan/SequentialVerifier.cpp b/src/rl/plan/SequentialVerifier.cpp index c2ec5921..87be37a1 100644 --- a/src/rl/plan/SequentialVerifier.cpp +++ b/src/rl/plan/SequentialVerifier.cpp @@ -59,10 +59,7 @@ namespace rl return true; } - this->model->setPosition(inter); - this->model->updateFrames(); - - if (this->model->isColliding()) + if (this->model->isColliding(inter)) { return true; } diff --git a/src/rl/plan/SimpleModel.cpp b/src/rl/plan/SimpleModel.cpp index 0e23fc8c..11dd2298 100644 --- a/src/rl/plan/SimpleModel.cpp +++ b/src/rl/plan/SimpleModel.cpp @@ -106,6 +106,14 @@ namespace rl return false; } + bool + SimpleModel::isColliding(const ::rl::math::Vector& q) + { + this->setPosition(q); + this->updateFrames(); + return this->isColliding(); + } + void SimpleModel::reset() { diff --git a/src/rl/plan/SimpleModel.h b/src/rl/plan/SimpleModel.h index 52d7e425..cba7361e 100644 --- a/src/rl/plan/SimpleModel.h +++ b/src/rl/plan/SimpleModel.h @@ -50,6 +50,8 @@ namespace rl virtual bool isColliding(); + virtual bool isColliding(const ::rl::math::Vector& q); + virtual void reset(); protected: From e14a0ea28954b6092ada9b7655a4ae27920278fc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 31 May 2019 13:21:58 +0200 Subject: [PATCH 278/546] Prefer std::abs over std::fabs --- src/rl/plan/PrmUtilityGuided.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index f8f0d8d4..8ae7c4e6 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -81,7 +81,7 @@ namespace rl } #else // This works better in our examples. Here we define entropy by using samples where we are unsure, if they are colliding. - if (::std::fabs(pFree - static_cast< ::rl::math::Real>(0.5)) < ::std::fabs(pBest - static_cast< ::rl::math::Real>(0.5))) + if (::std::abs(pFree - static_cast< ::rl::math::Real>(0.5)) < ::std::abs(pBest - static_cast< ::rl::math::Real>(0.5))) { pBest = pFree; bestSample = sample; From a3021b2c36d60f10d71c5eb9a24753999f21e410 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 31 May 2019 13:40:28 +0200 Subject: [PATCH 279/546] Remove validation check in edge verifiers --- src/rl/plan/RecursiveVerifier.cpp | 5 ----- src/rl/plan/SequentialVerifier.cpp | 5 ----- 2 files changed, 10 deletions(-) diff --git a/src/rl/plan/RecursiveVerifier.cpp b/src/rl/plan/RecursiveVerifier.cpp index 794ea28e..eea06eec 100644 --- a/src/rl/plan/RecursiveVerifier.cpp +++ b/src/rl/plan/RecursiveVerifier.cpp @@ -68,11 +68,6 @@ namespace rl this->model->interpolate(u, v, static_cast< ::rl::math::Real>(midpoint) / static_cast< ::rl::math::Real>(steps), inter); - if (!this->model->isValid(inter)) - { - return true; - } - if (this->model->isColliding(inter)) { return true; diff --git a/src/rl/plan/SequentialVerifier.cpp b/src/rl/plan/SequentialVerifier.cpp index 87be37a1..3da97f63 100644 --- a/src/rl/plan/SequentialVerifier.cpp +++ b/src/rl/plan/SequentialVerifier.cpp @@ -54,11 +54,6 @@ namespace rl { this->model->interpolate(u, v, static_cast< ::rl::math::Real>(i + 1) / static_cast< ::rl::math::Real>(steps), inter); - if (!this->model->isValid(inter)) - { - return true; - } - if (this->model->isColliding(inter)) { return true; From ef307431bc5a83bfdf2dba6a98fd4f2847ad20a1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 1 Jun 2019 19:08:59 +0200 Subject: [PATCH 280/546] Fix rlSplineTranslationTest --- tests/rlSplineTest/rlSplineTranslationTest.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/tests/rlSplineTest/rlSplineTranslationTest.cpp b/tests/rlSplineTest/rlSplineTranslationTest.cpp index 90958fd9..0b9ec7a3 100644 --- a/tests/rlSplineTest/rlSplineTranslationTest.cpp +++ b/tests/rlSplineTest/rlSplineTranslationTest.cpp @@ -74,6 +74,7 @@ main(int argc, char** argv) for (std::size_t degree = 5; degree < 15; ++degree) { rl::math::Polynomial p(degree); + p.upper() = 1; for (std::size_t n = 0; n < p.degree() + 1; ++n) { From d09fa603bfb7346b6abaa9d2c8372c00f3432d36 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 1 Jun 2019 20:30:34 +0200 Subject: [PATCH 281/546] Update float comparison in rlSplineTranslationTest --- tests/rlSplineTest/rlSplineTranslationTest.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/rlSplineTest/rlSplineTranslationTest.cpp b/tests/rlSplineTest/rlSplineTranslationTest.cpp index 0b9ec7a3..1b0a2233 100644 --- a/tests/rlSplineTest/rlSplineTranslationTest.cpp +++ b/tests/rlSplineTest/rlSplineTranslationTest.cpp @@ -32,7 +32,7 @@ void printPoly(const rl::math::Polynomial& p) { for (int n = p.degree(); n >= 0; --n) { - if (p.coefficient(n).matrix().squaredNorm() != 0) + if (p.coefficient(n).matrix().squaredNorm() > 0) { std::cout << p.coefficient(n) << "*x^" << n << " "; } From e99ec470da3d5de4d04208a964b2e69c9f094dbf Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 1 Jun 2019 20:30:53 +0200 Subject: [PATCH 282/546] Use member initializer list --- src/rl/math/NestedFunction.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/rl/math/NestedFunction.h b/src/rl/math/NestedFunction.h index b87592d4..beb96357 100644 --- a/src/rl/math/NestedFunction.h +++ b/src/rl/math/NestedFunction.h @@ -40,12 +40,10 @@ namespace rl { public: NestedFunction(const Function& inner, const Function& outer) : - Function(), + Function(inner.lower(), inner.upper()), inner(inner), outer(outer) { - this->lower() = this->inner.lower(); - this->upper() = this->inner.upper(); } virtual ~NestedFunction() From 4e58598f1f98e0cbae838b8002fe576e900c865c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 2 Jun 2019 00:40:22 +0200 Subject: [PATCH 283/546] Use std::cbrt --- src/rl/math/Polynomial.h | 7 +++--- src/rl/math/algorithm.h | 13 ----------- src/rl/std/CMakeLists.txt | 1 + src/rl/std/cmath | 45 +++++++++++++++++++++++++++++++++++++++ 4 files changed, 50 insertions(+), 16 deletions(-) create mode 100644 src/rl/std/cmath diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index 6777e7bf..7167bcc2 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -32,6 +32,7 @@ #define EIGEN_TRANSFORM_PLUGIN #include +#include #include #include @@ -570,7 +571,7 @@ namespace rl else if (::std::abs(p) <= ::std::numeric_limits::epsilon() && ::std::abs(q) > ::std::numeric_limits::epsilon()) { ::std::vector roots(1); - roots[0] = cbrt(-q) - back; + roots[0] = ::std::cbrt(-q) - back; return roots; } else if (::std::abs(p) > ::std::numeric_limits::epsilon() && ::std::abs(q) <= ::std::numeric_limits::epsilon()) @@ -606,8 +607,8 @@ namespace rl else { Real sqrtDet = ::std::sqrt(det); - Real u = cbrt(-q / 2 + sqrtDet); - Real v = cbrt(-q / 2 - sqrtDet); + Real u = ::std::cbrt(-q / 2 + sqrtDet); + Real v = ::std::cbrt(-q / 2 - sqrtDet); ::std::vector roots(1); roots[0] = u + v - back; return roots; diff --git a/src/rl/math/algorithm.h b/src/rl/math/algorithm.h index 7917d9a8..e856cf11 100644 --- a/src/rl/math/algorithm.h +++ b/src/rl/math/algorithm.h @@ -35,19 +35,6 @@ namespace rl { namespace math { - template - inline T cbrt(const T& arg) - { - if (arg < 0) - { - return -::std::pow(-arg, static_cast(1) / static_cast(3)); - } - else - { - return ::std::pow(arg, static_cast(1) / static_cast(3)); - } - } - template inline const T& clamp(const T& v, const T& lo, const T& hi, Compare comp) { diff --git a/src/rl/std/CMakeLists.txt b/src/rl/std/CMakeLists.txt index 93561eeb..6fb9f1db 100644 --- a/src/rl/std/CMakeLists.txt +++ b/src/rl/std/CMakeLists.txt @@ -1,6 +1,7 @@ set( BASE_HDRS chrono + cmath condition_variable future iterator diff --git a/src/rl/std/cmath b/src/rl/std/cmath new file mode 100644 index 00000000..31408ee2 --- /dev/null +++ b/src/rl/std/cmath @@ -0,0 +1,45 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_STD_CMATH +#define RL_STD_CMATH + +#ifdef _MSC_VER +#include <../include/cmath> + +#if _MSC_VER < 1800 +#include + +namespace std +{ + using ::boost::math::cbrt; +} +#endif // _MSC_VER < 1800 +#else // _MSC_VER +#include_next +#endif // _MSC_VER + +#endif // RL_STD_CMATH From f3390ec5872def59bd282dfe2a9ed14994fda078 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 3 Jun 2019 20:29:53 +0200 Subject: [PATCH 284/546] Inherit Eigen::AlignedBox typedefs --- src/rl/math/AlignedBox.h | 22 +++++++++++++++++----- 1 file changed, 17 insertions(+), 5 deletions(-) diff --git a/src/rl/math/AlignedBox.h b/src/rl/math/AlignedBox.h index 8bc62588..db9c7af1 100644 --- a/src/rl/math/AlignedBox.h +++ b/src/rl/math/AlignedBox.h @@ -39,11 +39,23 @@ namespace rl { namespace math { - template - class AlignedBox : public ::Eigen::AlignedBox + template + class AlignedBox : public ::Eigen::AlignedBox<_Scalar, _AmbientDim> { public: - using ::Eigen::AlignedBox::AlignedBox; + typedef typename ::Eigen::AlignedBox<_Scalar, _AmbientDim>::Scalar Scalar; + + typedef typename ::Eigen::AlignedBox<_Scalar, _AmbientDim>::ScalarTraits ScalarTraits; + + typedef typename ::Eigen::AlignedBox<_Scalar, _AmbientDim>::Index Index; + + typedef typename ::Eigen::AlignedBox<_Scalar, _AmbientDim>::RealScalar RealScalar; + + typedef typename ::Eigen::AlignedBox<_Scalar, _AmbientDim>::NonInteger NonInteger; + + typedef typename ::Eigen::AlignedBox<_Scalar, _AmbientDim>::VectorType VectorType; + + using ::Eigen::AlignedBox<_Scalar, _AmbientDim>::AlignedBox; template inline NonInteger interiorDistance(const ::Eigen::MatrixBase& p) const @@ -55,8 +67,8 @@ namespace rl for (Index k = 0; k < this->dim(); ++k) { - dist = min(dist, max(p[k] - m_min[k], Scalar(0))); - dist = min(dist, max(m_max[k] - p[k], Scalar(0))); + dist = min(dist, max(p[k] - this->m_min[k], Scalar(0))); + dist = min(dist, max(this->m_max[k] - p[k], Scalar(0))); } return dist; From b2bef925d8adbd580ed8c3eced5f18faed54e990 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 3 Jun 2019 21:12:33 +0200 Subject: [PATCH 285/546] Avoid inheriting constructors for GCC < 4.8 --- src/rl/math/AlignedBox.h | 26 +++++++++++++++++++++++++- 1 file changed, 25 insertions(+), 1 deletion(-) diff --git a/src/rl/math/AlignedBox.h b/src/rl/math/AlignedBox.h index db9c7af1..c3a9ba03 100644 --- a/src/rl/math/AlignedBox.h +++ b/src/rl/math/AlignedBox.h @@ -55,7 +55,31 @@ namespace rl typedef typename ::Eigen::AlignedBox<_Scalar, _AmbientDim>::VectorType VectorType; - using ::Eigen::AlignedBox<_Scalar, _AmbientDim>::AlignedBox; + inline AlignedBox() : + ::Eigen::AlignedBox<_Scalar, _AmbientDim>::AlignedBox() + { + } + + inline explicit AlignedBox(Index dim) : + ::Eigen::AlignedBox<_Scalar, _AmbientDim>::AlignedBox(dim) + { + } + + template + inline AlignedBox(const OtherVectorType1& min, const OtherVectorType2& max) : + ::Eigen::AlignedBox<_Scalar, _AmbientDim>::AlignedBox(min, max) + { + } + + template + inline explicit AlignedBox(const ::Eigen::MatrixBase& p) : + ::Eigen::AlignedBox<_Scalar, _AmbientDim>::AlignedBox(p) + { + } + + ~AlignedBox() + { + } template inline NonInteger interiorDistance(const ::Eigen::MatrixBase& p) const From 0fabc30b5fda4a5485e1e43dd750a82f2069e91d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 6 Jun 2019 17:48:07 +0200 Subject: [PATCH 286/546] Remove preallocation for radius search --- src/rl/math/GnatNearestNeighbors.h | 16 ++++++++++------ src/rl/math/KdtreeBoundingBoxNearestNeighbors.h | 10 ++++------ src/rl/math/KdtreeNearestNeighbors.h | 16 ++++++++++------ src/rl/math/LinearNearestNeighbors.h | 11 ++++++++++- 4 files changed, 34 insertions(+), 19 deletions(-) diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index 7facabcd..3a4d7966 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -453,7 +453,16 @@ namespace rl ::std::vector search(const Value& query, const ::std::size_t* k, const Distance* radius, const bool& sorted) const { ::std::vector neighbors; - neighbors.reserve(nullptr != k ? *k : this->values); + + if (this->empty()) + { + return neighbors; + } + + if (nullptr != k) + { + neighbors.reserve(::std::min(*k, this->size())); + } ::std::size_t checks = 0; @@ -485,11 +494,6 @@ namespace rl ::std::sort_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } - if (nullptr == k) - { - neighbors.shrink_to_fit(); - } - return neighbors; } diff --git a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h index 82e9c651..84418eda 100644 --- a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h @@ -512,7 +512,10 @@ namespace rl return neighbors; } - neighbors.reserve(nullptr != k ? *k : this->values); + if (nullptr != k) + { + neighbors.reserve(::std::min(*k, this->size())); + } ::std::size_t checks = 0; @@ -553,11 +556,6 @@ namespace rl ::std::sort_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } - if (nullptr == k) - { - neighbors.shrink_to_fit(); - } - return neighbors; } diff --git a/src/rl/math/KdtreeNearestNeighbors.h b/src/rl/math/KdtreeNearestNeighbors.h index 4480923d..e807f75b 100644 --- a/src/rl/math/KdtreeNearestNeighbors.h +++ b/src/rl/math/KdtreeNearestNeighbors.h @@ -416,7 +416,16 @@ namespace rl using ::std::size; ::std::vector neighbors; - neighbors.reserve(nullptr != k ? *k : this->values); + + if (this->empty()) + { + return neighbors; + } + + if (nullptr != k) + { + neighbors.reserve(::std::min(*k, this->size())); + } ::std::size_t checks = 0; @@ -437,11 +446,6 @@ namespace rl ::std::sort_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } - if (nullptr == k) - { - neighbors.shrink_to_fit(); - } - return neighbors; } diff --git a/src/rl/math/LinearNearestNeighbors.h b/src/rl/math/LinearNearestNeighbors.h index d07534a2..59270d44 100644 --- a/src/rl/math/LinearNearestNeighbors.h +++ b/src/rl/math/LinearNearestNeighbors.h @@ -247,7 +247,16 @@ namespace rl ::std::vector search(const Value& query, const ::std::size_t* k, const Distance* radius, const bool& sorted) const { ::std::vector neighbors; - neighbors.reserve(nullptr != k ? *k : this->size()); + + if (this->empty()) + { + return neighbors; + } + + if (nullptr != k) + { + neighbors.reserve(::std::min(*k, this->size())); + } ::std::vector distances(this->container.size()); From b85f089646d71895d15b64987453111cc0f5e8dc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 30 Apr 2019 21:06:55 +0200 Subject: [PATCH 287/546] Update vector and matrix initialization --- src/rl/kin/Frame.cpp | 2 +- src/rl/kin/Joint.cpp | 2 +- src/rl/kin/Kinematics.cpp | 6 ++--- src/rl/kin/Link.cpp | 6 ++--- src/rl/kin/Transform.cpp | 2 +- src/rl/mdl/Body.cpp | 11 ++++----- src/rl/mdl/Dynamic.cpp | 24 ++++++++----------- src/rl/mdl/Frame.cpp | 30 +++++++++-------------- src/rl/mdl/Joint.cpp | 50 +++++++++++++-------------------------- src/rl/mdl/Kinematic.cpp | 9 ++++--- src/rl/mdl/Model.cpp | 15 ++++-------- src/rl/mdl/Transform.cpp | 5 ++-- 12 files changed, 62 insertions(+), 100 deletions(-) diff --git a/src/rl/kin/Frame.cpp b/src/rl/kin/Frame.cpp index 1f3c8492..d6068490 100644 --- a/src/rl/kin/Frame.cpp +++ b/src/rl/kin/Frame.cpp @@ -32,7 +32,7 @@ namespace rl { Frame::Frame() : Element(), - frame() + frame(::rl::math::Transform::Identity()) { } diff --git a/src/rl/kin/Joint.cpp b/src/rl/kin/Joint.cpp index 838fc721..00579970 100644 --- a/src/rl/kin/Joint.cpp +++ b/src/rl/kin/Joint.cpp @@ -42,7 +42,7 @@ namespace rl speed(0), theta(0), wraparound(false), - q() + q(0) { } diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index f7e80502..60cbd632 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -1035,8 +1035,8 @@ namespace rl } } - this->jacobian.resize(this->leaves.size() * 6, this->joints.size()); - this->jacobianInverse.resize(this->joints.size(), this->leaves.size() * 6); + this->jacobian = ::rl::math::Matrix::Identity(this->leaves.size() * 6, this->joints.size()); + this->jacobianInverse = ::rl::math::Matrix::Identity(this->joints.size(), this->leaves.size() * 6); } void @@ -1104,7 +1104,7 @@ namespace rl { if (this->joints[j]->leaves.count(this->leaves[i]) > 0) { - ::rl::math::MatrixBlock jacobian = this->jacobian.block(6 * i, j, 6, 1); // TODO + ::rl::math::MatrixBlock jacobian = this->jacobian.block(6 * i, j, 6, 1); this->joints[j]->jacobian(this->tree[this->leaves[i]]->frame, jacobian); } } diff --git a/src/rl/kin/Link.cpp b/src/rl/kin/Link.cpp index 0fb4ce86..547ca071 100644 --- a/src/rl/kin/Link.cpp +++ b/src/rl/kin/Link.cpp @@ -33,9 +33,9 @@ namespace rl Link::Link() : Frame(), collision(true), - cog(), - inertia(), - mass(0), + cog(::rl::math::Vector3::Zero()), + inertia(::rl::math::Matrix33::Identity()), + mass(1), selfcollision() { } diff --git a/src/rl/kin/Transform.cpp b/src/rl/kin/Transform.cpp index 299a6f75..9089acc4 100644 --- a/src/rl/kin/Transform.cpp +++ b/src/rl/kin/Transform.cpp @@ -35,7 +35,7 @@ namespace rl Element(), in(nullptr), out(nullptr), - transform() + transform(::rl::math::Transform::Identity()) { } diff --git a/src/rl/mdl/Body.cpp b/src/rl/mdl/Body.cpp index bf8d32d4..b9ddcadb 100644 --- a/src/rl/mdl/Body.cpp +++ b/src/rl/mdl/Body.cpp @@ -34,16 +34,13 @@ namespace rl { Body::Body() : Frame(), - cm(), + cm(::rl::math::Vector3::Zero()), collision(true), - fX(), - ic(), + fX(::rl::math::ForceVector::Zero()), + ic(::rl::math::Matrix33::Identity()), m(1), selfcollision() { - this->cm.setZero(); // TODO - this->fX.setZero(); // TODO - this->ic.setIdentity(); // TODO } Body::~Body() @@ -121,7 +118,7 @@ namespace rl this->i.cog() = this->m * this->cm; // Ic - m * cx * cx - this->i.inertia() = this->ic - this->m * this->cm.cross33() * this->cm.cross33(); // TODO + this->i.inertia() = this->ic - this->m * this->cm.cross33() * this->cm.cross33(); } void diff --git a/src/rl/mdl/Dynamic.cpp b/src/rl/mdl/Dynamic.cpp index 0784c89a..c120a957 100644 --- a/src/rl/mdl/Dynamic.cpp +++ b/src/rl/mdl/Dynamic.cpp @@ -68,8 +68,7 @@ namespace rl ::rl::math::Vector g(3); this->getWorldGravity(g); - ::rl::math::Vector tmp(this->getDof()); - tmp.setZero(); //TODO + ::rl::math::Vector tmp = ::rl::math::Vector::Zero(this->getDof()); this->setAcceleration(tmp); this->setWorldGravity(0, 0, 0); @@ -89,8 +88,7 @@ namespace rl void Dynamic::calculateGravity(::rl::math::Vector& G) { - ::rl::math::Vector tmp(this->getDof()); - tmp.setZero(); //TODO + ::rl::math::Vector tmp = ::rl::math::Vector::Zero(this->getDof()); this->setVelocity(tmp); this->setAcceleration(tmp); @@ -111,8 +109,7 @@ namespace rl ::rl::math::Vector g(3); this->getWorldGravity(g); - ::rl::math::Vector tmp(this->getDof()); - tmp.setZero(); //TODO + ::rl::math::Vector tmp = ::rl::math::Vector::Zero(this->getDof()); this->setVelocity(tmp); this->setWorldGravity(0, 0, 0); @@ -145,8 +142,7 @@ namespace rl ::rl::math::Vector g(3); this->getWorldGravity(g); - ::rl::math::Vector tmp(this->getDof()); - tmp.setZero(); //TODO + ::rl::math::Vector tmp = ::rl::math::Vector::Zero(this->getDof()); this->setVelocity(tmp); this->setWorldGravity(0, 0, 0); @@ -176,7 +172,7 @@ namespace rl void Dynamic::calculateOperationalMassMatrixInverse(const ::rl::math::Matrix& J, const ::rl::math::Matrix& invM, ::rl::math::Matrix& invMx) const { - invMx = J * invM * J.transpose(); // TODO + invMx = J * invM * J.transpose(); } void @@ -280,11 +276,11 @@ namespace rl { Kinematic::update(); - this->M.resize(this->getDof(), this->getDof()); - this->V.resize(this->getDof()); - this->G.resize(this->getDof()); - this->invM.resize(this->getDof(), this->getDof()); - this->invMx.resize(6 * this->getOperationalDof(), 6 * this->getOperationalDof()); + this->M = ::rl::math::Matrix::Identity(this->getDof(), this->getDof()); + this->V = ::rl::math::Vector::Zero(this->getDof()); + this->G = ::rl::math::Vector::Zero(this->getDof()); + this->invM = ::rl::math::Matrix::Identity(this->getDof(), this->getDof()); + this->invMx = ::rl::math::Matrix::Identity(6 * this->getOperationalDof(), 6 * this->getOperationalDof()); } } } diff --git a/src/rl/mdl/Frame.cpp b/src/rl/mdl/Frame.cpp index d80b8f7b..824aea7f 100644 --- a/src/rl/mdl/Frame.cpp +++ b/src/rl/mdl/Frame.cpp @@ -32,24 +32,16 @@ namespace rl { Frame::Frame() : Element(), - a(), - c(), - f(), - i(), - iA(), - pA(), - v(), - x(), + a(::rl::math::MotionVector::Zero()), + c(::rl::math::MotionVector::Zero()), + f(::rl::math::ForceVector::Zero()), + i(::rl::math::RigidBodyInertia::Identity()), + iA(::rl::math::ArticulatedBodyInertia::Identity()), + pA(::rl::math::ForceVector::Zero()), + v(::rl::math::MotionVector::Zero()), + x(::rl::math::PlueckerTransform::Identity()), descriptor() { - this->a.setZero(); // TODO - this->c.setZero(); // TODO - this->f.setZero(); // TODO - this->i.setIdentity(); // TODO - this->iA.setIdentity(); // TODO - this->pA.setZero(); // TODO - this->v.setZero(); // TODO - this->x.setIdentity(); // TODO } Frame::~Frame() @@ -64,8 +56,8 @@ namespace rl void Frame::forwardDynamics1() { - this->iA.setZero(); // TODO - this->pA.setZero(); // TODO + this->iA.setZero(); + this->pA.setZero(); } void @@ -97,7 +89,7 @@ namespace rl void Frame::inverseDynamics1() { - this->f.setZero(); // TODO + this->f.setZero(); } void diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index 71f9178d..1f49d4ec 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -34,44 +34,28 @@ namespace rl namespace mdl { Joint::Joint(const ::std::size_t& dofPosition, const ::std::size_t& dofVelocity) : - a(), - c(), - D(dofVelocity, dofVelocity), - max(dofPosition), - min(dofPosition), - offset(dofPosition), - q(dofPosition), + a(::rl::math::MotionVector::Zero()), + c(::rl::math::MotionVector::Zero()), + D(::rl::math::Matrix::Zero(dofVelocity, dofVelocity)), + max(::rl::math::Vector::Constant(dofPosition, ::std::numeric_limits< ::rl::math::Real>::max())), + min(::rl::math::Vector::Constant(dofPosition, -::std::numeric_limits< ::rl::math::Real>::max())), + offset(::rl::math::Vector::Zero(dofPosition)), + q(::rl::math::Vector::Zero(dofPosition)), qUnits(dofPosition), - qd(dofVelocity), + qd(::rl::math::Vector::Zero(dofVelocity)), qdUnits(dofVelocity), - qdd(dofVelocity), + qdd(::rl::math::Vector::Zero(dofVelocity)), qddUnits(dofVelocity), - S(6, dofVelocity), - speed(dofVelocity), + S(::rl::math::Matrix::Zero(6, dofVelocity)), + speed(::rl::math::Vector::Constant(dofVelocity, ::std::numeric_limits< ::rl::math::Real>::max())), speedUnits(dofVelocity), - tau(dofVelocity), + tau(::rl::math::Vector::Zero(dofVelocity)), tauUnits(dofVelocity), - u(dofVelocity), - U(6, dofVelocity), - v(), - wraparound(dofPosition) - { - this->a.setZero(); // TODO - this->c.setZero(); // TODO - this->D.setZero(); // TODO - this->max.setConstant(::std::numeric_limits< ::rl::math::Real>::max()); // TODO - this->min.setConstant(-::std::numeric_limits< ::rl::math::Real>::max()); // TODO - this->offset.setZero(); // TODO - this->q.setZero(); // TODO - this->qd.setZero(); // TODO - this->qdd.setZero(); // TODO - this->S.setZero(); // TODO - this->speed.setConstant(::std::numeric_limits< ::rl::math::Real>::max()); // TODO - this->tau.setZero(); // TODO - this->u.setZero(); // TODO - this->U.setZero(); // TODO - this->v.setZero(); // TODO - this->wraparound.setConstant(false); // TODO + u(::rl::math::Vector::Zero(dofVelocity)), + U(::rl::math::Matrix::Zero(6, dofVelocity)), + v(::rl::math::MotionVector::Zero()), + wraparound(::Eigen::Matrix::Constant(dofPosition, false)) + { } Joint::~Joint() diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 85b73436..69795ff4 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -102,8 +102,7 @@ namespace rl void Kinematic::calculateJacobianDerivative(::rl::math::Vector& Jdqd, const bool& inWorldFrame) { - ::rl::math::Vector tmp(this->getDof()); - tmp.setZero(); // TODO + ::rl::math::Vector tmp = ::rl::math::Vector::Zero(this->getDof()); this->setAcceleration(tmp); this->forwardVelocity(); @@ -234,9 +233,9 @@ namespace rl { Metric::update(); - this->invJ.resize(this->getDof(), 6 * this->getOperationalDof()); - this->J.resize(6 * this->getOperationalDof(), this->getDof()); - this->Jdqd.resize(6 * this->getOperationalDof()); + this->invJ = ::rl::math::Matrix::Identity(this->getDof(), 6 * this->getOperationalDof()); + this->J = ::rl::math::Matrix::Identity(6 * this->getOperationalDof(), this->getDof()); + this->Jdqd = ::rl::math::Vector::Zero(6 * this->getOperationalDof()); } } } diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 7f059941..f74616f4 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -772,16 +772,11 @@ namespace rl } } - this->gammaPosition.resize(this->getDofPosition(), this->getDofPosition()); - this->gammaPosition.setIdentity(); - this->gammaVelocity.resize(this->getDof(), this->getDof()); - this->gammaVelocity.setIdentity(); - this->home.resize(this->getDofPosition()); - this->home.setZero(); - this->invGammaPosition.resize(this->getDofPosition(), this->getDofPosition()); - this->invGammaPosition.setIdentity(); - this->invGammaVelocity.resize(this->getDof(), this->getDof()); - this->invGammaVelocity.setIdentity(); + this->gammaPosition = ::rl::math::Matrix::Identity(this->getDofPosition(), this->getDofPosition()); + this->gammaVelocity = ::rl::math::Matrix::Identity(this->getDof(), this->getDof()); + this->home = ::rl::math::Vector::Zero(this->getDofPosition()); + this->invGammaPosition = ::rl::math::Matrix::Identity(this->getDofPosition(), this->getDofPosition()); + this->invGammaVelocity = ::rl::math::Matrix::Identity(this->getDof(), this->getDof()); } ::rl::math::Transform& diff --git a/src/rl/mdl/Transform.cpp b/src/rl/mdl/Transform.cpp index 46d88d25..ebe61b19 100644 --- a/src/rl/mdl/Transform.cpp +++ b/src/rl/mdl/Transform.cpp @@ -35,10 +35,9 @@ namespace rl Element(), in(nullptr), out(nullptr), - x(), + x(::rl::math::PlueckerTransform::Identity()), descriptor() { - this->x.setIdentity(); // TODO } Transform::~Transform() @@ -55,7 +54,7 @@ namespace rl Transform::forwardDynamics1() { this->forwardVelocity(); - this->out->c.setZero(); // TODO + this->out->c.setZero(); } void From f7039941a44ba8c39e9e6cc7a63c1862d88ba770 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 5 Aug 2019 17:12:22 +0200 Subject: [PATCH 288/546] Update gravity initialization --- demos/rlDynamics2Demo/rlDynamics2Demo.cpp | 5 --- src/rl/mdl/Dynamic.cpp | 39 ++++------------------- src/rl/mdl/Dynamic.h | 8 ----- src/rl/mdl/Model.cpp | 12 +++++++ src/rl/mdl/Model.h | 4 +++ src/rl/mdl/UrdfFactory.cpp | 2 +- src/rl/mdl/World.cpp | 36 +++++++++++++++------ src/rl/mdl/World.h | 12 +++++-- src/rl/mdl/XmlFactory.cpp | 8 +++-- 9 files changed, 64 insertions(+), 62 deletions(-) diff --git a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp index 30243b97..447a6412 100644 --- a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp +++ b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp @@ -61,9 +61,6 @@ main(int argc, char** argv) qdd(i) = boost::lexical_cast(argv[i + 2 + dynamic->getDofPosition() + dynamic->getDof()]); } - rl::math::Vector g(3); - dynamic->getWorldGravity(g); - std::cout << "===============================================================================" << std::endl; // forward position @@ -114,7 +111,6 @@ main(int argc, char** argv) dynamic->setPosition(q); dynamic->setVelocity(qd); dynamic->setAcceleration(qdd); - dynamic->setWorldGravity(g); dynamic->forwardVelocity(); dynamic->forwardAcceleration(); std::cout << "xdd = " << dynamic->getOperationalAcceleration(0).linear().transpose() << " " << dynamic->getOperationalAcceleration(0).angular().transpose() << std::endl; @@ -170,7 +166,6 @@ main(int argc, char** argv) rl::math::Vector G(dynamic->getDof()); dynamic->setPosition(q); - dynamic->setWorldGravity(g); dynamic->calculateGravity(G); std::cout << "G = " << G.transpose() << std::endl; diff --git a/src/rl/mdl/Dynamic.cpp b/src/rl/mdl/Dynamic.cpp index c120a957..3bdaee78 100644 --- a/src/rl/mdl/Dynamic.cpp +++ b/src/rl/mdl/Dynamic.cpp @@ -65,13 +65,12 @@ namespace rl void Dynamic::calculateCentrifugalCoriolis(::rl::math::Vector& V) { - ::rl::math::Vector g(3); - this->getWorldGravity(g); + ::rl::math::Vector3 g = this->getWorldGravity(); ::rl::math::Vector tmp = ::rl::math::Vector::Zero(this->getDof()); this->setAcceleration(tmp); - this->setWorldGravity(0, 0, 0); + this->setWorldGravity(::rl::math::Vector3::Zero()); this->inverseDynamics(); V = this->getTorque(); @@ -106,13 +105,12 @@ namespace rl void Dynamic::calculateMassMatrix(::rl::math::Matrix& M) { - ::rl::math::Vector g(3); - this->getWorldGravity(g); + ::rl::math::Vector3 g = this->getWorldGravity(); ::rl::math::Vector tmp = ::rl::math::Vector::Zero(this->getDof()); this->setVelocity(tmp); - this->setWorldGravity(0, 0, 0); + this->setWorldGravity(::rl::math::Vector3::Zero()); for (::std::size_t i = 0; i < this->getDof(); ++i) { @@ -139,13 +137,12 @@ namespace rl void Dynamic::calculateMassMatrixInverse(::rl::math::Matrix& invM) { - ::rl::math::Vector g(3); - this->getWorldGravity(g); + ::rl::math::Vector3 g = this->getWorldGravity(); ::rl::math::Vector tmp = ::rl::math::Vector::Zero(this->getDof()); this->setVelocity(tmp); - this->setWorldGravity(0, 0, 0); + this->setWorldGravity(::rl::math::Vector3::Zero()); for (::std::size_t i = 0; i < this->getDof(); ++i) { @@ -224,18 +221,6 @@ namespace rl return this->invMx; } - void - Dynamic::getWorldGravity(::rl::math::Real& x, ::rl::math::Real& y, ::rl::math::Real& z) const - { - dynamic_cast(this->tree[this->root].get())->getGravity(x, y, z); - } - - void - Dynamic::getWorldGravity(::rl::math::Vector& xyz) const - { - this->getWorldGravity(xyz(0), xyz(1), xyz(2)); - } - void Dynamic::inverseDynamics() { @@ -259,18 +244,6 @@ namespace rl } } - void - Dynamic::setWorldGravity(const ::rl::math::Real& x, const ::rl::math::Real& y, const ::rl::math::Real& z) - { - dynamic_cast(this->tree[this->root].get())->setGravity(x, y, z); - } - - void - Dynamic::setWorldGravity(const ::rl::math::Vector& xyz) - { - this->setWorldGravity(xyz(0), xyz(1), xyz(2)); - } - void Dynamic::update() { diff --git a/src/rl/mdl/Dynamic.h b/src/rl/mdl/Dynamic.h index ac3cb70d..9b1b265e 100644 --- a/src/rl/mdl/Dynamic.h +++ b/src/rl/mdl/Dynamic.h @@ -212,10 +212,6 @@ namespace rl */ const ::rl::math::Matrix& getOperationalMassMatrixInverse() const; - void getWorldGravity(::rl::math::Real& x, ::rl::math::Real& y, ::rl::math::Real& z) const; - - void getWorldGravity(::rl::math::Vector& xyz) const; - /** * Inverse dynamics via recursive Newton-Euler algorithm. * @@ -230,10 +226,6 @@ namespace rl void inverseForce(); - void setWorldGravity(const ::rl::math::Real& x, const ::rl::math::Real& y, const ::rl::math::Real& z); - - void setWorldGravity(const ::rl::math::Vector& xyz); - virtual void update(); protected: diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index f74616f4..77e45194 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -531,6 +531,12 @@ namespace rl return dynamic_cast(this->tree[this->root].get()); } + const ::rl::math::Vector3& + Model::getWorldGravity() const + { + return dynamic_cast(this->tree[this->root].get())->getGravity(); + } + ::Eigen::Matrix Model::getWraparounds() const { @@ -700,6 +706,12 @@ namespace rl } } + void + Model::setWorldGravity(const ::rl::math::Vector3& gravity) + { + dynamic_cast(this->tree[this->root].get())->setGravity(gravity); + } + ::rl::math::Transform& Model::tool(const ::std::size_t& i) { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 16a25032..d56d1987 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -153,6 +153,8 @@ namespace rl World* getWorld() const; + const ::rl::math::Vector3& getWorldGravity() const; + ::Eigen::Matrix getWraparounds() const; bool isColliding(const ::std::size_t& i) const; @@ -189,6 +191,8 @@ namespace rl void setVelocity(const ::rl::math::Vector& qd); + void setWorldGravity(const ::rl::math::Vector3& gravity); + ::rl::math::Transform& tool(const ::std::size_t& i = 0); const ::rl::math::Transform& tool(const ::std::size_t& i = 0) const; diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 492e16c8..537843cf 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -328,7 +328,7 @@ ::std::cout << "\tname: " << r->getName() << ::std::endl; World* world = new World(); model->add(world); - world->setGravity(0, 0, 9.80665); + world->setGravity(::rl::math::Vector3(0, 0, 9.80665)); Frame* root = nullptr; diff --git a/src/rl/mdl/World.cpp b/src/rl/mdl/World.cpp index 8793d8d6..206b16b0 100644 --- a/src/rl/mdl/World.cpp +++ b/src/rl/mdl/World.cpp @@ -31,7 +31,8 @@ namespace rl namespace mdl { World::World() : - Frame() + Frame(), + gravity(::rl::math::Vector3::Zero()) { } @@ -40,19 +41,36 @@ namespace rl } void - World::getGravity(::rl::math::Real& x, ::rl::math::Real& y, ::rl::math::Real& z) const + World::forwardAcceleration() { - x = this->a.linear().x(); - y = this->a.linear().y(); - z = this->a.linear().z(); + this->a.linear().setZero(); } void - World::setGravity(const ::rl::math::Real& x, const ::rl::math::Real& y, const ::rl::math::Real& z) + World::forwardDynamics1() { - this->a.linear().x() = x; - this->a.linear().y() = y; - this->a.linear().z() = z; + this->iA.setZero(); + this->pA.setZero(); + this->a.linear() = this->gravity; + } + + const ::rl::math::Vector3& + World::getGravity() const + { + return this->gravity; + } + + void + World::inverseDynamics1() + { + this->f.setZero(); + this->a.linear() = this->gravity; + } + + void + World::setGravity(const ::rl::math::Vector3& gravity) + { + this->gravity = gravity; } } } diff --git a/src/rl/mdl/World.h b/src/rl/mdl/World.h index 5f519fb3..56d02407 100644 --- a/src/rl/mdl/World.h +++ b/src/rl/mdl/World.h @@ -40,14 +40,20 @@ namespace rl virtual ~World(); - void getGravity(::rl::math::Real& x, ::rl::math::Real& y, ::rl::math::Real& z) const; + void forwardAcceleration(); - void setGravity(const ::rl::math::Real& x, const ::rl::math::Real& y, const ::rl::math::Real& z); + void forwardDynamics1(); + + const ::rl::math::Vector3& getGravity() const; + + void inverseDynamics1(); + + void setGravity(const ::rl::math::Vector3& gravity); protected: private: - + ::rl::math::Vector3 gravity; }; } } diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index 42b8ae16..6f24844b 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -175,9 +175,11 @@ namespace rl w->x.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); w->setGravity( - path.eval("number(g/x)").getValue< ::rl::math::Real>(0), - path.eval("number(g/y)").getValue< ::rl::math::Real>(0), - path.eval("number(g/z)").getValue< ::rl::math::Real>(0) + ::rl::math::Vector3( + path.eval("number(g/x)").getValue< ::rl::math::Real>(0), + path.eval("number(g/y)").getValue< ::rl::math::Real>(0), + path.eval("number(g/z)").getValue< ::rl::math::Real>(0) + ) ); frame = w; From 279e3c595c7093b764e4ec585c46a233ecd8ac90 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 22 Apr 2019 13:54:36 +0200 Subject: [PATCH 289/546] Remove extra whitespace --- src/rl/kin/Puma.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/rl/kin/Puma.h b/src/rl/kin/Puma.h index 1feae8bc..d3ea8e22 100644 --- a/src/rl/kin/Puma.h +++ b/src/rl/kin/Puma.h @@ -110,4 +110,3 @@ namespace rl } #endif // RL_KIN_PUMA_H - From afe6ec9b7d3608856955ac596656de31984ef620 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 7 Jun 2019 22:15:38 +0200 Subject: [PATCH 290/546] Revert remove of variable for OpenMP --- src/rl/math/GnatNearestNeighbors.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index 3a4d7966..204de98e 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -667,6 +667,10 @@ namespace rl } } +#ifdef _OPENMP + ::std::size_t size = node.data.size(); +#endif + node.data.clear(); node.data.shrink_to_fit(); From baa920e87760ba49dc77e29d09d8699ea5afa40e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 8 Jun 2019 22:19:51 +0200 Subject: [PATCH 291/546] Optimize LinearNearestNeighbors --- src/rl/math/LinearNearestNeighbors.h | 64 +++++++++++++++++++++------- 1 file changed, 49 insertions(+), 15 deletions(-) diff --git a/src/rl/math/LinearNearestNeighbors.h b/src/rl/math/LinearNearestNeighbors.h index 59270d44..5211591a 100644 --- a/src/rl/math/LinearNearestNeighbors.h +++ b/src/rl/math/LinearNearestNeighbors.h @@ -258,9 +258,17 @@ namespace rl neighbors.reserve(::std::min(*k, this->size())); } - ::std::vector distances(this->container.size()); - #ifdef _OPENMP + ::std::vector< ::std::vector> neighbors2(::omp_get_max_threads()); + + if (nullptr != k) + { + for (::std::size_t i = 0; i < neighbors2.size(); ++i) + { + neighbors2[i].reserve(::std::min(*k, this->size()) / ::omp_get_max_threads()); + } + } + #pragma omp parallel for #if _OPENMP < 200805 for (::std::ptrdiff_t i = 0; i < this->container.size(); ++i) @@ -268,34 +276,60 @@ namespace rl for (::std::size_t i = 0; i < this->container.size(); ++i) #endif #else - for (::std::size_t i = 0; i < this->container.size(); ++i) -#endif - { - distances[i] = this->metric(query, this->container[i]); - } + ::std::vector& neighbors3 = neighbors; for (::std::size_t i = 0; i < this->container.size(); ++i) +#endif { - if (nullptr == k || neighbors.size() < *k || distances[i] < neighbors.front().first) +#ifdef _OPENMP + ::std::vector& neighbors3 = neighbors2[::omp_get_thread_num()]; +#endif + + Distance distance = this->metric(query, this->container[i]); + + if (nullptr == k || neighbors3.size() < *k || distance < neighbors3.front().first) { - if (nullptr == radius || distances[i] < *radius) + if (nullptr == radius || distance < *radius) { - if (nullptr != k && *k == neighbors.size()) + if (nullptr != k && *k == neighbors3.size()) { - ::std::pop_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); - neighbors.pop_back(); + ::std::pop_heap(neighbors3.begin(), neighbors3.end(), NeighborCompare()); + neighbors3.pop_back(); } #if defined(_MSC_VER) && _MSC_VER < 1800 - neighbors.push_back(::std::make_pair(distances[i], this->container[i])); + neighbors3.push_back(::std::make_pair(distance, this->container[i])); #else - neighbors.emplace_back(distances[i], this->container[i]); + neighbors3.emplace_back(distance, this->container[i]); #endif - ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); + ::std::push_heap(neighbors3.begin(), neighbors3.end(), NeighborCompare()); } } } +#ifdef _OPENMP + for (::std::size_t i = 0; i < neighbors2.size(); ++i) + { + for (::std::size_t j = 0; j < neighbors2[i].size(); ++j) + { + if (nullptr == k || neighbors.size() < *k || neighbors2[i][j].first < neighbors.front().first) + { + if (nullptr == radius || neighbors2[i][j].first < *radius) + { + if (nullptr != k && *k == neighbors.size()) + { + ::std::pop_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); + neighbors.pop_back(); + } + + neighbors.push_back(::std::move(neighbors2[i][j])); + ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); + } + } + } + } +#endif + if (sorted) { ::std::sort_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); From 97f94b9fb5e34b2f6dfe091fd75fb6fc44b8d238 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 8 Jun 2019 22:20:35 +0200 Subject: [PATCH 292/546] Use std::move for branches in nearest neighbors search --- src/rl/math/GnatNearestNeighbors.h | 2 +- src/rl/math/KdtreeBoundingBoxNearestNeighbors.h | 2 +- src/rl/math/KdtreeNearestNeighbors.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index 204de98e..672750bf 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -471,7 +471,7 @@ namespace rl while (!branches.empty() && (!this->checks || checks < this->checks)) { - Branch branch = branches.front(); + Branch branch = ::std::move(branches.front()); ::std::pop_heap(branches.begin(), branches.end(), BranchCompare()); branches.pop_back(); diff --git a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h index 84418eda..14c2ebd8 100644 --- a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h @@ -545,7 +545,7 @@ namespace rl while (!branches.empty() && (!this->checks || checks < this->checks)) { - Branch branch = branches.front(); + Branch branch = ::std::move(branches.front()); ::std::pop_heap(branches.begin(), branches.end(), BranchCompare()); branches.pop_back(); this->search(*branch.node, query, k, radius, branches, neighbors, checks, branch.dist, branch.sidedist); diff --git a/src/rl/math/KdtreeNearestNeighbors.h b/src/rl/math/KdtreeNearestNeighbors.h index e807f75b..f4b07873 100644 --- a/src/rl/math/KdtreeNearestNeighbors.h +++ b/src/rl/math/KdtreeNearestNeighbors.h @@ -435,7 +435,7 @@ namespace rl while (!branches.empty() && (!this->checks || checks < this->checks)) { - Branch branch = branches.front(); + Branch branch = ::std::move(branches.front()); ::std::pop_heap(branches.begin(), branches.end(), BranchCompare()); branches.pop_back(); this->search(*branch.node, query, k, radius, branches, neighbors, checks, branch.dist, branch.sidedist); From f0a2825f98b3fb2c98d6f816697fd1e836bcf5dc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 8 Jun 2019 22:21:19 +0200 Subject: [PATCH 293/546] Optimize k-d tree sidedist --- .../math/KdtreeBoundingBoxNearestNeighbors.h | 23 +++++++++++++------ src/rl/math/KdtreeNearestNeighbors.h | 23 +++++++++++++------ 2 files changed, 32 insertions(+), 14 deletions(-) diff --git a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h index 14c2ebd8..e0caa081 100644 --- a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h @@ -278,6 +278,13 @@ namespace rl { } + Branch(Distance& dist, ::std::vector&& sidedist, const Node* node) : + dist(dist), + node(node), + sidedist(::std::move(sidedist)) + { + } + Distance dist; const Node* node; @@ -559,7 +566,7 @@ namespace rl return neighbors; } - void search(const Node& node, const Value& query, const ::std::size_t* k, const Distance* radius, ::std::vector& branches, ::std::vector& neighbors, ::std::size_t& checks, const Distance& mindist, const ::std::vector& sidedist) const + void search(const Node& node, const Value& query, const ::std::size_t* k, const Distance* radius, ::std::vector& branches, ::std::vector& neighbors, ::std::size_t& checks, const Distance& mindist, ::std::vector& sidedist) const { using ::std::begin; @@ -611,19 +618,21 @@ namespace rl if (nullptr == k || neighbors.size() < *k || newdist <= neighbors.front().first) { - ::std::vector newsidedist(sidedist); - newsidedist[node.index] = cutdist; - if (!this->checks) { - this->search(*node.children[worst], query, k, radius, branches, neighbors, checks, newdist, newsidedist); + Distance dist = sidedist[node.index]; + sidedist[node.index] = cutdist; + this->search(*node.children[worst], query, k, radius, branches, neighbors, checks, newdist, sidedist); + sidedist[node.index] = dist; } else { + ::std::vector newsidedist(sidedist); + newsidedist[node.index] = cutdist; #if defined(_MSC_VER) && _MSC_VER < 1800 - branches.push_back(Branch(newdist, newsidedist, node.children[worst].get())); + branches.push_back(Branch(newdist, ::std::move(newsidedist), node.children[worst].get())); #else - branches.emplace_back(newdist, newsidedist, node.children[worst].get()); + branches.emplace_back(newdist, ::std::move(newsidedist), node.children[worst].get()); #endif ::std::push_heap(branches.begin(), branches.end(), BranchCompare()); } diff --git a/src/rl/math/KdtreeNearestNeighbors.h b/src/rl/math/KdtreeNearestNeighbors.h index f4b07873..c865bdc5 100644 --- a/src/rl/math/KdtreeNearestNeighbors.h +++ b/src/rl/math/KdtreeNearestNeighbors.h @@ -247,6 +247,13 @@ namespace rl { } + Branch(Distance& dist, ::std::vector&& sidedist, const Node* node) : + dist(dist), + node(node), + sidedist(::std::move(sidedist)) + { + } + Distance dist; const Node* node; @@ -449,7 +456,7 @@ namespace rl return neighbors; } - void search(const Node& node, const Value& query, const ::std::size_t* k, const Distance* radius, ::std::vector& branches, ::std::vector& neighbors, ::std::size_t& checks, const Distance& mindist, const ::std::vector& sidedist) const + void search(const Node& node, const Value& query, const ::std::size_t* k, const Distance* radius, ::std::vector& branches, ::std::vector& neighbors, ::std::size_t& checks, const Distance& mindist, ::std::vector& sidedist) const { using ::std::begin; @@ -496,19 +503,21 @@ namespace rl if (nullptr == k || neighbors.size() < *k || newdist <= neighbors.front().first) { - ::std::vector newsidedist(sidedist); - newsidedist[node.cut.index] = cutdist; - if (!this->checks) { - this->search(*node.children[worst], query, k, radius, branches, neighbors, checks, newdist, newsidedist); + Distance dist = sidedist[node.cut.index]; + sidedist[node.cut.index] = cutdist; + this->search(*node.children[worst], query, k, radius, branches, neighbors, checks, newdist, sidedist); + sidedist[node.cut.index] = dist; } else { + ::std::vector newsidedist(sidedist); + newsidedist[node.cut.index] = cutdist; #if defined(_MSC_VER) && _MSC_VER < 1800 - branches.push_back(Branch(newdist, newsidedist, node.children[worst].get())); + branches.push_back(Branch(newdist, ::std::move(newsidedist), node.children[worst].get())); #else - branches.emplace_back(newdist, newsidedist, node.children[worst].get()); + branches.emplace_back(newdist, ::std::move(newsidedist), node.children[worst].get()); #endif ::std::push_heap(branches.begin(), branches.end(), BranchCompare()); } From 998ecc153a0e8490e0ba8aebb4c91d81fac352a1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 8 Jun 2019 22:23:46 +0200 Subject: [PATCH 294/546] Compare distance in rlNearestNeighborsTest --- .../rlNearestNeighborsTest.cpp | 41 +++++++++---------- 1 file changed, 19 insertions(+), 22 deletions(-) diff --git a/tests/rlNearestNeighborsTest/rlNearestNeighborsTest.cpp b/tests/rlNearestNeighborsTest/rlNearestNeighborsTest.cpp index 28263b2f..98ad0ea3 100644 --- a/tests/rlNearestNeighborsTest/rlNearestNeighborsTest.cpp +++ b/tests/rlNearestNeighborsTest/rlNearestNeighborsTest.cpp @@ -18,7 +18,7 @@ template std::vector> -test(const std::vector& points, const std::vector& queries, const bool& iterative) +test(const std::vector& points, const std::vector& queries, const bool& iterative, const bool& squared) { std::vector> results; @@ -68,7 +68,8 @@ test(const std::vector& points, const std::vectortranspose() << " dist " << neighbors[j].first << std::endl; + rl::math::Real distance = squared ? std::sqrt(neighbors[j].first) : neighbors[j].first; + std::cout << "found " << neighbors[j].second->transpose() << " dist " << distance << std::endl; break; } @@ -91,41 +92,35 @@ test(const std::vector& points, const std::vector MetricSquared; std::cout << "** LinearNearestNeighbors *********************************************" << std::endl; - std::vector::Neighbor>> linear = test>(points, queries, iterative); + std::vector::Neighbor>> linear = test>(points, queries, iterative, false); std::cout << "** LinearNearestNeighbors **************************************" << std::endl; - std::vector::Neighbor>> linear2 = test>(points, queries, iterative); + std::vector::Neighbor>> linear2 = test>(points, queries, iterative, true); std::cout << "** GnatNearestNeighbors ***********************************************" << std::endl; - std::vector::Neighbor>> gnat = test>(points, queries, iterative); + std::vector::Neighbor>> gnat = test>(points, queries, iterative, false); std::cout << "** KdtreeBoundingBoxNearestNeighbors ***************************" << std::endl; - std::vector::Neighbor>> kdtreeBoundingBox = test>(points, queries, iterative); + std::vector::Neighbor>> kdtreeBoundingBox = test>(points, queries, iterative, true); std::cout << "** KdtreeNearestNeighbors **************************************" << std::endl; - std::vector::Neighbor>> kdtree = test>(points, queries, iterative); + std::vector::Neighbor>> kdtree = test>(points, queries, iterative, true); for (std::size_t i = 0; i < linear.size(); ++i) { for (std::size_t j = 0; j < linear[i].size(); ++j) { - if (!linear[i][j].second->isApprox(*gnat[i][j].second)) - { - std::cerr << "rlNearestNeighborsTest: LinearNearestNeighbors != GnatNearestNeighbors" << std::endl; - std::cerr << "[" << i << "][" << j << "] " << linear[i][j].first << " LinearNearestNeighbors: " << linear[i][j].second->transpose() << std::endl; - std::cerr << "[" << i << "][" << j << "] " << gnat[i][j].first << " GnatNearestNeighbors: " << gnat[i][j].second->transpose() << std::endl; - exit(EXIT_FAILURE); - } - - if (!linear[i][j].second->isApprox(*linear2[i][j].second)) + if (!Eigen::internal::isApprox(linear[i][j].first, std::sqrt(linear2[i][j].first)) || + !linear[i][j].second->isApprox(*linear2[i][j].second)) { std::cerr << "rlNearestNeighborsTest: LinearNearestNeighbors != LinearNearestNeighbors" << std::endl; std::cerr << "[" << i << "][" << j << "] " << linear[i][j].first << " LinearNearestNeighbors: " << linear[i][j].second->transpose() << std::endl; - std::cerr << "[" << i << "][" << j << "] " << linear2[i][j].first << " LinearNearestNeighbors: " << linear2[i][j].second->transpose() << std::endl; + std::cerr << "[" << i << "][" << j << "] " << std::sqrt(linear2[i][j].first) << " LinearNearestNeighbors: " << linear2[i][j].second->transpose() << std::endl; exit(EXIT_FAILURE); } - if (!linear[i][j].second->isApprox(*gnat[i][j].second)) + if (!Eigen::internal::isApprox(linear[i][j].first, gnat[i][j].first) || + !linear[i][j].second->isApprox(*gnat[i][j].second)) { std::cerr << "rlNearestNeighborsTest: LinearNearestNeighbors != GnatNearestNeighbors" << std::endl; std::cerr << "[" << i << "][" << j << "] " << linear[i][j].first << " LinearNearestNeighbors: " << linear[i][j].second->transpose() << std::endl; @@ -133,19 +128,21 @@ test(const std::vector& points, const std::vectorisApprox(*kdtreeBoundingBox[i][j].second)) + if (!Eigen::internal::isApprox(linear[i][j].first, std::sqrt(kdtreeBoundingBox[i][j].first)) || + !linear[i][j].second->isApprox(*kdtreeBoundingBox[i][j].second)) { std::cerr << "rlNearestNeighborsTest: LinearNearestNeighbors != KdtreeBoundingBoxNearestNeighbors" << std::endl; std::cerr << "[" << i << "][" << j << "] " << linear[i][j].first << " LinearNearestNeighbors: " << linear[i][j].second->transpose() << std::endl; - std::cerr << "[" << i << "][" << j << "] " << kdtreeBoundingBox[i][j].first << " KdtreeBoundingBoxNearestNeighbors: " << kdtreeBoundingBox[i][j].second->transpose() << std::endl; + std::cerr << "[" << i << "][" << j << "] " << std::sqrt(kdtreeBoundingBox[i][j].first) << " KdtreeBoundingBoxNearestNeighbors: " << kdtreeBoundingBox[i][j].second->transpose() << std::endl; exit(EXIT_FAILURE); } - if (!linear[i][j].second->isApprox(*kdtree[i][j].second)) + if (!Eigen::internal::isApprox(linear[i][j].first, std::sqrt(kdtree[i][j].first)) || + !linear[i][j].second->isApprox(*kdtree[i][j].second)) { std::cerr << "rlNearestNeighborsTest: LinearNearestNeighbors != KdtreeNearestNeighbors" << std::endl; std::cerr << "[" << i << "][" << j << "] " << linear[i][j].first << " LinearNearestNeighbors: " << linear[i][j].second->transpose() << std::endl; - std::cerr << "[" << i << "][" << j << "] " << kdtree[i][j].first << " KdtreeNearestNeighbors: " << kdtree[i][j].second->transpose() << std::endl; + std::cerr << "[" << i << "][" << j << "] " << std::sqrt(kdtree[i][j].first) << " KdtreeNearestNeighbors: " << kdtree[i][j].second->transpose() << std::endl; exit(EXIT_FAILURE); } } From 11d57921bf0d48abc89f3978c31d51bdd74144df Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 9 Jun 2019 16:05:16 +0200 Subject: [PATCH 295/546] Use const correctness in rl::plan::Prm::AStarHeuristic --- src/rl/plan/Prm.cpp | 2 +- src/rl/plan/Prm.h | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/rl/plan/Prm.cpp b/src/rl/plan/Prm.cpp index 697f40d6..ec776128 100644 --- a/src/rl/plan/Prm.cpp +++ b/src/rl/plan/Prm.cpp @@ -264,7 +264,7 @@ namespace rl return true; } - Prm::AStarHeuristic::AStarHeuristic(Model* model, Graph& graph, Vertex& goal) : + Prm::AStarHeuristic::AStarHeuristic(const Model* model, const Graph& graph, const Vertex& goal) : goal(goal), graph(graph), model(model) diff --git a/src/rl/plan/Prm.h b/src/rl/plan/Prm.h index 35bc10ca..cd4a265b 100644 --- a/src/rl/plan/Prm.h +++ b/src/rl/plan/Prm.h @@ -152,18 +152,18 @@ namespace rl class AStarHeuristic : public ::boost::astar_heuristic { public: - AStarHeuristic(Model* model, Graph& graph, Vertex& goal); + AStarHeuristic(const Model* model, const Graph& graph, const Vertex& goal); ::rl::math::Real operator()(Vertex u); protected: private: - Vertex& goal; + const Vertex& goal; - Graph& graph; + const Graph& graph; - Model* model; + const Model* model; }; typedef ::boost::graph_traits::edge_descriptor Edge; From 2c8ecd6f1d4d4b831e2444c3912483ea1482586b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 14 Jun 2019 17:08:35 +0200 Subject: [PATCH 296/546] Fix A* heuristic function --- src/rl/plan/Prm.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/plan/Prm.cpp b/src/rl/plan/Prm.cpp index ec776128..07099088 100644 --- a/src/rl/plan/Prm.cpp +++ b/src/rl/plan/Prm.cpp @@ -274,7 +274,7 @@ namespace rl ::rl::math::Real Prm::AStarHeuristic::operator()(Vertex u) { - return this->model->transformedDistance(*this->graph[u].q, *this->graph[this->goal].q); + return this->model->distance(*this->graph[u].q, *this->graph[this->goal].q); } } } From ec8c3799708e74ec49da9d0b80a7f0988b934901 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 5 Jul 2019 15:33:59 +0200 Subject: [PATCH 297/546] Add TrapezoidalAccelerationAtRest for quaternions --- src/rl/math/SplineQuaternion.h | 60 ++++++++++++++++++++++++++++++++++ 1 file changed, 60 insertions(+) diff --git a/src/rl/math/SplineQuaternion.h b/src/rl/math/SplineQuaternion.h index 06ae99f0..73f54d2b 100644 --- a/src/rl/math/SplineQuaternion.h +++ b/src/rl/math/SplineQuaternion.h @@ -161,6 +161,66 @@ namespace rl return f; } + static Spline TrapezoidalAccelerationAtRest(const Quaternion& y0, const Quaternion& y1, const Vector3& vmax, const Vector3& amax, const Vector3& jmax) + { + using ::std::abs; + using ::std::atan2; + + Spline f; + + Quaternion dy = y0.conjugate() * y1; + Real norm = dy.vec().norm(); + Real dtheta = 2 * atan2(norm, abs(dy.w())); + Vector3 e = dy.vec(); + + if (norm > 0) + { + e /= norm; + } + + Vector3 q0 = Vector3::Zero(); + Vector3 q1 = e * dtheta; + + Spline f2 = Spline::TrapezoidalAccelerationAtRest(q0, q1, vmax, amax, jmax); + + for (::std::size_t i = 0; i < f2.size(); ++i) + { + Polynomial fi(f2[i].degree()); + + ::rl::math::Real dx = f2[i].upper() - f2[i].lower(); + ::rl::math::Real dx2 = dx * dx; + ::rl::math::Real dx3 = dx2 * dx; + + switch (f2[i].degree()) + { + case 1: + fi.coefficient(0) = -f2[i].coefficient(0); + fi.coefficient(1) = f2[i].coefficient(0) + dx * f2[i].coefficient(1); + break; + case 2: + fi.coefficient(0) = f2[i].coefficient(0); + fi.coefficient(1) = -2 * f2[i].coefficient(0) - dx * f2[i].coefficient(1); + fi.coefficient(2) = f2[i].coefficient(0) + dx * f2[i].coefficient(1) + dx2 * f2[i].coefficient(2); + break; + case 3: + fi.coefficient(0) = -f2[i].coefficient(0); + fi.coefficient(1) = 3 * f2[i].coefficient(0) + dx * f2[i].coefficient(1); + fi.coefficient(2) = -3 * f2[i].coefficient(0) - 2 * dx * f2[i].coefficient(1) - dx2 * f2[i].coefficient(2); + fi.coefficient(3) = f2[i].coefficient(0) + dx * f2[i].coefficient(1) + dx2 * f2[i].coefficient(2) + dx3 * f2[i].coefficient(3); + break; + default: + break; + } + + fi.lower() = f2[i].lower(); + fi.upper() = f2[i].upper(); + fi.y0 = y0; + f.push_back(fi); + } + + return f; + } + Polynomial& at(const ::std::size_t& i) { return this->polynomials.at(i); From d6884c761e3f8afd2586d3dbeb1cb8500c7987f4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 18 Sep 2019 17:06:46 +0200 Subject: [PATCH 298/546] Fix Jacobian derivative world frame transformation --- src/rl/mdl/Kinematic.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 69795ff4..9858a9d5 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -112,8 +112,9 @@ namespace rl { if (inWorldFrame) { - Jdqd.segment(j * 6, 3) = this->getOperationalPosition(j).linear() * this->getOperationalAcceleration(j).linear(); - Jdqd.segment(j * 6 + 3, 3) = this->getOperationalPosition(j).linear() * this->getOperationalAcceleration(j).angular(); + rl::math::Matrix33 wR = this->getOperationalVelocity(j).angular().cross33() * this->getOperationalPosition(j).linear(); + Jdqd.segment(j * 6, 3) = this->getOperationalPosition(j).linear() * this->getOperationalAcceleration(j).linear() + wR * this->getOperationalVelocity(j).linear(); + Jdqd.segment(j * 6 + 3, 3) = this->getOperationalPosition(j).linear() * this->getOperationalAcceleration(j).angular() + wR * this->getOperationalVelocity(j).angular(); } else { From 846114b758440069b50c8326dfd7a991fc972c53 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 19 Sep 2019 11:47:26 +0200 Subject: [PATCH 299/546] Update rl::math::Unit enum --- src/rl/math/Unit.h | 397 +++++++++++++++++++++++++++++++-------------- 1 file changed, 273 insertions(+), 124 deletions(-) diff --git a/src/rl/math/Unit.h b/src/rl/math/Unit.h index 66007877..4df649f1 100644 --- a/src/rl/math/Unit.h +++ b/src/rl/math/Unit.h @@ -36,150 +36,299 @@ namespace rl namespace math { /** - *

SI base units

- * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - *
NameSymbolMeasure
metermlength
kilogramkgmass
secondstime
ampereAelectric current
kelvinKthermodynamic temperature
molemolquantity of matter (mass/mass)
candelacdluminous intensity
- * - *

SI derived units

- * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - * - *
NameSymbolQuantityExpression in terms of SI base units
radianradAngle
hertzHzfrequencys-1
newtonNForce, Weightm · kg · s-2
voltVElectrical potential difference, Electromotive forcem2 · kg · s-3 · A-1
degree Celsius@htmlonly °C @endhtmlonlyThermodynamic temperatureTºC = TK - 273.16
meter per secondm · s-1speed, velocitym · s-1
meter per second squaredm · s-2accelerationm · s-2
radian per secondrad · s-1angular velocitys-1
newton secondN · smomentum, impulsekg · m · s-1
newton meter secondN · m · sangular momentumkg · m2 · s-1
newton meterN · mTorque, moment of forcekg · m2 · s-2
+ * Values describing [base units](https://en.wikipedia.org/wiki/SI_base_unit) and + * [derived units](https://en.wikipedia.org/wiki/SI_derived_unit) of the + * [International System of Units](https://en.wikipedia.org/wiki/International_System_of_Units). */ enum Unit { + /** + * Value used for describing dimensionless quantities. + */ UNIT_NONE, + /** + * The [second](https://en.wikipedia.org/wiki/Second) (symbol **s**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [time](https://en.wikipedia.org/wiki/Time). + */ + UNIT_SECOND, + /** + * The [meter](https://en.wikipedia.org/wiki/Meter) (symbol **m**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [length](https://en.wikipedia.org/wiki/Length). + */ UNIT_METER, + /** + * The [kilogram](https://en.wikipedia.org/wiki/Kilogram) (symbol **kg**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [mass](https://en.wikipedia.org/wiki/Mass). + */ UNIT_KILOGRAM, - UNIT_SECOND, + /** + * The [ampere](https://en.wikipedia.org/wiki/Ampere) (symbol **A**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [electric current](https://en.wikipedia.org/wiki/Electric_current). + */ UNIT_AMPERE, + /** + * The [kelvin](https://en.wikipedia.org/wiki/Kelvin) (symbol **K**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [thermodynamic temperature](https://en.wikipedia.org/wiki/Thermodynamic_temperature). + */ UNIT_KELVIN, + /** + * The [mole](https://en.wikipedia.org/wiki/Mole_%28unit%29) (symbol **mol**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [amount of substance](https://en.wikipedia.org/wiki/Amount_of_substance). + */ UNIT_MOLE, + /** + * The [candela](https://en.wikipedia.org/wiki/Candela) (symbol **cd**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [luminous intensity](https://en.wikipedia.org/wiki/Luminous_intensity). + */ UNIT_CANDELA, + /** + * The [radian](https://en.wikipedia.org/wiki/Radian) (symbol **rad**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [plane angle](https://en.wikipedia.org/wiki/Angle). + */ UNIT_RADIAN, + /** + * The [steradian](https://en.wikipedia.org/wiki/Radian) (symbol **sr**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [solid angle](https://en.wikipedia.org/wiki/Solid_angle). + */ + UNIT_STERADIAN, + /** + * The [hertz](https://en.wikipedia.org/wiki/Hertz) (symbol **Hz**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [frequency](https://en.wikipedia.org/wiki/Frequency) + * and is defined as s-1. + */ UNIT_HERTZ, + /** + * The [newton](https://en.wikipedia.org/wiki/Newton_(unit)) (symbol **N**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [force](https://en.wikipedia.org/wiki/Force) + * and is defined as kg · m · s-2. + */ UNIT_NEWTON, + /** + * The [pascal](https://en.wikipedia.org/wiki/Pascal_(unit)) (symbol **Pa**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [pressure](https://en.wikipedia.org/wiki/Pressure) + * and is defined as kg · m-1 · s-2. + */ + UNIT_PASCAL, + /** + * The [joule](https://en.wikipedia.org/wiki/Joule) (symbol **J**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [energy](https://en.wikipedia.org/wiki/Energy) + * and is defined as kg · m-2 · s-2. + */ + UNIT_JOULE, + /** + * The [watt](https://en.wikipedia.org/wiki/Watt) (symbol **W**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [power](https://en.wikipedia.org/wiki/Power_(physics)) + * and is defined as kg · m-2 · s-3. + */ + UNIT_WATT, + /** + * The [coulomb](https://en.wikipedia.org/wiki/Coulomb) (symbol **C**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electric charge](https://en.wikipedia.org/wiki/Electric_charge) + * and is defined as s · A. + */ + UNIT_COULOMB, + /** + * The [volt](https://en.wikipedia.org/wiki/Volt) (symbol **V**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electric potential](https://en.wikipedia.org/wiki/Electric_potential), + * [electric potential difference](https://en.wikipedia.org/wiki/Electric_potential_difference), and + * [electromotive force](https://en.wikipedia.org/wiki/Electromotive_force) + * and is defined as kg · m2 · s-3 · A-1. + */ UNIT_VOLT, + /** + * The [farad](https://en.wikipedia.org/wiki/Farad) (symbol **F**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electrical capacitance](https://en.wikipedia.org/wiki/Capacitance) + * and is defined as kg-1 · m-2 · s4 · A2. + */ + UNIT_FARAD, + /** + * The [ohm](https://en.wikipedia.org/wiki/Ohm) (symbol **Ω**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electrical resistance](https://en.wikipedia.org/wiki/Electrical_resistance) + * and is defined as kg · m2 · s-3 · A-2. + */ + UNIT_OHM, + /** + * The [siemens](https://en.wikipedia.org/wiki/Siemens_(unit)) (symbol **S**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electrical conductance](https://en.wikipedia.org/wiki/Electric_conductance) + * and is defined as kg-1 · m-2 · s3 · A2. + */ + UNIT_SIEMENS, + /** + * The [weber](https://en.wikipedia.org/wiki/Weber_(unit)) (symbol **Wb**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [magnetic flux](https://en.wikipedia.org/wiki/Magnetic_flux) + * and is defined as kg · m2 · s-2 · A-1. + */ + UNIT_WEBER, + /** + * The [tesla](https://en.wikipedia.org/wiki/Tesla_(unit)) (symbol **T**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [magnetic flux density](https://en.wikipedia.org/wiki/Magnetic_flux_density) + * and is defined as kg · s-2 · A-1. + */ + UNIT_TESLA, + /** + * The [henry](https://en.wikipedia.org/wiki/Henry_(unit)) (symbol **H**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electrical inductance](https://en.wikipedia.org/wiki/Inductance) + * and is defined as kg · m2 · s-2 · A-2. + */ + UNIT_HENRY, + /** + * The [degree Celsius](https://en.wikipedia.org/wiki/Degree_Celsius) (symbol **ºC**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * referring to a temperature on the Celsius scale and is defined as temperature + * relative to 273.15 K. + */ UNIT_CELSIUS, + /** + * The [lumen](https://en.wikipedia.org/wiki/Lumen_(unit)) (symbol **lm**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [luminous flux](https://en.wikipedia.org/wiki/Luminous_flux) + * and is defined as cd · sr. + */ + UNIT_LUMEN, + /** + * The [lux](https://en.wikipedia.org/wiki/Lux) (symbol **lx**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [illuminance](https://en.wikipedia.org/wiki/Illuminance) + * and is defined as m-2 · cd. + */ + UNIT_LUX, + /** + * The [becquerel](https://en.wikipedia.org/wiki/Becquerel) (symbol **Bq**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [radioactivity](https://en.wikipedia.org/wiki/Radioactivity) + * and is defined as s-1. + */ + UNIT_BECQUEREL, + /** + * The [gray](https://en.wikipedia.org/wiki/Gray_(unit)) (symbol **Gy**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [absorbed dose](https://en.wikipedia.org/wiki/Absorbed_dose) + * of [ionising radiation](https://en.wikipedia.org/wiki/Ionizing_radiation) + * and is defined as m2 · s-2. + */ + UNIT_GRAY, + /** + * The [sievert](https://en.wikipedia.org/wiki/Sievert) (symbol **Sv**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [equivalent dose](https://en.wikipedia.org/wiki/Equivalent_dose) + * of [ionising radiation](https://en.wikipedia.org/wiki/Ionizing_radiation) + * and is defined as m2 · s-2. + */ + UNIT_SIEVERT, + /** + * The [katal](https://en.wikipedia.org/wiki/Katal) (symbol **kat**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [catalytic activity](https://en.wikipedia.org/wiki/Catalytic_activity) + * and is defined as mol · s-1. + */ + UNIT_KATAL, + /** + * The [square meter](https://en.wikipedia.org/wiki/Square_metre) (symbol **m2**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [area](https://en.wikipedia.org/wiki/Area) + * and is defined as m2. + */ + UNIT_SQUARE_METER, + /** + * The [cubic meter](https://en.wikipedia.org/wiki/Cubic_metre) (symbol **m3**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [volume](https://en.wikipedia.org/wiki/Volume) + * and is defined as m3. + */ + UNIT_CUBIC_METER, + /** + * The [meter per second](https://en.wikipedia.org/wiki/Metre_per_second) (symbol **m · s-1**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of both [speed](https://en.wikipedia.org/wiki/Speed) and + * [velocity](https://en.wikipedia.org/wiki/Velocity) + * and is defined as m · s-1. + */ UNIT_METER_PER_SECOND, + /** + * The [meter per second squared](https://en.wikipedia.org/wiki/Metre_per_second_squared) (symbol **m · s-2**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [acceleration](https://en.wikipedia.org/wiki/Acceleration) + * and is defined as m · s-2. + */ UNIT_METER_PER_SECOND_SQUARED, + /** + * The kilogram per square meter (symbol **kg · m-2**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [surface density](https://en.wikipedia.org/wiki/Surface_density) + * and is defined as kg · m-2. + */ + UNIT_KILOGRAM_PER_SQUARE_METER, + /** + * The [kilogram per cubic meter](https://en.wikipedia.org/wiki/Kilogram_per_cubic_metre) (symbol **kg · m-3**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [density](https://en.wikipedia.org/wiki/Density) + * and is defined as kg · m-3. + */ + UNIT_KILOGRAM_PER_CUBIC_METER, + /** + * The [newton meter](https://en.wikipedia.org/wiki/Newton_metre) (symbol **N · m**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [torque](https://en.wikipedia.org/wiki/Torque) + * and is defined as kg · m2 · s-2. + */ + UNIT_NEWTON_METER, + /** + * The newton per meter (symbol **N · m-1**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [surface tension](https://en.wikipedia.org/wiki/Surface_tension) + * and is defined as kg · s-2. + */ + UNIT_NEWTON_PER_METER, + /** + * The [radian per second](https://en.wikipedia.org/wiki/Radian_per_second) (symbol **rad · s-1**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [angular velocity](https://en.wikipedia.org/wiki/Angular_velocity) + * and is defined as rad · s-1. + */ UNIT_RADIAN_PER_SECOND, + /** + * The [radian per second squared](https://en.wikipedia.org/wiki/Radian_per_second_squared) (symbol **rad · s-2**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [angular acceleration](https://en.wikipedia.org/wiki/Angular_acceleration) + * and is defined as rad · s-2. + */ UNIT_RADIAN_PER_SECOND_SQUARED, + /** + * The [newton second](https://en.wikipedia.org/wiki/Newton_second) (symbol **N · s**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [impulse](https://en.wikipedia.org/wiki/Impulse_(physics)) + * and is defined as kg · m · s-1. + */ UNIT_NEWTON_SECOND, - UNIT_NEWTON_METER_SECOND, - UNIT_NEWTON_METER + /** + * The newton meter second (symbol **N · m · s**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [angular momentum](https://en.wikipedia.org/wiki/Angular_momentum) + * and is defined as kg · m2 · s-1. + */ + UNIT_NEWTON_METER_SECOND }; static const Real DEG2RAD = static_cast(M_PI) / static_cast(180); From cf80459440ed2ca79d046dccf60a954be8469e26 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 19 Sep 2019 11:48:14 +0200 Subject: [PATCH 300/546] Add documentation for constants --- src/rl/math/Unit.h | 23 ++++++++++++++++++++++- 1 file changed, 22 insertions(+), 1 deletion(-) diff --git a/src/rl/math/Unit.h b/src/rl/math/Unit.h index 4df649f1..d6d29df7 100644 --- a/src/rl/math/Unit.h +++ b/src/rl/math/Unit.h @@ -331,11 +331,25 @@ namespace rl UNIT_NEWTON_METER_SECOND }; + /** + * Constant for converting an angular value in + * [degree](https://en.wikipedia.org/wiki/Degree_(angle)) to + * [radian](https://en.wikipedia.org/wiki/Radian). + * + * This is equal to a multiplication by π and a division by 180. + */ static const Real DEG2RAD = static_cast(M_PI) / static_cast(180); static const Real GIGA2UNIT = static_cast(1.0e+9); - /** [m · s-2] */ + /** + * Standard acceleration due to gravity. + * + * [Standard gravity](https://en.wikipedia.org/wiki/Standard_gravity) is the nominal + * [gravitational acceleration](https://en.wikipedia.org/wiki/Gravitational_acceleration) + * of an object in a vacuum near the surface of the earth. It is defined as 9.80665 m · s-2 + * by [ISO 80000-3](https://en.wikipedia.org/wiki/ISO_80000-3). + */ static const Real GRAVITY = static_cast(9.80665); static const Real KILO2UNIT = static_cast(1.0e+3); @@ -348,6 +362,13 @@ namespace rl static const Real NANO2UNIT = static_cast(1.0e-9); + /** + * Constant for converting an angular value in + * [radian](https://en.wikipedia.org/wiki/Radian) to + * [degree](https://en.wikipedia.org/wiki/Degree_(angle)). + * + * This is equal to a multiplication by 180 and a division by π. + */ static const Real RAD2DEG = static_cast(180) / static_cast(M_PI); static const Real UNIT2GIGA = static_cast(1.0e-9); From 075e990a522b3bc0cc68ca33196552d09a10339b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 7 Oct 2019 22:10:53 +0200 Subject: [PATCH 301/546] Fix socket address length for macOS --- src/rl/hal/Socket.cpp | 21 +++++++++++++++++++-- src/rl/hal/Socket.h | 2 ++ 2 files changed, 21 insertions(+), 2 deletions(-) diff --git a/src/rl/hal/Socket.cpp b/src/rl/hal/Socket.cpp index 342f625f..4aea8e9c 100644 --- a/src/rl/hal/Socket.cpp +++ b/src/rl/hal/Socket.cpp @@ -151,7 +151,7 @@ namespace rl void Socket::bind() { - int err = ::bind(this->fd, reinterpret_cast(&this->address.get()), sizeof(this->address.get())); + int err = ::bind(this->fd, reinterpret_cast(&this->address.get()), this->address.getLength()); #ifdef WIN32 if (SOCKET_ERROR == err) @@ -202,7 +202,7 @@ namespace rl void Socket::connect() { - int err = ::connect(this->fd, reinterpret_cast(&this->address.get()), sizeof(this->address.get())); + int err = ::connect(this->fd, reinterpret_cast(&this->address.get()), this->address.getLength()); #ifdef WIN32 if (SOCKET_ERROR == err) @@ -759,6 +759,23 @@ namespace rl return hexadecimal; } + ::std::size_t + Socket::Address::getLength() const + { + switch (this->addr.ss_family) + { + case AF_INET: + return sizeof(::sockaddr_in); + break; + case AF_INET6: + return sizeof(::sockaddr_in6); + break; + default: + return 0; + break; + } + } + ::std::string Socket::Address::getNameInfo(const bool& asNumeric) const { diff --git a/src/rl/hal/Socket.h b/src/rl/hal/Socket.h index 643efd35..d7f4ca32 100644 --- a/src/rl/hal/Socket.h +++ b/src/rl/hal/Socket.h @@ -70,6 +70,8 @@ namespace rl ::std::vector getHexadecimal(); + ::std::size_t getLength() const; + ::std::string getNameInfo(const bool& asNumeric = false) const; Socket::Address& operator=(const Socket::Address& other); From c0e6fb05dcac9d9f6cc1dec8cd79a44d6a2266cb Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 16 Oct 2019 16:59:18 +0200 Subject: [PATCH 302/546] Update Boost_ADDITIONAL_VERSIONS to support 1.71.0 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 9cf44e01..b61029a0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,7 +16,7 @@ include(GenerateExportHeader) include(GNUInstallDirs) include(Qt4AutomocMocOptionsBoost) -set(Boost_ADDITIONAL_VERSIONS "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") +set(Boost_ADDITIONAL_VERSIONS "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) From 65bfa74ea5b71eff838f9d0e4b2d315d26677304 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 16 Oct 2019 17:00:07 +0200 Subject: [PATCH 303/546] Update Boost to 1.71.0 --- 3rdparty/boost/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/boost/CMakeLists.txt b/3rdparty/boost/CMakeLists.txt index 2dacce9a..b7b94eb3 100644 --- a/3rdparty/boost/CMakeLists.txt +++ b/3rdparty/boost/CMakeLists.txt @@ -7,9 +7,9 @@ include(GNUInstallDirs) ExternalProject_Add( boost - URL https://dl.bintray.com/boostorg/release/1.70.0/source/boost_1_70_0.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_70_0.tar.bz2 - URL_MD5 242ecc63507711d6706b9b0c0d0c7d4f + URL https://dl.bintray.com/boostorg/release/1.71.0/source/boost_1_71_0.tar.bz2 + #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_71_0.tar.bz2 + URL_MD5 4cdf9b5c2dc01fb2b7b733d5af30e558 CONFIGURE_COMMAND "" BUILD_COMMAND "" BUILD_IN_SOURCE 1 From 8e70bc36796d1d2c169a6ae9e3cca9ee8afbad36 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 16 Oct 2019 17:18:21 +0200 Subject: [PATCH 304/546] Disable building of Python bindings for libxml2 and libxslt --- 3rdparty/libxml2/CMakeLists.txt | 2 +- 3rdparty/libxslt/CMakeLists.txt | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/3rdparty/libxml2/CMakeLists.txt b/3rdparty/libxml2/CMakeLists.txt index b2e7b472..f80c8549 100644 --- a/3rdparty/libxml2/CMakeLists.txt +++ b/3rdparty/libxml2/CMakeLists.txt @@ -10,6 +10,6 @@ ExternalProject_Add( URL https://github.com/roboticslibrary/libxml2/archive/patch.zip #URL ${CMAKE_CURRENT_SOURCE_DIR}/libxml2-2.9.5.tar.gz #URL_MD5 5ce0da9bdaa267b40c4ca36d35363b8b - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DLIBXML2_WITH_PYTHON=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) diff --git a/3rdparty/libxslt/CMakeLists.txt b/3rdparty/libxslt/CMakeLists.txt index e7bfa7d3..8b8ef2c8 100644 --- a/3rdparty/libxslt/CMakeLists.txt +++ b/3rdparty/libxslt/CMakeLists.txt @@ -10,6 +10,6 @@ ExternalProject_Add( URL https://github.com/roboticslibrary/libxslt/archive/patch.zip #URL ${CMAKE_CURRENT_SOURCE_DIR}/libxslt-1.1.30.tar.gz #URL_MD5 d41d8cd98f00b204e9800998ecf8427e - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DLIBXSLT_WITH_PYTHON=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From ce37a03da086fb135a74254afdf2042270d55615 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 28 Nov 2019 15:08:00 +0100 Subject: [PATCH 305/546] Update rlEetTest vertex and edge count --- tests/rlEetTest/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index 4e14f464..676fc29f 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -71,7 +71,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) solid ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml - 306 305 + 321 320 2 1 1 0 0 0 9 11 1 0 0 -90 ) From 658cdd8387397261ebf0f52d3bde74aae0379e24 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 28 Nov 2019 17:18:35 +0100 Subject: [PATCH 306/546] Add GitHub action for continuous integration --- .github/workflows/ci.yml | 107 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 107 insertions(+) create mode 100644 .github/workflows/ci.yml diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml new file mode 100644 index 00000000..630ec7ba --- /dev/null +++ b/.github/workflows/ci.yml @@ -0,0 +1,107 @@ +name: CI +on: + push: + branches: + - master + pull_request: + branches: + - master +jobs: + build: + runs-on: ${{ matrix.os }} + strategy: + fail-fast: false + matrix: + name: [macos-latest, ubuntu-latest-clang, ubuntu-latest-gcc] + include: + - name: macos-latest + cmake_prefix_path: /usr/local/opt/qt/lib/cmake + developer_dir: /Applications/Xcode_11.2.1.app/Contents/Developer + os: macos-latest + path: /usr/local/opt/ccache/libexec + - name: ubuntu-latest-clang + cc: clang + cxx: clang++ + os: ubuntu-latest + path: /usr/lib/ccache + - name: ubuntu-latest-gcc + cc: gcc + cxx: g++ + os: ubuntu-latest + path: /usr/lib/ccache + env: + CC: ${{ matrix.cc }} + CMAKE_PREFIX_PATH: ${{ matrix.cmake_prefix_path }} + CXX: ${{ matrix.cxx }} + DEVELOPER_DIR: ${{ matrix.developer_dir }} + steps: + - uses: actions/checkout@v1 + - if: matrix.os == 'macos-latest' + name: Set up Tap + run: | + brew tap roboticslibrary/rl + - if: matrix.os == 'ubuntu-latest' + name: Set up PPA + run: | + sudo apt-get install -y software-properties-common + sudo apt-add-repository -y -u ppa:roblib/ppa + - if: matrix.os == 'macos-latest' + name: Install dependencies for macOS + run: > + brew install + boost + bullet + ccache + cmake + coin + eigen + ninja + nlopt + ode + pqp + qt + solid + soqt + - if: matrix.os == 'ubuntu-latest' + name: Install dependencies for Ubuntu + run: > + sudo apt-get install -y + build-essential + ccache + clang + cmake + libboost-dev + libbullet-dev + libcomedi-dev + libdc1394-22-dev + libeigen3-dev + libnlopt-dev + libode-dev + libsimage-dev + libsolid3d-dev + libsoqt-dev + libxml2-dev + libxslt1-dev + ninja-build + - name: Cache compiler + uses: actions/cache@v1 + with: + path: ~/.ccache + key: ${{ runner.os }}-${{ matrix.cc }}-ccache + - name: Create build directory + run: | + cmake -E make_directory ${{ runner.workspace }}/build + - name: Update PATH + run: echo ::add-path::${{ matrix.path }} + - name: Configure CMake + working-directory: ${{ runner.workspace }}/build + run: | + cmake -G Ninja -D CMAKE_BUILD_TYPE=RelWithDebInfo $GITHUB_WORKSPACE + - name: Build + working-directory: ${{ runner.workspace }}/build + run: | + cmake --build . + - name: Test + working-directory: ${{ runner.workspace }}/build + run: | + ctest --output-on-failure From f8a4eb8948a415658aeccdd906e2cc45d5515a33 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 4 Dec 2019 18:01:02 +0100 Subject: [PATCH 307/546] Update check for configured ODE precision --- cmake/FindODE.cmake | 47 ++++++++++++++++++++++++++++++++------------- 1 file changed, 34 insertions(+), 13 deletions(-) diff --git a/cmake/FindODE.cmake b/cmake/FindODE.cmake index b8c2590b..4cddb193 100644 --- a/cmake/FindODE.cmake +++ b/cmake/FindODE.cmake @@ -1,4 +1,5 @@ include(CheckCSourceRuns) +include(CheckSymbolExists) include(FindPackageHandleStandardArgs) include(GNUInstallDirs) include(SelectLibraryConfigurations) @@ -126,19 +127,39 @@ find_library( select_library_configurations(ODE) -set(CMAKE_REQUIRED_DEFINITIONS -DdDOUBLE) -set(CMAKE_REQUIRED_INCLUDES ${ODE_INCLUDE_DIRS}) -set(CMAKE_REQUIRED_LIBRARIES ${ODE_LIBRARIES}) - -check_c_source_runs(" - #include - int main() { return 1 == dCheckConfiguration(\"ODE_double_precision\") ? 0 : 1; } -" ODE_DOUBLE_PRECISION) - -if(ODE_DOUBLE_PRECISION) - set(ODE_DEFINITIONS -DdDOUBLE) -else() - set(ODE_DEFINITIONS -DdSINGLE) +if(ODE_INCLUDE_DIRS AND ODE_LIBRARIES) + set(CMAKE_REQUIRED_INCLUDES ${ODE_INCLUDE_DIRS}) + + check_symbol_exists(dDOUBLE "ode/precision.h" ODE_HAVE_DOUBLE) + + if(NOT ODE_HAVE_DOUBLE) + check_symbol_exists(dSINGLE "ode/precision.h" ODE_HAVE_SINGLE) + endif() + + if(NOT ODE_HAVE_DOUBLE AND NOT ODE_HAVE_SINGLE) + set(CMAKE_REQUIRED_DEFINITIONS -DdDOUBLE) + set(CMAKE_REQUIRED_LIBRARIES ${ODE_LIBRARIES}) + + check_c_source_runs(" + #include + int main() { return 1 == dCheckConfiguration(\"ODE_double_precision\") ? 0 : 1; } + " ODE_DOUBLE_PRECISION) + + if(ODE_DOUBLE_PRECISION) + set(ODE_DEFINITIONS -DdDOUBLE) + else() + set(CMAKE_REQUIRED_DEFINITIONS -DdSINGLE) + + check_c_source_runs(" + #include + int main() { return 1 == dCheckConfiguration(\"ODE_single_precision\") ? 0 : 1; } + " ODE_SINGLE_PRECISION) + + if(ODE_SINGLE_PRECISION) + set(ODE_DEFINITIONS -DdSINGLE) + endif() + endif() + endif() endif() mark_as_advanced(ODE_DEFINITIONS) From 3c94031965f3c200dde4b4c5172d7cf748c0f844 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 7 Dec 2019 15:23:18 +0100 Subject: [PATCH 308/546] Remove unused function definition --- src/rl/sg/bullet/Scene.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/rl/sg/bullet/Scene.h b/src/rl/sg/bullet/Scene.h index 8cb40690..541fda19 100644 --- a/src/rl/sg/bullet/Scene.h +++ b/src/rl/sg/bullet/Scene.h @@ -76,8 +76,6 @@ namespace rl bool raycast(::rl::sg::Shape* shape, const ::rl::math::Vector3& source, const ::rl::math::Vector3& target, ::rl::math::Real& distance); - void setMargin(const ::rl::math::Real& margin); - ::btDbvtBroadphase broadphase; ::btDefaultCollisionConfiguration configuration; From 5e16b42f53bc393af060e208375b5bd40cd69ef4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 12 Dec 2019 18:35:48 +0100 Subject: [PATCH 309/546] Add support for UR firmware 3.6 to 3.12 and 5.0 to 5.6 --- src/rl/hal/UniversalRobotsRealtime.cpp | 126 +++++++++++++++++-------- src/rl/hal/UniversalRobotsRealtime.h | 35 ++++++- 2 files changed, 117 insertions(+), 44 deletions(-) diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index 520c93c8..a1156559 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -25,7 +25,6 @@ // #include -#include #include #include "DeviceException.h" @@ -229,6 +228,12 @@ namespace rl return static_cast(static_cast(this->in.safetyMode)); } + UniversalRobotsRealtime::SafetyStatus + UniversalRobotsRealtime::getSafetyStatus() const + { + return static_cast(static_cast(this->in.safetyStatus)); + } + void UniversalRobotsRealtime::open() { @@ -247,12 +252,35 @@ namespace rl void UniversalRobotsRealtime::step() { - ::std::array< ::std::uint8_t, 1108> buffer; - this->socket.recv(buffer.data(), buffer.size()); + ::std::array< ::std::uint8_t, 1116> buffer; + + this->socket.recv(buffer.data(), sizeof(this->in.messageSize)); #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) this->socket.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); #endif // __APPLE__ || __QNX__ || WIN32 - this->in.unserialize(buffer.data()); + + ::std::uint8_t* ptr = buffer.data(); + this->in.unserialize(ptr, this->in.messageSize); + + switch (this->in.messageSize) + { + case 756: + case 764: + case 812: + case 1044: + case 1060: + case 1108: + case 1116: + this->socket.recv(ptr, this->in.messageSize - sizeof(this->in.messageSize)); +#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) + this->socket.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); +#endif // __APPLE__ || __QNX__ || WIN32 + this->in.unserialize(ptr); + break; + default: + throw DeviceException("UniversalRobotsRealtime::step() - Incorrect message size " + ::std::to_string(this->in.messageSize)); + break; + } } void @@ -264,13 +292,6 @@ namespace rl void UniversalRobotsRealtime::Message::unserialize(::std::uint8_t* ptr) { - this->unserialize(ptr, this->messageSize); - - if (756 != this->messageSize && 764 != this->messageSize && 812 != this->messageSize && 1044 != this->messageSize && 1060 != this->messageSize && 1108 != this->messageSize) - { - throw DeviceException("UniversalRobotsRealtime::Message::unserialize() - Incorrect message size"); - } - this->unserialize(ptr, this->time); this->unserialize(ptr, this->qTarget); this->unserialize(ptr, this->qdTarget); @@ -281,30 +302,36 @@ namespace rl this->unserialize(ptr, this->qdActual); this->unserialize(ptr, this->iActual); - if (756 == this->messageSize) + switch (this->messageSize) { + case 756: ptr += 3 * sizeof(double); ptr += 15 * sizeof(double); this->unserialize(ptr, this->tcpForce); this->unserialize(ptr, this->toolVectorActual); this->unserialize(ptr, this->tcpSpeedActual); - } - else if (764 == this->messageSize || 812 == this->messageSize) - { + break; + case 764: + case 812: this->unserialize(ptr, this->toolAccelerometerValues); ptr += 15 * sizeof(double); this->unserialize(ptr, this->tcpForce); this->unserialize(ptr, this->toolVectorActual); this->unserialize(ptr, this->tcpSpeedActual); - } - else if (1044 == this->messageSize || 1060 == this->messageSize || 1108 == this->messageSize) - { + break; + case 1044: + case 1060: + case 1108: + case 1116: this->unserialize(ptr, this->iControl); this->unserialize(ptr, this->toolVectorActual); this->unserialize(ptr, this->tcpSpeedActual); this->unserialize(ptr, this->tcpForce); this->unserialize(ptr, this->toolVectorTarget); this->unserialize(ptr, this->tcpSpeedTarget); + break; + default: + break; } this->unserialize(ptr, this->digitalInputBits); @@ -312,43 +339,60 @@ namespace rl this->unserialize(ptr, this->controllerTimer); this->unserialize(ptr, this->testValue); - if (764 == this->messageSize || 812 == this->messageSize || 1044 == this->messageSize || 1060 == this->messageSize || 1108 == this->messageSize) + if (this->messageSize < 764) { - this->unserialize(ptr, this->robotMode); + return; } - if (812 == this->messageSize || 1044 == this->messageSize || 1060 == this->messageSize || 1108 == this->messageSize) + this->unserialize(ptr, this->robotMode); + + if (this->messageSize < 812) { - this->unserialize(ptr, this->jointModes); + return; } - if (1044 == this->messageSize || 1060 == this->messageSize || 1108 == this->messageSize) + this->unserialize(ptr, this->jointModes); + + if (this->messageSize < 1044) { - this->unserialize(ptr, this->safetyMode); - ptr += 6 * sizeof(double); - this->unserialize(ptr, this->toolAccelerometerValues); - ptr += 6 * sizeof(double); - this->unserialize(ptr, this->speedScaling); - this->unserialize(ptr, this->linearMomentumNorm); - ptr += 1 * sizeof(double); - ptr += 1 * sizeof(double); - this->unserialize(ptr, this->vMain); - this->unserialize(ptr, this->vRobot); - this->unserialize(ptr, this->iRobot); - this->unserialize(ptr, this->vActual); + return; } - if (1060 == this->messageSize || 1108 == this->messageSize) + this->unserialize(ptr, this->safetyMode); + ptr += 6 * sizeof(double); + this->unserialize(ptr, this->toolAccelerometerValues); + ptr += 6 * sizeof(double); + this->unserialize(ptr, this->speedScaling); + this->unserialize(ptr, this->linearMomentumNorm); + ptr += 1 * sizeof(double); + ptr += 1 * sizeof(double); + this->unserialize(ptr, this->vMain); + this->unserialize(ptr, this->vRobot); + this->unserialize(ptr, this->iRobot); + this->unserialize(ptr, this->vActual); + + if (this->messageSize < 1060) { - this->unserialize(ptr, this->digitalOutputs); - this->unserialize(ptr, this->programState); + return; } - if (1108 == this->messageSize) + this->unserialize(ptr, this->digitalOutputs); + this->unserialize(ptr, this->programState); + + if (this->messageSize < 1108) { - this->unserialize(ptr, this->elbowPosition); - this->unserialize(ptr, this->elbowVelocity); + return; } + + this->unserialize(ptr, this->elbowPosition); + this->unserialize(ptr, this->elbowVelocity); + + if (this->messageSize < 1116) + { + return; + } + + this->unserialize(ptr, this->safetyStatus); } template<> diff --git a/src/rl/hal/UniversalRobotsRealtime.h b/src/rl/hal/UniversalRobotsRealtime.h index 4088f499..f87076d5 100644 --- a/src/rl/hal/UniversalRobotsRealtime.h +++ b/src/rl/hal/UniversalRobotsRealtime.h @@ -46,7 +46,10 @@ namespace rl namespace hal { /** - * Universal Robots realtime interface (pre-3.0, 3.0, 3.1, 3.2, 3.3, 3.4, 3.5). + * Universal Robots realtime interface. + * + * Supports versions 1.5, 1.6, 1.7, 1.8, 3.0, 3.1, 3.2, 3.3, 3.4, 3.5, 3.6, + * 3.7, 3.8, 3.9, 3.10, 3.11, 3.12, 5.0, 5.1, 5.2, 5.3, 5.4, 5.5, 5.6. */ class RL_HAL_EXPORT UniversalRobotsRealtime : public CartesianForceSensor, @@ -62,6 +65,7 @@ namespace rl public: enum JointMode { + JOINT_MODE_RESET = 235, JOINT_MODE_SHUTTING_DOWN = 236, JOINT_MODE_PART_D_CALIBRATION = 237, JOINT_MODE_BACKDRIVE = 238, @@ -72,9 +76,10 @@ namespace rl JOINT_MODE_PART_D_CALIBRATION_ERROR = 248, JOINT_MODE_BOOTLOADER = 249, JOINT_MODE_CALIBRATION = 250, + JOINT_MODE_VIOLATION = 251, JOINT_MODE_FAULT = 252, JOINT_MODE_RUNNING = 253, - JOINT_MODE_IDLE_MODE = 255 + JOINT_MODE_IDLE = 255 }; enum ProgramState @@ -89,6 +94,7 @@ namespace rl enum RobotMode { + ROBOT_MODE_NO_CONTROLLER = -1, ROBOT_MODE_DISCONNECTED = 0, ROBOT_MODE_CONFIRM_SAFETY = 1, ROBOT_MODE_BOOTING = 2, @@ -110,7 +116,26 @@ namespace rl SAFETY_MODE_SYSTEM_EMERGENCY_STOP = 6, SAFETY_MODE_ROBOT_EMERGENCY_STOP = 7, SAFETY_MODE_VIOLATION = 8, - SAFETY_MODE_FAULT = 9 + SAFETY_MODE_FAULT = 9, + SAFETY_MODE_VALIDATE_JOINT_ID = 10, + SAFETY_MODE_UNDEFINED_SAFETY_MODE = 11 + }; + + enum SafetyStatus + { + SAFETY_STATUS_NORMAL = 1, + SAFETY_STATUS_REDUCED = 2, + SAFETY_STATUS_PROTECTIVE_STOP = 3, + SAFETY_STATUS_RECOVERY = 4, + SAFETY_STATUS_SAFEGUARD_STOP = 5, + SAFETY_STATUS_SYSTEM_EMERGENCY_STOP = 6, + SAFETY_STATUS_ROBOT_EMERGENCY_STOP = 7, + SAFETY_STATUS_VIOLATION = 8, + SAFETY_STATUS_FAULT = 9, + SAFETY_STATUS_VALIDATE_JOINT_ID = 10, + SAFETY_STATUS_UNDEFINED_SAFETY_MODE = 11, + SAFETY_STATUS_AUTOMATIC_MODE_SAFEGUARD_STOP = 12, + SAFETY_STATUS_SYSTEM_THREE_POSITION_ENABLING_STOP = 13 }; UniversalRobotsRealtime(const ::std::string& address); @@ -153,6 +178,8 @@ namespace rl SafetyMode getSafetyMode() const; + SafetyStatus getSafetyStatus() const; + void open(); void start(); @@ -252,6 +279,8 @@ namespace rl double elbowPosition[3]; double elbowVelocity[3]; + + double safetyStatus; }; Message in; From 4d15a39f3795a5577e790cdfc2d0481896267c3b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 21 Jan 2020 18:57:19 +0100 Subject: [PATCH 310/546] Fix typo --- src/rl/math/Spline.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index f2407638..444e786b 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -100,7 +100,7 @@ namespace rl * http://banach.millersville.edu/~bob/math375/CubicSpline/main.pdf * * @param[in] x \f$x_0, \ldots, x_n\f$ - * @param[in] y \f$f(x_0), \ldots, f_(x_n)\f$ + * @param[in] y \f$f(x_0), \ldots, f(x_n)\f$ * @param[in] yd0 \f$f'(x_0)\f$ * @param[in] yd1 \f$f'(x_n)\f$ */ @@ -198,7 +198,7 @@ namespace rl * http://banach.millersville.edu/~bob/math375/CubicSpline/main.pdf * * @param[in] x \f$x_0, \ldots, x_n\f$ - * @param[in] y \f$f(x_0), \ldots, f_(x_n)\f$ + * @param[in] y \f$f(x_0), \ldots, f(x_n)\f$ */ template static Spline CubicNatural(const Container1& x, const Container2& y) From c69b8656366d0617797e9bed3b6d49d16e803a37 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 31 Jan 2020 15:54:06 +0100 Subject: [PATCH 311/546] Update Boost to 1.72.0 --- 3rdparty/boost/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/boost/CMakeLists.txt b/3rdparty/boost/CMakeLists.txt index b7b94eb3..169d8400 100644 --- a/3rdparty/boost/CMakeLists.txt +++ b/3rdparty/boost/CMakeLists.txt @@ -7,9 +7,9 @@ include(GNUInstallDirs) ExternalProject_Add( boost - URL https://dl.bintray.com/boostorg/release/1.71.0/source/boost_1_71_0.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_71_0.tar.bz2 - URL_MD5 4cdf9b5c2dc01fb2b7b733d5af30e558 + URL https://dl.bintray.com/boostorg/release/1.72.0/source/boost_1_72_0.7z + #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_72_0.7z + URL_MD5 cbf2f2abf8cecf69210b60478bc51109 CONFIGURE_COMMAND "" BUILD_COMMAND "" BUILD_IN_SOURCE 1 From f767c36f161634db8eaf7f02b494fd156e85cccf Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 31 Jan 2020 15:54:37 +0100 Subject: [PATCH 312/546] Update Boost_ADDITIONAL_VERSIONS to support 1.72.0 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b61029a0..a3c0901d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -16,7 +16,7 @@ include(GenerateExportHeader) include(GNUInstallDirs) include(Qt4AutomocMocOptionsBoost) -set(Boost_ADDITIONAL_VERSIONS "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") +set(Boost_ADDITIONAL_VERSIONS "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) From dfaa3990c9cf37ec10aae417bc780608cd42058e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 31 Jan 2020 17:18:29 +0100 Subject: [PATCH 313/546] Update Coin3D versions and remote URLs --- 3rdparty/coin3d/coin/CMakeLists.txt | 9 +++++---- 3rdparty/coin3d/cpack.d/CMakeLists.txt | 9 +++++---- 3rdparty/coin3d/simage/CMakeLists.txt | 9 +++++---- 3rdparty/coin3d/soanydata/CMakeLists.txt | 9 +++++---- 3rdparty/coin3d/sogui/CMakeLists.txt | 9 +++++---- 3rdparty/coin3d/soqt/CMakeLists.txt | 9 +++++---- 6 files changed, 30 insertions(+), 24 deletions(-) diff --git a/3rdparty/coin3d/coin/CMakeLists.txt b/3rdparty/coin3d/coin/CMakeLists.txt index 30aca357..60dc3790 100644 --- a/3rdparty/coin3d/coin/CMakeLists.txt +++ b/3rdparty/coin3d/coin/CMakeLists.txt @@ -5,10 +5,11 @@ list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) ExternalProject_Add( coin DEPENDS boost cpack.d simage - #HG_REPOSITORY https://bitbucket.org/Coin3D/coin - #HG_TAG default - URL https://bitbucket.org/Coin3D/coin/get/default.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + #GIT_REPOSITORY https://github.com/coin3d/coin + #GIT_TAG Coin-4.0.0 + URL https://github.com/coin3d/coin/archive/Coin-4.0.0.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/coin-Coin-4.0.0.zip + URL_MD5 390c3db9cd5bb6644a20c7f88f37aaa2 PATCH_COMMAND ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DCOIN_BUILD_DOCUMENTATION=OFF -DCOIN_BUILD_TESTS=OFF diff --git a/3rdparty/coin3d/cpack.d/CMakeLists.txt b/3rdparty/coin3d/cpack.d/CMakeLists.txt index ee361662..e4dc681c 100644 --- a/3rdparty/coin3d/cpack.d/CMakeLists.txt +++ b/3rdparty/coin3d/cpack.d/CMakeLists.txt @@ -2,10 +2,11 @@ include(ExternalProject) ExternalProject_Add( cpack.d - #HG_REPOSITORY https://bitbucket.org/Coin3D/cpack.d - #HG_TAG default - URL https://bitbucket.org/Coin3D/cpack.d/get/default.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + #GIT_REPOSITORY https://bitbucket.org/Coin3D/cpack.d + #GIT_TAG b9ddb8116dd1bf98f2b1c858693c8b55cb80cad5 + URL https://github.com/coin3d/cpack.d/archive/b9ddb8116dd1bf98f2b1c858693c8b55cb80cad5.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/cpack.d-b9ddb8116dd1bf98f2b1c858693c8b55cb80cad5.zip + URL_MD5 35a40474754869bf86693349d00f49e2 CONFIGURE_COMMAND "" BUILD_COMMAND "" INSTALL_COMMAND "" diff --git a/3rdparty/coin3d/simage/CMakeLists.txt b/3rdparty/coin3d/simage/CMakeLists.txt index 3b23dd5f..ede3fedd 100644 --- a/3rdparty/coin3d/simage/CMakeLists.txt +++ b/3rdparty/coin3d/simage/CMakeLists.txt @@ -3,10 +3,11 @@ include(ExternalProject) ExternalProject_Add( simage DEPENDS cpack.d - #HG_REPOSITORY https://bitbucket.org/Coin3D/simage - #HG_TAG default - URL https://bitbucket.org/Coin3D/simage/get/default.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + #GIT_REPOSITORY https://github.com/coin3d/simage + #GIT_TAG simage-1.8.0 + URL https://github.com/coin3d/simage/archive/simage-1.8.0.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/simage-simage-1.8.0.tar.bz2 + URL_MD5 0d517db68d839dec57eff95226245d46 PATCH_COMMAND ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} diff --git a/3rdparty/coin3d/soanydata/CMakeLists.txt b/3rdparty/coin3d/soanydata/CMakeLists.txt index 7519ad02..7a9117bd 100644 --- a/3rdparty/coin3d/soanydata/CMakeLists.txt +++ b/3rdparty/coin3d/soanydata/CMakeLists.txt @@ -2,10 +2,11 @@ include(ExternalProject) ExternalProject_Add( soanydata - #HG_REPOSITORY https://bitbucket.org/Coin3D/soanydata - #HG_TAG default - URL https://bitbucket.org/Coin3D/soanydata/get/default.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + #GIT_REPOSITORY https://github.com/coin3d/soanydata + #GIT_TAG 3ff6e9203fbb0cc08a2bdf209212b7ef4d78a1f2 + URL https://github.com/coin3d/soanydata/archive/3ff6e9203fbb0cc08a2bdf209212b7ef4d78a1f2.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/soanydata-3ff6e9203fbb0cc08a2bdf209212b7ef4d78a1f2.zip + URL_MD5 17c8b33000f58fdb99d943e559d8fa21 CONFIGURE_COMMAND "" BUILD_COMMAND "" INSTALL_COMMAND "" diff --git a/3rdparty/coin3d/sogui/CMakeLists.txt b/3rdparty/coin3d/sogui/CMakeLists.txt index 782e7a59..18508e60 100644 --- a/3rdparty/coin3d/sogui/CMakeLists.txt +++ b/3rdparty/coin3d/sogui/CMakeLists.txt @@ -2,10 +2,11 @@ include(ExternalProject) ExternalProject_Add( sogui - #HG_REPOSITORY https://bitbucket.org/Coin3D/sogui - #HG_TAG default - URL https://bitbucket.org/Coin3D/sogui/get/default.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + #GIT_REPOSITORY https://github.com/coin3d/sogui + #GIT_TAG fb79af47cff89f0f3657501601a7ea5c11968b17 + URL https://github.com/coin3d/sogui/archive/fb79af47cff89f0f3657501601a7ea5c11968b17.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/sogui-fb79af47cff89f0f3657501601a7ea5c11968b17 + URL_MD5 2352490aadfd6612cb5e8aa7f619f12e CONFIGURE_COMMAND "" BUILD_COMMAND "" INSTALL_COMMAND "" diff --git a/3rdparty/coin3d/soqt/CMakeLists.txt b/3rdparty/coin3d/soqt/CMakeLists.txt index bb16b8ac..a110fe2e 100644 --- a/3rdparty/coin3d/soqt/CMakeLists.txt +++ b/3rdparty/coin3d/soqt/CMakeLists.txt @@ -5,10 +5,11 @@ list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) ExternalProject_Add( soqt DEPENDS coin cpack.d soanydata sogui - #HG_REPOSITORY https://bitbucket.org/Coin3D/soqt - #HG_TAG default - URL https://bitbucket.org/Coin3D/soqt/get/default.tar.bz2 - #URL ${CMAKE_CURRENT_SOURCE_DIR}/default.tar.bz2 + #GIT_REPOSITORY https://github.com/coin3d/soqt + #GIT_TAG SoQt-1.6.0 + URL https://github.com/coin3d/soqt/archive/SoQt-1.6.0.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/soqt-SoQt-1.6.0.zip + URL_MD5 856c38b464a4986f39fbc52f86a1f4a0 PATCH_COMMAND ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d && ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../soanydata/soanydata-prefix/src/soanydata /data && From 35dc4a37de4f180da8b0422c8e64e25f2bc94c51 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Mar 2020 17:30:14 +0100 Subject: [PATCH 314/546] Add using statements for base class functions --- src/rl/sg/bullet/Scene.h | 4 ++++ src/rl/sg/fcl/Scene.h | 2 ++ src/rl/sg/ode/Scene.h | 2 ++ src/rl/sg/pqp/Scene.h | 2 ++ src/rl/sg/solid/Scene.h | 4 ++++ 5 files changed, 14 insertions(+) diff --git a/src/rl/sg/bullet/Scene.h b/src/rl/sg/bullet/Scene.h index 541fda19..91b97c28 100644 --- a/src/rl/sg/bullet/Scene.h +++ b/src/rl/sg/bullet/Scene.h @@ -52,12 +52,16 @@ namespace rl virtual ~Scene(); + using ::rl::sg::SimpleScene::areColliding; + bool areColliding(::rl::sg::Body* first, ::rl::sg::Body* second); bool areColliding(::rl::sg::Shape* first, ::rl::sg::Shape* second); ::rl::sg::Model* create(); + using ::rl::sg::DepthScene::depth; + ::rl::math::Real depth(::rl::sg::Body* first, ::rl::sg::Body* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2); ::rl::math::Real depth(::rl::sg::Shape* first, ::rl::sg::Shape* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2); diff --git a/src/rl/sg/fcl/Scene.h b/src/rl/sg/fcl/Scene.h index 31b1eef5..1e7e88f7 100644 --- a/src/rl/sg/fcl/Scene.h +++ b/src/rl/sg/fcl/Scene.h @@ -65,6 +65,8 @@ namespace rl ::rl::sg::Model* create(); + using ::rl::sg::DepthScene::depth; + ::rl::math::Real depth(::rl::sg::Shape* first, ::rl::sg::Shape* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2); ::rl::math::Real distance(::rl::sg::Body* first, ::rl::sg::Body* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2); diff --git a/src/rl/sg/ode/Scene.h b/src/rl/sg/ode/Scene.h index 6e7462e9..fd568627 100644 --- a/src/rl/sg/ode/Scene.h +++ b/src/rl/sg/ode/Scene.h @@ -59,6 +59,8 @@ namespace rl ::rl::sg::Model* create(); + using ::rl::sg::DepthScene::depth; + ::rl::math::Real depth(::rl::sg::Shape* first, ::rl::sg::Shape* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2); bool isColliding(); diff --git a/src/rl/sg/pqp/Scene.h b/src/rl/sg/pqp/Scene.h index b7bd4295..6bcf7d9a 100644 --- a/src/rl/sg/pqp/Scene.h +++ b/src/rl/sg/pqp/Scene.h @@ -51,6 +51,8 @@ namespace rl virtual ~Scene(); + using ::rl::sg::SimpleScene::areColliding; + bool areColliding(::rl::sg::Shape* first, ::rl::sg::Shape* second); ::rl::sg::Model* create(); diff --git a/src/rl/sg/solid/Scene.h b/src/rl/sg/solid/Scene.h index f6cd7bab..58a3e864 100644 --- a/src/rl/sg/solid/Scene.h +++ b/src/rl/sg/solid/Scene.h @@ -55,10 +55,14 @@ namespace rl virtual ~Scene(); + using ::rl::sg::SimpleScene::areColliding; + bool areColliding(::rl::sg::Shape* first, ::rl::sg::Shape* second); ::rl::sg::Model* create(); + using ::rl::sg::DepthScene::depth; + ::rl::math::Real depth(::rl::sg::Shape* first, ::rl::sg::Shape* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2); using ::rl::sg::DistanceScene::distance; From bde503ca1e602b50404cec468674ced37a21f561 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 19 Apr 2020 14:42:48 +0200 Subject: [PATCH 315/546] Remove DEVELOPER_DIR workaround for Xcode 11.2 --- .github/workflows/ci.yml | 2 -- 1 file changed, 2 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 630ec7ba..76bea763 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -16,7 +16,6 @@ jobs: include: - name: macos-latest cmake_prefix_path: /usr/local/opt/qt/lib/cmake - developer_dir: /Applications/Xcode_11.2.1.app/Contents/Developer os: macos-latest path: /usr/local/opt/ccache/libexec - name: ubuntu-latest-clang @@ -33,7 +32,6 @@ jobs: CC: ${{ matrix.cc }} CMAKE_PREFIX_PATH: ${{ matrix.cmake_prefix_path }} CXX: ${{ matrix.cxx }} - DEVELOPER_DIR: ${{ matrix.developer_dir }} steps: - uses: actions/checkout@v1 - if: matrix.os == 'macos-latest' From d83e6f3c093e21fd27a7f3dedb41431c0c5ed417 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 25 Apr 2020 23:01:39 +0200 Subject: [PATCH 316/546] Update ODE to 0.16.1 --- 3rdparty/ode/CMakeLists.txt | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/3rdparty/ode/CMakeLists.txt b/3rdparty/ode/CMakeLists.txt index 57648fdc..0d2f977e 100644 --- a/3rdparty/ode/CMakeLists.txt +++ b/3rdparty/ode/CMakeLists.txt @@ -6,11 +6,11 @@ include(ExternalProject) ExternalProject_Add( ode - #HG_REPOSITORY https://bitbucket.org/odedevs/ode - #HG_TAG 0.16 - URL https://bitbucket.org/odedevs/ode/downloads/ode-0.16.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/ode-0.16.tar.gz - URL_MD5 5da260bdc3f7de1636ce85e72807bffb + #GIT_REPOSITORY https://bitbucket.org/odedevs/ode.git + #GIT_TAG 0.16.1 + URL https://bitbucket.org/odedevs/ode/downloads/ode-0.16.1.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/ode-0.16.1.tar.gz + URL_MD5 0af3efe98f19163c04083c554afff629 CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DODE_WITH_DEMOS=OFF -DODE_WITH_TESTS=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From 06377a9d8f96eba3e9893a6a7f81b3ce7bb65049 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 9 Mar 2020 17:30:59 +0100 Subject: [PATCH 317/546] Fix whitespace --- demos/rlRrtDemo/rlRrtDemo.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/rlRrtDemo/rlRrtDemo.cpp b/demos/rlRrtDemo/rlRrtDemo.cpp index a91d336a..72af4787 100644 --- a/demos/rlRrtDemo/rlRrtDemo.cpp +++ b/demos/rlRrtDemo/rlRrtDemo.cpp @@ -69,7 +69,7 @@ main(int argc, char** argv) factory.load(argv[1], &scene); std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[2])); - + rl::plan::SimpleModel model; model.kin = kinematics.get(); model.model = scene.getModel(0); From d9ea63978081f6c4d719fb0a641ad9474cf6f67c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 30 Apr 2020 20:39:19 +0200 Subject: [PATCH 318/546] Fix line endings --- examples/rlsg/box-6d-300505_maze.wrl | 3 ++- examples/rlsg/unimation-puma560/unimation-puma560.wrl | 3 ++- examples/rlsg/unimation-puma560_boxes.convex.wrl | 6 ++++-- examples/rlsg/unimation-puma560_boxes.wrl | 6 ++++-- 4 files changed, 12 insertions(+), 6 deletions(-) diff --git a/examples/rlsg/box-6d-300505_maze.wrl b/examples/rlsg/box-6d-300505_maze.wrl index abaa34eb..99fb26da 100644 --- a/examples/rlsg/box-6d-300505_maze.wrl +++ b/examples/rlsg/box-6d-300505_maze.wrl @@ -46,6 +46,7 @@ Transform { } DEF maze Inline { url "maze.wrl" - } ] + } + ] } diff --git a/examples/rlsg/unimation-puma560/unimation-puma560.wrl b/examples/rlsg/unimation-puma560/unimation-puma560.wrl index 4af38a2b..9478b1d6 100644 --- a/examples/rlsg/unimation-puma560/unimation-puma560.wrl +++ b/examples/rlsg/unimation-puma560/unimation-puma560.wrl @@ -58,5 +58,6 @@ Transform { url "link6.wrl" } ] - } ] + } + ] } diff --git a/examples/rlsg/unimation-puma560_boxes.convex.wrl b/examples/rlsg/unimation-puma560_boxes.convex.wrl index 33a8d412..8b151deb 100644 --- a/examples/rlsg/unimation-puma560_boxes.convex.wrl +++ b/examples/rlsg/unimation-puma560_boxes.convex.wrl @@ -5,9 +5,11 @@ Transform { children [ Inline { url "unimation-puma560.convex/unimation-puma560.wrl" - } ] + } + ] } DEF boxes Inline { url "boxes.wrl" - } ] + } + ] } diff --git a/examples/rlsg/unimation-puma560_boxes.wrl b/examples/rlsg/unimation-puma560_boxes.wrl index 4f25ab4e..717b24bd 100644 --- a/examples/rlsg/unimation-puma560_boxes.wrl +++ b/examples/rlsg/unimation-puma560_boxes.wrl @@ -5,9 +5,11 @@ Transform { children [ Inline { url "unimation-puma560/unimation-puma560.wrl" - } ] + } + ] } DEF boxes Inline { url "boxes.wrl" - } ] + } + ] } From df893b2dd9d04a218eb820b7f9853203f5475a46 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 4 May 2020 22:36:21 +0200 Subject: [PATCH 319/546] Update check for supported file endings --- extras/wrlview/MainWindow.cpp | 14 ++++++++++++-- extras/wrlview/MainWindow.h | 2 ++ 2 files changed, 14 insertions(+), 2 deletions(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index c4cfa702..34b5171c 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -67,6 +67,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : origin1000Switch(nullptr), root(nullptr), scene(nullptr), + supportedFileEndings(), viewer(nullptr), widget(new QWidget(this)) { @@ -159,6 +160,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->offscreenRenderer = new SoOffscreenRenderer(this->viewer->getViewportRegion()); + this->supportedFileEndings << ".iv" << ".iv.gz" << ".ivz" << ".wrl" << ".wrl.gz" << ".wrz"; + this->setCentralWidget(this->widget); this->setFocusProxy(this->viewer->getWidget()); @@ -535,7 +538,14 @@ MainWindow::inlineFetchUrlCallback(const SbString& url, void* userData, SoVRMLIn void MainWindow::load(const QString filename) { - if (!(filename.endsWith(".iv") || filename.endsWith(".wrl") || filename.endsWith(".wrl.gz") || filename.endsWith(".wrz"))) + bool fileEndingSupported = false; + + for (int i = 0; i < this->supportedFileEndings.size(); ++i) + { + fileEndingSupported |= filename.endsWith(this->supportedFileEndings[i], Qt::CaseInsensitive); + } + + if (!fileEndingSupported) { QMessageBox::critical(this, "Error", "File format not supported."); return; @@ -575,7 +585,7 @@ MainWindow::load(const QString filename) void MainWindow::open() { - QString filename = QFileDialog::getOpenFileName(this, "", this->filename, "All Formats (*.iv *.wrl *.wrl.gz *.wrz)"); + QString filename = QFileDialog::getOpenFileName(this, "", this->filename, "All Formats (*" + this->supportedFileEndings.join(" *") + ")"); if (!filename.isEmpty()) { diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index 03fb1c9c..df063f78 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -139,6 +139,8 @@ class MainWindow : public QMainWindow SoSeparator* scene; + QStringList supportedFileEndings; + SoQtExaminerViewer* viewer; QMenu* viewMenu; From 5497c379daf7395bdb33b33f4593d12f3c1b4919 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 4 May 2020 22:40:31 +0200 Subject: [PATCH 320/546] Use absolute file path --- extras/wrlview/MainWindow.cpp | 21 +++++++++++---------- 1 file changed, 11 insertions(+), 10 deletions(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 34b5171c..94ef0165 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -538,25 +538,26 @@ MainWindow::inlineFetchUrlCallback(const SbString& url, void* userData, SoVRMLIn void MainWindow::load(const QString filename) { + QFileInfo fileInfo(filename); + QString absoluteFilename = QDir::toNativeSeparators(QDir::cleanPath(fileInfo.absoluteFilePath())); + QDir::setCurrent(fileInfo.path()); + bool fileEndingSupported = false; for (int i = 0; i < this->supportedFileEndings.size(); ++i) { - fileEndingSupported |= filename.endsWith(this->supportedFileEndings[i], Qt::CaseInsensitive); + fileEndingSupported |= absoluteFilename.endsWith(this->supportedFileEndings[i], Qt::CaseInsensitive); } if (!fileEndingSupported) { - QMessageBox::critical(this, "Error", "File format not supported."); + QMessageBox::critical(this, "Error", "Format of file '" + absoluteFilename + "' not supported."); return; } - QFileInfo fileInfo(filename); - QDir::setCurrent(fileInfo.path()); - - if (!this->input.openFile(filename.toStdString().c_str(), true)) + if (!this->input.openFile(absoluteFilename.toStdString().c_str(), true)) { - QMessageBox::critical(this, "Error", "File not found."); + QMessageBox::critical(this, "Error", "File '" + absoluteFilename + "' not found."); return; } @@ -573,13 +574,13 @@ MainWindow::load(const QString filename) if (nullptr == this->scene) { - QMessageBox::critical(this, "Error", "Error reading file."); + QMessageBox::critical(this, "Error", "Error reading file '" + absoluteFilename + "'."); return; } this->root->addChild(this->scene); - this->filename = filename; - this->setWindowTitle(filename + " - wrlview"); + this->filename = absoluteFilename; + this->setWindowTitle(absoluteFilename + " - wrlview"); } void From 17796f9bc824a76e0184bf83e9d312a71f36e35c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 4 May 2020 22:43:45 +0200 Subject: [PATCH 321/546] Add support for reading STL files --- extras/wrlview/CMakeLists.txt | 20 +++++++++++++++- extras/wrlview/MainWindow.cpp | 45 ++++++++++++++++++++++++++++------- 2 files changed, 55 insertions(+), 10 deletions(-) diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index fdad220d..db8f22e3 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -41,6 +41,24 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) ${SoQt_DEFINITIONS} ) + set(CMAKE_REQUIRED_DEFINITIONS ${Coin_DEFINITIONS}) + set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) + set(CMAKE_REQUIRED_LIBRARIES ${Coin_LIBRARIES}) + check_include_file_cxx(ForeignFiles/SoSTLFileKit.h HAVE_SOSTLFILEKIT_H) + if(HAVE_SOSTLFILEKIT_H) + target_compile_definitions(wrlview PRIVATE HAVE_SOSTLFILEKIT_H) + check_cxx_source_compiles(" + #include + int main() { SoSTLFileKit* stlFileKit = new SoSTLFileKit(); stlFileKit->convert(); return 0; } + " HAVE_SOSTLFILEKIT_CONVERT) + if(HAVE_SOSTLFILEKIT_CONVERT) + target_compile_definitions(wrlview PRIVATE HAVE_SOSTLFILEKIT_CONVERT) + endif() + endif() + unset(CMAKE_REQUIRED_DEFINITIONS) + unset(CMAKE_REQUIRED_INCLUDES) + unset(CMAKE_REQUIRED_LIBRARIES) + target_include_directories( wrlview PRIVATE @@ -60,7 +78,7 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) set_target_properties( wrlview PROPERTIES - VERSION 0.1.13 + VERSION 0.1.14 ) if(WIN32) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 94ef0165..8b644f7f 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -38,6 +38,9 @@ #include #include #include +#ifdef HAVE_SOSTLFILEKIT_H +#include +#endif #include #include #include @@ -161,6 +164,10 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->offscreenRenderer = new SoOffscreenRenderer(this->viewer->getViewportRegion()); this->supportedFileEndings << ".iv" << ".iv.gz" << ".ivz" << ".wrl" << ".wrl.gz" << ".wrz"; +#if defined(HAVE_SOSTLFILEKIT_H) && defined(HAVE_SOSTLFILEKIT_CONVERT) + this->supportedFileEndings << ".stl"; +#endif + this->supportedFileEndings.sort(); this->setCentralWidget(this->widget); this->setFocusProxy(this->viewer->getWidget()); @@ -555,12 +562,6 @@ MainWindow::load(const QString filename) return; } - if (!this->input.openFile(absoluteFilename.toStdString().c_str(), true)) - { - QMessageBox::critical(this, "Error", "File '" + absoluteFilename + "' not found."); - return; - } - if (nullptr != this->scene) { this->root->removeChild(this->scene); @@ -568,9 +569,35 @@ MainWindow::load(const QString filename) this->setWindowTitle("wrlview"); } - this->scene = SoDB::readAll(&this->input); - - this->input.closeFile(); +#if defined(HAVE_SOSTLFILEKIT_H) && defined(HAVE_SOSTLFILEKIT_CONVERT) + if (absoluteFilename.endsWith(".stl", Qt::CaseInsensitive)) + { + SoSTLFileKit* stlFileKit = new ::SoSTLFileKit(); + stlFileKit->ref(); + + if (!stlFileKit->readFile(absoluteFilename.toStdString().c_str())) + { + stlFileKit->unref(); + QMessageBox::critical(this, "Error", "Error reading file '" + absoluteFilename + "'."); + return; + } + + this->scene = stlFileKit->convert(); + stlFileKit->unref(); + } + else +#endif + { + if (!this->input.openFile(absoluteFilename.toStdString().c_str(), true)) + { + QMessageBox::critical(this, "Error", "File '" + absoluteFilename + "' not found."); + return; + } + + this->scene = SoDB::readAll(&this->input); + + this->input.closeFile(); + } if (nullptr == this->scene) { From b5bc94ae43582fc88aeeb49e1d2be9568c55bc7b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 5 May 2020 13:43:48 +0200 Subject: [PATCH 322/546] Add URDF factory to dynamics demos --- demos/rlDynamics1Demo/rlDynamics1Demo.cpp | 16 ++++++++++++++-- demos/rlDynamics2Demo/rlDynamics2Demo.cpp | 16 ++++++++++++++-- 2 files changed, 28 insertions(+), 4 deletions(-) diff --git a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp index 43b76e58..0e7045e8 100644 --- a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp +++ b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp @@ -30,6 +30,7 @@ #include #include #include +#include #include int @@ -43,8 +44,19 @@ main(int argc, char** argv) try { - rl::mdl::XmlFactory factory; - std::shared_ptr dynamic = std::dynamic_pointer_cast(factory.create(argv[1])); + std::string filename(argv[1]); + std::shared_ptr dynamic; + + if ("urdf" == filename.substr(filename.length() - 4, 4)) + { + rl::mdl::UrdfFactory factory; + dynamic = std::dynamic_pointer_cast(factory.create(filename)); + } + else + { + rl::mdl::XmlFactory factory; + dynamic = std::dynamic_pointer_cast(factory.create(filename)); + } rl::math::Vector q(dynamic->getDofPosition()); rl::math::Vector qd(dynamic->getDof()); diff --git a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp index 447a6412..ef67f349 100644 --- a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp +++ b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp @@ -30,6 +30,7 @@ #include #include #include +#include #include int @@ -43,8 +44,19 @@ main(int argc, char** argv) try { - rl::mdl::XmlFactory factory; - std::shared_ptr dynamic = std::dynamic_pointer_cast(factory.create(argv[1])); + std::string filename(argv[1]); + std::shared_ptr dynamic; + + if ("urdf" == filename.substr(filename.length() - 4, 4)) + { + rl::mdl::UrdfFactory factory; + dynamic = std::dynamic_pointer_cast(factory.create(filename)); + } + else + { + rl::mdl::XmlFactory factory; + dynamic = std::dynamic_pointer_cast(factory.create(filename)); + } rl::math::Vector q(dynamic->getDofPosition()); rl::math::Vector qd(dynamic->getDof()); From e6302b90caa892a22d268bf8289f85d28a8b768d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 May 2020 22:35:30 +0200 Subject: [PATCH 323/546] Add check for file SoQtBasic.h when looking for GUI_TOOLKIT_VERSION --- cmake/FindSoQt.cmake | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/cmake/FindSoQt.cmake b/cmake/FindSoQt.cmake index bdb4fab5..05e7cea7 100644 --- a/cmake/FindSoQt.cmake +++ b/cmake/FindSoQt.cmake @@ -124,9 +124,11 @@ set(SoQt_DEFINITIONS -DSOQT_DLL) mark_as_advanced(SoQt_DEFINITIONS) -file(STRINGS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h" GUI_TOOLKIT_VERSION_DEFINE REGEX "#define GUI_TOOLKIT_VERSION.*[0-9]+.*") -string(REGEX REPLACE ".*([0-9])([0-9])([0-9]).*" "\\1" GUI_TOOLKIT_VERSION_MAJOR "${GUI_TOOLKIT_VERSION_DEFINE}") -set(SoQt${GUI_TOOLKIT_VERSION_MAJOR}_FOUND ON) +if(EXISTS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h") + file(STRINGS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h" GUI_TOOLKIT_VERSION_DEFINE REGEX "#define GUI_TOOLKIT_VERSION.*[0-9]+.*") + string(REGEX REPLACE ".*([0-9])([0-9])([0-9]).*" "\\1" GUI_TOOLKIT_VERSION_MAJOR "${GUI_TOOLKIT_VERSION_DEFINE}") + set(SoQt${GUI_TOOLKIT_VERSION_MAJOR}_FOUND ON) +endif() find_package_handle_standard_args( SoQt From 542f8b29d3076bc8aba16b0f533e5b9870347e39 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 9 May 2020 15:51:01 +0200 Subject: [PATCH 324/546] Update exception messages --- src/rl/mdl/XmlFactory.cpp | 22 +++++++++++----------- src/rl/sg/XmlFactory.cpp | 8 ++++---- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index 6f24844b..0583eb82 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -91,7 +91,7 @@ namespace rl if (models.empty()) { - throw Exception("rl::mdl::XmlFactory::load() - No models found in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - No models found in file '" + filename + "'"); } for (int i = 0; i < ::std::min(1, models.size()); ++i) @@ -191,7 +191,7 @@ namespace rl if (id2frame.find(frame->getName()) != id2frame.end()) { - throw Exception("rl::mdl::XmlFactory::load() - Frame with ID " + frame->getName() + " not unique in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Frame with ID '" + frame->getName() + "' not unique in file '" + filename + "'"); } id2frame[frame->getName()] = frame; @@ -210,7 +210,7 @@ namespace rl if (id2frame.find(b1Id) == id2frame.end()) { - throw Exception("rl::mdl::XmlFactory::load() - Body with ID " + b1Id + " not found in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Body with ID '" + b1Id + "' not found in file '" + filename + "'"); } Body* b1 = dynamic_cast(id2frame[b1Id]); @@ -225,7 +225,7 @@ namespace rl if (id2frame.find(b2IdRef) == id2frame.end()) { - throw Exception("rl::mdl::XmlFactory::load() - Body with IDREF " + b2IdRef + " in Body with ID " + b1Id + " not found in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Body with IDREF '" + b2IdRef + "' in Body with ID '" + b1Id + "' not found in file '" + filename + "'"); } Body* b2 = dynamic_cast(id2frame[b2IdRef]); @@ -255,7 +255,7 @@ namespace rl if (id2frame.find(aIdRef) == id2frame.end()) { - throw Exception("rl::mdl::XmlFactory::load() - Frame A with IDREF " + aIdRef + " in Transform with ID " + name + " not found in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Frame A with IDREF '" + aIdRef + "' in Transform with ID '" + name + "' not found in file '" + filename + "'"); } Frame* a = id2frame[aIdRef]; @@ -264,7 +264,7 @@ namespace rl if (id2frame.find(bIdRef) == id2frame.end()) { - throw Exception("rl::mdl::XmlFactory::load() - Frame B with IDREF " + bIdRef + " in Transform with ID " + name + " not found in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Frame B with IDREF '" + bIdRef + "' in Transform with ID '" + name + "' not found in file '" + filename + "'"); } Frame* b = id2frame[bIdRef]; @@ -431,7 +431,7 @@ namespace rl { if (home.size() != model->getDofPosition()) { - throw Exception("rl::mdl::XmlFactory::load() - Incorrect size of home position vector in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect size of home position vector in file '" + filename + "'"); } ::rl::math::Vector q(home.size()); @@ -460,7 +460,7 @@ namespace rl if (m != model->getDofPosition()) { - throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of rows in gamma position matrix in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of rows in gamma position matrix in file '" + filename + "'"); } ::rl::math::Matrix G(m, n); @@ -473,7 +473,7 @@ namespace rl if (path.eval("count(col)").getValue< ::std::size_t>(0) != model->getDofPosition()) { - throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of columns in gamma position matrix in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of columns in gamma position matrix in file '" + filename + "'"); } ::rl::xml::NodeSet cols = path.eval("col").getValue< ::rl::xml::NodeSet>(); @@ -498,7 +498,7 @@ namespace rl if (m != model->getDof()) { - throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of rows in gamma velocity matrix in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of rows in gamma velocity matrix in file '" + filename + "'"); } ::rl::math::Matrix G(m, n); @@ -511,7 +511,7 @@ namespace rl if (path.eval("count(col)").getValue< ::std::size_t>(0) != model->getDof()) { - throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of columns in gamma velocity matrix in file " + filename); + throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of columns in gamma velocity matrix in file '" + filename + "'"); } ::rl::xml::NodeSet cols = path.eval("col").getValue< ::rl::xml::NodeSet>(); diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp index a872826b..2a50649d 100644 --- a/src/rl/sg/XmlFactory.cpp +++ b/src/rl/sg/XmlFactory.cpp @@ -77,7 +77,7 @@ namespace rl if (scenes.empty()) { - throw Exception("rl::sg::XmlFactory::load() - No scenes found in file " + filename); + throw Exception("rl::sg::XmlFactory::load() - No scenes found in file '" + filename + "'"); } for (int i = 0; i < ::std::min(1, scenes.size()); ++i) @@ -86,14 +86,14 @@ namespace rl if (!input.openFile(scenes[i].getLocalPath(scenes[i].getProperty("href")).c_str() ,true)) { - throw Exception("rl::sg::XmlFactory::load() - Failed to open file"); + throw Exception("rl::sg::XmlFactory::load() - Failed to open file '" + filename + "'"); } ::SoVRMLGroup* root = SoDB::readAllVRML(&input); if (nullptr == root) { - throw Exception("rl::sg::XmlFactory::load() - Failed to read file"); + throw Exception("rl::sg::XmlFactory::load() - Failed to read file '" + filename + "'"); } ::SbViewportRegion viewportRegion; @@ -161,7 +161,7 @@ namespace rl { if (::std::abs(bodyScaleFactor[l] - 1) > static_cast< ::rl::math::Real>(1.0e-6)) { - throw Exception("rl::sg::XmlFactory::load() - bodyScaleFactor not supported"); + throw Exception("rl::sg::XmlFactory::load() - bodyScaleFactor not supported in body '" + body->getName() + "'"); } } } From ab1dad9a9315a8d26c50677a0e2dc3999f0d1fc6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 9 May 2020 19:07:03 +0200 Subject: [PATCH 325/546] Add initialization of angular acceleration in world frame --- src/rl/mdl/World.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/rl/mdl/World.cpp b/src/rl/mdl/World.cpp index 206b16b0..f50e6fcc 100644 --- a/src/rl/mdl/World.cpp +++ b/src/rl/mdl/World.cpp @@ -43,15 +43,17 @@ namespace rl void World::forwardAcceleration() { + this->a.angular().setZero(); this->a.linear().setZero(); } void World::forwardDynamics1() { + this->a.angular().setZero(); + this->a.linear() = this->gravity; this->iA.setZero(); this->pA.setZero(); - this->a.linear() = this->gravity; } const ::rl::math::Vector3& @@ -63,8 +65,9 @@ namespace rl void World::inverseDynamics1() { - this->f.setZero(); + this->a.angular().setZero(); this->a.linear() = this->gravity; + this->f.setZero(); } void From b2afc76972d4fb1bce42e3d316adb9906d6b09ca Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 9 May 2020 22:54:10 +0200 Subject: [PATCH 326/546] Add arithmetic operators for rigid body inertia --- src/rl/math/spatial/ArticulatedBodyInertia.h | 6 +++++ .../math/spatial/ArticulatedBodyInertia.hxx | 26 +++++++++++++++++++ 2 files changed, 32 insertions(+) diff --git a/src/rl/math/spatial/ArticulatedBodyInertia.h b/src/rl/math/spatial/ArticulatedBodyInertia.h index 499732f2..0f4c7ece 100644 --- a/src/rl/math/spatial/ArticulatedBodyInertia.h +++ b/src/rl/math/spatial/ArticulatedBodyInertia.h @@ -173,6 +173,9 @@ namespace rl return res; } + template + ArticulatedBodyInertia operator+(const RigidBodyInertia& other) const; + template ArticulatedBodyInertia operator-(const ArticulatedBodyInertia& other) const { @@ -183,6 +186,9 @@ namespace rl return res; } + template + ArticulatedBodyInertia operator-(const RigidBodyInertia& other) const; + template ArticulatedBodyInertia operator*(const OtherScalar& other) const { diff --git a/src/rl/math/spatial/ArticulatedBodyInertia.hxx b/src/rl/math/spatial/ArticulatedBodyInertia.hxx index 3d2592ab..75508ccf 100644 --- a/src/rl/math/spatial/ArticulatedBodyInertia.hxx +++ b/src/rl/math/spatial/ArticulatedBodyInertia.hxx @@ -45,6 +45,32 @@ namespace rl return *this; } + template + template + inline + ArticulatedBodyInertia + ArticulatedBodyInertia::operator+(const RigidBodyInertia& other) const + { + ArticulatedBodyInertia res; + res.cog() = cog() + other.cog().cross33(); + res.inertia() = inertia() + other.inertia(); + res.mass() = mass() + ::Eigen::Matrix::Identity() * other.mass(); + return res; + } + + template + template + inline + ArticulatedBodyInertia + ArticulatedBodyInertia::operator-(const RigidBodyInertia& other) const + { + ArticulatedBodyInertia res; + res.cog() = cog() - other.cog().cross33(); + res.inertia() = inertia() - other.inertia(); + res.mass() = mass() - ::Eigen::Matrix::Identity() * other.mass(); + return res; + } + template template inline From ba77a37c9b7a5af46463c4c3b264af91363bee20 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 9 May 2020 22:54:48 +0200 Subject: [PATCH 327/546] Add compound assignment operators --- src/rl/math/spatial/ArticulatedBodyInertia.h | 42 ++++++++ .../math/spatial/ArticulatedBodyInertia.hxx | 24 +++++ src/rl/math/spatial/ForceVector.h | 32 +++++++ src/rl/math/spatial/MotionVector.h | 32 +++++++ src/rl/math/spatial/RigidBodyInertia.h | 36 +++++++ .../rlSpatialArticulatedBodyInertiaTest.cpp | 95 ++++++++++++++++++- .../rlSpatialForceVectorTest.cpp | 59 ++++++++++++ .../rlSpatialMotionVectorTest.cpp | 59 ++++++++++++ .../rlSpatialRigidBodyInertiaTest.cpp | 31 +++++- 9 files changed, 404 insertions(+), 6 deletions(-) diff --git a/src/rl/math/spatial/ArticulatedBodyInertia.h b/src/rl/math/spatial/ArticulatedBodyInertia.h index 0f4c7ece..8afaf6e5 100644 --- a/src/rl/math/spatial/ArticulatedBodyInertia.h +++ b/src/rl/math/spatial/ArticulatedBodyInertia.h @@ -163,6 +163,48 @@ namespace rl template ArticulatedBodyInertia& operator=(const RigidBodyInertia& other); + template + ArticulatedBodyInertia& operator+=(const ArticulatedBodyInertia& other) + { + cog() += other.cog(); + inertia() += other.inertia(); + mass() += other.mass(); + return *this; + } + + template + ArticulatedBodyInertia& operator+=(const RigidBodyInertia& other); + + template + ArticulatedBodyInertia& operator-=(const ArticulatedBodyInertia& other) + { + cog() -= other.cog(); + inertia() -= other.inertia(); + mass() -= other.mass(); + return *this; + } + + template + ArticulatedBodyInertia& operator-=(const RigidBodyInertia& other); + + template + ArticulatedBodyInertia& operator*=(const OtherScalar& other) + { + cog() *= other; + inertia() *= other; + mass() *= other; + return *this; + } + + template + ArticulatedBodyInertia& operator/=(const OtherScalar& other) + { + cog() /= other; + inertia() /= other; + mass() /= other; + return *this; + } + template ArticulatedBodyInertia operator+(const ArticulatedBodyInertia& other) const { diff --git a/src/rl/math/spatial/ArticulatedBodyInertia.hxx b/src/rl/math/spatial/ArticulatedBodyInertia.hxx index 75508ccf..0faf4b7c 100644 --- a/src/rl/math/spatial/ArticulatedBodyInertia.hxx +++ b/src/rl/math/spatial/ArticulatedBodyInertia.hxx @@ -45,6 +45,30 @@ namespace rl return *this; } + template + template + inline + ArticulatedBodyInertia& + ArticulatedBodyInertia::operator+=(const RigidBodyInertia& other) + { + cog() += other.cog().cross33(); + inertia() += other.inertia(); + mass() += ::Eigen::Matrix::Identity() * other.mass(); + return *this; + } + + template + template + inline + ArticulatedBodyInertia& + ArticulatedBodyInertia::operator-=(const RigidBodyInertia& other) + { + cog() -= other.cog().cross33(); + inertia() -= other.inertia(); + mass() -= ::Eigen::Matrix::Identity() * other.mass(); + return *this; + } + template template inline diff --git a/src/rl/math/spatial/ForceVector.h b/src/rl/math/spatial/ForceVector.h index a9b385ef..77c49659 100644 --- a/src/rl/math/spatial/ForceVector.h +++ b/src/rl/math/spatial/ForceVector.h @@ -121,6 +121,38 @@ namespace rl return *this; } + template + ForceVector& operator+=(const ForceVector& other) + { + moment() += other.moment(); + force() += other.force(); + return *this; + } + + template + ForceVector& operator-=(const ForceVector& other) + { + moment() -= other.moment(); + force() -= other.force(); + return *this; + } + + template + ForceVector& operator*=(const OtherScalar& other) + { + moment() *= other; + force() *= other; + return *this; + } + + template + ForceVector& operator/=(const OtherScalar& other) + { + moment() /= other; + force() /= other; + return *this; + } + template ForceVector operator+(const ForceVector& other) const { diff --git a/src/rl/math/spatial/MotionVector.h b/src/rl/math/spatial/MotionVector.h index 7db92aa2..d2da59c2 100644 --- a/src/rl/math/spatial/MotionVector.h +++ b/src/rl/math/spatial/MotionVector.h @@ -153,6 +153,38 @@ namespace rl return *this; } + template + MotionVector& operator+=(const MotionVector& other) + { + angular() += other.angular(); + linear() += other.linear(); + return *this; + } + + template + MotionVector& operator-=(const MotionVector& other) + { + angular() -= other.angular(); + linear() -= other.linear(); + return *this; + } + + template + MotionVector& operator*=(const OtherScalar& other) + { + angular() *= other; + linear() *= other; + return *this; + } + + template + MotionVector& operator/=(const OtherScalar& other) + { + angular() /= other; + linear() /= other; + return *this; + } + template MotionVector operator+(const MotionVector& other) const { diff --git a/src/rl/math/spatial/RigidBodyInertia.h b/src/rl/math/spatial/RigidBodyInertia.h index 534ec130..7ec1c6a7 100644 --- a/src/rl/math/spatial/RigidBodyInertia.h +++ b/src/rl/math/spatial/RigidBodyInertia.h @@ -160,6 +160,42 @@ namespace rl return *this; } + template + RigidBodyInertia& operator+=(const RigidBodyInertia& other) + { + cog() += other.cog(); + inertia() += other.inertia(); + mass() += other.mass(); + return *this; + } + + template + RigidBodyInertia& operator-=(const RigidBodyInertia& other) + { + cog() -= other.cog(); + inertia() -= other.inertia(); + mass() -= other.mass(); + return *this; + } + + template + RigidBodyInertia& operator*=(const OtherScalar& other) + { + cog() *= other; + inertia() *= other; + mass() *= other; + return *this; + } + + template + RigidBodyInertia& operator/=(const OtherScalar& other) + { + cog() /= other; + inertia() /= other; + mass() /= other; + return *this; + } + template RigidBodyInertia operator+(const RigidBodyInertia& other) const { diff --git a/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp b/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp index 8a094f3c..ba144d43 100644 --- a/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp +++ b/tests/rlSpatialTest/rlSpatialArticulatedBodyInertiaTest.cpp @@ -46,6 +46,10 @@ main(int argc, char** argv) rl::math::ArticulatedBodyInertia abi3 = abi1 + abi2; rl::math::ArticulatedBodyInertia abi4 = abi3 - abi2; + rl::math::ArticulatedBodyInertia abi3b = abi1; + abi3b += abi2; + rl::math::ArticulatedBodyInertia abi4b = abi3b; + abi4b -= abi2; if (!abi4.matrix().isApprox(abi1.matrix())) { @@ -55,23 +59,68 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } + if (!abi3.matrix().isApprox(abi3b.matrix())) + { + std::cerr << "abi1 + abi2 != abi1 += abi2" << std::endl; + std::cerr << "abi1 + abi2 = " << std::endl << abi3.matrix() << std::endl; + std::cerr << "abi1 += abi2 = " << std::endl << abi3b.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!abi4b.matrix().isApprox(abi1.matrix())) + { + std::cerr << "abi1 += abi2 -= abi2 != abi1" << std::endl; + std::cerr << "abi1 += abi2 -= abi2 = " << std::endl << abi4b.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + rl::math::ArticulatedBodyInertia abi1_2 = abi1 * 2; + rl::math::ArticulatedBodyInertia abi1_2b = abi1; + abi1_2b *= 2; rl::math::ArticulatedBodyInertia abi1_abi1 = abi1 + abi1; - rl::math::ArticulatedBodyInertia abi1_2_05 = abi1_2 * 0.5; + rl::math::ArticulatedBodyInertia abi1_2_05 = abi1_2 * static_cast(0.5); + rl::math::ArticulatedBodyInertia abi1_abi1_2 = abi1_abi1 / 2; + rl::math::ArticulatedBodyInertia abi1_abi1_2b = abi1_abi1; + abi1_abi1_2b /= 2; if (!abi1_2.matrix().isApprox(abi1_abi1.matrix())) { - std::cerr << "abi1 * 2 != abi1 + abi1" << std::endl; - std::cerr << "abi1 * 2 = " << std::endl << abi1_2.matrix() << std::endl; + std::cerr << "abi1 * 2.0 != abi1 + abi1" << std::endl; + std::cerr << "abi1 * 2.0 = " << std::endl << abi1_2.matrix() << std::endl; std::cerr << "abi1 + abi1 = " << std::endl << abi1_abi1.matrix() << std::endl; exit(EXIT_FAILURE); } + if (!abi1_2.matrix().isApprox(abi1_2b.matrix())) + { + std::cerr << "abi1 * 2.0 != abi1 *= 2.0" << std::endl; + std::cerr << "abi1 * 2.0 = " << std::endl << abi1_2.matrix() << std::endl; + std::cerr << "abi1 *= 2.0 = " << std::endl << abi1_2b.matrix() << std::endl; + exit(EXIT_FAILURE); + } + if (!abi1_2_05.matrix().isApprox(abi1.matrix())) { - std::cerr << "abi1 * 2 * 0.5 != abi1" << std::endl; - std::cerr << "abi1 * 2 * 0.5 = " << std::endl << abi1_2.matrix() << std::endl; + std::cerr << "abi1 * 2.0 * 0.5 != abi1" << std::endl; + std::cerr << "abi1 * 2.0 * 0.5 = " << std::endl << abi1_2.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!abi1.matrix().isApprox(abi1_abi1_2.matrix())) + { + std::cerr << "abi1 != abi1 + abi1 / 2.0" << std::endl; std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + std::cerr << "abi1 + abi1 / 2.0 = " << std::endl << abi1_abi1_2.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!abi1.matrix().isApprox(abi1_abi1_2b.matrix())) + { + std::cerr << "abi1 != abi1 + abi1 /= 2.0" << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + std::cerr << "abi1 + abi1 /= 2.0 = " << std::endl << abi1_abi1_2b.matrix() << std::endl; exit(EXIT_FAILURE); } @@ -110,5 +159,41 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } + rl::math::RigidBodyInertia rbi1; + rbi1.cog().setRandom(); + rbi1.inertia().setRandom(); + rbi1.mass() = static_cast(1.23); + + rl::math::ArticulatedBodyInertia abi7 = abi1 + rbi1; + rl::math::ArticulatedBodyInertia abi8 = abi7 - rbi1; + rl::math::ArticulatedBodyInertia abi7b = abi1; + abi7b += rbi1; + rl::math::ArticulatedBodyInertia abi8b = abi7b; + abi8b -= rbi1; + + if (!abi8.matrix().isApprox(abi1.matrix())) + { + std::cerr << "abi1 + rbi1 - rbi1 != abi1" << std::endl; + std::cerr << "abi1 + rbi1 - rbi1 = " << std::endl << abi8.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!abi7.matrix().isApprox(abi7b.matrix())) + { + std::cerr << "abi1 + rbi1 != abi1 += rbi1" << std::endl; + std::cerr << "abi1 + rbi1 = " << std::endl << abi7.matrix() << std::endl; + std::cerr << "abi1 += rbi2 = " << std::endl << abi7b.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!abi8b.matrix().isApprox(abi1.matrix())) + { + std::cerr << "abi1 += rbi1 -= rbi1 != abi1" << std::endl; + std::cerr << "abi1 += rbi1 -= rbi1 = " << std::endl << abi8b.matrix() << std::endl; + std::cerr << "abi1 = " << std::endl << abi1.matrix() << std::endl; + exit(EXIT_FAILURE); + } + return EXIT_SUCCESS; } diff --git a/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp b/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp index 6583be69..8cd5e4bd 100644 --- a/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp +++ b/tests/rlSpatialTest/rlSpatialForceVectorTest.cpp @@ -94,6 +94,55 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } + rl::math::ForceVector fv1_fv1 = fv1 + fv1; + rl::math::ForceVector fv1_2 = fv1 * 2; + rl::math::ForceVector fv1_2b = fv1; + fv1_2b *= 2; + rl::math::ForceVector fv1_2_05 = fv1_2 * static_cast(0.5); + rl::math::ForceVector fv1_fv1_2 = fv1_fv1 / 2; + rl::math::ForceVector fv1_fv1_2b = fv1_fv1; + fv1_fv1_2b /= 2; + + if (!fv1_2.matrix().isApprox(fv1_fv1.matrix())) + { + std::cerr << "fv1 * 2.0 != fv1 + fv1" << std::endl; + std::cerr << "fv1 * 2.0 = " << fv1_2.matrix().transpose() << std::endl; + std::cerr << "fv1 + fv1 = " << fv1_fv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!fv1_2.matrix().isApprox(fv1_2b.matrix())) + { + std::cerr << "fv1 * 2.0 != fv1 *= 2.0" << std::endl; + std::cerr << "fv1 * 2.0 = " << fv1_2.matrix().transpose() << std::endl; + std::cerr << "fv1 *= 2.0 = " << fv1_2b.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!fv1_2_05.matrix().isApprox(fv1.matrix())) + { + std::cerr << "fv1 * 2.0 / 0.5 != fv1" << std::endl; + std::cerr << "fv1 * 2.0 / 0.5 = " << fv1_2_05.matrix().transpose() << std::endl; + std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!fv1.matrix().isApprox(fv1_fv1_2.matrix())) + { + std::cerr << "fv1 != fv1 + fv1 / 2.0" << std::endl; + std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; + std::cerr << "fv1 + fv1 / 2.0 = " << fv1_fv1_2.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!fv1.matrix().isApprox(fv1_fv1_2b.matrix())) + { + std::cerr << "fv1 != fv1 + fv1 /= 2.0" << std::endl; + std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; + std::cerr << "fv1 + fv1 /= 2.0 = " << fv1_fv1_2b.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + rl::math::Vector6 v5 = v1 * static_cast(1.23); rl::math::ForceVector fv5 = fv1 * static_cast(1.23); @@ -126,5 +175,15 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } + rl::math::ForceVector fv8 = fv1; + + if (!fv8.matrix().isApprox(fv1.matrix())) + { + std::cerr << "fv8 != fv1" << std::endl; + std::cerr << "fv8 = " << fv8.matrix().transpose() << std::endl; + std::cerr << "fv1 = " << fv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + return EXIT_SUCCESS; } diff --git a/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp b/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp index b43431f4..0a190d98 100644 --- a/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp +++ b/tests/rlSpatialTest/rlSpatialMotionVectorTest.cpp @@ -94,6 +94,55 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } + rl::math::MotionVector mv1_mv1 = mv1 + mv1; + rl::math::MotionVector mv1_2 = mv1 * 2; + rl::math::MotionVector mv1_2b = mv1; + mv1_2b *= 2; + rl::math::MotionVector mv1_2_05 = mv1_2 * static_cast(0.5); + rl::math::MotionVector mv1_mv1_2 = mv1_mv1 / 2; + rl::math::MotionVector mv1_mv1_2b = mv1_mv1; + mv1_mv1_2b /= 2; + + if (!mv1_2.matrix().isApprox(mv1_mv1.matrix())) + { + std::cerr << "mv1 * 2.0 != mv1 + mv1" << std::endl; + std::cerr << "mv1 * 2.0 = " << mv1_2.matrix().transpose() << std::endl; + std::cerr << "mv1 + mv1 = " << mv1_mv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!mv1_2.matrix().isApprox(mv1_2b.matrix())) + { + std::cerr << "mv1 * 2.0 != mv1 *= 2.0" << std::endl; + std::cerr << "mv1 * 2.0 = " << mv1_2.matrix().transpose() << std::endl; + std::cerr << "mv1 *= 2.0 = " << mv1_2b.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!mv1_2_05.matrix().isApprox(mv1.matrix())) + { + std::cerr << "mv1 * 2.0 / 0.5 != mv1" << std::endl; + std::cerr << "mv1 * 2.0 / 0.5 = " << mv1_2_05.matrix().transpose() << std::endl; + std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!mv1.matrix().isApprox(mv1_mv1_2.matrix())) + { + std::cerr << "mv1 != mv1 + mv1 / 2.0" << std::endl; + std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; + std::cerr << "mv1 + mv1 / 2.0 = " << mv1_mv1_2.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + + if (!mv1.matrix().isApprox(mv1_mv1_2b.matrix())) + { + std::cerr << "mv1 != mv1 + mv1 /= 2.0" << std::endl; + std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; + std::cerr << "mv1 + mv1 /= 2.0 = " << mv1_mv1_2b.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + rl::math::Vector6 v5 = v1 * static_cast(1.23); rl::math::MotionVector mv5 = mv1 * static_cast(1.23); @@ -126,5 +175,15 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } + rl::math::MotionVector mv8 = mv1; + + if (!mv8.matrix().isApprox(mv1.matrix())) + { + std::cerr << "mv8 != mv1" << std::endl; + std::cerr << "mv8 = " << mv8.matrix().transpose() << std::endl; + std::cerr << "mv1 = " << mv1.matrix().transpose() << std::endl; + exit(EXIT_FAILURE); + } + return EXIT_SUCCESS; } diff --git a/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp b/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp index 9ab3d451..de67f80a 100644 --- a/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp +++ b/tests/rlSpatialTest/rlSpatialRigidBodyInertiaTest.cpp @@ -56,8 +56,13 @@ main(int argc, char** argv) } rl::math::RigidBodyInertia rbi1_2 = rbi1 * 2; + rl::math::RigidBodyInertia rbi1_2b = rbi1; + rbi1_2b *= 2; rl::math::RigidBodyInertia rbi1_rbi1 = rbi1 + rbi1; - rl::math::RigidBodyInertia rbi1_2_05 = rbi1_2 * 0.5; + rl::math::RigidBodyInertia rbi1_2_05 = rbi1_2 * static_cast(0.5); + rl::math::RigidBodyInertia rbi1_rbi1_2 = rbi1_rbi1 / 2; + rl::math::RigidBodyInertia rbi1_rbi1_2b = rbi1_rbi1; + rbi1_rbi1_2b /= 2; if (!rbi1_2.matrix().isApprox(rbi1_rbi1.matrix())) { @@ -67,6 +72,14 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } + if (!rbi1_2.matrix().isApprox(rbi1_2b.matrix())) + { + std::cerr << "rbi1 * 2.0 != rbi1 *= 2.0" << std::endl; + std::cerr << "rbi1 * 2.0 = " << std::endl << rbi1_2.matrix() << std::endl; + std::cerr << "rbi1 *= 2.0 = " << std::endl << rbi1_2b.matrix() << std::endl; + exit(EXIT_FAILURE); + } + if (!rbi1_2_05.matrix().isApprox(rbi1.matrix())) { std::cerr << "rbi1 * 2 * 0.5 != rbi1" << std::endl; @@ -75,6 +88,22 @@ main(int argc, char** argv) exit(EXIT_FAILURE); } + if (!rbi1.matrix().isApprox(rbi1_rbi1_2.matrix())) + { + std::cerr << "rbi1 != rbi1 + rbi1 / 2.0" << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + std::cerr << "rbi1 + rbi1 / 2.0 = " << std::endl << rbi1_rbi1_2.matrix() << std::endl; + exit(EXIT_FAILURE); + } + + if (!rbi1.matrix().isApprox(rbi1_rbi1_2b.matrix())) + { + std::cerr << "rbi1 != rbi1 + rbi1 /= 2.0" << std::endl; + std::cerr << "rbi1 = " << std::endl << rbi1.matrix() << std::endl; + std::cerr << "rbi1 + rbi1 /= 2.0 = " << std::endl << rbi1_rbi1_2b.matrix() << std::endl; + exit(EXIT_FAILURE); + } + rl::math::PlueckerTransform pt1; pt1.linear() = rl::math::Quaternion::Random().toRotationMatrix(); pt1.translation().setRandom(); From e8151bfebd539b1064c0cb8e5d47cf278b658925 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 11 May 2020 16:50:26 +0200 Subject: [PATCH 328/546] Use CMake policy CMP0075 to handle Coin auto linking --- CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index a3c0901d..e8c8d2cd 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,5 +1,9 @@ cmake_minimum_required(VERSION 2.8.11) +if(POLICY CMP0075) + cmake_policy(SET CMP0075 NEW) +endif() + project(rl) set(VERSION_MAJOR 0) From 4eb37e5d22250ea84cd3839507a855c7ee1b6855 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 14 May 2020 21:14:10 +0200 Subject: [PATCH 329/546] Add version info to resource files --- CMakeLists.txt | 3 +++ demos/rlAxisControllerDemo/CMakeLists.txt | 1 + demos/rlCameraDemo/CMakeLists.txt | 1 + demos/rlCoachKin/CMakeLists.txt | 2 +- demos/rlCoachMdl/CMakeLists.txt | 2 +- demos/rlCollisionDemo/CMakeLists.txt | 2 +- demos/rlDenavitHartenbergDemo/CMakeLists.txt | 1 + demos/rlDynamics1Demo/CMakeLists.txt | 1 + demos/rlDynamics2Demo/CMakeLists.txt | 1 + demos/rlEulerAnglesDemo/CMakeLists.txt | 1 + demos/rlFilterDemo/CMakeLists.txt | 3 +++ demos/rlGripperDemo/CMakeLists.txt | 2 ++ demos/rlInterpolatorDemo/CMakeLists.txt | 1 + demos/rlInversePositionDemo/CMakeLists.txt | 1 + demos/rlJacobianDemo/CMakeLists.txt | 1 + demos/rlLaserDemo/CMakeLists.txt | 1 + demos/rlLoadXmlDemo/CMakeLists.txt | 1 + demos/rlPcaDemo/CMakeLists.txt | 1 + demos/rlPlanDemo/CMakeLists.txt | 2 +- demos/rlPolynomialRootsDemo/CMakeLists.txt | 1 + demos/rlPrmDemo/CMakeLists.txt | 1 + demos/rlPumaDemo/CMakeLists.txt | 1 + demos/rlQuaternionDemo/CMakeLists.txt | 1 + demos/rlRangeSensorDemo/CMakeLists.txt | 1 + demos/rlRotationConverterDemo/CMakeLists.txt | 2 +- demos/rlRrtDemo/CMakeLists.txt | 1 + demos/rlSimulator/CMakeLists.txt | 2 +- .../CMakeLists.txt | 1 + demos/rlSocketDemo/CMakeLists.txt | 2 ++ demos/rlThreadsDemo/CMakeLists.txt | 1 + demos/rlTimerDemo/CMakeLists.txt | 1 + .../rlTrapezoidalVelocityDemo/CMakeLists.txt | 1 + demos/rlViewDemo/CMakeLists.txt | 2 +- extras/wrlview/CMakeLists.txt | 12 +++++++++-- extras/wrlview/wrlview.rc | 1 - extras/wrlview/wrlview.rc.in | 20 +++++++++++++++++++ robotics-library.rc | 1 - robotics-library.rc.in | 20 +++++++++++++++++++ src/rl/hal/CMakeLists.txt | 1 + src/rl/kin/CMakeLists.txt | 1 + src/rl/mdl/CMakeLists.txt | 1 + src/rl/plan/CMakeLists.txt | 1 + src/rl/sg/CMakeLists.txt | 1 + tests/rlCircularTest/CMakeLists.txt | 1 + tests/rlCollisionTest/CMakeLists.txt | 2 ++ tests/rlDynamicsTest/CMakeLists.txt | 1 + tests/rlEetTest/CMakeLists.txt | 1 + tests/rlHalEndianTest/CMakeLists.txt | 1 + .../rlInverseKinematicsKinTest/CMakeLists.txt | 1 + .../rlInverseKinematicsMdlTest/CMakeLists.txt | 1 + tests/rlJacobianKinTest/CMakeLists.txt | 1 + tests/rlJacobianMdlTest/CMakeLists.txt | 1 + tests/rlMathDeltaTest/CMakeLists.txt | 1 + tests/rlNearestNeighborsTest/CMakeLists.txt | 1 + tests/rlPrmTest/CMakeLists.txt | 1 + tests/rlSpatialTest/CMakeLists.txt | 6 +++++- tests/rlSplineTest/CMakeLists.txt | 6 +++++- 57 files changed, 117 insertions(+), 13 deletions(-) delete mode 100644 extras/wrlview/wrlview.rc create mode 100644 extras/wrlview/wrlview.rc.in delete mode 100644 robotics-library.rc create mode 100644 robotics-library.rc.in diff --git a/CMakeLists.txt b/CMakeLists.txt index e8c8d2cd..4baf7845 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,6 +9,7 @@ project(rl) set(VERSION_MAJOR 0) set(VERSION_MINOR 7) set(VERSION_PATCH 0) +set(VERSION_TWEAK 0) set(VERSION ${VERSION_MAJOR}.${VERSION_MINOR}.${VERSION_PATCH}) list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake) @@ -73,6 +74,8 @@ cmake_dependent_option(RL_BUILD_PLAN "Build path planning component" ON "RL_BUIL include_directories(BEFORE src/rl/std) +configure_file(robotics-library.rc.in robotics-library.rc) + add_subdirectory(src/rl/std) add_subdirectory(src) add_subdirectory(examples) diff --git a/demos/rlAxisControllerDemo/CMakeLists.txt b/demos/rlAxisControllerDemo/CMakeLists.txt index 8a4fae81..9b371f37 100644 --- a/demos/rlAxisControllerDemo/CMakeLists.txt +++ b/demos/rlAxisControllerDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlAxisControllerDemo rlAxisControllerDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlCameraDemo/CMakeLists.txt b/demos/rlCameraDemo/CMakeLists.txt index 99b16610..bcd29b6e 100644 --- a/demos/rlCameraDemo/CMakeLists.txt +++ b/demos/rlCameraDemo/CMakeLists.txt @@ -4,6 +4,7 @@ if(libdc1394_FOUND) add_executable( rlCameraDemo rlCameraDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlCoachKin/CMakeLists.txt b/demos/rlCoachKin/CMakeLists.txt index 92c4252f..82188a53 100644 --- a/demos/rlCoachKin/CMakeLists.txt +++ b/demos/rlCoachKin/CMakeLists.txt @@ -42,7 +42,6 @@ if(QT_FOUND AND SoQt_FOUND) Server.cpp Socket.cpp SoGradientBackground.cpp - ${rl_SOURCE_DIR}/robotics-library.rc ) add_executable( @@ -50,6 +49,7 @@ if(QT_FOUND AND SoQt_FOUND) WIN32 ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) target_compile_definitions( diff --git a/demos/rlCoachMdl/CMakeLists.txt b/demos/rlCoachMdl/CMakeLists.txt index dd4b79f6..0df42656 100644 --- a/demos/rlCoachMdl/CMakeLists.txt +++ b/demos/rlCoachMdl/CMakeLists.txt @@ -42,7 +42,6 @@ if(QT_FOUND AND SoQt_FOUND) Server.cpp Socket.cpp SoGradientBackground.cpp - ${rl_SOURCE_DIR}/robotics-library.rc ) add_executable( @@ -50,6 +49,7 @@ if(QT_FOUND AND SoQt_FOUND) WIN32 ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) target_compile_definitions( diff --git a/demos/rlCollisionDemo/CMakeLists.txt b/demos/rlCollisionDemo/CMakeLists.txt index cfc44a46..7db79883 100644 --- a/demos/rlCollisionDemo/CMakeLists.txt +++ b/demos/rlCollisionDemo/CMakeLists.txt @@ -42,7 +42,6 @@ if(QT_FOUND AND SoQt_FOUND) MainWindow.cpp rlCollisionDemo.cpp SoGradientBackground.cpp - ${rl_SOURCE_DIR}/robotics-library.rc ) add_executable( @@ -50,6 +49,7 @@ if(QT_FOUND AND SoQt_FOUND) WIN32 ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) target_compile_definitions( diff --git a/demos/rlDenavitHartenbergDemo/CMakeLists.txt b/demos/rlDenavitHartenbergDemo/CMakeLists.txt index 3dbc2266..6cb3491c 100644 --- a/demos/rlDenavitHartenbergDemo/CMakeLists.txt +++ b/demos/rlDenavitHartenbergDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlDenavitHartenbergDemo rlDenavitHartenbergDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlDynamics1Demo/CMakeLists.txt b/demos/rlDynamics1Demo/CMakeLists.txt index 58f18455..7fdaf4fd 100644 --- a/demos/rlDynamics1Demo/CMakeLists.txt +++ b/demos/rlDynamics1Demo/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(Boost REQUIRED) add_executable( rlDynamics1Demo rlDynamics1Demo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/demos/rlDynamics2Demo/CMakeLists.txt b/demos/rlDynamics2Demo/CMakeLists.txt index e18f88a7..7c472b9c 100644 --- a/demos/rlDynamics2Demo/CMakeLists.txt +++ b/demos/rlDynamics2Demo/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(Boost REQUIRED) add_executable( rlDynamics2Demo rlDynamics2Demo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/demos/rlEulerAnglesDemo/CMakeLists.txt b/demos/rlEulerAnglesDemo/CMakeLists.txt index e4c2e8cd..0ffce666 100644 --- a/demos/rlEulerAnglesDemo/CMakeLists.txt +++ b/demos/rlEulerAnglesDemo/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(Boost REQUIRED) add_executable( rlEulerAnglesDemo rlEulerAnglesDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/demos/rlFilterDemo/CMakeLists.txt b/demos/rlFilterDemo/CMakeLists.txt index bbb8770f..74ad46d9 100644 --- a/demos/rlFilterDemo/CMakeLists.txt +++ b/demos/rlFilterDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlKalmanDemo rlKalmanDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( @@ -11,6 +12,7 @@ target_link_libraries( add_executable( rlKalmanDemo2 rlKalmanDemo2.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( @@ -21,6 +23,7 @@ target_link_libraries( add_executable( rlLowPassDemo rlLowPassDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlGripperDemo/CMakeLists.txt b/demos/rlGripperDemo/CMakeLists.txt index f74743eb..ebfe3d56 100644 --- a/demos/rlGripperDemo/CMakeLists.txt +++ b/demos/rlGripperDemo/CMakeLists.txt @@ -5,6 +5,7 @@ endif() add_executable( rlGripperDemo rlGripperDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) @@ -33,6 +34,7 @@ endif() add_executable( rlRobotiqModelCDemo rlRobotiqModelCDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlInterpolatorDemo/CMakeLists.txt b/demos/rlInterpolatorDemo/CMakeLists.txt index f195df4e..fb9a43bb 100644 --- a/demos/rlInterpolatorDemo/CMakeLists.txt +++ b/demos/rlInterpolatorDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlInterpolatorDemo rlInterpolatorDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlInversePositionDemo/CMakeLists.txt b/demos/rlInversePositionDemo/CMakeLists.txt index 41f6a8dd..f343534e 100644 --- a/demos/rlInversePositionDemo/CMakeLists.txt +++ b/demos/rlInversePositionDemo/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(Boost REQUIRED) add_executable( rlInversePositionDemo rlInversePositionDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) diff --git a/demos/rlJacobianDemo/CMakeLists.txt b/demos/rlJacobianDemo/CMakeLists.txt index 0a28f443..c34d4ab2 100644 --- a/demos/rlJacobianDemo/CMakeLists.txt +++ b/demos/rlJacobianDemo/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(Boost REQUIRED) add_executable( rlJacobianDemo rlJacobianDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/demos/rlLaserDemo/CMakeLists.txt b/demos/rlLaserDemo/CMakeLists.txt index 9a476328..e453d67c 100644 --- a/demos/rlLaserDemo/CMakeLists.txt +++ b/demos/rlLaserDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlLaserDemo rlLaserDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlLoadXmlDemo/CMakeLists.txt b/demos/rlLoadXmlDemo/CMakeLists.txt index 9cf35b5d..e61a8673 100644 --- a/demos/rlLoadXmlDemo/CMakeLists.txt +++ b/demos/rlLoadXmlDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlLoadXmlDemo rlLoadXmlDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlPcaDemo/CMakeLists.txt b/demos/rlPcaDemo/CMakeLists.txt index c09bcf7d..ace9f6cc 100644 --- a/demos/rlPcaDemo/CMakeLists.txt +++ b/demos/rlPcaDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlPcaDemo rlPcaDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index 9e6b97b2..3eb84a29 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -56,7 +56,6 @@ if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE SoGradientBackground.cpp Thread.cpp Viewer.cpp - ${rl_SOURCE_DIR}/robotics-library.rc ) add_executable( @@ -64,6 +63,7 @@ if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE WIN32 ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) target_compile_definitions( diff --git a/demos/rlPolynomialRootsDemo/CMakeLists.txt b/demos/rlPolynomialRootsDemo/CMakeLists.txt index 53c1775c..4376900b 100644 --- a/demos/rlPolynomialRootsDemo/CMakeLists.txt +++ b/demos/rlPolynomialRootsDemo/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(Boost REQUIRED) add_executable( rlPolynomialRootsDemo rlPolynomialRootsDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/demos/rlPrmDemo/CMakeLists.txt b/demos/rlPrmDemo/CMakeLists.txt index 60a57c2d..b1942795 100644 --- a/demos/rlPrmDemo/CMakeLists.txt +++ b/demos/rlPrmDemo/CMakeLists.txt @@ -8,6 +8,7 @@ if(Bullet_FOUND OR ODE_FOUND OR SOLID3_FOUND) add_executable( rlPrmDemo rlPrmDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/demos/rlPumaDemo/CMakeLists.txt b/demos/rlPumaDemo/CMakeLists.txt index db109f04..af1cd6b0 100644 --- a/demos/rlPumaDemo/CMakeLists.txt +++ b/demos/rlPumaDemo/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(Boost REQUIRED) add_executable( rlPumaDemo rlPumaDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/demos/rlQuaternionDemo/CMakeLists.txt b/demos/rlQuaternionDemo/CMakeLists.txt index 193aebae..cbaef04c 100644 --- a/demos/rlQuaternionDemo/CMakeLists.txt +++ b/demos/rlQuaternionDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlQuaternionDemo rlQuaternionDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlRangeSensorDemo/CMakeLists.txt b/demos/rlRangeSensorDemo/CMakeLists.txt index 8cb3f5cf..c2d580e3 100644 --- a/demos/rlRangeSensorDemo/CMakeLists.txt +++ b/demos/rlRangeSensorDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlRangeSensorDemo rlRangeSensorDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlRotationConverterDemo/CMakeLists.txt b/demos/rlRotationConverterDemo/CMakeLists.txt index 25323eb8..ca619d38 100644 --- a/demos/rlRotationConverterDemo/CMakeLists.txt +++ b/demos/rlRotationConverterDemo/CMakeLists.txt @@ -39,13 +39,13 @@ if(QT_FOUND) rlRotationConverterDemo.cpp RotationMatrixModel.cpp TableView.cpp - ${rl_SOURCE_DIR}/robotics-library.rc ) add_executable( rlRotationConverterDemo WIN32 ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlRrtDemo/CMakeLists.txt b/demos/rlRrtDemo/CMakeLists.txt index 5b2f0975..df21e9f8 100644 --- a/demos/rlRrtDemo/CMakeLists.txt +++ b/demos/rlRrtDemo/CMakeLists.txt @@ -8,6 +8,7 @@ if(Bullet_FOUND OR ODE_FOUND OR SOLID3_FOUND) add_executable( rlRrtDemo rlRrtDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index 2c28f38a..a90e50db 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -46,7 +46,6 @@ if(QT_FOUND AND SoQt_FOUND) Server.cpp Socket.cpp SoGradientBackground.cpp - ${rl_SOURCE_DIR}/robotics-library.rc ) add_executable( @@ -54,6 +53,7 @@ if(QT_FOUND AND SoQt_FOUND) WIN32 ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) target_compile_definitions( diff --git a/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt b/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt index 89f0ac7f..be9be4ac 100644 --- a/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt +++ b/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt @@ -5,6 +5,7 @@ endif() add_executable( rlSixAxisForceTorqueSensorDemo rlSixAxisForceTorqueSensorDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) diff --git a/demos/rlSocketDemo/CMakeLists.txt b/demos/rlSocketDemo/CMakeLists.txt index d4fe40ce..2e4ddea3 100644 --- a/demos/rlSocketDemo/CMakeLists.txt +++ b/demos/rlSocketDemo/CMakeLists.txt @@ -3,6 +3,7 @@ find_package(Boost REQUIRED) add_executable( rlSocketDemoClient rlSocketDemoClient.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( @@ -19,6 +20,7 @@ target_link_libraries( add_executable( rlSocketDemoServer rlSocketDemoServer.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/demos/rlThreadsDemo/CMakeLists.txt b/demos/rlThreadsDemo/CMakeLists.txt index df03cc61..68e87db0 100644 --- a/demos/rlThreadsDemo/CMakeLists.txt +++ b/demos/rlThreadsDemo/CMakeLists.txt @@ -5,6 +5,7 @@ endif() add_executable( rlThreadsDemo rlThreadsDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) diff --git a/demos/rlTimerDemo/CMakeLists.txt b/demos/rlTimerDemo/CMakeLists.txt index fc0e745e..d59bbe0f 100644 --- a/demos/rlTimerDemo/CMakeLists.txt +++ b/demos/rlTimerDemo/CMakeLists.txt @@ -7,6 +7,7 @@ endif() add_executable( rlTimerDemo rlTimerDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) diff --git a/demos/rlTrapezoidalVelocityDemo/CMakeLists.txt b/demos/rlTrapezoidalVelocityDemo/CMakeLists.txt index 765c15e9..e010dcf3 100644 --- a/demos/rlTrapezoidalVelocityDemo/CMakeLists.txt +++ b/demos/rlTrapezoidalVelocityDemo/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlTrapezoidalVelocityDemo rlTrapezoidalVelocityDemo.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/demos/rlViewDemo/CMakeLists.txt b/demos/rlViewDemo/CMakeLists.txt index 52943525..128e1760 100644 --- a/demos/rlViewDemo/CMakeLists.txt +++ b/demos/rlViewDemo/CMakeLists.txt @@ -22,7 +22,7 @@ if(QT_FOUND AND SoQt_FOUND) rlViewDemo WIN32 rlViewDemo.cpp - ${rl_SOURCE_DIR}/robotics-library.rc + ${rl_BINARY_DIR}/robotics-library.rc ) target_compile_definitions( diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index db8f22e3..d0169e6c 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -1,5 +1,11 @@ project(wrlview) +set(VERSION_MAJOR 0) +set(VERSION_MINOR 1) +set(VERSION_PATCH 14) +set(VERSION_TWEAK 0) +set(VERSION ${VERSION_MAJOR}.${VERSION_MINOR}.${VERSION_PATCH}) + find_package(SoQt) if(RL_USE_QT5 AND SoQt5_FOUND) @@ -23,6 +29,8 @@ find_package(Coin) find_package(OpenGL) if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) + configure_file(wrlview.rc.in wrlview.rc) + add_executable( wrlview WIN32 @@ -31,7 +39,7 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) SoGradientBackground.cpp SoGradientBackground.h wrlview.cpp - wrlview.rc + ${CMAKE_CURRENT_BINARY_DIR}/wrlview.rc ) target_compile_definitions( @@ -78,7 +86,7 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) set_target_properties( wrlview PROPERTIES - VERSION 0.1.14 + VERSION ${VERSION} ) if(WIN32) diff --git a/extras/wrlview/wrlview.rc b/extras/wrlview/wrlview.rc deleted file mode 100644 index cac2854f..00000000 --- a/extras/wrlview/wrlview.rc +++ /dev/null @@ -1 +0,0 @@ -IDI_ICON1 ICON DISCARDABLE "wrlview.ico" diff --git a/extras/wrlview/wrlview.rc.in b/extras/wrlview/wrlview.rc.in new file mode 100644 index 00000000..f132bf76 --- /dev/null +++ b/extras/wrlview/wrlview.rc.in @@ -0,0 +1,20 @@ +IDI_ICON1 ICON DISCARDABLE "wrlview.ico" + +1 VERSIONINFO +FILEVERSION @VERSION_MAJOR@,@VERSION_MINOR@,@VERSION_PATCH@,@VERSION_TWEAK@ +PRODUCTVERSION @VERSION_MAJOR@,@VERSION_MINOR@,@VERSION_PATCH@,@VERSION_TWEAK@ +{ + BLOCK "StringFileInfo" + { + BLOCK "00000000" + { + VALUE "FileVersion", "@VERSION@\0" + VALUE "ProductName", "wrlview\0" + VALUE "ProductVersion", "@VERSION@\0" + } + } + BLOCK "VarFileInfo" + { + VALUE "Translation", 0x000, 0 + } +} diff --git a/robotics-library.rc b/robotics-library.rc deleted file mode 100644 index 0bc97ba1..00000000 --- a/robotics-library.rc +++ /dev/null @@ -1 +0,0 @@ -IDI_ICON1 ICON DISCARDABLE "robotics-library.ico" diff --git a/robotics-library.rc.in b/robotics-library.rc.in new file mode 100644 index 00000000..12b0782a --- /dev/null +++ b/robotics-library.rc.in @@ -0,0 +1,20 @@ +IDI_ICON1 ICON DISCARDABLE "@rl_SOURCE_DIR@/robotics-library.ico" + +1 VERSIONINFO +FILEVERSION @VERSION_MAJOR@,@VERSION_MINOR@,@VERSION_PATCH@,@VERSION_TWEAK@ +PRODUCTVERSION @VERSION_MAJOR@,@VERSION_MINOR@,@VERSION_PATCH@,@VERSION_TWEAK@ +{ + BLOCK "StringFileInfo" + { + BLOCK "00000000" + { + VALUE "FileVersion", "@VERSION@\0" + VALUE "ProductName", "Robotics Library\0" + VALUE "ProductVersion", "@VERSION@\0" + } + } + BLOCK "VarFileInfo" + { + VALUE "Translation", 0x000, 0 + } +} diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 79e10d53..81d6476a 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -170,6 +170,7 @@ add_library( hal ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) target_compile_definitions( diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index f5eb406f..fb8336d8 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -34,6 +34,7 @@ add_library( kin ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) if(NOT CMAKE_VERSION VERSION_LESS 3.8) diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 96e28129..fc2af39b 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -78,6 +78,7 @@ add_library( mdl ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index 0f39e938..88930be4 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -92,6 +92,7 @@ add_library( plan ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 36719428..d20a368f 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -169,6 +169,7 @@ add_library( sg ${HDRS} ${SRCS} + ${rl_BINARY_DIR}/robotics-library.rc ) if(NOT CMAKE_VERSION VERSION_LESS 3.8) diff --git a/tests/rlCircularTest/CMakeLists.txt b/tests/rlCircularTest/CMakeLists.txt index 894b3868..beb8639f 100644 --- a/tests/rlCircularTest/CMakeLists.txt +++ b/tests/rlCircularTest/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlCircularTest rlCircularTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/tests/rlCollisionTest/CMakeLists.txt b/tests/rlCollisionTest/CMakeLists.txt index b8883f26..0136d686 100644 --- a/tests/rlCollisionTest/CMakeLists.txt +++ b/tests/rlCollisionTest/CMakeLists.txt @@ -11,6 +11,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 add_executable( rlCollisionTest rlCollisionTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( @@ -36,6 +37,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 add_executable( rlSceneCollisionTest rlSceneCollisionTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/tests/rlDynamicsTest/CMakeLists.txt b/tests/rlDynamicsTest/CMakeLists.txt index 9f694fec..a9359cf7 100644 --- a/tests/rlDynamicsTest/CMakeLists.txt +++ b/tests/rlDynamicsTest/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlDynamicsTest rlDynamicsTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index 676fc29f..a1d5161d 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -10,6 +10,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) add_executable( rlEetTest rlEetTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/tests/rlHalEndianTest/CMakeLists.txt b/tests/rlHalEndianTest/CMakeLists.txt index 8a9284f2..c5e4e5c8 100644 --- a/tests/rlHalEndianTest/CMakeLists.txt +++ b/tests/rlHalEndianTest/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlHalEndianTest rlHalEndianTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/tests/rlInverseKinematicsKinTest/CMakeLists.txt b/tests/rlInverseKinematicsKinTest/CMakeLists.txt index 5aec19b3..331e1dc0 100644 --- a/tests/rlInverseKinematicsKinTest/CMakeLists.txt +++ b/tests/rlInverseKinematicsKinTest/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlInverseKinematicsKinTest rlInverseKinematicsKinTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/tests/rlInverseKinematicsMdlTest/CMakeLists.txt b/tests/rlInverseKinematicsMdlTest/CMakeLists.txt index 862c9220..7bdef2ad 100644 --- a/tests/rlInverseKinematicsMdlTest/CMakeLists.txt +++ b/tests/rlInverseKinematicsMdlTest/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlInverseKinematicsMdlTest rlInverseKinematicsMdlTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/tests/rlJacobianKinTest/CMakeLists.txt b/tests/rlJacobianKinTest/CMakeLists.txt index a2822c89..df563d80 100644 --- a/tests/rlJacobianKinTest/CMakeLists.txt +++ b/tests/rlJacobianKinTest/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlJacobianKinTest rlJacobianKinTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/tests/rlJacobianMdlTest/CMakeLists.txt b/tests/rlJacobianMdlTest/CMakeLists.txt index 315b75a8..329827e5 100644 --- a/tests/rlJacobianMdlTest/CMakeLists.txt +++ b/tests/rlJacobianMdlTest/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlJacobianMdlTest rlJacobianMdlTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/tests/rlMathDeltaTest/CMakeLists.txt b/tests/rlMathDeltaTest/CMakeLists.txt index 42cd32c7..f3706cc1 100644 --- a/tests/rlMathDeltaTest/CMakeLists.txt +++ b/tests/rlMathDeltaTest/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable( rlMathDeltaTest rlMathDeltaTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_link_libraries( diff --git a/tests/rlNearestNeighborsTest/CMakeLists.txt b/tests/rlNearestNeighborsTest/CMakeLists.txt index e3e13fd3..d8393acd 100644 --- a/tests/rlNearestNeighborsTest/CMakeLists.txt +++ b/tests/rlNearestNeighborsTest/CMakeLists.txt @@ -4,6 +4,7 @@ add_executable( rlNearestNeighborsTest iterator.h rlNearestNeighborsTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) diff --git a/tests/rlPrmTest/CMakeLists.txt b/tests/rlPrmTest/CMakeLists.txt index 8b5e6e3f..1c81bf81 100644 --- a/tests/rlPrmTest/CMakeLists.txt +++ b/tests/rlPrmTest/CMakeLists.txt @@ -11,6 +11,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 add_executable( rlPrmTest rlPrmTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc ) target_include_directories( diff --git a/tests/rlSpatialTest/CMakeLists.txt b/tests/rlSpatialTest/CMakeLists.txt index 72b1e7a1..30644128 100644 --- a/tests/rlSpatialTest/CMakeLists.txt +++ b/tests/rlSpatialTest/CMakeLists.txt @@ -11,7 +11,11 @@ set( ) foreach(TEST ${TESTS}) - add_executable(${TEST} ${TEST}.cpp) + add_executable( + ${TEST} + ${TEST}.cpp + ${rl_BINARY_DIR}/robotics-library.rc + ) target_link_libraries(${TEST} math) add_test(NAME ${TEST} COMMAND ${TEST}) endforeach() diff --git a/tests/rlSplineTest/CMakeLists.txt b/tests/rlSplineTest/CMakeLists.txt index 9f229edb..194ff4a1 100644 --- a/tests/rlSplineTest/CMakeLists.txt +++ b/tests/rlSplineTest/CMakeLists.txt @@ -11,7 +11,11 @@ set( ) foreach(TEST ${TESTS}) - add_executable(${TEST} ${TEST}.cpp) + add_executable( + ${TEST} + ${TEST}.cpp + ${rl_BINARY_DIR}/robotics-library.rc + ) target_link_libraries(${TEST} math) add_test(NAME ${TEST} COMMAND ${TEST}) endforeach() From ef52f66568b3c2094ebff31550e221acedf72e05 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 16 May 2020 16:24:05 +0200 Subject: [PATCH 330/546] Add RL prefix to CMake options --- doc/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/CMakeLists.txt b/doc/CMakeLists.txt index e09ea116..d64bc4c5 100644 --- a/doc/CMakeLists.txt +++ b/doc/CMakeLists.txt @@ -4,7 +4,7 @@ find_package(Perl) configure_file(Doxyfile.in Doxyfile) -if(BUILD_DOCUMENTATION) +if(RL_BUILD_DOCUMENTATION) add_custom_target(doc ALL ${DOXYGEN_EXECUTABLE} ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile) elseif(DOXYGEN_FOUND) add_custom_target(doc ${DOXYGEN_EXECUTABLE} ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile) From f1fb5ff3b836da99d8c23e326dfb4a1599a38985 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 16 May 2020 17:52:25 +0200 Subject: [PATCH 331/546] Update forward declarations --- src/rl/math/spatial/ArticulatedBodyInertia.h | 2 ++ src/rl/math/spatial/ForceVector.h | 1 - src/rl/math/spatial/PlueckerTransform.h | 3 +++ 3 files changed, 5 insertions(+), 1 deletion(-) diff --git a/src/rl/math/spatial/ArticulatedBodyInertia.h b/src/rl/math/spatial/ArticulatedBodyInertia.h index 8afaf6e5..bb8bea28 100644 --- a/src/rl/math/spatial/ArticulatedBodyInertia.h +++ b/src/rl/math/spatial/ArticulatedBodyInertia.h @@ -36,7 +36,9 @@ namespace rl namespace spatial { template class ForceVector; + template class MotionVector; + template class RigidBodyInertia; /** diff --git a/src/rl/math/spatial/ForceVector.h b/src/rl/math/spatial/ForceVector.h index 77c49659..71cc051f 100644 --- a/src/rl/math/spatial/ForceVector.h +++ b/src/rl/math/spatial/ForceVector.h @@ -35,7 +35,6 @@ namespace rl { namespace spatial { - template class ArticulatedBodyInertia; template class MotionVector; /** diff --git a/src/rl/math/spatial/PlueckerTransform.h b/src/rl/math/spatial/PlueckerTransform.h index 49f9c307..46f104b8 100644 --- a/src/rl/math/spatial/PlueckerTransform.h +++ b/src/rl/math/spatial/PlueckerTransform.h @@ -43,8 +43,11 @@ namespace rl namespace spatial { template class ArticulatedBodyInertia; + template class ForceVector; + template class MotionVector; + template class RigidBodyInertia; /** From ed3cc5fd29568ba9c25bce44546e37a10c7caba5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 16 May 2020 18:21:10 +0200 Subject: [PATCH 332/546] Use CMake policy CMP0072 to prefer GLVND by default --- CMakeLists.txt | 4 ++++ extras/CMakeLists.txt | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4baf7845..d88e8369 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,5 +1,9 @@ cmake_minimum_required(VERSION 2.8.11) +if(POLICY CMP0072) + cmake_policy(SET CMP0072 NEW) +endif() + if(POLICY CMP0075) cmake_policy(SET CMP0075 NEW) endif() diff --git a/extras/CMakeLists.txt b/extras/CMakeLists.txt index d1bc1e74..e8bc8936 100644 --- a/extras/CMakeLists.txt +++ b/extras/CMakeLists.txt @@ -1,5 +1,9 @@ cmake_minimum_required(VERSION 2.8.11) +if(POLICY CMP0072) + cmake_policy(SET CMP0072 NEW) +endif() + project(extras) add_subdirectory(byu2wrl) From 5a1f41194bdba1d74e314bebca05188074e48786 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 17 May 2020 02:06:45 +0200 Subject: [PATCH 333/546] Update Coin library names --- cmake/FindCoin.cmake | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/cmake/FindCoin.cmake b/cmake/FindCoin.cmake index b79d21a0..6e88f0e6 100644 --- a/cmake/FindCoin.cmake +++ b/cmake/FindCoin.cmake @@ -128,7 +128,7 @@ file( find_library( Coin_LIBRARY_DEBUG NAMES - Coind coin2d coin3d Coin4d Inventord + Coind coin2d coin3d Coin4d HINTS ${Coin_LIBRARY_HINTS} PATHS @@ -138,7 +138,7 @@ find_library( find_library( Coin_LIBRARY_RELEASE NAMES - Coin coin2 coin3 Coin4 Inventor + Coin coin2 coin3 Coin4 HINTS ${Coin_LIBRARY_HINTS} PATHS From 74854346cc452e9cd33c70de1d452961f685e5a0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 18 May 2020 19:07:38 +0200 Subject: [PATCH 334/546] Update Boost to 1.73.0 --- 3rdparty/boost/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/3rdparty/boost/CMakeLists.txt b/3rdparty/boost/CMakeLists.txt index 169d8400..5c019f55 100644 --- a/3rdparty/boost/CMakeLists.txt +++ b/3rdparty/boost/CMakeLists.txt @@ -7,9 +7,9 @@ include(GNUInstallDirs) ExternalProject_Add( boost - URL https://dl.bintray.com/boostorg/release/1.72.0/source/boost_1_72_0.7z - #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_72_0.7z - URL_MD5 cbf2f2abf8cecf69210b60478bc51109 + URL https://dl.bintray.com/boostorg/release/1.73.0/source/boost_1_73_0.7z + #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_73_0.7z + URL_MD5 b647977d33441b17e9276ce37309008f CONFIGURE_COMMAND "" BUILD_COMMAND "" BUILD_IN_SOURCE 1 From b65fef1716b1b4eb3e0ad0314e0a93963d98c7fc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 18 May 2020 19:07:56 +0200 Subject: [PATCH 335/546] Update Boost_ADDITIONAL_VERSIONS to support 1.73.0 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d88e8369..98a335c5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -25,7 +25,7 @@ include(GenerateExportHeader) include(GNUInstallDirs) include(Qt4AutomocMocOptionsBoost) -set(Boost_ADDITIONAL_VERSIONS "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") +set(Boost_ADDITIONAL_VERSIONS "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) From b05afe49c459fe3233f8bfbf623ec22fa0845ae2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 7 Aug 2019 17:43:47 +0200 Subject: [PATCH 336/546] Upgrade Doxygen configuration --- doc/Doxyfile.in | 636 +++++++++++++++++++++++++++++++----------------- 1 file changed, 410 insertions(+), 226 deletions(-) diff --git a/doc/Doxyfile.in b/doc/Doxyfile.in index bf6871f9..baf80fbb 100644 --- a/doc/Doxyfile.in +++ b/doc/Doxyfile.in @@ -1,4 +1,4 @@ -# Doxyfile 1.8.7 +# Doxyfile 1.8.15 # This file describes the settings to be used by the documentation system # doxygen (www.doxygen.org) for a project. @@ -17,11 +17,11 @@ # Project related configuration options #--------------------------------------------------------------------------- -# This tag specifies the encoding used for all characters in the config file -# that follow. The default is UTF-8 which is also the encoding used for all text -# before the first occurrence of this tag. Doxygen uses libiconv (or the iconv -# built into libc) for the transcoding. See http://www.gnu.org/software/libiconv -# for the list of possible encodings. +# This tag specifies the encoding used for all characters in the configuration +# file that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# https://www.gnu.org/software/libiconv/ for the list of possible encodings. # The default value is: UTF-8. DOXYFILE_ENCODING = UTF-8 @@ -44,12 +44,12 @@ PROJECT_NUMBER = "${VERSION}" # for a project that appears at the top of each page and should give viewer a # quick idea about the purpose of the project. Keep the description short. -PROJECT_BRIEF = +PROJECT_BRIEF = -# With the PROJECT_LOGO tag one can specify an logo or icon that is included in -# the documentation. The maximum height of the logo should not exceed 55 pixels -# and the maximum width should not exceed 200 pixels. Doxygen will copy the logo -# to the output directory. +# With the PROJECT_LOGO tag one can specify a logo or an icon that is included +# in the documentation. The maximum height of the logo should not exceed 55 +# pixels and the maximum width should not exceed 200 pixels. Doxygen will copy +# the logo to the output directory. PROJECT_LOGO = "${rl_SOURCE_DIR}/robotics-library.svg" @@ -60,7 +60,7 @@ PROJECT_LOGO = "${rl_SOURCE_DIR}/robotics-library.svg" OUTPUT_DIRECTORY = "${CMAKE_CURRENT_BINARY_DIR}" -# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create 4096 sub- +# If the CREATE_SUBDIRS tag is set to YES then doxygen will create 4096 sub- # directories (in 2 levels) under the output directory of each output format and # will distribute the generated files over these directories. Enabling this # option can be useful when feeding doxygen a huge amount of source files, where @@ -93,14 +93,22 @@ ALLOW_UNICODE_NAMES = NO OUTPUT_LANGUAGE = English -# If the BRIEF_MEMBER_DESC tag is set to YES doxygen will include brief member +# The OUTPUT_TEXT_DIRECTION tag is used to specify the direction in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all generated output in the proper direction. +# Possible values are: None, LTR, RTL and Context. +# The default value is: None. + +OUTPUT_TEXT_DIRECTION = None + +# If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member # descriptions after the members that are listed in the file and class # documentation (similar to Javadoc). Set to NO to disable this. # The default value is: YES. BRIEF_MEMBER_DESC = YES -# If the REPEAT_BRIEF tag is set to YES doxygen will prepend the brief +# If the REPEAT_BRIEF tag is set to YES, doxygen will prepend the brief # description of a member or function before the detailed description # # Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the @@ -145,7 +153,7 @@ ALWAYS_DETAILED_SEC = NO INLINE_INHERITED_MEMB = NO -# If the FULL_PATH_NAMES tag is set to YES doxygen will prepend the full path +# If the FULL_PATH_NAMES tag is set to YES, doxygen will prepend the full path # before files name in the file list and in the header files. If set to NO the # shortest path that makes the file name unique will be used # The default value is: YES. @@ -171,7 +179,7 @@ STRIP_FROM_PATH = "${rl_SOURCE_DIR}/src" # specify the list of include paths that are normally passed to the compiler # using the -I flag. -STRIP_FROM_INC_PATH = +STRIP_FROM_INC_PATH = # If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but # less readable) file names. This can be useful is your file systems doesn't @@ -215,9 +223,9 @@ MULTILINE_CPP_IS_BRIEF = NO INHERIT_DOCS = YES -# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce a -# new page for each member. If set to NO, the documentation of a member will be -# part of the file/class/namespace that contains it. +# If the SEPARATE_MEMBER_PAGES tag is set to YES then doxygen will produce a new +# page for each member. If set to NO, the documentation of a member will be part +# of the file/class/namespace that contains it. # The default value is: NO. SEPARATE_MEMBER_PAGES = NO @@ -236,15 +244,20 @@ TAB_SIZE = 4 # will allow you to put the command \sideeffect (or @sideeffect) in the # documentation, which will result in a user-defined paragraph with heading # "Side Effects:". You can put \n's in the value part of an alias to insert -# newlines. +# newlines (in the resulting output). You can put ^^ in the value part of an +# alias to insert a newline as if a physical newline was in the original file. +# When you need a literal { or } or , in the value part of an alias you have to +# escape them by means of a backslash (\), this can lead to conflicts with the +# commands \{ and \} for these it is advised to use the version @{ and @} or use +# a double escape (\\{ and \\}) -ALIASES = +ALIASES = # This tag can be used to specify a number of word-keyword mappings (TCL only). # A mapping has the form "name=value". For example adding "class=itcl::class" # will allow you to use the command class in the itcl::class meaning. -TCL_SUBST = +TCL_SUBST = # Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources # only. Doxygen will then generate output that is more tailored for C. For @@ -274,28 +287,37 @@ OPTIMIZE_FOR_FORTRAN = NO OPTIMIZE_OUTPUT_VHDL = NO +# Set the OPTIMIZE_OUTPUT_SLICE tag to YES if your project consists of Slice +# sources only. Doxygen will then generate output that is more tailored for that +# language. For instance, namespaces will be presented as modules, types will be +# separated into more groups, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_SLICE = NO + # Doxygen selects the parser to use depending on the extension of the files it # parses. With this tag you can assign which parser to use for a given # extension. Doxygen has a built-in mapping, but you can override or extend it # using this tag. The format is ext=language, where ext is a file extension, and # language is one of the parsers supported by doxygen: IDL, Java, Javascript, -# C#, C, C++, D, PHP, Objective-C, Python, Fortran (fixed format Fortran: -# FortranFixed, free formatted Fortran: FortranFree, unknown formatted Fortran: -# Fortran. In the later case the parser tries to guess whether the code is fixed -# or free formatted code, this is the default for Fortran type files), VHDL. For -# instance to make doxygen treat .inc files as Fortran files (default is PHP), -# and .f files as C (default is Fortran), use: inc=Fortran f=C. +# Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice, +# Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: +# FortranFree, unknown formatted Fortran: Fortran. In the later case the parser +# tries to guess whether the code is fixed or free formatted code, this is the +# default for Fortran type files), VHDL, tcl. For instance to make doxygen treat +# .inc files as Fortran files (default is PHP), and .f files as C (default is +# Fortran), use: inc=Fortran f=C. # -# Note For files without extension you can use no_extension as a placeholder. +# Note: For files without extension you can use no_extension as a placeholder. # # Note that for custom extensions you also need to set FILE_PATTERNS otherwise # the files are not read by doxygen. -EXTENSION_MAPPING = +EXTENSION_MAPPING = # If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments # according to the Markdown format, which allows for more readable -# documentation. See http://daringfireball.net/projects/markdown/ for details. +# documentation. See https://daringfireball.net/projects/markdown/ for details. # The output of markdown processing is further processed by doxygen, so you can # mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in # case of backward compatibilities issues. @@ -303,10 +325,19 @@ EXTENSION_MAPPING = MARKDOWN_SUPPORT = YES +# When the TOC_INCLUDE_HEADINGS tag is set to a non-zero value, all headings up +# to that level are automatically included in the table of contents, even if +# they do not have an id attribute. +# Note: This feature currently applies only to Markdown headings. +# Minimum value: 0, maximum value: 99, default value: 0. +# This tag requires that the tag MARKDOWN_SUPPORT is set to YES. + +TOC_INCLUDE_HEADINGS = 0 + # When enabled doxygen tries to link words that correspond to documented # classes, or namespaces to their corresponding documentation. Such a link can -# be prevented in individual cases by by putting a % sign in front of the word -# or globally by setting AUTOLINK_SUPPORT to NO. +# be prevented in individual cases by putting a % sign in front of the word or +# globally by setting AUTOLINK_SUPPORT to NO. # The default value is: YES. AUTOLINK_SUPPORT = YES @@ -328,7 +359,7 @@ BUILTIN_STL_SUPPORT = NO CPP_CLI_SUPPORT = NO # Set the SIP_SUPPORT tag to YES if your project consists of sip (see: -# http://www.riverbankcomputing.co.uk/software/sip/intro) sources only. Doxygen +# https://www.riverbankcomputing.com/software/sip/intro) sources only. Doxygen # will parse them like normal C++ but will assume all classes use public instead # of private inheritance when no explicit protection keyword is present. # The default value is: NO. @@ -346,13 +377,20 @@ SIP_SUPPORT = NO IDL_PROPERTY_SUPPORT = YES # If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC -# tag is set to YES, then doxygen will reuse the documentation of the first +# tag is set to YES then doxygen will reuse the documentation of the first # member in the group (if any) for the other members of the group. By default # all members of a group must be documented explicitly. # The default value is: NO. DISTRIBUTE_GROUP_DOC = NO +# If one adds a struct or class to a group and this option is enabled, then also +# any nested class or struct is added to the same group. By default this option +# is disabled and one has to add nested compounds explicitly via \ingroup. +# The default value is: NO. + +GROUP_NESTED_COMPOUNDS = NO + # Set the SUBGROUPING tag to YES to allow class member groups of the same type # (for instance a group of public functions) to be put as a subgroup of that # type (e.g. under the Public Functions section). Set it to NO to prevent @@ -411,7 +449,7 @@ LOOKUP_CACHE_SIZE = 0 # Build related configuration options #--------------------------------------------------------------------------- -# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# If the EXTRACT_ALL tag is set to YES, doxygen will assume all entities in # documentation are documented, even if no documentation was available. Private # class members and static file members will be hidden unless the # EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES. @@ -421,35 +459,35 @@ LOOKUP_CACHE_SIZE = 0 EXTRACT_ALL = YES -# If the EXTRACT_PRIVATE tag is set to YES all private members of a class will +# If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will # be included in the documentation. # The default value is: NO. EXTRACT_PRIVATE = YES -# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal +# If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal # scope will be included in the documentation. # The default value is: NO. EXTRACT_PACKAGE = NO -# If the EXTRACT_STATIC tag is set to YES all static members of a file will be +# If the EXTRACT_STATIC tag is set to YES, all static members of a file will be # included in the documentation. # The default value is: NO. EXTRACT_STATIC = YES -# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) defined -# locally in source files will be included in the documentation. If set to NO +# If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined +# locally in source files will be included in the documentation. If set to NO, # only classes defined in header files are included. Does not have any effect # for Java sources. # The default value is: YES. EXTRACT_LOCAL_CLASSES = NO -# This flag is only useful for Objective-C code. When set to YES local methods, +# This flag is only useful for Objective-C code. If set to YES, local methods, # which are defined in the implementation section but not in the interface are -# included in the documentation. If set to NO only methods in the interface are +# included in the documentation. If set to NO, only methods in the interface are # included. # The default value is: NO. @@ -474,21 +512,21 @@ HIDE_UNDOC_MEMBERS = NO # If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all # undocumented classes that are normally visible in the class hierarchy. If set -# to NO these classes will be included in the various overviews. This option has -# no effect if EXTRACT_ALL is enabled. +# to NO, these classes will be included in the various overviews. This option +# has no effect if EXTRACT_ALL is enabled. # The default value is: NO. HIDE_UNDOC_CLASSES = NO # If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend -# (class|struct|union) declarations. If set to NO these declarations will be +# (class|struct|union) declarations. If set to NO, these declarations will be # included in the documentation. # The default value is: NO. HIDE_FRIEND_COMPOUNDS = NO # If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any -# documentation blocks found inside the body of a function. If set to NO these +# documentation blocks found inside the body of a function. If set to NO, these # blocks will be appended to the function's detailed documentation block. # The default value is: NO. @@ -502,7 +540,7 @@ HIDE_IN_BODY_DOCS = NO INTERNAL_DOCS = NO # If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file -# names in lower-case letters. If set to YES upper-case letters are also +# names in lower-case letters. If set to YES, upper-case letters are also # allowed. This is useful if you have classes or files whose names only differ # in case and if your file system supports case sensitive file names. Windows # and Mac users are advised to set this option to NO. @@ -511,12 +549,19 @@ INTERNAL_DOCS = NO CASE_SENSE_NAMES = NO # If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with -# their full class and namespace scopes in the documentation. If set to YES the +# their full class and namespace scopes in the documentation. If set to YES, the # scope will be hidden. # The default value is: NO. HIDE_SCOPE_NAMES = NO +# If the HIDE_COMPOUND_REFERENCE tag is set to NO (default) then doxygen will +# append additional text to a page's title, such as Class Reference. If set to +# YES the compound reference will be hidden. +# The default value is: NO. + +HIDE_COMPOUND_REFERENCE= NO + # If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of # the files that are included by a file in the documentation of that file. # The default value is: YES. @@ -544,14 +589,14 @@ INLINE_INFO = YES # If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the # (detailed) documentation of file and class members alphabetically by member -# name. If set to NO the members will appear in declaration order. +# name. If set to NO, the members will appear in declaration order. # The default value is: YES. SORT_MEMBER_DOCS = YES # If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief # descriptions of file, namespace and class members alphabetically by member -# name. If set to NO the members will appear in declaration order. Note that +# name. If set to NO, the members will appear in declaration order. Note that # this will also influence the order of the classes in the class list. # The default value is: NO. @@ -596,27 +641,25 @@ SORT_BY_SCOPE_NAME = NO STRICT_PROTO_MATCHING = NO -# The GENERATE_TODOLIST tag can be used to enable ( YES) or disable ( NO) the -# todo list. This list is created by putting \todo commands in the -# documentation. +# The GENERATE_TODOLIST tag can be used to enable (YES) or disable (NO) the todo +# list. This list is created by putting \todo commands in the documentation. # The default value is: YES. GENERATE_TODOLIST = YES -# The GENERATE_TESTLIST tag can be used to enable ( YES) or disable ( NO) the -# test list. This list is created by putting \test commands in the -# documentation. +# The GENERATE_TESTLIST tag can be used to enable (YES) or disable (NO) the test +# list. This list is created by putting \test commands in the documentation. # The default value is: YES. GENERATE_TESTLIST = YES -# The GENERATE_BUGLIST tag can be used to enable ( YES) or disable ( NO) the bug +# The GENERATE_BUGLIST tag can be used to enable (YES) or disable (NO) the bug # list. This list is created by putting \bug commands in the documentation. # The default value is: YES. GENERATE_BUGLIST = YES -# The GENERATE_DEPRECATEDLIST tag can be used to enable ( YES) or disable ( NO) +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or disable (NO) # the deprecated list. This list is created by putting \deprecated commands in # the documentation. # The default value is: YES. @@ -627,7 +670,7 @@ GENERATE_DEPRECATEDLIST= YES # sections, marked by \if ... \endif and \cond # ... \endcond blocks. -ENABLED_SECTIONS = +ENABLED_SECTIONS = # The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the # initial value of a variable or macro / define can have for it to appear in the @@ -641,8 +684,8 @@ ENABLED_SECTIONS = MAX_INITIALIZER_LINES = 30 # Set the SHOW_USED_FILES tag to NO to disable the list of files generated at -# the bottom of the documentation of classes and structs. If set to YES the list -# will mention the files that were used to generate the documentation. +# the bottom of the documentation of classes and structs. If set to YES, the +# list will mention the files that were used to generate the documentation. # The default value is: YES. SHOW_USED_FILES = YES @@ -669,7 +712,7 @@ SHOW_NAMESPACES = YES # by doxygen. Whatever the program writes to standard output is used as the file # version. For an example see the documentation. -FILE_VERSION_FILTER = +FILE_VERSION_FILTER = # The LAYOUT_FILE tag can be used to specify a layout file which will be parsed # by doxygen. The layout file controls the global structure of the generated @@ -682,18 +725,17 @@ FILE_VERSION_FILTER = # DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE # tag is left empty. -LAYOUT_FILE = +LAYOUT_FILE = # The CITE_BIB_FILES tag can be used to specify one or more bib files containing # the reference definitions. This must be a list of .bib files. The .bib # extension is automatically appended if omitted. This requires the bibtex tool -# to be installed. See also http://en.wikipedia.org/wiki/BibTeX for more info. +# to be installed. See also https://en.wikipedia.org/wiki/BibTeX for more info. # For LaTeX the style of the bibliography can be controlled using # LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the -# search path. Do not use file names with spaces, bibtex cannot handle them. See -# also \cite for info how to create references. +# search path. See also \cite for info how to create references. -CITE_BIB_FILES = +CITE_BIB_FILES = #--------------------------------------------------------------------------- # Configuration options related to warning and progress messages @@ -707,7 +749,7 @@ CITE_BIB_FILES = QUIET = NO # The WARNINGS tag can be used to turn on/off the warning messages that are -# generated to standard error ( stderr) by doxygen. If WARNINGS is set to YES +# generated to standard error (stderr) by doxygen. If WARNINGS is set to YES # this implies that the warnings are on. # # Tip: Turn warnings on while writing the documentation. @@ -715,7 +757,7 @@ QUIET = NO WARNINGS = YES -# If the WARN_IF_UNDOCUMENTED tag is set to YES, then doxygen will generate +# If the WARN_IF_UNDOCUMENTED tag is set to YES then doxygen will generate # warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag # will automatically be disabled. # The default value is: YES. @@ -732,12 +774,19 @@ WARN_IF_DOC_ERROR = YES # This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that # are documented, but have no documentation for their parameters or return -# value. If set to NO doxygen will only warn about wrong or incomplete parameter -# documentation, but not about the absence of documentation. +# value. If set to NO, doxygen will only warn about wrong or incomplete +# parameter documentation, but not about the absence of documentation. If +# EXTRACT_ALL is set to YES then this flag will automatically be disabled. # The default value is: NO. WARN_NO_PARAMDOC = NO +# If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when +# a warning is encountered. +# The default value is: NO. + +WARN_AS_ERROR = NO + # The WARN_FORMAT tag determines the format of the warning messages that doxygen # can produce. The string should contain the $file, $line, and $text tags, which # will be replaced by the file and line number from which the warning originated @@ -752,7 +801,7 @@ WARN_FORMAT = "$file:$line: $text" # messages should be written. If left blank the output is written to standard # error (stderr). -WARN_LOGFILE = +WARN_LOGFILE = #--------------------------------------------------------------------------- # Configuration options related to the input files @@ -761,7 +810,7 @@ WARN_LOGFILE = # The INPUT tag is used to specify the files and/or directories that contain # documented source files. You may enter file names like myfile.cpp or # directories like /usr/src/myproject. Separate the files or directories with -# spaces. +# spaces. See also FILE_PATTERNS and EXTENSION_MAPPING # Note: If this tag is empty the current directory is searched. INPUT = "${rl_SOURCE_DIR}/src/rl" @@ -769,7 +818,7 @@ INPUT = "${rl_SOURCE_DIR}/src/rl" # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses # libiconv (or the iconv built into libc) for the transcoding. See the libiconv -# documentation (see: http://www.gnu.org/software/libiconv) for the list of +# documentation (see: https://www.gnu.org/software/libiconv/) for the list of # possible encodings. # The default value is: UTF-8. @@ -777,12 +826,17 @@ INPUT_ENCODING = UTF-8 # If the value of the INPUT tag contains directories, you can use the # FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and -# *.h) to filter out the source-files in the directories. If left blank the -# following patterns are tested:*.c, *.cc, *.cxx, *.cpp, *.c++, *.java, *.ii, -# *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, *.hh, *.hxx, *.hpp, -# *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, *.m, *.markdown, -# *.md, *.mm, *.dox, *.py, *.f90, *.f, *.for, *.tcl, *.vhd, *.vhdl, *.ucf, -# *.qsf, *.as and *.js. +# *.h) to filter out the source-files in the directories. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# read by doxygen. +# +# If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, +# *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, +# *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, +# *.m, *.markdown, *.md, *.mm, *.dox, *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, +# *.f, *.for, *.tcl, *.vhd, *.vhdl, *.ucf, *.qsf and *.ice. FILE_PATTERNS = *.c \ *.cc \ @@ -840,7 +894,7 @@ RECURSIVE = YES # Note that relative paths are relative to the directory from which doxygen is # run. -EXCLUDE = +EXCLUDE = # The EXCLUDE_SYMLINKS tag can be used to select whether or not files or # directories that are symbolic links (a Unix file system feature) are excluded @@ -856,7 +910,7 @@ EXCLUDE_SYMLINKS = NO # Note that the wildcards are matched against the file with absolute path, so to # exclude all test directories for example use the pattern */test/* -EXCLUDE_PATTERNS = +EXCLUDE_PATTERNS = # The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names # (namespaces, classes, functions, etc.) that should be excluded from the @@ -867,13 +921,13 @@ EXCLUDE_PATTERNS = # Note that the wildcards are matched against the file with absolute path, so to # exclude all test directories use the pattern */test/* -EXCLUDE_SYMBOLS = +EXCLUDE_SYMBOLS = # The EXAMPLE_PATH tag can be used to specify one or more files or directories # that contain example code fragments that are included (see the \include # command). -EXAMPLE_PATH = +EXAMPLE_PATH = # If the value of the EXAMPLE_PATH tag contains directories, you can use the # EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and @@ -893,7 +947,7 @@ EXAMPLE_RECURSIVE = NO # that contain images that are to be included in the documentation (see the # \image command). -IMAGE_PATH = +IMAGE_PATH = # The INPUT_FILTER tag can be used to specify a program that doxygen should # invoke to filter for each input file. Doxygen will invoke the filter program @@ -909,8 +963,12 @@ IMAGE_PATH = # Note that the filter must not add or remove lines; it is applied before the # code is scanned, but not when the output code is generated. If lines are added # or removed, the anchors will not be placed correctly. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. -INPUT_FILTER = +INPUT_FILTER = # The FILTER_PATTERNS tag can be used to specify filters on a per file pattern # basis. Doxygen will compare the file name with each pattern and apply the @@ -918,11 +976,15 @@ INPUT_FILTER = # (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how # filters are used. If the FILTER_PATTERNS tag is empty or if none of the # patterns match the file name, INPUT_FILTER is applied. +# +# Note that for custom extensions or not directly supported extensions you also +# need to set EXTENSION_MAPPING for the extension otherwise the files are not +# properly processed by doxygen. -FILTER_PATTERNS = +FILTER_PATTERNS = # If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using -# INPUT_FILTER ) will also be used to filter the input files that are used for +# INPUT_FILTER) will also be used to filter the input files that are used for # producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES). # The default value is: NO. @@ -934,14 +996,14 @@ FILTER_SOURCE_FILES = NO # *.ext= (so without naming a filter). # This tag requires that the tag FILTER_SOURCE_FILES is set to YES. -FILTER_SOURCE_PATTERNS = +FILTER_SOURCE_PATTERNS = # If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that # is part of the input, its contents will be placed on the main page # (index.html). This can be useful if you have a project on for instance GitHub # and want to reuse the introduction page also for the doxygen output. -USE_MDFILE_AS_MAINPAGE = +USE_MDFILE_AS_MAINPAGE = #--------------------------------------------------------------------------- # Configuration options related to source browsing @@ -970,7 +1032,7 @@ INLINE_SOURCES = NO STRIP_CODE_COMMENTS = YES # If the REFERENCED_BY_RELATION tag is set to YES then for each documented -# function all documented functions referencing it will be listed. +# entity all documented functions referencing it will be listed. # The default value is: NO. REFERENCED_BY_RELATION = NO @@ -982,7 +1044,7 @@ REFERENCED_BY_RELATION = NO REFERENCES_RELATION = NO # If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set -# to YES, then the hyperlinks from functions in REFERENCES_RELATION and +# to YES then the hyperlinks from functions in REFERENCES_RELATION and # REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will # link to the documentation. # The default value is: YES. @@ -1002,12 +1064,12 @@ SOURCE_TOOLTIPS = YES # If the USE_HTAGS tag is set to YES then the references to source code will # point to the HTML generated by the htags(1) tool instead of doxygen built-in # source browser. The htags tool is part of GNU's global source tagging system -# (see http://www.gnu.org/software/global/global.html). You will need version +# (see https://www.gnu.org/software/global/global.html). You will need version # 4.8.6 or higher. # # To use it do the following: # - Install the latest version of global -# - Enable SOURCE_BROWSER and USE_HTAGS in the config file +# - Enable SOURCE_BROWSER and USE_HTAGS in the configuration file # - Make sure the INPUT points to the root of the source tree # - Run doxygen as normal # @@ -1029,13 +1091,13 @@ USE_HTAGS = NO VERBATIM_HEADERS = YES -# If the CLANG_ASSISTED_PARSING tag is set to YES, then doxygen will use the +# If the CLANG_ASSISTED_PARSING tag is set to YES then doxygen will use the # clang parser (see: http://clang.llvm.org/) for more accurate parsing at the # cost of reduced performance. This can be particularly helpful with template # rich C++ code for which doxygen's built-in parser lacks the necessary type # information. # Note: The availability of this option depends on whether or not doxygen was -# compiled with the --with-libclang option. +# generated with the -Duse_libclang=ON option for CMake. # The default value is: NO. CLANG_ASSISTED_PARSING = NO @@ -1046,7 +1108,17 @@ CLANG_ASSISTED_PARSING = NO # specified with INPUT and INCLUDE_PATH. # This tag requires that the tag CLANG_ASSISTED_PARSING is set to YES. -CLANG_OPTIONS = +CLANG_OPTIONS = + +# If clang assisted parsing is enabled you can provide the clang parser with the +# path to the compilation database (see: +# http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html) used when the files +# were built. This is equivalent to specifying the "-p" option to a clang tool, +# such as clang-check. These options will then be passed to the parser. +# Note: The availability of this option depends on whether or not doxygen was +# generated with the -Duse_libclang=ON option for CMake. + +CLANG_DATABASE_PATH = #--------------------------------------------------------------------------- # Configuration options related to the alphabetical class index @@ -1072,13 +1144,13 @@ COLS_IN_ALPHA_INDEX = 5 # while generating the index headers. # This tag requires that the tag ALPHABETICAL_INDEX is set to YES. -IGNORE_PREFIX = +IGNORE_PREFIX = #--------------------------------------------------------------------------- # Configuration options related to the HTML output #--------------------------------------------------------------------------- -# If the GENERATE_HTML tag is set to YES doxygen will generate HTML output +# If the GENERATE_HTML tag is set to YES, doxygen will generate HTML output # The default value is: YES. GENERATE_HTML = YES @@ -1116,7 +1188,7 @@ HTML_FILE_EXTENSION = .html # of the possible markers and block names see the documentation. # This tag requires that the tag GENERATE_HTML is set to YES. -HTML_HEADER = +HTML_HEADER = # The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each # generated HTML page. If the tag is left blank doxygen will generate a standard @@ -1126,7 +1198,7 @@ HTML_HEADER = # that doxygen normally uses. # This tag requires that the tag GENERATE_HTML is set to YES. -HTML_FOOTER = +HTML_FOOTER = # The HTML_STYLESHEET tag can be used to specify a user-defined cascading style # sheet that is used by each HTML page. It can be used to fine-tune the look of @@ -1138,15 +1210,17 @@ HTML_FOOTER = # obsolete. # This tag requires that the tag GENERATE_HTML is set to YES. -HTML_STYLESHEET = +HTML_STYLESHEET = -# The HTML_EXTRA_STYLESHEET tag can be used to specify an additional user- -# defined cascading style sheet that is included after the standard style sheets +# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined +# cascading style sheets that are included after the standard style sheets # created by doxygen. Using this option one can overrule certain style aspects. # This is preferred over using HTML_STYLESHEET since it does not replace the -# standard style sheet and is therefor more robust against future updates. -# Doxygen will copy the style sheet file to the output directory. For an example -# see the documentation. +# standard style sheet and is therefore more robust against future updates. +# Doxygen will copy the style sheet files to the output directory. +# Note: The order of the extra style sheet files is of importance (e.g. the last +# style sheet in the list overrules the setting of the previous ones in the +# list). For an example see the documentation. # This tag requires that the tag GENERATE_HTML is set to YES. HTML_EXTRA_STYLESHEET = "${CMAKE_CURRENT_SOURCE_DIR}/extra.css" @@ -1159,12 +1233,12 @@ HTML_EXTRA_STYLESHEET = "${CMAKE_CURRENT_SOURCE_DIR}/extra.css" # files will be copied as-is; there are no commands or markers available. # This tag requires that the tag GENERATE_HTML is set to YES. -HTML_EXTRA_FILES = "${CMAKE_CURRENT_SOURCE_DIR}/extra.sty" +HTML_EXTRA_FILES = # The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen -# will adjust the colors in the stylesheet and background images according to +# will adjust the colors in the style sheet and background images according to # this color. Hue is specified as an angle on a colorwheel, see -# http://en.wikipedia.org/wiki/Hue for more information. For instance the value +# https://en.wikipedia.org/wiki/Hue for more information. For instance the value # 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 # purple, and 360 is red again. # Minimum value: 0, maximum value: 359, default value: 220. @@ -1193,12 +1267,24 @@ HTML_COLORSTYLE_GAMMA = 80 # If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML # page will contain the date and time when the page was generated. Setting this -# to NO can help when comparing the output of multiple runs. -# The default value is: YES. +# to YES can help to show when doxygen was last run and thus if the +# documentation is up to date. +# The default value is: NO. # This tag requires that the tag GENERATE_HTML is set to YES. HTML_TIMESTAMP = YES +# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML +# documentation will contain a main index with vertical navigation menus that +# are dynamically created via Javascript. If disabled, the navigation index will +# consists of multiple levels of tabs that are statically embedded in every HTML +# page. Disable this option to support browsers that do not have Javascript, +# like the Qt help browser. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_MENUS = YES + # If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML # documentation will contain sections that can be hidden and shown after the # page has loaded. @@ -1222,13 +1308,13 @@ HTML_INDEX_NUM_ENTRIES = 100 # If the GENERATE_DOCSET tag is set to YES, additional index files will be # generated that can be used as input for Apple's Xcode 3 integrated development -# environment (see: http://developer.apple.com/tools/xcode/), introduced with -# OSX 10.5 (Leopard). To create a documentation set, doxygen will generate a +# environment (see: https://developer.apple.com/xcode/), introduced with OSX +# 10.5 (Leopard). To create a documentation set, doxygen will generate a # Makefile in the HTML output directory. Running make will produce the docset in # that directory and running make install will install the docset in # ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at -# startup. See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html -# for more information. +# startup. See https://developer.apple.com/library/archive/featuredarticles/Doxy +# genXcode/_index.html for more information. # The default value is: NO. # This tag requires that the tag GENERATE_HTML is set to YES. @@ -1267,7 +1353,7 @@ DOCSET_PUBLISHER_NAME = Publisher # If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three # additional HTML index files: index.hhp, index.hhc, and index.hhk. The # index.hhp is a project file that can be read by Microsoft's HTML Help Workshop -# (see: http://www.microsoft.com/en-us/download/details.aspx?id=21138) on +# (see: https://www.microsoft.com/en-us/download/details.aspx?id=21138) on # Windows. # # The HTML Help Workshop contains a compiler that can convert all HTML output @@ -1287,31 +1373,31 @@ GENERATE_HTMLHELP = NO # written to the html output directory. # This tag requires that the tag GENERATE_HTMLHELP is set to YES. -CHM_FILE = +CHM_FILE = # The HHC_LOCATION tag can be used to specify the location (absolute path -# including file name) of the HTML help compiler ( hhc.exe). If non-empty +# including file name) of the HTML help compiler (hhc.exe). If non-empty, # doxygen will try to run the HTML help compiler on the generated index.hhp. # The file has to be specified with full path. # This tag requires that the tag GENERATE_HTMLHELP is set to YES. -HHC_LOCATION = +HHC_LOCATION = -# The GENERATE_CHI flag controls if a separate .chi index file is generated ( -# YES) or that it should be included in the master .chm file ( NO). +# The GENERATE_CHI flag controls if a separate .chi index file is generated +# (YES) or that it should be included in the master .chm file (NO). # The default value is: NO. # This tag requires that the tag GENERATE_HTMLHELP is set to YES. GENERATE_CHI = NO -# The CHM_INDEX_ENCODING is used to encode HtmlHelp index ( hhk), content ( hhc) +# The CHM_INDEX_ENCODING is used to encode HtmlHelp index (hhk), content (hhc) # and project file content. # This tag requires that the tag GENERATE_HTMLHELP is set to YES. -CHM_INDEX_ENCODING = +CHM_INDEX_ENCODING = -# The BINARY_TOC flag controls whether a binary table of contents is generated ( -# YES) or a normal table of contents ( NO) in the .chm file. Furthermore it +# The BINARY_TOC flag controls whether a binary table of contents is generated +# (YES) or a normal table of contents (NO) in the .chm file. Furthermore it # enables the Previous and Next buttons. # The default value is: NO. # This tag requires that the tag GENERATE_HTMLHELP is set to YES. @@ -1339,11 +1425,11 @@ GENERATE_QHP = NO # the HTML output folder. # This tag requires that the tag GENERATE_QHP is set to YES. -QCH_FILE = +QCH_FILE = # The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help # Project output. For more information please see Qt Help Project / Namespace -# (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#namespace). +# (see: http://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). # The default value is: org.doxygen.Project. # This tag requires that the tag GENERATE_QHP is set to YES. @@ -1351,7 +1437,7 @@ QHP_NAMESPACE = org.doxygen.Project # The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt # Help Project output. For more information please see Qt Help Project / Virtual -# Folders (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#virtual- +# Folders (see: http://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual- # folders). # The default value is: doc. # This tag requires that the tag GENERATE_QHP is set to YES. @@ -1360,33 +1446,33 @@ QHP_VIRTUAL_FOLDER = doc # If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom # filter to add. For more information please see Qt Help Project / Custom -# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- +# Filters (see: http://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- # filters). # This tag requires that the tag GENERATE_QHP is set to YES. -QHP_CUST_FILTER_NAME = +QHP_CUST_FILTER_NAME = # The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the # custom filter to add. For more information please see Qt Help Project / Custom -# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- +# Filters (see: http://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- # filters). # This tag requires that the tag GENERATE_QHP is set to YES. -QHP_CUST_FILTER_ATTRS = +QHP_CUST_FILTER_ATTRS = # The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this # project's filter section matches. Qt Help Project / Filter Attributes (see: -# http://qt-project.org/doc/qt-4.8/qthelpproject.html#filter-attributes). +# http://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). # This tag requires that the tag GENERATE_QHP is set to YES. -QHP_SECT_FILTER_ATTRS = +QHP_SECT_FILTER_ATTRS = # The QHG_LOCATION tag can be used to specify the location of Qt's # qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the # generated .qhp file. # This tag requires that the tag GENERATE_QHP is set to YES. -QHG_LOCATION = +QHG_LOCATION = # If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be # generated, together with the HTML files, they form an Eclipse help plugin. To @@ -1425,7 +1511,7 @@ DISABLE_INDEX = NO # index structure (just like the one that is generated for HTML Help). For this # to work a browser that supports JavaScript, DHTML, CSS and frames is required # (i.e. any modern browser). Windows users are probably better off using the -# HTML help feature. Via custom stylesheets (see HTML_EXTRA_STYLESHEET) one can +# HTML help feature. Via custom style sheets (see HTML_EXTRA_STYLESHEET) one can # further fine-tune the look of the index. As an example, the default style # sheet generated by doxygen has an example that shows how to put an image at # the root of the tree instead of the PROJECT_NAME. Since the tree basically has @@ -1453,7 +1539,7 @@ ENUM_VALUES_PER_LINE = 4 TREEVIEW_WIDTH = 250 -# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open links to +# If the EXT_LINKS_IN_WINDOW option is set to YES, doxygen will open links to # external symbols imported via tag files in a separate window. # The default value is: NO. # This tag requires that the tag GENERATE_HTML is set to YES. @@ -1469,7 +1555,7 @@ EXT_LINKS_IN_WINDOW = NO FORMULA_FONTSIZE = 10 -# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# Use the FORMULA_TRANSPARENT tag to determine whether or not the images # generated for formulas are transparent PNGs. Transparent PNGs are not # supported properly for IE 6.0, but are supported on all modern browsers. # @@ -1481,8 +1567,8 @@ FORMULA_FONTSIZE = 10 FORMULA_TRANSPARENT = YES # Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see -# http://www.mathjax.org) which uses client side Javascript for the rendering -# instead of using prerendered bitmaps. Use this if you do not have LaTeX +# https://www.mathjax.org) which uses client side Javascript for the rendering +# instead of using pre-rendered bitmaps. Use this if you do not have LaTeX # installed or if you want to formulas look prettier in the HTML output. When # enabled you may also need to install MathJax separately and configure the path # to it using the MATHJAX_RELPATH option. @@ -1508,8 +1594,8 @@ MATHJAX_FORMAT = HTML-CSS # MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax # Content Delivery Network so you can quickly see the result without installing # MathJax. However, it is strongly recommended to install a local copy of -# MathJax from http://www.mathjax.org before deployment. -# The default value is: http://cdn.mathjax.org/mathjax/latest. +# MathJax from https://www.mathjax.org before deployment. +# The default value is: https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/. # This tag requires that the tag USE_MATHJAX is set to YES. MATHJAX_RELPATH = https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.2 @@ -1519,7 +1605,7 @@ MATHJAX_RELPATH = https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.2 # MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols # This tag requires that the tag USE_MATHJAX is set to YES. -MATHJAX_EXTENSIONS = +MATHJAX_EXTENSIONS = # The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces # of code that will be used on startup of the MathJax code. See the MathJax site @@ -1568,9 +1654,9 @@ SERVER_BASED_SEARCH = NO # external search engine pointed to by the SEARCHENGINE_URL option to obtain the # search results. # -# Doxygen ships with an example indexer ( doxyindexer) and search engine +# Doxygen ships with an example indexer (doxyindexer) and search engine # (doxysearch.cgi) which are based on the open source search engine library -# Xapian (see: http://xapian.org/). +# Xapian (see: https://xapian.org/). # # See the section "External Indexing and Searching" for details. # The default value is: NO. @@ -1581,13 +1667,13 @@ EXTERNAL_SEARCH = NO # The SEARCHENGINE_URL should point to a search engine hosted by a web server # which will return the search results when EXTERNAL_SEARCH is enabled. # -# Doxygen ships with an example indexer ( doxyindexer) and search engine +# Doxygen ships with an example indexer (doxyindexer) and search engine # (doxysearch.cgi) which are based on the open source search engine library -# Xapian (see: http://xapian.org/). See the section "External Indexing and +# Xapian (see: https://xapian.org/). See the section "External Indexing and # Searching" for details. # This tag requires that the tag SEARCHENGINE is set to YES. -SEARCHENGINE_URL = +SEARCHENGINE_URL = # When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the unindexed # search data is written to a file for indexing by an external tool. With the @@ -1603,7 +1689,7 @@ SEARCHDATA_FILE = searchdata.xml # projects and redirect the results back to the right project. # This tag requires that the tag SEARCHENGINE is set to YES. -EXTERNAL_SEARCH_ID = +EXTERNAL_SEARCH_ID = # The EXTRA_SEARCH_MAPPINGS tag can be used to enable searching through doxygen # projects other than the one defined by this configuration file, but that are @@ -1613,13 +1699,13 @@ EXTERNAL_SEARCH_ID = # EXTRA_SEARCH_MAPPINGS = tagname1=loc1 tagname2=loc2 ... # This tag requires that the tag SEARCHENGINE is set to YES. -EXTRA_SEARCH_MAPPINGS = +EXTRA_SEARCH_MAPPINGS = #--------------------------------------------------------------------------- # Configuration options related to the LaTeX output #--------------------------------------------------------------------------- -# If the GENERATE_LATEX tag is set to YES doxygen will generate LaTeX output. +# If the GENERATE_LATEX tag is set to YES, doxygen will generate LaTeX output. # The default value is: YES. GENERATE_LATEX = NO @@ -1635,22 +1721,35 @@ LATEX_OUTPUT = latex # The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be # invoked. # -# Note that when enabling USE_PDFLATEX this option is only used for generating -# bitmaps for formulas in the HTML output, but not in the Makefile that is -# written to the output directory. -# The default file is: latex. +# Note that when not enabling USE_PDFLATEX the default is latex when enabling +# USE_PDFLATEX the default is pdflatex and when in the later case latex is +# chosen this is overwritten by pdflatex. For specific output languages the +# default can have been set differently, this depends on the implementation of +# the output language. # This tag requires that the tag GENERATE_LATEX is set to YES. LATEX_CMD_NAME = "${LATEX_COMPILER}" # The MAKEINDEX_CMD_NAME tag can be used to specify the command name to generate # index for LaTeX. +# Note: This tag is used in the Makefile / make.bat. +# See also: LATEX_MAKEINDEX_CMD for the part in the generated output file +# (.tex). # The default file is: makeindex. # This tag requires that the tag GENERATE_LATEX is set to YES. MAKEINDEX_CMD_NAME = "${MAKEINDEX_COMPILER}" -# If the COMPACT_LATEX tag is set to YES doxygen generates more compact LaTeX +# The LATEX_MAKEINDEX_CMD tag can be used to specify the command name to +# generate index for LaTeX. +# Note: This tag is used in the generated output file (.tex). +# See also: MAKEINDEX_CMD_NAME for the part in the Makefile / make.bat. +# The default value is: \makeindex. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_MAKEINDEX_CMD = \makeindex + +# If the COMPACT_LATEX tag is set to YES, doxygen generates more compact LaTeX # documents. This may be useful for small projects and may help to save some # trees in general. # The default value is: NO. @@ -1668,13 +1767,18 @@ COMPACT_LATEX = NO PAPER_TYPE = a4 # The EXTRA_PACKAGES tag can be used to specify one or more LaTeX package names -# that should be included in the LaTeX output. To get the times font for -# instance you can specify -# EXTRA_PACKAGES=times +# that should be included in the LaTeX output. The package can be specified just +# by its name or with the correct syntax as to be used with the LaTeX +# \usepackage command. To get the times font for instance you can specify : +# EXTRA_PACKAGES=times or EXTRA_PACKAGES={times} +# To use the option intlimits with the amsmath package you can specify: +# EXTRA_PACKAGES=[intlimits]{amsmath} # If left blank no extra packages will be included. # This tag requires that the tag GENERATE_LATEX is set to YES. -EXTRA_PACKAGES = amsmath,amssymb,extra +EXTRA_PACKAGES = amsmath \ + amssymb \ + extra # The LATEX_HEADER tag can be used to specify a personal LaTeX header for the # generated LaTeX document. The header should contain everything until the first @@ -1684,22 +1788,35 @@ EXTRA_PACKAGES = amsmath,amssymb,extra # # Note: Only use a user-defined header if you know what you are doing! The # following commands have a special meaning inside the header: $title, -# $datetime, $date, $doxygenversion, $projectname, $projectnumber. Doxygen will -# replace them by respectively the title of the page, the current date and time, -# only the current date, the version number of doxygen, the project name (see -# PROJECT_NAME), or the project number (see PROJECT_NUMBER). +# $datetime, $date, $doxygenversion, $projectname, $projectnumber, +# $projectbrief, $projectlogo. Doxygen will replace $title with the empty +# string, for the replacement values of the other commands the user is referred +# to HTML_HEADER. # This tag requires that the tag GENERATE_LATEX is set to YES. -LATEX_HEADER = +LATEX_HEADER = # The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for the # generated LaTeX document. The footer should contain everything after the last -# chapter. If it is left blank doxygen will generate a standard footer. +# chapter. If it is left blank doxygen will generate a standard footer. See +# LATEX_HEADER for more information on how to generate a default footer and what +# special commands can be used inside the footer. # # Note: Only use a user-defined footer if you know what you are doing! # This tag requires that the tag GENERATE_LATEX is set to YES. -LATEX_FOOTER = +LATEX_FOOTER = + +# The LATEX_EXTRA_STYLESHEET tag can be used to specify additional user-defined +# LaTeX style sheets that are included after the standard style sheets created +# by doxygen. Using this option one can overrule certain style aspects. Doxygen +# will copy the style sheet files to the output directory. +# Note: The order of the extra style sheet files is of importance (e.g. the last +# style sheet in the list overrules the setting of the previous ones in the +# list). +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_EXTRA_STYLESHEET = "${CMAKE_CURRENT_SOURCE_DIR}/extra.sty" # The LATEX_EXTRA_FILES tag can be used to specify one or more extra images or # other source files which should be copied to the LATEX_OUTPUT output @@ -1707,7 +1824,7 @@ LATEX_FOOTER = # markers available. # This tag requires that the tag GENERATE_LATEX is set to YES. -LATEX_EXTRA_FILES = "${CMAKE_CURRENT_SOURCE_DIR}/extra.sty" +LATEX_EXTRA_FILES = # If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated is # prepared for conversion to PDF (using ps2pdf or pdflatex). The PDF file will @@ -1718,8 +1835,8 @@ LATEX_EXTRA_FILES = "${CMAKE_CURRENT_SOURCE_DIR}/extra.sty" PDF_HYPERLINKS = YES -# If the LATEX_PDFLATEX tag is set to YES, doxygen will use pdflatex to generate -# the PDF file directly from the LaTeX files. Set this option to YES to get a +# If the USE_PDFLATEX tag is set to YES, doxygen will use pdflatex to generate +# the PDF file directly from the LaTeX files. Set this option to YES, to get a # higher quality PDF documentation. # The default value is: YES. # This tag requires that the tag GENERATE_LATEX is set to YES. @@ -1754,17 +1871,33 @@ LATEX_SOURCE_CODE = NO # The LATEX_BIB_STYLE tag can be used to specify the style to use for the # bibliography, e.g. plainnat, or ieeetr. See -# http://en.wikipedia.org/wiki/BibTeX and \cite for more info. +# https://en.wikipedia.org/wiki/BibTeX and \cite for more info. # The default value is: plain. # This tag requires that the tag GENERATE_LATEX is set to YES. LATEX_BIB_STYLE = plain +# If the LATEX_TIMESTAMP tag is set to YES then the footer of each generated +# page will contain the date and time when the page was generated. Setting this +# to NO can help when comparing the output of multiple runs. +# The default value is: NO. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_TIMESTAMP = NO + +# The LATEX_EMOJI_DIRECTORY tag is used to specify the (relative or absolute) +# path from which the emoji images will be read. If a relative path is entered, +# it will be relative to the LATEX_OUTPUT directory. If left blank the +# LATEX_OUTPUT directory will be used. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_EMOJI_DIRECTORY = + #--------------------------------------------------------------------------- # Configuration options related to the RTF output #--------------------------------------------------------------------------- -# If the GENERATE_RTF tag is set to YES doxygen will generate RTF output. The +# If the GENERATE_RTF tag is set to YES, doxygen will generate RTF output. The # RTF output is optimized for Word 97 and may not look too pretty with other RTF # readers/editors. # The default value is: NO. @@ -1779,7 +1912,7 @@ GENERATE_RTF = NO RTF_OUTPUT = rtf -# If the COMPACT_RTF tag is set to YES doxygen generates more compact RTF +# If the COMPACT_RTF tag is set to YES, doxygen generates more compact RTF # documents. This may be useful for small projects and may help to save some # trees in general. # The default value is: NO. @@ -1799,28 +1932,38 @@ COMPACT_RTF = NO RTF_HYPERLINKS = NO -# Load stylesheet definitions from file. Syntax is similar to doxygen's config -# file, i.e. a series of assignments. You only have to provide replacements, -# missing definitions are set to their default value. +# Load stylesheet definitions from file. Syntax is similar to doxygen's +# configuration file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. # # See also section "Doxygen usage" for information on how to generate the # default style sheet that doxygen normally uses. # This tag requires that the tag GENERATE_RTF is set to YES. -RTF_STYLESHEET_FILE = +RTF_STYLESHEET_FILE = # Set optional variables used in the generation of an RTF document. Syntax is -# similar to doxygen's config file. A template extensions file can be generated -# using doxygen -e rtf extensionFile. +# similar to doxygen's configuration file. A template extensions file can be +# generated using doxygen -e rtf extensionFile. +# This tag requires that the tag GENERATE_RTF is set to YES. + +RTF_EXTENSIONS_FILE = + +# If the RTF_SOURCE_CODE tag is set to YES then doxygen will include source code +# with syntax highlighting in the RTF output. +# +# Note that which sources are shown also depends on other settings such as +# SOURCE_BROWSER. +# The default value is: NO. # This tag requires that the tag GENERATE_RTF is set to YES. -RTF_EXTENSIONS_FILE = +RTF_SOURCE_CODE = NO #--------------------------------------------------------------------------- # Configuration options related to the man page output #--------------------------------------------------------------------------- -# If the GENERATE_MAN tag is set to YES doxygen will generate man pages for +# If the GENERATE_MAN tag is set to YES, doxygen will generate man pages for # classes and files. # The default value is: NO. @@ -1849,7 +1992,7 @@ MAN_EXTENSION = .3 # MAN_EXTENSION with the initial . removed. # This tag requires that the tag GENERATE_MAN is set to YES. -MAN_SUBDIR = +MAN_SUBDIR = # If the MAN_LINKS tag is set to YES and doxygen generates man output, then it # will generate one additional man file for each entity documented in the real @@ -1864,7 +2007,7 @@ MAN_LINKS = NO # Configuration options related to the XML output #--------------------------------------------------------------------------- -# If the GENERATE_XML tag is set to YES doxygen will generate an XML file that +# If the GENERATE_XML tag is set to YES, doxygen will generate an XML file that # captures the structure of the code including all documentation. # The default value is: NO. @@ -1878,7 +2021,7 @@ GENERATE_XML = NO XML_OUTPUT = xml -# If the XML_PROGRAMLISTING tag is set to YES doxygen will dump the program +# If the XML_PROGRAMLISTING tag is set to YES, doxygen will dump the program # listings (including syntax highlighting and cross-referencing information) to # the XML output. Note that enabling this will significantly increase the size # of the XML output. @@ -1887,11 +2030,18 @@ XML_OUTPUT = xml XML_PROGRAMLISTING = YES +# If the XML_NS_MEMB_FILE_SCOPE tag is set to YES, doxygen will include +# namespace members in file scope as well, matching the HTML output. +# The default value is: NO. +# This tag requires that the tag GENERATE_XML is set to YES. + +XML_NS_MEMB_FILE_SCOPE = NO + #--------------------------------------------------------------------------- # Configuration options related to the DOCBOOK output #--------------------------------------------------------------------------- -# If the GENERATE_DOCBOOK tag is set to YES doxygen will generate Docbook files +# If the GENERATE_DOCBOOK tag is set to YES, doxygen will generate Docbook files # that can be used to generate PDF. # The default value is: NO. @@ -1905,14 +2055,23 @@ GENERATE_DOCBOOK = NO DOCBOOK_OUTPUT = docbook +# If the DOCBOOK_PROGRAMLISTING tag is set to YES, doxygen will include the +# program listings (including syntax highlighting and cross-referencing +# information) to the DOCBOOK output. Note that enabling this will significantly +# increase the size of the DOCBOOK output. +# The default value is: NO. +# This tag requires that the tag GENERATE_DOCBOOK is set to YES. + +DOCBOOK_PROGRAMLISTING = NO + #--------------------------------------------------------------------------- # Configuration options for the AutoGen Definitions output #--------------------------------------------------------------------------- -# If the GENERATE_AUTOGEN_DEF tag is set to YES doxygen will generate an AutoGen -# Definitions (see http://autogen.sf.net) file that captures the structure of -# the code including all documentation. Note that this feature is still -# experimental and incomplete at the moment. +# If the GENERATE_AUTOGEN_DEF tag is set to YES, doxygen will generate an +# AutoGen Definitions (see http://autogen.sourceforge.net/) file that captures +# the structure of the code including all documentation. Note that this feature +# is still experimental and incomplete at the moment. # The default value is: NO. GENERATE_AUTOGEN_DEF = NO @@ -1921,7 +2080,7 @@ GENERATE_AUTOGEN_DEF = NO # Configuration options related to the Perl module output #--------------------------------------------------------------------------- -# If the GENERATE_PERLMOD tag is set to YES doxygen will generate a Perl module +# If the GENERATE_PERLMOD tag is set to YES, doxygen will generate a Perl module # file that captures the structure of the code including all documentation. # # Note that this feature is still experimental and incomplete at the moment. @@ -1929,7 +2088,7 @@ GENERATE_AUTOGEN_DEF = NO GENERATE_PERLMOD = NO -# If the PERLMOD_LATEX tag is set to YES doxygen will generate the necessary +# If the PERLMOD_LATEX tag is set to YES, doxygen will generate the necessary # Makefile rules, Perl scripts and LaTeX code to be able to generate PDF and DVI # output from the Perl module output. # The default value is: NO. @@ -1937,9 +2096,9 @@ GENERATE_PERLMOD = NO PERLMOD_LATEX = NO -# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be nicely +# If the PERLMOD_PRETTY tag is set to YES, the Perl module output will be nicely # formatted so it can be parsed by a human reader. This is useful if you want to -# understand what is going on. On the other hand, if this tag is set to NO the +# understand what is going on. On the other hand, if this tag is set to NO, the # size of the Perl module output will be much smaller and Perl will parse it # just the same. # The default value is: YES. @@ -1953,20 +2112,20 @@ PERLMOD_PRETTY = YES # overwrite each other's variables. # This tag requires that the tag GENERATE_PERLMOD is set to YES. -PERLMOD_MAKEVAR_PREFIX = +PERLMOD_MAKEVAR_PREFIX = #--------------------------------------------------------------------------- # Configuration options related to the preprocessor #--------------------------------------------------------------------------- -# If the ENABLE_PREPROCESSING tag is set to YES doxygen will evaluate all +# If the ENABLE_PREPROCESSING tag is set to YES, doxygen will evaluate all # C-preprocessor directives found in the sources and include files. # The default value is: YES. ENABLE_PREPROCESSING = YES -# If the MACRO_EXPANSION tag is set to YES doxygen will expand all macro names -# in the source code. If set to NO only conditional compilation will be +# If the MACRO_EXPANSION tag is set to YES, doxygen will expand all macro names +# in the source code. If set to NO, only conditional compilation will be # performed. Macro expansion can be done in a controlled way by setting # EXPAND_ONLY_PREDEF to YES. # The default value is: NO. @@ -1982,7 +2141,7 @@ MACRO_EXPANSION = NO EXPAND_ONLY_PREDEF = NO -# If the SEARCH_INCLUDES tag is set to YES the includes files in the +# If the SEARCH_INCLUDES tag is set to YES, the include files in the # INCLUDE_PATH will be searched if a #include is found. # The default value is: YES. # This tag requires that the tag ENABLE_PREPROCESSING is set to YES. @@ -1994,7 +2153,7 @@ SEARCH_INCLUDES = YES # preprocessor. # This tag requires that the tag SEARCH_INCLUDES is set to YES. -INCLUDE_PATH = +INCLUDE_PATH = # You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard # patterns (like *.h and *.hpp) to filter out the header-files in the @@ -2002,7 +2161,7 @@ INCLUDE_PATH = # used. # This tag requires that the tag ENABLE_PREPROCESSING is set to YES. -INCLUDE_FILE_PATTERNS = +INCLUDE_FILE_PATTERNS = # The PREDEFINED tag can be used to specify one or more macro names that are # defined before the preprocessor is started (similar to the -D option of e.g. @@ -2021,7 +2180,7 @@ PREDEFINED = DOXYGEN_SHOULD_PARSE_THIS # definition found in the source code. # This tag requires that the tag ENABLE_PREPROCESSING is set to YES. -EXPAND_AS_DEFINED = +EXPAND_AS_DEFINED = # If the SKIP_FUNCTION_MACROS tag is set to YES then doxygen's preprocessor will # remove all references to function-like macros that are alone on a line, have @@ -2050,28 +2209,29 @@ SKIP_FUNCTION_MACROS = YES # the path). If a tag file is not located in the directory in which doxygen is # run, you must also specify the path to the tagfile here. -TAGFILES = +TAGFILES = # When a file name is specified after GENERATE_TAGFILE, doxygen will create a # 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 = -# 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. +# 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. # The default value is: NO. ALLEXTERNALS = NO -# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed in -# the modules index. If set to NO, only the current project's groups will be +# If the EXTERNAL_GROUPS tag is set to YES, all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will be # listed. # The default value is: YES. EXTERNAL_GROUPS = YES -# If the EXTERNAL_PAGES tag is set to YES all external pages will be listed in +# If the EXTERNAL_PAGES tag is set to YES, all external pages will be listed in # the related pages index. If set to NO, only the current project's pages will # be listed. # The default value is: YES. @@ -2088,7 +2248,7 @@ PERL_PATH = "${PERL_EXECUTABLE}" # Configuration options related to the dot tool #--------------------------------------------------------------------------- -# If the CLASS_DIAGRAMS tag is set to YES doxygen will generate a class diagram +# If the CLASS_DIAGRAMS tag is set to YES, doxygen will generate a class diagram # (in HTML and LaTeX) for classes with base or super classes. Setting the tag to # NO turns the diagrams off. Note that this option also works with HAVE_DOT # disabled, but it is recommended to install and use dot, since it yields more @@ -2104,16 +2264,16 @@ CLASS_DIAGRAMS = NO # the mscgen tool resides. If left empty the tool is assumed to be found in the # default search path. -MSCGEN_PATH = +MSCGEN_PATH = # You can include diagrams made with dia in doxygen documentation. Doxygen will # then run dia to produce the diagram and insert it in the documentation. The # DIA_PATH tag allows you to specify the directory where the dia binary resides. # If left empty dia is assumed to be found in the default search path. -DIA_PATH = +DIA_PATH = -# If set to YES, the inheritance and collaboration graphs will hide inheritance +# If set to YES the inheritance and collaboration graphs will hide inheritance # and usage relations if the target is undocumented or is not a class. # The default value is: YES. @@ -2138,7 +2298,7 @@ HAVE_DOT = ${DOXYGEN_DOT_FOUND} DOT_NUM_THREADS = 0 -# When you want a differently looking font n the dot files that doxygen +# When you want a differently looking font in the dot files that doxygen # generates you can specify the font name using DOT_FONTNAME. You need to make # sure dot is able to find the font, which can be done by putting it in a # standard location or by setting the DOTFONTPATH environment variable or by @@ -2160,7 +2320,7 @@ DOT_FONTSIZE = 10 # the path where dot can find it using this tag. # This tag requires that the tag HAVE_DOT is set to YES. -DOT_FONTPATH = +DOT_FONTPATH = # If the CLASS_GRAPH tag is set to YES then doxygen will generate a graph for # each documented class showing the direct and indirect inheritance relations. @@ -2186,7 +2346,7 @@ COLLABORATION_GRAPH = NO GROUP_GRAPHS = YES -# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# If the UML_LOOK tag is set to YES, doxygen will generate inheritance and # collaboration diagrams in a style similar to the OMG's Unified Modeling # Language. # The default value is: NO. @@ -2238,7 +2398,8 @@ INCLUDED_BY_GRAPH = YES # # Note that enabling this option will significantly increase the time of a run. # So in most cases it will be better to enable call graphs for selected -# functions only using the \callgraph command. +# functions only using the \callgraph command. Disabling a call graph can be +# accomplished by means of the command \hidecallgraph. # The default value is: NO. # This tag requires that the tag HAVE_DOT is set to YES. @@ -2249,7 +2410,8 @@ CALL_GRAPH = NO # # Note that enabling this option will significantly increase the time of a run. # So in most cases it will be better to enable caller graphs for selected -# functions only using the \callergraph command. +# functions only using the \callergraph command. Disabling a caller graph can be +# accomplished by means of the command \hidecallergraph. # The default value is: NO. # This tag requires that the tag HAVE_DOT is set to YES. @@ -2272,11 +2434,15 @@ GRAPHICAL_HIERARCHY = YES DIRECTORY_GRAPH = YES # The DOT_IMAGE_FORMAT tag can be used to set the image format of the images -# generated by dot. +# generated by dot. For an explanation of the image formats see the section +# output formats in the documentation of the dot tool (Graphviz (see: +# http://www.graphviz.org/)). # Note: If you choose svg you need to set HTML_FILE_EXTENSION to xhtml in order # to make the SVG files visible in IE 9+ (other browsers do not have this # requirement). -# Possible values are: png, jpg, gif and svg. +# Possible values are: png, jpg, gif, svg, png:gd, png:gd:gd, png:cairo, +# png:cairo:gd, png:cairo:cairo, png:cairo:gdiplus, png:gdiplus and +# png:gdiplus:gdiplus. # The default value is: png. # This tag requires that the tag HAVE_DOT is set to YES. @@ -2305,19 +2471,37 @@ DOT_PATH = "${DOXYGEN_DOT_PATH}" # command). # This tag requires that the tag HAVE_DOT is set to YES. -DOTFILE_DIRS = +DOTFILE_DIRS = # The MSCFILE_DIRS tag can be used to specify one or more directories that # contain msc files that are included in the documentation (see the \mscfile # command). -MSCFILE_DIRS = +MSCFILE_DIRS = # The DIAFILE_DIRS tag can be used to specify one or more directories that # contain dia files that are included in the documentation (see the \diafile # command). -DIAFILE_DIRS = +DIAFILE_DIRS = + +# When using plantuml, the PLANTUML_JAR_PATH tag should be used to specify the +# path where java can find the plantuml.jar file. If left blank, it is assumed +# PlantUML is not used or called during a preprocessing step. Doxygen will +# generate a warning when it encounters a \startuml command in this case and +# will not generate output for the diagram. + +PLANTUML_JAR_PATH = + +# When using plantuml, the PLANTUML_CFG_FILE tag can be used to specify a +# configuration file for plantuml. + +PLANTUML_CFG_FILE = + +# When using plantuml, the specified paths are searched for files specified by +# the !include statement in a plantuml block. + +PLANTUML_INCLUDE_PATH = # The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of nodes # that will be shown in the graph. If the number of nodes in a graph becomes @@ -2355,7 +2539,7 @@ MAX_DOT_GRAPH_DEPTH = 0 DOT_TRANSPARENT = NO -# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# Set the DOT_MULTI_TARGETS tag to YES to allow dot to generate multiple output # files in one run (i.e. multiple -o and -T options on the command line). This # makes dot run faster, but since only newer versions of dot (>1.8.10) support # this, this feature is disabled by default. @@ -2372,7 +2556,7 @@ DOT_MULTI_TARGETS = NO GENERATE_LEGEND = YES -# If the DOT_CLEANUP tag is set to YES doxygen will remove the intermediate dot +# If the DOT_CLEANUP tag is set to YES, doxygen will remove the intermediate dot # files that are used to generate the various graphs. # The default value is: YES. # This tag requires that the tag HAVE_DOT is set to YES. From 6fa59c9b9f3b57536980eeeb988857fc9edf5b6b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 7 Aug 2019 23:12:05 +0200 Subject: [PATCH 337/546] Expand EIGEN_MAKE_ALIGNED_OPERATOR_NEW in Doxygen configuration --- doc/Doxyfile.in | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/doc/Doxyfile.in b/doc/Doxyfile.in index baf80fbb..e1f80caa 100644 --- a/doc/Doxyfile.in +++ b/doc/Doxyfile.in @@ -2131,7 +2131,7 @@ ENABLE_PREPROCESSING = YES # The default value is: NO. # This tag requires that the tag ENABLE_PREPROCESSING is set to YES. -MACRO_EXPANSION = NO +MACRO_EXPANSION = YES # If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES then # the macro expansion is limited to the macros specified with the PREDEFINED and @@ -2139,7 +2139,7 @@ MACRO_EXPANSION = NO # The default value is: NO. # This tag requires that the tag ENABLE_PREPROCESSING is set to YES. -EXPAND_ONLY_PREDEF = NO +EXPAND_ONLY_PREDEF = YES # If the SEARCH_INCLUDES tag is set to YES, the include files in the # INCLUDE_PATH will be searched if a #include is found. @@ -2171,7 +2171,8 @@ INCLUDE_FILE_PATTERNS = # recursively expanded use the := operator instead of the = operator. # This tag requires that the tag ENABLE_PREPROCESSING is set to YES. -PREDEFINED = DOXYGEN_SHOULD_PARSE_THIS +PREDEFINED = DOXYGEN_SHOULD_PARSE_THIS \ + EIGEN_MAKE_ALIGNED_OPERATOR_NEW= # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then this # tag can be used to specify a list of macro names that should be expanded. The From a707097a1ad099c461b021f06c066b48abe6f9d8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 18 Sep 2019 17:36:03 +0200 Subject: [PATCH 338/546] Minor fix --- src/rl/mdl/Kinematic.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 9858a9d5..72080e94 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -112,7 +112,7 @@ namespace rl { if (inWorldFrame) { - rl::math::Matrix33 wR = this->getOperationalVelocity(j).angular().cross33() * this->getOperationalPosition(j).linear(); + ::rl::math::Matrix33 wR = this->getOperationalVelocity(j).angular().cross33() * this->getOperationalPosition(j).linear(); Jdqd.segment(j * 6, 3) = this->getOperationalPosition(j).linear() * this->getOperationalAcceleration(j).linear() + wR * this->getOperationalVelocity(j).linear(); Jdqd.segment(j * 6 + 3, 3) = this->getOperationalPosition(j).linear() * this->getOperationalAcceleration(j).angular() + wR * this->getOperationalVelocity(j).angular(); } From ebe6c1b4d5b781283521d2b10b3707c53d11ddc8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 5 Dec 2019 18:35:01 +0100 Subject: [PATCH 339/546] Update Eigen remote URLs --- 3rdparty/eigen/CMakeLists.txt | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/3rdparty/eigen/CMakeLists.txt b/3rdparty/eigen/CMakeLists.txt index b2ba5c77..52468250 100644 --- a/3rdparty/eigen/CMakeLists.txt +++ b/3rdparty/eigen/CMakeLists.txt @@ -6,11 +6,11 @@ include(ExternalProject) ExternalProject_Add( eigen - #HG_REPOSITORY https://bitbucket.org/eigen/eigen/ - #HG_TAG 3.3.7 - URL https://bitbucket.org/eigen/eigen/get/3.3.7.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/eigen-eigen-323c052e1731.tar.gz - URL_MD5 f2a417d083fe8ca4b8ed2bc613d20f07 + #GIT_REPOSITORY https://gitlab.com/libeigen/eigen.git + #GIT_TAG 3.3.7 + URL https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/eigen-3.3.7.tar.gz + URL_MD5 9e30f67e8531477de4117506fe44669b CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_TESTING=OFF -DEIGEN_TEST_NOQT=ON INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From e273b13cfaf1f9971b271ef3264af02dbb78280e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 18 May 2020 20:06:59 +0200 Subject: [PATCH 340/546] Upgrade Doxygen configuration --- doc/CMakeLists.txt | 1 - doc/Doxyfile.in | 95 +++++++++++++++++++++++++++------------------- 2 files changed, 55 insertions(+), 41 deletions(-) diff --git a/doc/CMakeLists.txt b/doc/CMakeLists.txt index d64bc4c5..5835a842 100644 --- a/doc/CMakeLists.txt +++ b/doc/CMakeLists.txt @@ -1,6 +1,5 @@ find_package(Doxygen) find_package(LATEX) -find_package(Perl) configure_file(Doxyfile.in Doxyfile) diff --git a/doc/Doxyfile.in b/doc/Doxyfile.in index e1f80caa..9a678d5b 100644 --- a/doc/Doxyfile.in +++ b/doc/Doxyfile.in @@ -1,4 +1,4 @@ -# Doxyfile 1.8.15 +# Doxyfile 1.8.17 # This file describes the settings to be used by the documentation system # doxygen (www.doxygen.org) for a project. @@ -197,6 +197,16 @@ SHORT_NAMES = NO JAVADOC_AUTOBRIEF = YES +# If the JAVADOC_BANNER tag is set to YES then doxygen will interpret a line +# such as +# /*************** +# as being the beginning of a Javadoc-style comment "banner". If set to NO, the +# Javadoc-style will behave just like regular comments and it will not be +# interpreted by doxygen. +# The default value is: NO. + +JAVADOC_BANNER = NO + # If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first # line (until the first dot) of a Qt-style comment as the brief description. If # set to NO, the Qt-style will behave just like regular Qt-style comments (thus @@ -299,7 +309,7 @@ OPTIMIZE_OUTPUT_SLICE = NO # parses. With this tag you can assign which parser to use for a given # extension. Doxygen has a built-in mapping, but you can override or extend it # using this tag. The format is ext=language, where ext is a file extension, and -# language is one of the parsers supported by doxygen: IDL, Java, Javascript, +# language is one of the parsers supported by doxygen: IDL, Java, JavaScript, # Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice, # Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: # FortranFree, unknown formatted Fortran: Fortran. In the later case the parser @@ -329,10 +339,10 @@ MARKDOWN_SUPPORT = YES # to that level are automatically included in the table of contents, even if # they do not have an id attribute. # Note: This feature currently applies only to Markdown headings. -# Minimum value: 0, maximum value: 99, default value: 0. +# Minimum value: 0, maximum value: 99, default value: 5. # This tag requires that the tag MARKDOWN_SUPPORT is set to YES. -TOC_INCLUDE_HEADINGS = 0 +TOC_INCLUDE_HEADINGS = 5 # When enabled doxygen tries to link words that correspond to documented # classes, or namespaces to their corresponding documentation. Such a link can @@ -465,6 +475,12 @@ EXTRACT_ALL = YES EXTRACT_PRIVATE = YES +# If the EXTRACT_PRIV_VIRTUAL tag is set to YES, documented private virtual +# methods of a class will be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIV_VIRTUAL = YES + # If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal # scope will be included in the documentation. # The default value is: NO. @@ -519,8 +535,8 @@ HIDE_UNDOC_MEMBERS = NO HIDE_UNDOC_CLASSES = NO # If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend -# (class|struct|union) declarations. If set to NO, these declarations will be -# included in the documentation. +# declarations. If set to NO, these declarations will be included in the +# documentation. # The default value is: NO. HIDE_FRIEND_COMPOUNDS = NO @@ -543,7 +559,7 @@ INTERNAL_DOCS = NO # names in lower-case letters. If set to YES, upper-case letters are also # allowed. This is useful if you have classes or files whose names only differ # in case and if your file system supports case sensitive file names. Windows -# and Mac users are advised to set this option to NO. +# (including Cygwin) ands Mac users are advised to set this option to NO. # The default value is: system dependent. CASE_SENSE_NAMES = NO @@ -835,8 +851,10 @@ INPUT_ENCODING = UTF-8 # If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, # *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, # *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, -# *.m, *.markdown, *.md, *.mm, *.dox, *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, -# *.f, *.for, *.tcl, *.vhd, *.vhdl, *.ucf, *.qsf and *.ice. +# *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C comment), +# *.doc (to be provided as doxygen C comment), *.txt (to be provided as doxygen +# C comment), *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f, *.for, *.tcl, *.vhd, +# *.vhdl, *.ucf, *.qsf and *.ice. FILE_PATTERNS = *.c \ *.cc \ @@ -869,8 +887,14 @@ FILE_PATTERNS = *.c \ *.md \ *.mm \ *.dox \ + *.doc \ + *.txt \ *.py \ + *.pyw \ *.f90 \ + *.f95 \ + *.f03 \ + *.f08 \ *.f \ *.for \ *.tcl \ @@ -878,8 +902,7 @@ FILE_PATTERNS = *.c \ *.vhdl \ *.ucf \ *.qsf \ - *.as \ - *.js + *.ice # The RECURSIVE tag can be used to specify whether or not subdirectories should # be searched for input files as well. @@ -1272,13 +1295,13 @@ HTML_COLORSTYLE_GAMMA = 80 # The default value is: NO. # This tag requires that the tag GENERATE_HTML is set to YES. -HTML_TIMESTAMP = YES +HTML_TIMESTAMP = NO # If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML # documentation will contain a main index with vertical navigation menus that -# are dynamically created via Javascript. If disabled, the navigation index will +# are dynamically created via JavaScript. If disabled, the navigation index will # consists of multiple levels of tabs that are statically embedded in every HTML -# page. Disable this option to support browsers that do not have Javascript, +# page. Disable this option to support browsers that do not have JavaScript, # like the Qt help browser. # The default value is: YES. # This tag requires that the tag GENERATE_HTML is set to YES. @@ -1429,7 +1452,7 @@ QCH_FILE = # The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help # Project output. For more information please see Qt Help Project / Namespace -# (see: http://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). +# (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). # The default value is: org.doxygen.Project. # This tag requires that the tag GENERATE_QHP is set to YES. @@ -1437,7 +1460,7 @@ QHP_NAMESPACE = org.doxygen.Project # The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt # Help Project output. For more information please see Qt Help Project / Virtual -# Folders (see: http://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual- +# Folders (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual- # folders). # The default value is: doc. # This tag requires that the tag GENERATE_QHP is set to YES. @@ -1446,7 +1469,7 @@ QHP_VIRTUAL_FOLDER = doc # If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom # filter to add. For more information please see Qt Help Project / Custom -# Filters (see: http://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- +# Filters (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- # filters). # This tag requires that the tag GENERATE_QHP is set to YES. @@ -1454,7 +1477,7 @@ QHP_CUST_FILTER_NAME = # The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the # custom filter to add. For more information please see Qt Help Project / Custom -# Filters (see: http://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- +# Filters (see: https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom- # filters). # This tag requires that the tag GENERATE_QHP is set to YES. @@ -1462,7 +1485,7 @@ QHP_CUST_FILTER_ATTRS = # The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this # project's filter section matches. Qt Help Project / Filter Attributes (see: -# http://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). # This tag requires that the tag GENERATE_QHP is set to YES. QHP_SECT_FILTER_ATTRS = @@ -1566,8 +1589,14 @@ FORMULA_FONTSIZE = 10 FORMULA_TRANSPARENT = YES +# The FORMULA_MACROFILE can contain LaTeX \newcommand and \renewcommand commands +# to create new LaTeX commands to be used in formulas as building blocks. See +# the section "Including formulas" for details. + +FORMULA_MACROFILE = + # Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see -# https://www.mathjax.org) which uses client side Javascript for the rendering +# https://www.mathjax.org) which uses client side JavaScript for the rendering # instead of using pre-rendered bitmaps. Use this if you do not have LaTeX # installed or if you want to formulas look prettier in the HTML output. When # enabled you may also need to install MathJax separately and configure the path @@ -1598,7 +1627,7 @@ MATHJAX_FORMAT = HTML-CSS # The default value is: https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/. # This tag requires that the tag USE_MATHJAX is set to YES. -MATHJAX_RELPATH = https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.2 +MATHJAX_RELPATH = https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/ # The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax # extension names that should be enabled during MathJax rendering. For example @@ -1637,7 +1666,7 @@ MATHJAX_CODEFILE = "${CMAKE_CURRENT_SOURCE_DIR}/extra.js" SEARCHENGINE = YES # When the SERVER_BASED_SEARCH tag is enabled the search engine will be -# implemented using a web server instead of a web client using Javascript. There +# implemented using a web server instead of a web client using JavaScript. There # are two flavors of web server based searching depending on the EXTERNAL_SEARCH # setting. When disabled, doxygen will generate a PHP script for searching and # an index file used by the script. When EXTERNAL_SEARCH is enabled the indexing @@ -1741,13 +1770,14 @@ LATEX_CMD_NAME = "${LATEX_COMPILER}" MAKEINDEX_CMD_NAME = "${MAKEINDEX_COMPILER}" # The LATEX_MAKEINDEX_CMD tag can be used to specify the command name to -# generate index for LaTeX. +# generate index for LaTeX. In case there is no backslash (\) as first character +# it will be automatically added in the LaTeX code. # Note: This tag is used in the generated output file (.tex). # See also: MAKEINDEX_CMD_NAME for the part in the Makefile / make.bat. -# The default value is: \makeindex. +# The default value is: makeindex. # This tag requires that the tag GENERATE_LATEX is set to YES. -LATEX_MAKEINDEX_CMD = \makeindex +LATEX_MAKEINDEX_CMD = makeindex # If the COMPACT_LATEX tag is set to YES, doxygen generates more compact LaTeX # documents. This may be useful for small projects and may help to save some @@ -2239,12 +2269,6 @@ EXTERNAL_GROUPS = YES EXTERNAL_PAGES = YES -# The PERL_PATH should be the absolute path and name of the perl script -# interpreter (i.e. the result of 'which perl'). -# The default file (with absolute path) is: /usr/bin/perl. - -PERL_PATH = "${PERL_EXECUTABLE}" - #--------------------------------------------------------------------------- # Configuration options related to the dot tool #--------------------------------------------------------------------------- @@ -2258,15 +2282,6 @@ PERL_PATH = "${PERL_EXECUTABLE}" CLASS_DIAGRAMS = NO -# You can define message sequence charts within doxygen comments using the \msc -# command. Doxygen will then run the mscgen tool (see: -# http://www.mcternan.me.uk/mscgen/)) to produce the chart and insert it in the -# documentation. The MSCGEN_PATH tag allows you to specify the directory where -# the mscgen tool resides. If left empty the tool is assumed to be found in the -# default search path. - -MSCGEN_PATH = - # You can include diagrams made with dia in doxygen documentation. Doxygen will # then run dia to produce the diagram and insert it in the documentation. The # DIA_PATH tag allows you to specify the directory where the dia binary resides. From a37243cf90566936e6dba8940e5af4594bcf5e6c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 19 May 2020 12:05:23 +0200 Subject: [PATCH 341/546] Remove unused variable --- demos/rlPlanDemo/Thread.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index a13261b1..8a2b4eb0 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -381,7 +381,6 @@ Thread::run() this->drawSweptVolume(path); } - rl::math::Vector diff(MainWindow::instance()->model->getDofPosition()); rl::math::Vector inter(MainWindow::instance()->model->getDofPosition()); while (this->animate) @@ -401,8 +400,6 @@ Thread::run() for (; i != path.end() && j != path.end(); ++i, ++j) { - diff = *j - *i; - rl::math::Real steps = std::ceil(MainWindow::instance()->model->distance(*i, *j) / delta); for (std::size_t k = 1; k < steps + 1; ++k) @@ -428,8 +425,6 @@ Thread::run() for (; ri != path.rend() && rj != path.rend(); ++ri, ++rj) { - diff = *rj - *ri; - rl::math::Real steps = std::ceil(MainWindow::instance()->model->distance(*ri, *rj) / delta); for (std::size_t k = 1; k < steps + 1; ++k) From 1b52f3b70dbd920bc7928d5729c4a28a2b1ef4a0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 20 May 2020 16:27:42 +0200 Subject: [PATCH 342/546] Fix whitespace --- src/rl/math/Polynomial.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index 7167bcc2..fb59bac9 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -666,7 +666,7 @@ namespace rl return scaled; } - + /** * Translates a polynomial along the x-axis by a given parameter translation. * @@ -684,7 +684,7 @@ namespace rl { translated.coefficient(n) = TypeTraits::Zero(TypeTraits::size(this->coefficient(n))); } - + for (::std::size_t n = 0; n < this->degree() + 1; ++n) { T c = this->coefficient(n); @@ -694,12 +694,12 @@ namespace rl { // b is the binomial coefficient n over k translated.coefficient(k) += b * ::std::pow(translation, static_cast(n - k)) * c; - + // compute next binomial coefficient, integer division is ok because b is divisible b = b * (n - k) / (k + 1); } } - + return translated; } From 54a3c0df2813f094f8324e633545ca0b764f0620 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 20 May 2020 17:15:09 +0200 Subject: [PATCH 343/546] Update test for translation of polynomials --- .../rlSplineTest/rlSplineTranslationTest.cpp | 94 ++++++++++--------- 1 file changed, 51 insertions(+), 43 deletions(-) diff --git a/tests/rlSplineTest/rlSplineTranslationTest.cpp b/tests/rlSplineTest/rlSplineTranslationTest.cpp index 1b0a2233..43ac230f 100644 --- a/tests/rlSplineTest/rlSplineTranslationTest.cpp +++ b/tests/rlSplineTest/rlSplineTranslationTest.cpp @@ -25,79 +25,87 @@ // #include -#include -#include +#include +#include -void printPoly(const rl::math::Polynomial& p) +std::ostream& operator<<(std::ostream& os, const rl::math::Polynomial& p) { + bool first = true; + for (int n = p.degree(); n >= 0; --n) { - if (p.coefficient(n).matrix().squaredNorm() > 0) + if (std::abs(p.coefficient(n)) > ::std::numeric_limits::epsilon()) { - std::cout << p.coefficient(n) << "*x^" << n << " "; + if (first) + { + os << p.coefficient(n); + } + else + { + os << (rl::math::sign(p.coefficient(n)) < 0 ? " - " : " + ") << std::abs(p.coefficient(n)); + } + + if (n > 0) + { + os << " x^" << n; + } + + first = false; } } - std::cout << std::endl; + return os; } -bool testPolynomialTranslation(const rl::math::Polynomial& p) +bool testPolynomialTranslation(const rl::math::Polynomial& p) { - rl::math::Real eps = 1e-6; - rl::math::Real translation = 0.2 + (p.degree() / 3); - rl::math::Polynomial q = p.translatedX(translation); - printPoly(p); - printPoly(q); - bool ok = true; + rl::math::Real translation = Eigen::internal::random(-10.0, 10.0); + rl::math::Polynomial q = p.translatedX(translation); + + std::cout << p.degree() << ": p(x) = " << p << std::endl; + std::cout << q.degree() << ": q(x) = " << q << std::endl; + std::cout << p.degree() << ": p(x) = q(x " << (rl::math::sign(translation) < 0 ? "-" : "+") << " " << std::abs(translation) << ")" << std::endl; for (rl::math::Real x = 0; x < 1; x += 0.1) { - if ((p(x) - q(x - translation)).matrix().squaredNorm() > eps) + rl::math::Real squaredNorm = std::pow(p(x) - q(x - translation), 2); + + if (squaredNorm > 1.0e-6) { - ok = false; + std::cerr << "testPolynomialTranslation: Error at degree " << p.degree() << std::endl; + std::cerr << "p(" << x << ") = " << p(x) << std::endl; + std::cerr << "q(" << x - translation << ") = " << q(x - translation) << std::endl; + std::cerr << "squaredNorm: " << squaredNorm << std::endl; + return false; } } - if (!ok) - { - std::cerr << "testPolynomialTranslation: at degree " << p.degree() << " a difference was detected." << std::endl; - } - - return ok; + return true; } int main(int argc, char** argv) { - bool ok = true; - - for (std::size_t degree = 5; degree < 15; ++degree) + for (std::size_t degree = 0; degree < 10; ++degree) { - rl::math::Polynomial p(degree); + if (degree > 0) + { + std::cout << std::endl; + } + + rl::math::Polynomial p(degree); p.upper() = 1; for (std::size_t n = 0; n < p.degree() + 1; ++n) { - p.coefficient(n) = rl::math::ArrayX::Zero(1); + p.coefficient(n) = Eigen::internal::random(-10.0, 10.0); } - p.coefficient(degree) = rl::math::ArrayX::Constant(1, 1.7); - p.coefficient(degree / 2) = rl::math::ArrayX::Constant(1, -2.5); - p.coefficient(degree / 3) = rl::math::ArrayX::Constant(1, 1.5); - ok &= testPolynomialTranslation(p); - - p.coefficient(degree - 1) = rl::math::ArrayX::Constant(1, -0.5); - ok &= testPolynomialTranslation(p); + if (!testPolynomialTranslation(p)) + { + return EXIT_FAILURE; + } } - if (ok) - { - std::cout << "rlSplineTranslationTest: Verify Polynomial::translatedX done." << std::endl; - return EXIT_SUCCESS; - } - else - { - std::cerr << "rlSplineTranslationTest: Polynomial::translatedX is wrong." << std::endl; - return EXIT_FAILURE; - } + return EXIT_SUCCESS; } From 2e8947f04a561780b1fe99765e23d18eb8314f12 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 20 May 2020 22:22:48 +0200 Subject: [PATCH 344/546] Fix namespaces --- src/rl/hal/Ati.h | 4 +-- src/rl/hal/Jr3.h | 4 +-- src/rl/hal/LeuzeRs4.cpp | 2 +- src/rl/hal/SickS300.cpp | 6 ++--- src/rl/hal/UniversalRobotsRtde.cpp | 32 ++++++++++++------------ src/rl/math/Spline.h | 18 ++++++------- src/rl/mdl/Model.cpp | 4 +-- src/rl/plan/WorkspaceSphereExplorer.cpp | 4 +-- src/rl/sg/solid/Scene.cpp | 8 +++--- src/rl/util/rtai/chrono.h | 2 +- src/rl/util/xenomai/chrono.h | 2 +- src/rl/util/xenomai/condition_variable.h | 2 +- src/rl/xml/Document.h | 2 +- 13 files changed, 45 insertions(+), 45 deletions(-) diff --git a/src/rl/hal/Ati.h b/src/rl/hal/Ati.h index e1316572..6f6424c1 100644 --- a/src/rl/hal/Ati.h +++ b/src/rl/hal/Ati.h @@ -101,9 +101,9 @@ namespace rl /** The number of the calibration within the file (usually 1). */ unsigned short int index; - std::array values; + ::std::array values; - std::array voltages; + ::std::array voltages; }; } } diff --git a/src/rl/hal/Jr3.h b/src/rl/hal/Jr3.h index 6b6b7326..871a2ca0 100644 --- a/src/rl/hal/Jr3.h +++ b/src/rl/hal/Jr3.h @@ -85,9 +85,9 @@ namespace rl private: Comedi comedi; - std::array values; + ::std::array values; - std::array zeroes; + ::std::array zeroes; }; } } diff --git a/src/rl/hal/LeuzeRs4.cpp b/src/rl/hal/LeuzeRs4.cpp index 23b7fd4f..65317b38 100644 --- a/src/rl/hal/LeuzeRs4.cpp +++ b/src/rl/hal/LeuzeRs4.cpp @@ -511,7 +511,7 @@ namespace rl { if (i > 0) { - ::std::this_thread::sleep_for(std::chrono::milliseconds(40)); + ::std::this_thread::sleep_for(::std::chrono::milliseconds(40)); } do diff --git a/src/rl/hal/SickS300.cpp b/src/rl/hal/SickS300.cpp index 900ca267..d8614291 100644 --- a/src/rl/hal/SickS300.cpp +++ b/src/rl/hal/SickS300.cpp @@ -324,7 +324,7 @@ ::std::cout << "buf[" << i + 4 << "] " << hex(buf[i + 4]) << ::std::endl; } ::std::uint16_t length = Endian::hostWord(buf[6], buf[7]); -std::cout << "length " << length << std::endl; +::std::cout << "length " << length << ::std::endl; if (length != 552) { @@ -355,10 +355,10 @@ ::std::cout << "version " << hex(buf[11]) << hex(buf[10]) << ::std::endl; Endian::hostWord(buf[17], buf[16]), Endian::hostWord(buf[15], buf[14]) ); -::std::cout << "scanNumber " << scanNumber << std::endl; +::std::cout << "scanNumber " << scanNumber << ::std::endl; ::std::uint16_t telegramNumber = Endian::hostWord(buf[19], buf[18]); -::std::cout << "telegramNumber " << telegramNumber << std::endl; +::std::cout << "telegramNumber " << telegramNumber << ::std::endl; for (::std::size_t i = 0; i < 2; ++i) { diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 98badc93..a2632133 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -644,7 +644,7 @@ namespace rl #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) this->socket4.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); #endif // __APPLE__ || __QNX__ || WIN32 -// std::cout << "size: " << size << std::endl; +// ::std::cout << "size: " << size << ::std::endl; ::std::uint8_t* ptr = buffer.data(); @@ -652,18 +652,18 @@ namespace rl { ::std::uint16_t packageSize; this->unserialize(ptr, packageSize); -// std::cout << "packageSize: " << packageSize << std::endl; +// ::std::cout << "packageSize: " << packageSize << ::std::endl; ::std::uint8_t packageType; this->unserialize(ptr, packageType); -// std::cout << "packageType: " << packageType << std::endl; +// ::std::cout << "packageType: " << packageType << ::std::endl; switch (packageType) { case COMMAND_CONTROL_PACKAGE_PAUSE: ::std::uint8_t pauseAccepted; this->unserialize(ptr, pauseAccepted); -// std::cout << "accepted: " << static_cast(pauseAccepted & 0x01) << std::endl; +// ::std::cout << "accepted: " << static_cast(pauseAccepted & 0x01) << ::std::endl; if (!pauseAccepted) { @@ -675,7 +675,7 @@ namespace rl { ::std::uint8_t recipeId; this->unserialize(ptr, recipeId); -// std::cout << "recipeId: " << static_cast(recipeId) << std::endl; +// ::std::cout << "recipeId: " << static_cast(recipeId) << ::std::endl; if (0 == recipeId) { @@ -683,17 +683,17 @@ namespace rl } ::std::string variableTypes(reinterpret_cast(ptr), packageSize - 4); -// std::cout << "variableTypes: " << variableTypes << std::endl; +// ::std::cout << "variableTypes: " << variableTypes << ::std::endl; ptr += packageSize - 4; } break; case COMMAND_CONTROL_PACKAGE_SETUP_OUTPUTS: { ::std::string variableTypes(reinterpret_cast(ptr), packageSize - 3); -// std::cout << "variableTypes: " << variableTypes << std::endl; +// ::std::cout << "variableTypes: " << variableTypes << ::std::endl; ptr += packageSize - 3; - if (std::string::npos != variableTypes.find("NOT_FOUND")) + if (::std::string::npos != variableTypes.find("NOT_FOUND")) { throw DeviceException("Output recipe invalid"); } @@ -702,7 +702,7 @@ namespace rl case COMMAND_CONTROL_PACKAGE_START: ::std::uint8_t startAccepted; this->unserialize(ptr, startAccepted); -// std::cout << "accepted: " << static_cast(startAccepted & 0x01) << std::endl; +// ::std::cout << "accepted: " << static_cast(startAccepted & 0x01) << ::std::endl; if (!startAccepted) { @@ -746,18 +746,18 @@ namespace rl break; case COMMAND_GET_URCONTROL_VERSION: this->unserialize(ptr, this->version.major); -// std::cout << "major: " << this->version.major << std::endl; +// ::std::cout << "major: " << this->version.major << ::std::endl; this->unserialize(ptr, this->version.minor); -// std::cout << "minor: " << this->version.minor << std::endl; +// ::std::cout << "minor: " << this->version.minor << ::std::endl; this->unserialize(ptr, this->version.bugfix); -// std::cout << "bugfix: " << this->version.bugfix << std::endl; +// ::std::cout << "bugfix: " << this->version.bugfix << ::std::endl; this->unserialize(ptr, this->version.build); -// std::cout << "build: " << this->version.build << std::endl; +// ::std::cout << "build: " << this->version.build << ::std::endl; break; case COMMAND_REQUEST_PROTOCOL_VERSION: ::std::uint8_t protocolAccepted; this->unserialize(ptr, protocolAccepted); -// std::cout << "accepted: " << static_cast(protocolAccepted & 0x01) << std::endl; +// ::std::cout << "accepted: " << static_cast(protocolAccepted & 0x01) << ::std::endl; if (!protocolAccepted) { @@ -769,10 +769,10 @@ namespace rl { ::std::uint8_t level; this->unserialize(ptr, level); -// std::cout << "level: " << static_cast(level) << std::endl; +// ::std::cout << "level: " << static_cast(level) << ::std::endl; ::std::string message(reinterpret_cast(ptr), packageSize - 4); -// std::cout << "message: " << message << std::endl; +// ::std::cout << "message: " << message << ::std::endl; ptr += packageSize - 4; if (level < 2) diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 444e786b..6b15f603 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -351,8 +351,8 @@ namespace rl Real parabolicIntervalPrev = (x[i] - x[i - 1]) * parabolicPercent; Real parabolicIntervalNext = (x[i + 1] - x[i]) * parabolicPercent; Real parabolicIntervalNextNext = (x[i + 2] - x[i + 1]) * parabolicPercent; - parabolicIntervalPrev = std::min(parabolicIntervalPrev, parabolicIntervalNext); - parabolicIntervalNext = std::min(parabolicIntervalNext, parabolicIntervalNextNext); + parabolicIntervalPrev = ::std::min(parabolicIntervalPrev, parabolicIntervalNext); + parabolicIntervalNext = ::std::min(parabolicIntervalNext, parabolicIntervalNextNext); Real deltaXPrev = x[i] - x[i - 1]; Real deltaXNext = x[i + 1] - x[i]; Real deltaXNextNext = x[i + 2] - x[i + 1]; @@ -375,7 +375,7 @@ namespace rl { Real parabolicIntervalPrev = (x[n - 2] - x[n - 3]) * parabolicPercent; Real parabolicIntervalNext = (x[n - 1] - x[n - 2]) * parabolicPercent; - parabolicIntervalPrev = std::min(parabolicIntervalPrev, parabolicIntervalNext); + parabolicIntervalPrev = ::std::min(parabolicIntervalPrev, parabolicIntervalNext); Real deltaXPrev = x[n - 2] - x[n - 3]; Real deltaXNext = x[n - 1] - x[n - 2]; Real linearInterval = deltaXNext - (parabolicIntervalPrev/2) - (parabolicIntervalNext/2); @@ -498,8 +498,8 @@ namespace rl Real quarticIntervalPrev = (x[i] - x[i - 1]) * quarticPercent; Real quarticIntervalNext = (x[i + 1] - x[i]) * quarticPercent; Real quarticIntervalNextNext = (x[i + 2] - x[i + 1]) * quarticPercent; - quarticIntervalPrev = std::min(quarticIntervalPrev, quarticIntervalNext); - quarticIntervalNext = std::min(quarticIntervalNext, quarticIntervalNextNext); + quarticIntervalPrev = ::std::min(quarticIntervalPrev, quarticIntervalNext); + quarticIntervalNext = ::std::min(quarticIntervalNext, quarticIntervalNextNext); Real deltaXPrev = x[i] - x[i - 1]; Real deltaXNext = x[i + 1] - x[i]; Real deltaXNextNext = x[i + 2] - x[i + 1]; @@ -522,7 +522,7 @@ namespace rl { Real quarticIntervalPrev = (x[n - 2] - x[n - 3]) * quarticPercent; Real quarticIntervalNext = (x[n - 1] - x[n - 2]) * quarticPercent; - quarticIntervalPrev = std::min(quarticIntervalPrev, quarticIntervalNext); + quarticIntervalPrev = ::std::min(quarticIntervalPrev, quarticIntervalNext); Real deltaXPrev = x[n - 2] - x[n - 3]; Real deltaXNext = x[n - 1] - x[n - 2]; Real linearInterval = deltaXNext - (quarticIntervalPrev/2) - (quarticIntervalNext/2); @@ -645,8 +645,8 @@ namespace rl Real sexticIntervalPrev = (x[i] - x[i - 1]) * sexticPercent; Real sexticIntervalNext = (x[i + 1] - x[i]) * sexticPercent; Real sexticIntervalNextNext = (x[i + 2] - x[i + 1]) * sexticPercent; - sexticIntervalPrev = std::min(sexticIntervalPrev, sexticIntervalNext); - sexticIntervalNext = std::min(sexticIntervalNext, sexticIntervalNextNext); + sexticIntervalPrev = ::std::min(sexticIntervalPrev, sexticIntervalNext); + sexticIntervalNext = ::std::min(sexticIntervalNext, sexticIntervalNextNext); Real deltaXPrev = x[i] - x[i - 1]; Real deltaXNext = x[i + 1] - x[i]; Real deltaXNextNext = x[i + 2] - x[i + 1]; @@ -669,7 +669,7 @@ namespace rl { Real sexticIntervalPrev = (x[n - 2] - x[n - 3]) * sexticPercent; Real sexticIntervalNext = (x[n - 1] - x[n - 2]) * sexticPercent; - sexticIntervalPrev = std::min(sexticIntervalPrev, sexticIntervalNext); + sexticIntervalPrev = ::std::min(sexticIntervalPrev, sexticIntervalNext); Real deltaXPrev = x[n - 2] - x[n - 3]; Real deltaXNext = x[n - 1] - x[n - 2]; Real linearInterval = deltaXNext - (sexticIntervalPrev/2) - (sexticIntervalNext/2); diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 77e45194..cd7d53b5 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -630,7 +630,7 @@ namespace rl for (::std::ptrdiff_t i = 0; i < svd.singularValues().size(); ++i) { - singularValues[i] = svd.singularValues()[i] > std::numeric_limits< ::rl::math::Real>::epsilon() ? 1 / svd.singularValues()[i] : 0; + singularValues[i] = svd.singularValues()[i] > ::std::numeric_limits< ::rl::math::Real>::epsilon() ? 1 / svd.singularValues()[i] : 0; } this->invGammaPosition = svd.matrixV() * singularValues.asDiagonal() * svd.matrixU().transpose(); @@ -645,7 +645,7 @@ namespace rl for (::std::ptrdiff_t i = 0; i < svd.singularValues().size(); ++i) { - singularValues[i] = svd.singularValues()[i] > std::numeric_limits< ::rl::math::Real>::epsilon() ? 1 / svd.singularValues()[i] : 0; + singularValues[i] = svd.singularValues()[i] > ::std::numeric_limits< ::rl::math::Real>::epsilon() ? 1 / svd.singularValues()[i] : 0; } this->invGammaVelocity = svd.matrixV() * singularValues.asDiagonal() * svd.matrixU().transpose(); diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index d86df324..e24149d3 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -38,8 +38,8 @@ namespace rl { WorkspaceSphereExplorer::WorkspaceSphereExplorer() : boundingBox( - ::rl::math::Vector3::Constant(-std::numeric_limits< ::rl::math::Real>::max()), - ::rl::math::Vector3::Constant(std::numeric_limits< ::rl::math::Real>::max()) + ::rl::math::Vector3::Constant(-::std::numeric_limits< ::rl::math::Real>::max()), + ::rl::math::Vector3::Constant(::std::numeric_limits< ::rl::math::Real>::max()) ), goal(), greedy(GREEDY_SPACE), diff --git a/src/rl/sg/solid/Scene.cpp b/src/rl/sg/solid/Scene.cpp index c1f0c84f..728331a9 100644 --- a/src/rl/sg/solid/Scene.cpp +++ b/src/rl/sg/solid/Scene.cpp @@ -225,7 +225,7 @@ namespace rl nullptr, vector1, vector2, - std::numeric_limits::max(), + ::std::numeric_limits::max(), ¶m, normal ); @@ -235,7 +235,7 @@ namespace rl hit[1] = vector1[1] + (vector2[1] - vector1[1]) * param; hit[2] = vector1[2] + (vector2[2] - vector1[2]) * param; - distance = std::sqrt(std::pow(hit[0] - source[0], 2) + std::pow(hit[1] - source[1], 2) + std::pow(hit[2] - source[2], 2));; + distance = ::std::sqrt(::std::pow(hit[0] - source[0], 2) + ::std::pow(hit[1] - source[1], 2) + ::std::pow(hit[2] - source[2], 2));; return static_cast< ::rl::sg::Shape*>(object); } @@ -260,7 +260,7 @@ namespace rl static_cast(shape)->object, vector1, vector2, - std::numeric_limits::max(), + ::std::numeric_limits::max(), ¶m, normal ); @@ -270,7 +270,7 @@ namespace rl hit[1] = vector1[1] + (vector2[1] - vector1[1]) * param; hit[2] = vector1[2] + (vector2[2] - vector1[2]) * param; - distance = std::sqrt(std::pow(hit[0] - source[0], 2) + std::pow(hit[1] - source[1], 2) + std::pow(hit[2] - source[2], 2));; + distance = ::std::sqrt(::std::pow(hit[0] - source[0], 2) + ::std::pow(hit[1] - source[1], 2) + ::std::pow(hit[2] - source[2], 2));; return (DT_TRUE == object) ? true : false; } diff --git a/src/rl/util/rtai/chrono.h b/src/rl/util/rtai/chrono.h index 5cb2ce47..e245e9cc 100644 --- a/src/rl/util/rtai/chrono.h +++ b/src/rl/util/rtai/chrono.h @@ -86,7 +86,7 @@ namespace rl ); } - static time_point from_time_t(std::time_t t) + static time_point from_time_t(::std::time_t t) { return ::std::chrono::time_point_cast( ::std::chrono::time_point( diff --git a/src/rl/util/xenomai/chrono.h b/src/rl/util/xenomai/chrono.h index 460d88d1..b9252963 100644 --- a/src/rl/util/xenomai/chrono.h +++ b/src/rl/util/xenomai/chrono.h @@ -86,7 +86,7 @@ namespace rl ); } - static time_point from_time_t(std::time_t t) + static time_point from_time_t(::std::time_t t) { return ::std::chrono::time_point_cast( ::std::chrono::time_point( diff --git a/src/rl/util/xenomai/condition_variable.h b/src/rl/util/xenomai/condition_variable.h index af7b7601..6e425113 100644 --- a/src/rl/util/xenomai/condition_variable.h +++ b/src/rl/util/xenomai/condition_variable.h @@ -182,7 +182,7 @@ namespace rl condition_variable_any() : M_cond(), - M_mutex(std::make_shared()) + M_mutex(::std::make_shared()) { } diff --git a/src/rl/xml/Document.h b/src/rl/xml/Document.h index f84192c8..1e7df011 100644 --- a/src/rl/xml/Document.h +++ b/src/rl/xml/Document.h @@ -129,7 +129,7 @@ namespace rl Document& operator=(Document&& other) { - this->doc = std::move(other.doc); + this->doc = ::std::move(other.doc); return *this; } From 0aaead906f699338ca5f890f0af0e23cdf42a06f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 20 May 2020 23:59:09 +0200 Subject: [PATCH 345/546] Remove workarounds for compilers not fully compatible with C++11 --- CMakeLists.txt | 7 -- demos/rlGripperDemo/CMakeLists.txt | 21 ----- demos/rlInversePositionDemo/CMakeLists.txt | 11 --- demos/rlSimulator/CMakeLists.txt | 15 ---- .../CMakeLists.txt | 19 ----- demos/rlThreadsDemo/CMakeLists.txt | 21 ----- demos/rlTimerDemo/CMakeLists.txt | 19 ----- rl-config.cmake.in | 2 - src/CMakeLists.txt | 3 + src/rl/hal/CMakeLists.txt | 21 +---- src/rl/kin/CMakeLists.txt | 1 + src/rl/kin/Kinematics.cpp | 4 +- src/rl/math/CMakeLists.txt | 6 ++ src/rl/math/GnatNearestNeighbors.h | 16 ---- .../math/KdtreeBoundingBoxNearestNeighbors.h | 24 ++---- src/rl/math/KdtreeNearestNeighbors.h | 28 ++----- src/rl/math/LinearNearestNeighbors.h | 4 - src/rl/math/Spline.h | 12 --- src/rl/math/TypeTraits.h | 5 +- src/rl/math/algorithm.h | 17 ----- src/rl/mdl/CMakeLists.txt | 12 +-- src/rl/mdl/Joint.cpp | 4 +- src/rl/mdl/SixDof.cpp | 8 +- src/rl/plan/CMakeLists.txt | 11 --- src/rl/plan/RecursiveVerifier.cpp | 12 --- src/rl/sg/CMakeLists.txt | 1 + src/rl/std/CMakeLists.txt | 55 ++++++++++---- src/rl/std/{chrono => algorithm.h} | 45 ++++++----- src/rl/std/condition_variable | 50 ------------ src/rl/std/dummy.cpp | 0 src/rl/std/future | 62 --------------- src/rl/std/iterator | 68 ----------------- src/rl/std/{cmath => iterator.h} | 37 +++++---- src/rl/std/{random => memory.h} | 53 +++++++------ src/rl/std/mutex | 76 ------------------- src/rl/std/regex | 73 ------------------ src/rl/std/string | 69 ----------------- src/rl/std/thread | 52 ------------- tests/rlNearestNeighborsTest/CMakeLists.txt | 11 --- .../rlQuarticLinearQuarticTest.cpp | 4 +- .../rlSplineTest/rlSexticLinearSexticTest.cpp | 2 - 41 files changed, 157 insertions(+), 804 deletions(-) rename src/rl/std/{chrono => algorithm.h} (69%) delete mode 100644 src/rl/std/condition_variable create mode 100644 src/rl/std/dummy.cpp delete mode 100644 src/rl/std/future delete mode 100644 src/rl/std/iterator rename src/rl/std/{cmath => iterator.h} (76%) rename src/rl/std/{random => memory.h} (61%) delete mode 100644 src/rl/std/mutex delete mode 100644 src/rl/std/regex delete mode 100644 src/rl/std/string delete mode 100644 src/rl/std/thread diff --git a/CMakeLists.txt b/CMakeLists.txt index 98a335c5..759b3980 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -76,11 +76,8 @@ cmake_dependent_option(RL_BUILD_SG "Build scene graph abstraction component" ON cmake_dependent_option(RL_BUILD_PLAN "Build path planning component" ON "RL_BUILD_KIN;RL_BUILD_MATH;RL_BUILD_MDL;RL_BUILD_SG;RL_BUILD_UTIL;RL_BUILD_XML" OFF) -include_directories(BEFORE src/rl/std) - configure_file(robotics-library.rc.in robotics-library.rc) -add_subdirectory(src/rl/std) add_subdirectory(src) add_subdirectory(examples) @@ -99,8 +96,6 @@ foreach(TARGET ${TARGETS}) list(APPEND RL_LIBRARIES "rl::${TARGET}") endforeach(TARGET) -set(RL_INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/src/rl/std) - configure_package_config_file( rl-config.cmake.in rl-config.cmake INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${VERSION} @@ -112,8 +107,6 @@ export( FILE ${CMAKE_CURRENT_BINARY_DIR}/rl-export.cmake ) -set(RL_INCLUDE_DIRS \${PACKAGE_PREFIX_DIR}/include/rl-${VERSION}/rl/std) - configure_package_config_file( rl-config.cmake.in rl-config-install.cmake INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${VERSION} diff --git a/demos/rlGripperDemo/CMakeLists.txt b/demos/rlGripperDemo/CMakeLists.txt index ebfe3d56..c775d131 100644 --- a/demos/rlGripperDemo/CMakeLists.txt +++ b/demos/rlGripperDemo/CMakeLists.txt @@ -1,36 +1,15 @@ -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - find_package(Boost REQUIRED COMPONENTS thread) -endif() - add_executable( rlGripperDemo rlGripperDemo.cpp ${rl_BINARY_DIR}/robotics-library.rc ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - rlGripperDemo - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) - - target_include_directories(rlGripperDemo PUBLIC ${Boost_INCLUDE_DIR}) -endif() - target_link_libraries( rlGripperDemo hal util ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_link_libraries(rlGripperDemo ${Boost_LIBRARIES}) -endif() - add_executable( rlRobotiqModelCDemo rlRobotiqModelCDemo.cpp diff --git a/demos/rlInversePositionDemo/CMakeLists.txt b/demos/rlInversePositionDemo/CMakeLists.txt index f343534e..29f6b1b5 100644 --- a/demos/rlInversePositionDemo/CMakeLists.txt +++ b/demos/rlInversePositionDemo/CMakeLists.txt @@ -6,17 +6,6 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - rlInversePositionDemo - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) -endif() - target_include_directories( rlInversePositionDemo PUBLIC diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index a90e50db..f3d6cf2f 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -1,7 +1,3 @@ -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - find_package(Boost REQUIRED) -endif() - find_package(OpenGL REQUIRED) find_package(SoQt) @@ -62,17 +58,6 @@ if(QT_FOUND AND SoQt_FOUND) ${SoQt_DEFINITIONS} ) - if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - rlSimulator - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) - endif() - target_include_directories( rlSimulator PUBLIC diff --git a/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt b/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt index be9be4ac..ba9ffe38 100644 --- a/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt +++ b/demos/rlSixAxisForceTorqueSensorDemo/CMakeLists.txt @@ -1,30 +1,11 @@ -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - find_package(Boost REQUIRED COMPONENTS thread) -endif() - add_executable( rlSixAxisForceTorqueSensorDemo rlSixAxisForceTorqueSensorDemo.cpp ${rl_BINARY_DIR}/robotics-library.rc ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - rlSixAxisForceTorqueSensorDemo - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) -endif() - target_link_libraries( rlSixAxisForceTorqueSensorDemo hal util ) - -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_link_libraries(rlSixAxisForceTorqueSensorDemo ${Boost_LIBRARIES}) -endif() diff --git a/demos/rlThreadsDemo/CMakeLists.txt b/demos/rlThreadsDemo/CMakeLists.txt index 68e87db0..b4ee3206 100644 --- a/demos/rlThreadsDemo/CMakeLists.txt +++ b/demos/rlThreadsDemo/CMakeLists.txt @@ -1,31 +1,10 @@ -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - find_package(Boost REQUIRED COMPONENTS thread) -endif() - add_executable( rlThreadsDemo rlThreadsDemo.cpp ${rl_BINARY_DIR}/robotics-library.rc ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - rlThreadsDemo - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) - - target_include_directories(rlThreadsDemo PUBLIC ${Boost_INCLUDE_DIR}) -endif() - target_link_libraries( rlThreadsDemo util ) - -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_link_libraries(rlThreadsDemo ${Boost_LIBRARIES}) -endif() diff --git a/demos/rlTimerDemo/CMakeLists.txt b/demos/rlTimerDemo/CMakeLists.txt index d59bbe0f..cd61dde4 100644 --- a/demos/rlTimerDemo/CMakeLists.txt +++ b/demos/rlTimerDemo/CMakeLists.txt @@ -1,26 +1,7 @@ project(rlTimerDemo) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - find_package(Boost REQUIRED COMPONENTS thread) -endif() - add_executable( rlTimerDemo rlTimerDemo.cpp ${rl_BINARY_DIR}/robotics-library.rc ) - -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - rlTimerDemo - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) - - target_include_directories(rlTimerDemo PUBLIC ${Boost_INCLUDE_DIR}) - - target_link_libraries(rlTimerDemo ${Boost_LIBRARIES}) -endif() diff --git a/rl-config.cmake.in b/rl-config.cmake.in index 75f5b297..bbbd6096 100644 --- a/rl-config.cmake.in +++ b/rl-config.cmake.in @@ -21,6 +21,4 @@ set(RL_INCLUDE_DIRS "@RL_INCLUDE_DIRS@") set(RL_LIBRARY_DIRS "@RL_LIBRARY_DIRS@") set(RL_LIBRARIES "@RL_LIBRARIES@") -include_directories(BEFORE ${RL_INCLUDE_DIRS}) - check_required_components(RL) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index aadfd290..e7d58e75 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -1,3 +1,6 @@ +add_subdirectory(rl/std) +list(APPEND TARGETS std) + if(RL_BUILD_MATH) add_subdirectory(rl/math) list(APPEND TARGETS math) diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 81d6476a..33ddb842 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -1,8 +1,4 @@ -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - find_package(Boost REQUIRED COMPONENTS thread) -else() - find_package(Boost REQUIRED) -endif() +find_package(Boost REQUIRED) find_package(ATIDAQ) find_package(cifX) @@ -179,17 +175,6 @@ target_compile_definitions( BOOST_ALL_NO_LIB ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - hal - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) -endif() - if(BIG_ENDIAN) target_compile_definitions(hal PRIVATE HAVE_BIG_ENDIAN) else() @@ -206,10 +191,6 @@ target_link_libraries( util ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_link_libraries(hal ${Boost_LIBRARIES}) -endif() - target_include_directories( hal PUBLIC diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index fb8336d8..b015cb70 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -53,6 +53,7 @@ target_include_directories( target_link_libraries( kin math + std xml ) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 60cbd632..36d94940 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -25,9 +25,9 @@ // #include -#include #include #include +#include #include #include #include @@ -112,7 +112,7 @@ namespace rl } else { - q(i) = ::rl::math::clamp(q(i), this->joints[i]->min, this->joints[i]->max); + q(i) = ::rl::std17::clamp(q(i), this->joints[i]->min, this->joints[i]->max); } } } diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index 14c01952..0e32f026 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -84,6 +84,12 @@ target_include_directories( ${EIGEN3_INCLUDE_DIRS} ) +target_link_libraries( + math + INTERFACE + std +) + if(CMAKE_VERSION VERSION_LESS 3.0) set_target_properties( math diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index 672750bf..8dbf614c 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -515,11 +515,7 @@ namespace rl neighbors.pop_back(); } -#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) - neighbors.push_back(::std::make_pair(distance, node.data[i])); -#else neighbors.emplace_back(::std::piecewise_construct, ::std::forward_as_tuple(distance), ::std::forward_as_tuple(node.data[i])); -#endif ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } } @@ -553,11 +549,7 @@ namespace rl neighbors.pop_back(); } -#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) - neighbors.push_back(::std::make_pair(distances[i], node.children[i].pivot)); -#else neighbors.emplace_back(::std::piecewise_construct, ::std::forward_as_tuple(distances[i]), ::std::forward_as_tuple(node.children[i].pivot)); -#endif ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } } @@ -596,11 +588,7 @@ namespace rl if (distances[i] - distance <= node.children[i].max[i] && distances[i] + distance >= node.children[i].min[i]) { -#if defined(_MSC_VER) && _MSC_VER < 1800 - branches.push_back(::std::make_pair(distances[i], &node.children[i])); -#else branches.emplace_back(distances[i], &node.children[i]); -#endif ::std::push_heap(branches.begin(), branches.end(), BranchCompare()); } } @@ -617,11 +605,7 @@ namespace rl for (::std::size_t i = 0; i < centers.size(); ++i) { -#if defined(_MSC_VER) && _MSC_VER < 1800 - node.children.push_back(Node(i, node.degree - 1, this->nodeDegree, this->nodeDataMax)); -#else node.children.emplace_back(i, node.degree - 1, this->nodeDegree, this->nodeDataMax); -#endif node.children[i].pivot = ::std::move(node.data[centers[i]]); } diff --git a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h index e0caa081..3c3366bb 100644 --- a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h @@ -38,6 +38,8 @@ #include #include #include +#include +#include namespace rl { @@ -162,7 +164,7 @@ namespace rl template void insert(InputIterator first, InputIterator last) { - using ::std::size; + using ::rl::std17::size; if (this->empty()) { @@ -198,7 +200,7 @@ namespace rl void push(const Value& value) { using ::std::begin; - using ::std::size; + using ::rl::std17::size; if (this->boundingBox.empty()) { @@ -442,11 +444,7 @@ namespace rl break; } -#if __cplusplus > 201103L || _MSC_VER >= 1800 - node.children[i] = ::std::make_unique(); -#else - node.children[i].reset(new Node()); -#endif + node.children[i] = ::rl::std14::make_unique(); if (::std::distance(begin, end) > this->nodeDataMax) { @@ -472,7 +470,7 @@ namespace rl void push(Node& node, const Value& value) { using ::std::begin; - using ::std::size; + using ::rl::std17::size; if (nullptr == node.children[0] && nullptr == node.children[1]) { @@ -510,7 +508,7 @@ namespace rl ::std::vector search(const Value& query, const ::std::size_t* k, const Distance* radius, const bool& sorted) const { using ::std::begin; - using ::std::size; + using ::rl::std17::size; ::std::vector neighbors; @@ -586,11 +584,7 @@ namespace rl neighbors.pop_back(); } -#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) - neighbors.push_back(::std::make_pair(distance, node.data[i])); -#else neighbors.emplace_back(::std::piecewise_construct, ::std::forward_as_tuple(distance), ::std::forward_as_tuple(node.data[i])); -#endif ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } } @@ -629,11 +623,7 @@ namespace rl { ::std::vector newsidedist(sidedist); newsidedist[node.index] = cutdist; -#if defined(_MSC_VER) && _MSC_VER < 1800 - branches.push_back(Branch(newdist, ::std::move(newsidedist), node.children[worst].get())); -#else branches.emplace_back(newdist, ::std::move(newsidedist), node.children[worst].get()); -#endif ::std::push_heap(branches.begin(), branches.end(), BranchCompare()); } } diff --git a/src/rl/math/KdtreeNearestNeighbors.h b/src/rl/math/KdtreeNearestNeighbors.h index c865bdc5..3fbdf06f 100644 --- a/src/rl/math/KdtreeNearestNeighbors.h +++ b/src/rl/math/KdtreeNearestNeighbors.h @@ -37,6 +37,8 @@ #include #include #include +#include +#include namespace rl { @@ -341,11 +343,7 @@ namespace rl for (::std::size_t i = 0; i < 2; ++i) { -#if __cplusplus > 201103L || _MSC_VER >= 1800 - node.children[i] = ::std::make_unique(); -#else - node.children[i].reset(new Node()); -#endif + node.children[i] = ::rl::std14::make_unique(); InputIterator begin = 0 == i ? first : split; InputIterator end = 0 == i ? split : last; @@ -364,7 +362,7 @@ namespace rl void push(Node& node, const Value& value) { using ::std::begin; - using ::std::size; + using ::rl::std17::size; if (nullptr == node.children[0] && nullptr == node.children[1] && !node.data) { @@ -388,11 +386,7 @@ namespace rl for (::std::size_t i = 0; i < 2; ++i) { -#if __cplusplus > 201103L || _MSC_VER >= 1800 - node.children[i] = ::std::make_unique(); -#else - node.children[i].reset(new Node()); -#endif + node.children[i] = ::rl::std14::make_unique(); } bool less = *(begin(value) + node.cut.index) < *(begin(*node.data) + node.cut.index); @@ -420,7 +414,7 @@ namespace rl ::std::vector search(const Value& query, const ::std::size_t* k, const Distance* radius, const bool& sorted) const { - using ::std::size; + using ::rl::std17::size; ::std::vector neighbors; @@ -476,11 +470,7 @@ namespace rl neighbors.pop_back(); } -#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) - neighbors.push_back(::std::make_pair(distance, *node.data)); -#else neighbors.emplace_back(::std::piecewise_construct, ::std::forward_as_tuple(distance), ::std::forward_as_tuple(*node.data)); -#endif ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } } @@ -514,11 +504,7 @@ namespace rl { ::std::vector newsidedist(sidedist); newsidedist[node.cut.index] = cutdist; -#if defined(_MSC_VER) && _MSC_VER < 1800 - branches.push_back(Branch(newdist, ::std::move(newsidedist), node.children[worst].get())); -#else branches.emplace_back(newdist, ::std::move(newsidedist), node.children[worst].get()); -#endif ::std::push_heap(branches.begin(), branches.end(), BranchCompare()); } } @@ -529,7 +515,7 @@ namespace rl Cut select(InputIterator first, InputIterator last) { using ::std::begin; - using ::std::size; + using ::rl::std17::size; ::std::size_t distance = ::std::distance(first, last); assert(distance > 0 || "mean expects at least one element"); diff --git a/src/rl/math/LinearNearestNeighbors.h b/src/rl/math/LinearNearestNeighbors.h index 5211591a..3574dc3b 100644 --- a/src/rl/math/LinearNearestNeighbors.h +++ b/src/rl/math/LinearNearestNeighbors.h @@ -297,11 +297,7 @@ namespace rl neighbors3.pop_back(); } -#if defined(_MSC_VER) && _MSC_VER < 1800 - neighbors3.push_back(::std::make_pair(distance, this->container[i])); -#else neighbors3.emplace_back(distance, this->container[i]); -#endif ::std::push_heap(neighbors3.begin(), neighbors3.end(), NeighborCompare()); } } diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 6b15f603..aaf62211 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -697,7 +697,6 @@ namespace rl return f; } -#if !(defined(_MSC_VER) && _MSC_VER < 1800) /** * Generates a spline of polynomials of degrees 4-1-4 from rest to rest * for one dimension. @@ -748,7 +747,6 @@ namespace rl return f; } -#endif /** * Generates a spline of polynomials of degrees 4-1-4 from rest to rest @@ -760,7 +758,6 @@ namespace rl * is omitted. * The result is the shortest synchronized 4-1-4 spline with continuous acceleration. */ -#if !(defined(_MSC_VER) && _MSC_VER < 1800) template static Spline QuarticLinearQuarticAtRest( const typename ::std::enable_if< ::std::is_class::value, U>::type& q0, @@ -768,9 +765,6 @@ namespace rl const typename ::std::enable_if< ::std::is_class::value, U>::type& vmax, const typename ::std::enable_if< ::std::is_class::value, U>::type& amax ) -#else - static Spline QuarticLinearQuarticAtRest(const T& q0, const T& q1, const T& vmax, const T& amax) -#endif { assert(q0.size() >= 1 && q0.size() == q1.size() && q0.size() == vmax.size() && q0.size() == amax.size() && "QuarticLinearQuarticAtRest: parameters must have same dimension."); @@ -834,7 +828,6 @@ namespace rl return f; } -#if !(defined(_MSC_VER) && _MSC_VER < 1800) /** * Generates a spline of polynomials of degrees 6-1-6 from rest to rest * for one dimension. @@ -888,7 +881,6 @@ namespace rl return f; } -#endif /** * Generates a spline of polynomials of degrees 6-1-6 from rest to rest @@ -900,7 +892,6 @@ namespace rl * is omitted. * The result is the shortest synchronized 6-1-6 spline with continuous jerk. */ -#if !(defined(_MSC_VER) && _MSC_VER < 1800) template static Spline SexticLinearSexticAtRest( const typename ::std::enable_if< ::std::is_class::value, U>::type& q0, @@ -908,9 +899,6 @@ namespace rl const typename ::std::enable_if< ::std::is_class::value, U>::type& vmax, const typename ::std::enable_if< ::std::is_class::value, U>::type& amax ) -#else - static Spline SexticLinearSexticAtRest(const T& q0, const T& q1, const T& vmax, const T& amax) -#endif { assert(q0.size() >= 1 && q0.size() == q1.size() && q0.size() == vmax.size() && q0.size() == amax.size() && "SexticLinearSexticAtRest: parameters must have same dimension."); diff --git a/src/rl/math/TypeTraits.h b/src/rl/math/TypeTraits.h index 7114545c..02091868 100644 --- a/src/rl/math/TypeTraits.h +++ b/src/rl/math/TypeTraits.h @@ -35,6 +35,7 @@ #include #include #include +#include namespace rl { @@ -59,7 +60,7 @@ namespace rl static T abs(const T& t) { using ::std::abs; - using ::std::size; + using ::rl::std17::size; using ::std::transform; T res(size(t)); transform(t.begin(), t.end(), res.begin(), static_cast(&abs)); @@ -110,7 +111,7 @@ namespace rl static ::std::size_t size(const T& t) { - using ::std::size; + using ::rl::std17::size; return size(t); } diff --git a/src/rl/math/algorithm.h b/src/rl/math/algorithm.h index e856cf11..fcf06506 100644 --- a/src/rl/math/algorithm.h +++ b/src/rl/math/algorithm.h @@ -27,27 +27,10 @@ #ifndef RL_MATH_ALGORITHM_H #define RL_MATH_ALGORITHM_H -#include -#include -#include - namespace rl { namespace math { - template - inline const T& clamp(const T& v, const T& lo, const T& hi, Compare comp) - { - assert(!comp(hi, lo)); - return comp(v, lo) ? lo : comp(hi, v) ? hi : v; - } - - template - inline const T& clamp(const T& v, const T& lo, const T& hi) - { - return clamp(v, lo, hi, ::std::less()); - } - template inline T sign(const T& arg) { diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index fc2af39b..b13dbb73 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -81,17 +81,6 @@ add_library( ${rl_BINARY_DIR}/robotics-library.rc ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - mdl - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) -endif() - if(NOT CMAKE_VERSION VERSION_LESS 3.8) target_compile_features(mdl PUBLIC cxx_std_11) endif() @@ -108,6 +97,7 @@ target_include_directories( target_link_libraries( mdl math + std xml ) diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index 1f49d4ec..64bf3648 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -24,7 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include +#include #include "Frame.h" #include "Joint.h" @@ -83,7 +83,7 @@ namespace rl } else { - q(i) = ::rl::math::clamp(q(i), this->min(i), this->max(i)); + q(i) = ::rl::std17::clamp(q(i), this->min(i), this->max(i)); } } } diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index d9d60b48..253171ec 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -24,8 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include #include +#include #include "SixDof.h" @@ -84,7 +84,7 @@ namespace rl { for (::std::size_t i = 0; i < 3; ++i) { - q(i) = ::rl::math::clamp(q(i), this->min(i), this->max(i)); + q(i) = ::rl::std17::clamp(q(i), this->min(i), this->max(i)); } ::Eigen::Map< ::rl::math::Quaternion>(q.tail<4>().data()).normalize(); @@ -101,7 +101,7 @@ namespace rl { for (::std::size_t i = 0; i < 3; ++i) { - q(i) = ::rl::math::clamp(mean(i) + rand(i) * sigma(i), this->min(i), this->max(i)); + q(i) = ::rl::std17::clamp(mean(i) + rand(i) * sigma(i), this->min(i), this->max(i)); } q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>(), ::Eigen::Map< const ::rl::math::Quaternion>(mean.tail<4>().data()), sigma.tail<3>()).coeffs(); @@ -184,7 +184,7 @@ namespace rl for (::std::size_t i = 0; i < 3; ++i) { - q2(i) = ::rl::math::clamp(q2(i), this->min(i), this->max(i)); + q2(i) = ::rl::std17::clamp(q2(i), this->min(i), this->max(i)); } } diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index 88930be4..60ae3908 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -95,17 +95,6 @@ add_library( ${rl_BINARY_DIR}/robotics-library.rc ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - plan - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) -endif() - if(NOT CMAKE_VERSION VERSION_LESS 3.8) target_compile_features(plan PUBLIC cxx_std_11) endif() diff --git a/src/rl/plan/RecursiveVerifier.cpp b/src/rl/plan/RecursiveVerifier.cpp index eea06eec..36265cbd 100644 --- a/src/rl/plan/RecursiveVerifier.cpp +++ b/src/rl/plan/RecursiveVerifier.cpp @@ -54,11 +54,7 @@ namespace rl { ::std::queue< ::std::pair< ::std::size_t, ::std::size_t>> queue; -#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) - queue.push(::std::make_pair(1, steps - 1)); -#else queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(1), ::std::forward_as_tuple(steps - 1)); -#endif ::rl::math::Vector inter(u.size()); @@ -75,20 +71,12 @@ namespace rl if (queue.front().first < midpoint) { -#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) - queue.push(::std::make_pair(queue.front().first, midpoint - 1)); -#else queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(queue.front().first), ::std::forward_as_tuple(midpoint - 1)); -#endif } if (queue.front().second > midpoint) { -#if (defined(_MSC_VER) && _MSC_VER < 1800) || (defined(__GNUC__) && __GNUC__ == 4 && __GNUC_MINOR__ < 8) - queue.push(::std::make_pair(midpoint + 1, queue.front().second)); -#else queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(midpoint + 1), ::std::forward_as_tuple(queue.front().second)); -#endif } queue.pop(); diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index d20a368f..035a3d9b 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -179,6 +179,7 @@ endif() target_link_libraries( sg math + std util xml ) diff --git a/src/rl/std/CMakeLists.txt b/src/rl/std/CMakeLists.txt index 6fb9f1db..41f44eff 100644 --- a/src/rl/std/CMakeLists.txt +++ b/src/rl/std/CMakeLists.txt @@ -1,18 +1,45 @@ set( - BASE_HDRS - chrono - cmath - condition_variable - future - iterator - mutex - random - regex - string - thread + HDRS + algorithm.h + iterator.h + memory.h ) -list(APPEND HDRS ${BASE_HDRS}) -add_custom_target(std_sources SOURCES ${HDRS}) +if(NOT CMAKE_VERSION VERSION_LESS 3.0) + add_library(std INTERFACE) + add_custom_target(std_sources SOURCES ${HDRS}) +else() + add_library(std STATIC ${HDRS} dummy.cpp) +endif() -install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/std COMPONENT development) +if(NOT CMAKE_VERSION VERSION_LESS 3.8) + target_compile_features(std INTERFACE cxx_std_11) +endif() + +install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/std COMPONENT development) + +if(CMAKE_VERSION VERSION_LESS 3.0) + set_target_properties( + std + PROPERTIES + OUTPUT_NAME rlstd + POSITION_INDEPENDENT_CODE ON + VERSION ${VERSION} + ) + + if(WIN32) + set_target_properties( + std + PROPERTIES + DEBUG_POSTFIX d + ) + endif() +endif() + +install( + TARGETS std + EXPORT rl + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime +) diff --git a/src/rl/std/chrono b/src/rl/std/algorithm.h similarity index 69% rename from src/rl/std/chrono rename to src/rl/std/algorithm.h index 1e5e5cc3..dd20c71e 100644 --- a/src/rl/std/chrono +++ b/src/rl/std/algorithm.h @@ -24,30 +24,37 @@ // POSSIBILITY OF SUCH DAMAGE. // -#ifndef RL_STD_CHRONO -#define RL_STD_CHRONO +#ifndef RL_STD_ALGORITHM_H +#define RL_STD_ALGORITHM_H -#if defined(_MSC_FULL_VER) && _MSC_FULL_VER >= 190023918 -#include <../include/chrono> -#elif defined(_MSC_VER) -#include +#include -namespace std -{ - namespace chrono = ::boost::chrono; -} -#else // _MSC_VER -#include_next +#ifndef __cpp_lib_clamp +#include +#include +#endif -#if __GNUC__ == 4 && __GNUC_MINOR__ < 7 && !__clang__ -namespace std +namespace rl { - namespace chrono + namespace std17 { - typedef monotonic_clock steady_clock; +#ifdef __cpp_lib_clamp + using ::std::clamp; +#else + template + inline const T& clamp(const T& v, const T& lo, const T& hi, Compare comp) + { + assert(!comp(hi, lo)); + return comp(v, lo) ? lo : comp(hi, v) ? hi : v; + } + + template + inline const T& clamp(const T& v, const T& lo, const T& hi) + { + return clamp(v, lo, hi, ::std::less()); + } +#endif } } -#endif // __GNUC__ -#endif // _MSC_VER -#endif // RL_STD_CHRONO +#endif // RL_MATH_ALGORITHM_H diff --git a/src/rl/std/condition_variable b/src/rl/std/condition_variable deleted file mode 100644 index 68cbe8aa..00000000 --- a/src/rl/std/condition_variable +++ /dev/null @@ -1,50 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 RL_STD_CONDITION_VARIABLE -#define RL_STD_CONDITION_VARIABLE - -#if defined(_MSC_FULL_VER) && _MSC_FULL_VER >= 190023918 -#include <../include/condition_variable> -#elif defined(_MSC_VER) -#define BOOST_THREAD_PROVIDES_FUTURE -#include - -namespace std -{ - using ::boost::condition_variable; - - using ::boost::condition_variable_any; - - using ::boost::cv_status; - - using ::boost::notify_all_at_thread_exit; -} -#else // _MSC_VER -#include_next -#endif // _MSC_VER - -#endif // RL_STD_CONDITION_VARIABLE diff --git a/src/rl/std/dummy.cpp b/src/rl/std/dummy.cpp new file mode 100644 index 00000000..e69de29b diff --git a/src/rl/std/future b/src/rl/std/future deleted file mode 100644 index 1918a7e1..00000000 --- a/src/rl/std/future +++ /dev/null @@ -1,62 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 RL_STD_FUTURE -#define RL_STD_FUTURE - -#if defined(_MSC_FULL_VER) && _MSC_FULL_VER >= 190023918 -#include <../include/future> -#elif defined(_MSC_VER) -#define BOOST_THREAD_PROVIDES_FUTURE -#include - -namespace std -{ - using ::boost::async; - - using ::boost::BOOST_THREAD_FUTURE; - - using ::boost::future_category; - - using ::boost::future_errc; - - using ::boost::future_error; - - using ::boost::future_status; - - using ::boost::launch; - - using ::boost::packaged_task; - - using ::boost::promise; - - using ::boost::shared_future; -} -#else // _MSC_VER -#include_next -#endif // _MSC_VER - -#endif // RL_STD_FUTURE diff --git a/src/rl/std/iterator b/src/rl/std/iterator deleted file mode 100644 index 5fe3e32a..00000000 --- a/src/rl/std/iterator +++ /dev/null @@ -1,68 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 RL_STD_ITERATOR -#define RL_STD_ITERATOR - -#ifdef _MSC_VER -#include <../include/iterator> -#else // _MSC_VER -#include_next -#endif // _MSC_VER - -#if defined(_MSC_VER) && _MSC_VER < 1900 -namespace std -{ - template - auto size(const T& t) -> decltype(t.size()) - { - return t.size(); - } - - template - size_t size(const T (&t)[N]) - { - return N; - } -} -#elif !defined(_MSC_VER) && !defined(__cpp_lib_nonmember_container_access) -namespace std -{ - template - constexpr auto size(const T& t) -> decltype(t.size()) - { - return t.size(); - } - - template - constexpr size_t size(const T (&t)[N]) - { - return N; - } -} -#endif - -#endif // RL_STD_ITERATOR diff --git a/src/rl/std/cmath b/src/rl/std/iterator.h similarity index 76% rename from src/rl/std/cmath rename to src/rl/std/iterator.h index 31408ee2..3434e260 100644 --- a/src/rl/std/cmath +++ b/src/rl/std/iterator.h @@ -24,22 +24,31 @@ // POSSIBILITY OF SUCH DAMAGE. // -#ifndef RL_STD_CMATH -#define RL_STD_CMATH +#ifndef RL_STD_ITERATOR_H +#define RL_STD_ITERATOR_H -#ifdef _MSC_VER -#include <../include/cmath> +#include -#if _MSC_VER < 1800 -#include - -namespace std +namespace rl { - using ::boost::math::cbrt; + namespace std17 + { +#ifdef __cpp_lib_nonmember_container_access + using ::std::size; +#else + template + constexpr auto size(const T& t) -> decltype(t.size()) + { + return t.size(); + } + + template + constexpr ::std::size_t size(const T (&t)[N]) + { + return N; + } +#endif + } } -#endif // _MSC_VER < 1800 -#else // _MSC_VER -#include_next -#endif // _MSC_VER -#endif // RL_STD_CMATH +#endif // RL_STD_ITERATOR_H diff --git a/src/rl/std/random b/src/rl/std/memory.h similarity index 61% rename from src/rl/std/random rename to src/rl/std/memory.h index e8809b51..593c4f41 100644 --- a/src/rl/std/random +++ b/src/rl/std/memory.h @@ -24,38 +24,41 @@ // POSSIBILITY OF SUCH DAMAGE. // -#ifndef RL_STD_RANDOM -#define RL_STD_RANDOM +#ifndef RL_STD_MEMORY_H +#define RL_STD_MEMORY_H -#if defined(_MSC_VER) && _MSC_VER >= 1600 -#include <../include/random> -#else // _MSC_VER -#include_next +#include -#if __GNUC__ == 4 && __GNUC_MINOR__ < 5 && !__clang__ -namespace std +#ifndef __cpp_lib_make_unique +#include +#endif + +namespace rl { - template - class uniform_int_distribution : public uniform_int< IntType > + namespace std14 { - public: - explicit uniform_int_distribution(IntType min = 0, IntType max = 9) : - uniform_int(min, max) +#ifdef __cpp_lib_make_unique + using ::std::make_unique; +#else + template + typename ::std::enable_if< ::std::is_array::value, ::std::unique_ptr>::type + make_unique(::std::size_t n) { + return ::std::unique_ptr(new typename ::std::remove_extent::type[n]()); } - }; - - template - class uniform_real_distribution : public uniform_real< RealType > - { - public: - explicit uniform_real_distribution(RealType min = RealType(0), RealType max = RealType(1)) : - uniform_real(min, max) + + template + typename ::std::enable_if::value, ::std::unique_ptr>::type + make_unique(Args&&... args) { + return ::std::unique_ptr(new T(::std::forward(args)...)); } - }; + + template + typename ::std::enable_if< ::std::extent::value != 0, ::std::unique_ptr>::type + make_unique(Args&&...) = delete; +#endif + } } -#endif // __GNUC__ -#endif // _MSC_VER -#endif // RL_STD_RANDOM +#endif // RL_STD_MEMORY_H diff --git a/src/rl/std/mutex b/src/rl/std/mutex deleted file mode 100644 index afa43c24..00000000 --- a/src/rl/std/mutex +++ /dev/null @@ -1,76 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 RL_STD_MUTEX -#define RL_STD_MUTEX - -#if defined(_MSC_FULL_VER) && _MSC_FULL_VER >= 190023918 -#include <../include/mutex> -#elif defined(_MSC_VER) -#include -#include -#include -#include - -namespace std -{ - using ::boost::adopt_lock; - - using ::boost::adopt_lock_t; - - using ::boost::call_once; - - using ::boost::defer_lock; - - using ::boost::defer_lock_t; - - using ::boost::lock; - - using ::boost::lock_guard; - - using ::boost::mutex; - - using ::boost::once_flag; - - using ::boost::recursive_mutex; - - using ::boost::recursive_timed_mutex; - - using ::boost::timed_mutex; - - using ::boost::try_lock; - - using ::boost::try_to_lock; - - using ::boost::try_to_lock_t; - - using ::boost::unique_lock; -} -#else // _MSC_VER -#include_next -#endif // _MSC_VER - -#endif // RL_STD_MUTEX diff --git a/src/rl/std/regex b/src/rl/std/regex deleted file mode 100644 index c7b11993..00000000 --- a/src/rl/std/regex +++ /dev/null @@ -1,73 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 RL_STD_REGEX -#define RL_STD_REGEX - -#if (defined(_MSC_VER) && _MSC_VER < 1600) || (__GNUC__ == 4 && __GNUC_MINOR__ < 9) -#include_next - -namespace std -{ - using ::boost::basic_regex; - - using ::boost::cmatch; - - using ::boost::csub_match; - - using ::boost::match_results; - - using ::boost::regex; - - using ::boost::regex_match; - - using ::boost::regex_search; - - using ::boost::regex_replace; - - using ::boost::smatch; - - using ::boost::sub_match; - - using ::boost::ssub_match; - - using ::boost::wcmatch; - - using ::boost::wcsub_match; - - using ::boost::wregex; - - using ::boost::wsmatch; - - using ::boost::wssub_match; -} -#elif defined(_MSC_VER) && _MSC_VER >= 1600 -#include <../include/regex> -#else // _MSC_VER || __GNUC__ -#include_next -#endif // _MSC_VER || __GNUC__ - -#endif // RL_STD_CHRONO diff --git a/src/rl/std/string b/src/rl/std/string deleted file mode 100644 index e8d748a4..00000000 --- a/src/rl/std/string +++ /dev/null @@ -1,69 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 RL_STD_STRING -#define RL_STD_STRING - -#ifdef _MSC_VER -#include <../include/string> - -#if _MSC_VER < 1800 -namespace std -{ - inline string to_string(int _Val) - { - char _Buf[2 * _MAX_INT_DIG]; - _CSTD sprintf_s(_Buf, sizeof(_Buf), "%d", _Val); - return (string(_Buf)); - } - - inline string to_string(unsigned int _Val) - { - char _Buf[2 * _MAX_INT_DIG]; - _CSTD sprintf_s(_Buf, sizeof(_Buf), "%u", _Val); - return (string(_Buf)); - } - - inline string to_string(long _Val) - { - char _Buf[2 * _MAX_INT_DIG]; - _CSTD sprintf_s(_Buf, sizeof(_Buf), "%ld", _Val); - return (string(_Buf)); - } - - inline string to_string(unsigned long _Val) - { - char _Buf[2 * _MAX_INT_DIG]; - _CSTD sprintf_s(_Buf, sizeof(_Buf), "%lu", _Val); - return (string(_Buf)); - } -} -#endif // _MSC_VER < 1800 -#else // _MSC_VER -#include_next -#endif // _MSC_VER - -#endif // RL_STD_STRING diff --git a/src/rl/std/thread b/src/rl/std/thread deleted file mode 100644 index ab7671db..00000000 --- a/src/rl/std/thread +++ /dev/null @@ -1,52 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 RL_STD_THREAD -#define RL_STD_THREAD - -#if defined(_MSC_FULL_VER) && _MSC_FULL_VER >= 190023918 -#include <../include/thread> -#elif defined(_MSC_VER) -#define BOOST_THREAD_PROVIDES_FUTURE -#include - -namespace std -{ - namespace this_thread = ::boost::this_thread; - - using ::boost::thread; -} -#else // _MSC_VER -#ifndef _GLIBCXX_USE_NANOSLEEP -#define _GLIBCXX_USE_NANOSLEEP -#include_next -#undef _GLIBCXX_USE_NANOSLEEP -#else // _GLIBCXX_USE_NANOSLEEP -#include_next -#endif // _GLIBCXX_USE_NANOSLEEP -#endif // _MSC_VER - -#endif // RL_STD_THREAD diff --git a/tests/rlNearestNeighborsTest/CMakeLists.txt b/tests/rlNearestNeighborsTest/CMakeLists.txt index d8393acd..582e5c6d 100644 --- a/tests/rlNearestNeighborsTest/CMakeLists.txt +++ b/tests/rlNearestNeighborsTest/CMakeLists.txt @@ -7,17 +7,6 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -if(MSVC AND CMAKE_CXX_COMPILER_VERSION VERSION_LESS 19.00.23918) - target_compile_definitions( - rlNearestNeighborsTest - PUBLIC - BOOST_ALL_NO_LIB - BOOST_CHRONO_HEADER_ONLY - BOOST_ERROR_CODE_HEADER_ONLY - BOOST_SYSTEM_NO_DEPRECATED - ) -endif() - target_include_directories( rlNearestNeighborsTest PUBLIC diff --git a/tests/rlSplineTest/rlQuarticLinearQuarticTest.cpp b/tests/rlSplineTest/rlQuarticLinearQuarticTest.cpp index f912eda8..ef8280f9 100644 --- a/tests/rlSplineTest/rlQuarticLinearQuarticTest.cpp +++ b/tests/rlSplineTest/rlQuarticLinearQuarticTest.cpp @@ -32,7 +32,6 @@ int main(int argc, char** argv) { -#if !(defined(_MSC_VER) && _MSC_VER < 1800) { for (std::size_t i = 0; i < 8; ++i) { @@ -78,7 +77,6 @@ main(int argc, char** argv) std::cout << "rlQuarticLinearQuarticTest(Real): Ok, done." << std::endl; } -#endif { for (std::size_t i = 0; i < 4; ++i) @@ -111,7 +109,7 @@ main(int argc, char** argv) rl::math::Spline f = rl::math::Spline::QuarticLinearQuarticAtRest(q0, q1, vmax, amax); -#if 1 +#if 0 // plot for [i=2:5] "interpolation.dat" using 1:i with lines std::ofstream stream; stream.open("interpolation.dat", std::fstream::trunc); diff --git a/tests/rlSplineTest/rlSexticLinearSexticTest.cpp b/tests/rlSplineTest/rlSexticLinearSexticTest.cpp index b4839c36..edb7fe24 100644 --- a/tests/rlSplineTest/rlSexticLinearSexticTest.cpp +++ b/tests/rlSplineTest/rlSexticLinearSexticTest.cpp @@ -32,7 +32,6 @@ int main(int argc, char** argv) { -#if !(defined(_MSC_VER) && _MSC_VER < 1800) { for (std::size_t i = 0; i < 8; ++i) { @@ -80,7 +79,6 @@ main(int argc, char** argv) std::cout << "rlSexticLinearSexticTest(Real): Ok, done." << std::endl; } -#endif { for (std::size_t i = 0; i < 4; ++i) From a81b4538a506452c63ad186ac1dc3703be3f72c3 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 21 May 2020 00:41:17 +0200 Subject: [PATCH 346/546] Remove extra whitespace required by older compilers --- demos/rlLoadXmlDemo/rlLoadXmlDemo.cpp | 2 +- .../rlSixAxisForceTorqueSensorDemo.cpp | 2 +- src/rl/hal/AnalogInputReader.cpp | 4 +- src/rl/hal/AnalogInputReader.h | 2 +- src/rl/hal/AnalogInputWriter.cpp | 2 +- src/rl/hal/AnalogInputWriter.h | 2 +- src/rl/hal/AnalogOutputReader.cpp | 4 +- src/rl/hal/AnalogOutputReader.h | 2 +- src/rl/hal/AnalogOutputWriter.cpp | 2 +- src/rl/hal/AnalogOutputWriter.h | 2 +- src/rl/hal/Coach.cpp | 2 +- src/rl/hal/Endian.cpp | 4 +- src/rl/hal/Endian.h | 6 +- src/rl/hal/Exception.cpp | 2 +- src/rl/hal/Gnuplot.cpp | 2 +- src/rl/hal/Gnuplot.h | 2 +- src/rl/hal/LeuzeRs4.cpp | 16 +- src/rl/hal/LeuzeRs4.h | 2 +- src/rl/hal/MitsubishiH7.cpp | 10 +- src/rl/hal/MitsubishiH7.h | 6 +- src/rl/hal/MitsubishiR3.cpp | 6 +- src/rl/hal/RobotiqModelC.cpp | 10 +- src/rl/hal/RobotiqModelC.h | 4 +- src/rl/hal/SchmersalLss300.cpp | 18 +- src/rl/hal/SchmersalLss300.h | 2 +- src/rl/hal/SchunkFpsF5.cpp | 26 +-- src/rl/hal/SchunkFpsF5.h | 2 +- src/rl/hal/Serial.cpp | 4 +- src/rl/hal/SickLms200.cpp | 40 ++-- src/rl/hal/SickLms200.h | 2 +- src/rl/hal/SickS300.cpp | 4 +- src/rl/hal/SickS300.h | 2 +- src/rl/hal/Socket.cpp | 16 +- src/rl/hal/UniversalRobotsDashboard.cpp | 46 ++-- src/rl/hal/UniversalRobotsRealtime.cpp | 4 +- src/rl/hal/UniversalRobotsRtde.cpp | 62 +++--- src/rl/hal/UniversalRobotsRtde.h | 24 +- src/rl/hal/WeissKms40.cpp | 12 +- src/rl/hal/WeissKms40.h | 4 +- src/rl/hal/WeissWsg50.cpp | 54 ++--- src/rl/kin/Joint.h | 2 +- src/rl/kin/Kinematics.cpp | 112 +++++----- src/rl/kin/Kinematics.h | 12 +- src/rl/kin/Puma.cpp | 30 +-- src/rl/kin/Puma.h | 6 +- src/rl/kin/Revolute.cpp | 6 +- src/rl/kin/Rhino.cpp | 8 +- src/rl/kin/Rhino.h | 6 +- src/rl/math/GnatNearestNeighbors.h | 14 +- .../math/KdtreeBoundingBoxNearestNeighbors.h | 8 +- src/rl/math/KdtreeNearestNeighbors.h | 8 +- src/rl/math/LinearNearestNeighbors.h | 2 +- src/rl/math/Spline.h | 32 +-- src/rl/math/TypeTraits.h | 4 +- src/rl/math/metrics/L2.h | 4 +- src/rl/math/metrics/L2Squared.h | 4 +- src/rl/mdl/AnalyticalInverseKinematics.cpp | 2 +- src/rl/mdl/AnalyticalInverseKinematics.h | 4 +- src/rl/mdl/InverseKinematics.h | 2 +- src/rl/mdl/IterativeInverseKinematics.cpp | 2 +- src/rl/mdl/JacobianInverseKinematics.cpp | 2 +- src/rl/mdl/JacobianInverseKinematics.h | 2 +- src/rl/mdl/Joint.cpp | 16 +- src/rl/mdl/Joint.h | 20 +- src/rl/mdl/Kinematic.cpp | 8 +- src/rl/mdl/Model.cpp | 30 +-- src/rl/mdl/Model.h | 14 +- src/rl/mdl/NloptInverseKinematics.cpp | 2 +- src/rl/mdl/NloptInverseKinematics.h | 4 +- src/rl/mdl/Revolute.cpp | 6 +- src/rl/mdl/RungeKuttaNystromIntegrator.cpp | 2 +- src/rl/mdl/SixDof.cpp | 6 +- src/rl/mdl/Spherical.cpp | 6 +- src/rl/mdl/UrdfFactory.cpp | 112 +++++----- src/rl/mdl/XmlFactory.cpp | 208 +++++++++--------- src/rl/plan/AddRrtConCon.cpp | 12 +- src/rl/plan/AdvancedOptimizer.cpp | 4 +- src/rl/plan/BridgeSampler.cpp | 4 +- src/rl/plan/DistanceModel.cpp | 14 +- src/rl/plan/Eet.cpp | 32 +-- src/rl/plan/Eet.h | 8 +- src/rl/plan/GaussianSampler.cpp | 2 +- src/rl/plan/GaussianSampler.h | 4 +- src/rl/plan/GnatNearestNeighbors.cpp | 4 +- src/rl/plan/GnatNearestNeighbors.h | 4 +- .../KdtreeBoundingBoxNearestNeighbors.cpp | 4 +- .../plan/KdtreeBoundingBoxNearestNeighbors.h | 4 +- src/rl/plan/KdtreeNearestNeighbors.cpp | 4 +- src/rl/plan/KdtreeNearestNeighbors.h | 4 +- src/rl/plan/MatrixPtr.h | 2 +- src/rl/plan/Model.cpp | 4 +- src/rl/plan/Model.h | 2 +- src/rl/plan/Prm.cpp | 22 +- src/rl/plan/PrmUtilityGuided.cpp | 16 +- src/rl/plan/PrmUtilityGuided.h | 4 +- src/rl/plan/RealList.h | 2 +- src/rl/plan/RecursiveVerifier.cpp | 4 +- src/rl/plan/Rrt.cpp | 8 +- src/rl/plan/Rrt.h | 2 +- src/rl/plan/RrtCon.cpp | 2 +- src/rl/plan/RrtConCon.cpp | 4 +- src/rl/plan/RrtDual.cpp | 4 +- src/rl/plan/RrtExtCon.cpp | 4 +- src/rl/plan/RrtExtExt.cpp | 4 +- src/rl/plan/RrtGoalBias.cpp | 4 +- src/rl/plan/RrtGoalBias.h | 4 +- src/rl/plan/SequentialVerifier.cpp | 2 +- src/rl/plan/SimpleModel.cpp | 4 +- src/rl/plan/TransformPtr.h | 2 +- src/rl/plan/UniformSampler.cpp | 2 +- src/rl/plan/UniformSampler.h | 4 +- src/rl/plan/Vector3List.h | 2 +- src/rl/plan/Vector3Ptr.h | 2 +- src/rl/plan/VectorList.h | 2 +- src/rl/plan/VectorPtr.h | 2 +- src/rl/plan/Verifier.cpp | 2 +- src/rl/plan/WorkspaceSphereExplorer.cpp | 14 +- src/rl/plan/WorkspaceSphereExplorer.h | 4 +- src/rl/sg/Body.cpp | 4 +- src/rl/sg/Body.h | 6 +- src/rl/sg/DistanceScene.cpp | 10 +- src/rl/sg/UrdfFactory.cpp | 116 +++++----- src/rl/sg/XmlFactory.cpp | 30 +-- src/rl/sg/bullet/Body.cpp | 12 +- src/rl/sg/bullet/Scene.cpp | 42 ++-- src/rl/sg/bullet/Shape.cpp | 24 +- src/rl/sg/bullet/Shape.h | 2 +- src/rl/sg/fcl/Body.h | 2 +- src/rl/sg/fcl/Scene.h | 10 +- src/rl/sg/fcl/Shape.h | 12 +- src/rl/sg/ode/Body.cpp | 8 +- src/rl/sg/ode/Scene.cpp | 64 +++--- src/rl/sg/ode/Shape.cpp | 16 +- src/rl/sg/ode/Shape.h | 4 +- src/rl/sg/pqp/Scene.cpp | 8 +- src/rl/sg/pqp/Shape.cpp | 2 +- src/rl/sg/pqp/Shape.h | 2 +- src/rl/sg/solid/Scene.cpp | 2 +- src/rl/sg/solid/Shape.h | 2 +- src/rl/std/memory.h | 4 +- src/rl/util/rtai/chrono.h | 2 +- src/rl/util/rtai/thread.h | 14 +- src/rl/util/xenomai/chrono.h | 2 +- src/rl/util/xenomai/condition_variable.h | 2 +- src/rl/util/xenomai/mutex.h | 4 +- src/rl/util/xenomai/thread.h | 14 +- src/rl/xml/Attribute.h | 4 +- src/rl/xml/Document.h | 6 +- src/rl/xml/DomParser.h | 2 +- src/rl/xml/Node.h | 12 +- src/rl/xml/NodeSet.h | 4 +- src/rl/xml/Object.h | 6 +- src/rl/xml/Path.h | 2 +- src/rl/xml/Schema.h | 6 +- src/rl/xml/Stylesheet.h | 14 +- tests/rlCollisionTest/rlCollisionTest.cpp | 4 +- .../rlInverseKinematicsKinTest.cpp | 2 +- 157 files changed, 922 insertions(+), 922 deletions(-) diff --git a/demos/rlLoadXmlDemo/rlLoadXmlDemo.cpp b/demos/rlLoadXmlDemo/rlLoadXmlDemo.cpp index 98875506..c45f3748 100644 --- a/demos/rlLoadXmlDemo/rlLoadXmlDemo.cpp +++ b/demos/rlLoadXmlDemo/rlLoadXmlDemo.cpp @@ -48,7 +48,7 @@ main(int argc, char** argv) { if (document.getRootElement().hasNamespace() && "http://www.w3.org/1999/XSL/Transform" == document.getRootElement().getNamespace().getHref()) { - ::std::map< ::std::string, ::std::string> parameters; + ::std::map<::std::string, ::std::string> parameters; for (int i = 2; i < argc - 1; i += 2) { diff --git a/demos/rlSixAxisForceTorqueSensorDemo/rlSixAxisForceTorqueSensorDemo.cpp b/demos/rlSixAxisForceTorqueSensorDemo/rlSixAxisForceTorqueSensorDemo.cpp index 48920d61..7f59c5f3 100644 --- a/demos/rlSixAxisForceTorqueSensorDemo/rlSixAxisForceTorqueSensorDemo.cpp +++ b/demos/rlSixAxisForceTorqueSensorDemo/rlSixAxisForceTorqueSensorDemo.cpp @@ -116,7 +116,7 @@ main(int argc, char** argv) std::cout << "Frame send divider: " << sensor.doGetFrameSendDivider() << std::endl; std::cout << "Tare: " << sensor.doGetTare() << std::endl; std::cout << "Filter: " << sensor.doGetFilter() << std::endl; - ::std::pair< ::std::chrono::system_clock::time_point, ::std::chrono::system_clock::duration> calibrationDateLifetime = sensor.doGetCalibrationDateLifetime(); + ::std::pair<::std::chrono::system_clock::time_point, ::std::chrono::system_clock::duration> calibrationDateLifetime = sensor.doGetCalibrationDateLifetime(); std::cout << "Calibration date: " << calibrationDateLifetime.first.time_since_epoch().count() << " " << toIsoString(calibrationDateLifetime.first) << std::endl; std::cout << "Calibration lifetime: " << calibrationDateLifetime.second.count() << " " << toIsoString(calibrationDateLifetime.first + calibrationDateLifetime.second) << std::endl; #endif diff --git a/src/rl/hal/AnalogInputReader.cpp b/src/rl/hal/AnalogInputReader.cpp index 58eabd4f..87c25ff4 100644 --- a/src/rl/hal/AnalogInputReader.cpp +++ b/src/rl/hal/AnalogInputReader.cpp @@ -39,10 +39,10 @@ namespace rl { } - ::std::vector< ::rl::math::Real> + ::std::vector<::rl::math::Real> AnalogInputReader::getAnalogInput() const { - ::std::vector< ::rl::math::Real> values; + ::std::vector<::rl::math::Real> values; for (::std::size_t i = 0; i < this->getAnalogInputCount(); ++i) { diff --git a/src/rl/hal/AnalogInputReader.h b/src/rl/hal/AnalogInputReader.h index 84cf52a4..1e437f11 100644 --- a/src/rl/hal/AnalogInputReader.h +++ b/src/rl/hal/AnalogInputReader.h @@ -43,7 +43,7 @@ namespace rl virtual ~AnalogInputReader(); - virtual ::std::vector< ::rl::math::Real> getAnalogInput() const; + virtual ::std::vector<::rl::math::Real> getAnalogInput() const; virtual ::rl::math::Real getAnalogInput(const ::std::size_t& i) const = 0; diff --git a/src/rl/hal/AnalogInputWriter.cpp b/src/rl/hal/AnalogInputWriter.cpp index c28ff925..aa596594 100644 --- a/src/rl/hal/AnalogInputWriter.cpp +++ b/src/rl/hal/AnalogInputWriter.cpp @@ -40,7 +40,7 @@ namespace rl } void - AnalogInputWriter::setAnalogInput(const ::std::vector< ::rl::math::Real>& values) + AnalogInputWriter::setAnalogInput(const ::std::vector<::rl::math::Real>& values) { for (::std::size_t i = 0; i < this->getAnalogInputCount(); ++i) { diff --git a/src/rl/hal/AnalogInputWriter.h b/src/rl/hal/AnalogInputWriter.h index a6a0aee3..6e5c5edc 100644 --- a/src/rl/hal/AnalogInputWriter.h +++ b/src/rl/hal/AnalogInputWriter.h @@ -43,7 +43,7 @@ namespace rl virtual ~AnalogInputWriter(); - virtual void setAnalogInput(const ::std::vector< ::rl::math::Real>& values); + virtual void setAnalogInput(const ::std::vector<::rl::math::Real>& values); virtual void setAnalogInput(const ::std::size_t& i, const ::rl::math::Real& value) = 0; diff --git a/src/rl/hal/AnalogOutputReader.cpp b/src/rl/hal/AnalogOutputReader.cpp index 2b7cc837..39b28ea6 100644 --- a/src/rl/hal/AnalogOutputReader.cpp +++ b/src/rl/hal/AnalogOutputReader.cpp @@ -39,10 +39,10 @@ namespace rl { } - ::std::vector< ::rl::math::Real> + ::std::vector<::rl::math::Real> AnalogOutputReader::getAnalogOutput() const { - ::std::vector< ::rl::math::Real> values; + ::std::vector<::rl::math::Real> values; for (::std::size_t i = 0; i < this->getAnalogOutputCount(); ++i) { diff --git a/src/rl/hal/AnalogOutputReader.h b/src/rl/hal/AnalogOutputReader.h index d6f6470c..872d6aaa 100644 --- a/src/rl/hal/AnalogOutputReader.h +++ b/src/rl/hal/AnalogOutputReader.h @@ -43,7 +43,7 @@ namespace rl virtual ~AnalogOutputReader(); - virtual ::std::vector< ::rl::math::Real> getAnalogOutput() const; + virtual ::std::vector<::rl::math::Real> getAnalogOutput() const; virtual ::rl::math::Real getAnalogOutput(const ::std::size_t& i) const = 0; diff --git a/src/rl/hal/AnalogOutputWriter.cpp b/src/rl/hal/AnalogOutputWriter.cpp index e4f72b72..3039cfa5 100644 --- a/src/rl/hal/AnalogOutputWriter.cpp +++ b/src/rl/hal/AnalogOutputWriter.cpp @@ -40,7 +40,7 @@ namespace rl } void - AnalogOutputWriter::setAnalogOutput(const ::std::vector< ::rl::math::Real>& values) + AnalogOutputWriter::setAnalogOutput(const ::std::vector<::rl::math::Real>& values) { for (::std::size_t i = 0; i < this->getAnalogOutputCount(); ++i) { diff --git a/src/rl/hal/AnalogOutputWriter.h b/src/rl/hal/AnalogOutputWriter.h index f471860a..05267e68 100644 --- a/src/rl/hal/AnalogOutputWriter.h +++ b/src/rl/hal/AnalogOutputWriter.h @@ -43,7 +43,7 @@ namespace rl virtual ~AnalogOutputWriter(); - virtual void setAnalogOutput(const ::std::vector< ::rl::math::Real>& values); + virtual void setAnalogOutput(const ::std::vector<::rl::math::Real>& values); virtual void setAnalogOutput(const ::std::size_t& i, const ::rl::math::Real& value) = 0; diff --git a/src/rl/hal/Coach.cpp b/src/rl/hal/Coach.cpp index 76c5ddab..6ff3c816 100644 --- a/src/rl/hal/Coach.cpp +++ b/src/rl/hal/Coach.cpp @@ -71,7 +71,7 @@ namespace rl { ::rl::math::Vector q(this->getDof()); - ::boost::iostreams::stream< ::boost::iostreams::basic_array_source> stream(this->in.data(), this->in.size()); + ::boost::iostreams::stream<::boost::iostreams::basic_array_source> stream(this->in.data(), this->in.size()); ::std::size_t cmd; stream >> cmd; diff --git a/src/rl/hal/Endian.cpp b/src/rl/hal/Endian.cpp index f374f099..dfeaf2ee 100644 --- a/src/rl/hal/Endian.cpp +++ b/src/rl/hal/Endian.cpp @@ -110,7 +110,7 @@ namespace rl #ifdef HAVE_BIG_ENDIAN return hostQuadWord(highDoubleWord, lowDoubleWord); #elif defined(HAVE_LITTLE_ENDIAN) - return (static_cast< ::std::uint64_t>(lowDoubleWord) << 32) | highDoubleWord; + return (static_cast<::std::uint64_t>(lowDoubleWord) << 32) | highDoubleWord; #endif } @@ -390,7 +390,7 @@ namespace rl Endian::littleQuadWord(const ::std::uint32_t& highDoubleWord, const ::std::uint32_t& lowDoubleWord) { #ifdef HAVE_BIG_ENDIAN - return (static_cast< ::std::uint64_t>(lowDoubleWord) << 32) | highDoubleWord; + return (static_cast<::std::uint64_t>(lowDoubleWord) << 32) | highDoubleWord; #elif defined(HAVE_LITTLE_ENDIAN) return hostQuadWord(highDoubleWord, lowDoubleWord); #endif diff --git a/src/rl/hal/Endian.h b/src/rl/hal/Endian.h index b15d8912..5d6692f4 100644 --- a/src/rl/hal/Endian.h +++ b/src/rl/hal/Endian.h @@ -116,7 +116,7 @@ namespace rl static ::std::uint64_t hostQuadWord(const ::std::uint32_t& highDoubleWord, const ::std::uint32_t& lowDoubleWord) { - return (static_cast< ::std::uint64_t>(highDoubleWord) << 32) | lowDoubleWord; + return (static_cast<::std::uint64_t>(highDoubleWord) << 32) | lowDoubleWord; } static void hostToBig(::std::int8_t& character) @@ -246,7 +246,7 @@ namespace rl static void reverse(float& real32) { - reverse(*reinterpret_cast< ::std::uint32_t*>(&real32)); + reverse(*reinterpret_cast<::std::uint32_t*>(&real32)); } static void reverse(::std::int64_t& quadWord) @@ -263,7 +263,7 @@ namespace rl static void reverse(double& real64) { - reverse(*reinterpret_cast< ::std::uint64_t*>(&real64)); + reverse(*reinterpret_cast<::std::uint64_t*>(&real64)); } protected: diff --git a/src/rl/hal/Exception.cpp b/src/rl/hal/Exception.cpp index 3cd65d28..5c40fbf1 100644 --- a/src/rl/hal/Exception.cpp +++ b/src/rl/hal/Exception.cpp @@ -58,7 +58,7 @@ namespace rl #ifdef WIN32 ::LPTSTR buffer = nullptr; ::FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM, nullptr, errnum, 0, reinterpret_cast(&buffer), 0, nullptr); - ::std::string message = nullptr != buffer ? buffer : ::boost::lexical_cast< ::std::string>(errnum); + ::std::string message = nullptr != buffer ? buffer : ::boost::lexical_cast<::std::string>(errnum); ::LocalFree(buffer); return message; #else // WIN32 diff --git a/src/rl/hal/Gnuplot.cpp b/src/rl/hal/Gnuplot.cpp index e6283d6d..0c6a8b69 100644 --- a/src/rl/hal/Gnuplot.cpp +++ b/src/rl/hal/Gnuplot.cpp @@ -154,7 +154,7 @@ namespace rl { ::std::size_t t = this->max - this->history.size(); - for (::std::list< ::rl::math::Vector>::iterator j = this->history.begin(); j != this->history.end(); ++j) + for (::std::list<::rl::math::Vector>::iterator j = this->history.begin(); j != this->history.end(); ++j) { #ifdef WIN32 fprintf(this->fp, "%Iu %f\n", t, (*j)(i) * ::rl::math::RAD2DEG); diff --git a/src/rl/hal/Gnuplot.h b/src/rl/hal/Gnuplot.h index 37207851..6a1242cb 100644 --- a/src/rl/hal/Gnuplot.h +++ b/src/rl/hal/Gnuplot.h @@ -68,7 +68,7 @@ namespace rl private: FILE* fp; - ::std::list< ::rl::math::Vector> history; + ::std::list<::rl::math::Vector> history; ::std::size_t max; diff --git a/src/rl/hal/LeuzeRs4.cpp b/src/rl/hal/LeuzeRs4.cpp index 65317b38..49eff015 100644 --- a/src/rl/hal/LeuzeRs4.cpp +++ b/src/rl/hal/LeuzeRs4.cpp @@ -214,7 +214,7 @@ namespace rl { assert(this->isConnected()); - return this->stepSize * static_cast< ::rl::math::Real>(0.36) * ::rl::math::DEG2RAD; + return this->stepSize * static_cast<::rl::math::Real>(0.36) * ::rl::math::DEG2RAD; } ::rl::math::Real @@ -222,7 +222,7 @@ namespace rl { assert(this->isConnected()); - return (-5 + this->startIndex * static_cast< ::rl::math::Real>(0.36)) * ::rl::math::DEG2RAD; + return (-5 + this->startIndex * static_cast<::rl::math::Real>(0.36)) * ::rl::math::DEG2RAD; } ::rl::math::Real @@ -230,7 +230,7 @@ namespace rl { assert(this->isConnected()); - return (185 - (528 - this->stopIndex) * static_cast< ::rl::math::Real>(0.36)) * ::rl::math::DEG2RAD; + return (185 - (528 - this->stopIndex) * static_cast<::rl::math::Real>(0.36)) * ::rl::math::DEG2RAD; } void @@ -241,7 +241,7 @@ namespace rl this->setConnected(true); #if 0 - ::std::array< ::std::uint8_t, 1099> buf; + ::std::array<::std::uint8_t, 1099> buf; // synchronize baud rates @@ -458,7 +458,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 1099> buf; + ::std::array<::std::uint8_t, 1099> buf; buf[2] = 0x10; buf[3] = 0x21; @@ -545,7 +545,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 1099> buf; + ::std::array<::std::uint8_t, 1099> buf; buf[2] = 0x19; buf[3] = 0x41; @@ -648,7 +648,7 @@ ::std::cout << "setting to 115,200 baud" << ::std::endl; { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 1099> buf; + ::std::array<::std::uint8_t, 1099> buf; buf[2] = 0x1A; buf[3] = 0x41; @@ -697,7 +697,7 @@ ::std::cout << "setting to 115,200 baud" << ::std::endl; if (2 == this->type) { - ::std::array< ::std::uint8_t, 1099> buf; + ::std::array<::std::uint8_t, 1099> buf; buf[2] = 0x24; buf[3] = 0x01; diff --git a/src/rl/hal/LeuzeRs4.h b/src/rl/hal/LeuzeRs4.h index 693288cf..d786728a 100644 --- a/src/rl/hal/LeuzeRs4.h +++ b/src/rl/hal/LeuzeRs4.h @@ -125,7 +125,7 @@ namespace rl BaudRate baudRate; - ::std::array< ::std::uint8_t, 1099> data; + ::std::array<::std::uint8_t, 1099> data; BaudRate desired; diff --git a/src/rl/hal/MitsubishiH7.cpp b/src/rl/hal/MitsubishiH7.cpp index 2e22754a..d95aaf90 100644 --- a/src/rl/hal/MitsubishiH7.cpp +++ b/src/rl/hal/MitsubishiH7.cpp @@ -101,10 +101,10 @@ namespace rl return x; } - ::Eigen::Matrix< ::std::int32_t, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::std::int32_t, ::Eigen::Dynamic, 1> MitsubishiH7::getCurrentFeedback() const { - ::Eigen::Matrix< ::std::int32_t, ::Eigen::Dynamic, 1> c(this->getDof()); + ::Eigen::Matrix<::std::int32_t, ::Eigen::Dynamic, 1> c(this->getDof()); switch (this->getDof()) { @@ -179,10 +179,10 @@ namespace rl return this->mode; } - ::Eigen::Matrix< ::std::int32_t, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::std::int32_t, ::Eigen::Dynamic, 1> MitsubishiH7::getMotorPulse() const { - ::Eigen::Matrix< ::std::int32_t, ::Eigen::Dynamic, 1> p(this->getDof()); + ::Eigen::Matrix<::std::int32_t, ::Eigen::Dynamic, 1> p(this->getDof()); switch (this->getDof()) { @@ -318,7 +318,7 @@ namespace rl } void - MitsubishiH7::setMotorPulse(const ::Eigen::Matrix< ::std::int32_t, ::Eigen::Dynamic, 1>& p) + MitsubishiH7::setMotorPulse(const ::Eigen::Matrix<::std::int32_t, ::Eigen::Dynamic, 1>& p) { assert(p.size() >= this->getDof()); diff --git a/src/rl/hal/MitsubishiH7.h b/src/rl/hal/MitsubishiH7.h index 21d63f4f..10351ab9 100644 --- a/src/rl/hal/MitsubishiH7.h +++ b/src/rl/hal/MitsubishiH7.h @@ -80,7 +80,7 @@ namespace rl ::rl::math::Transform getCartesianPosition() const; - ::Eigen::Matrix< ::std::int32_t, ::Eigen::Dynamic, 1> getCurrentFeedback() const; + ::Eigen::Matrix<::std::int32_t, ::Eigen::Dynamic, 1> getCurrentFeedback() const; ::std::size_t getFilter() const; @@ -90,7 +90,7 @@ namespace rl Mode getMode() const; - ::Eigen::Matrix< ::std::int32_t, ::Eigen::Dynamic, 1> getMotorPulse() const; + ::Eigen::Matrix<::std::int32_t, ::Eigen::Dynamic, 1> getMotorPulse() const; void halt(); @@ -110,7 +110,7 @@ namespace rl void setMode(const Mode& mode); - void setMotorPulse(const ::Eigen::Matrix< ::std::int32_t, ::Eigen::Dynamic, 1>& p); + void setMotorPulse(const ::Eigen::Matrix<::std::int32_t, ::Eigen::Dynamic, 1>& p); void setOutput(const ::std::uint16_t& bitTop, const ::std::uint16_t& bitMask, const ::std::uint16_t& ioData); diff --git a/src/rl/hal/MitsubishiR3.cpp b/src/rl/hal/MitsubishiR3.cpp index ba1cf427..b30b33dd 100644 --- a/src/rl/hal/MitsubishiR3.cpp +++ b/src/rl/hal/MitsubishiR3.cpp @@ -136,7 +136,7 @@ namespace rl state.stopSts.isProgramSelectEnable = stopSts[4]; state.stopSts.isPseudoInput = stopSts[6]; - ::std::vector< ::std::string> tokens; + ::std::vector<::std::string> tokens; ::std::string tmp = reply.substr(7); ::boost::split(tokens, tmp, ::boost::is_any_of(";")); @@ -219,7 +219,7 @@ namespace rl { ::std::array state; - ::std::vector< ::std::string> tokens; + ::std::vector<::std::string> tokens; ::std::string tmp = reply.substr(3); ::boost::split(tokens, tmp, ::boost::is_any_of(";")); @@ -314,7 +314,7 @@ namespace rl if ("QoK" == reply.substr(0, 3)) { - ::std::vector< ::std::string> tokens; + ::std::vector<::std::string> tokens; ::std::string tmp = reply.substr(3); ::boost::split(tokens, tmp, ::boost::is_any_of(";")); diff --git a/src/rl/hal/RobotiqModelC.cpp b/src/rl/hal/RobotiqModelC.cpp index be26181f..3b59ebc1 100644 --- a/src/rl/hal/RobotiqModelC.cpp +++ b/src/rl/hal/RobotiqModelC.cpp @@ -130,13 +130,13 @@ namespace rl ::rl::math::Real RobotiqModelC::getPositionPercentage() const { - return this->in[7] / static_cast< ::rl::math::Real>(0xFF); + return this->in[7] / static_cast<::rl::math::Real>(0xFF); } ::rl::math::Real RobotiqModelC::getPositionRequestEchoPercentage() const { - return this->in[6] / static_cast< ::rl::math::Real>(0xFF); + return this->in[6] / static_cast<::rl::math::Real>(0xFF); } void @@ -203,19 +203,19 @@ namespace rl void RobotiqModelC::setForcePercentage(const ::rl::math::Real& forcePercentage) { - this->out[12] = static_cast< ::std::uint8_t>(0xFF * forcePercentage); + this->out[12] = static_cast<::std::uint8_t>(0xFF * forcePercentage); } void RobotiqModelC::setPositionPercentage(const ::rl::math::Real& positionPercentage) { - this->out[10] = static_cast< ::std::uint8_t>(0xFF * positionPercentage); + this->out[10] = static_cast<::std::uint8_t>(0xFF * positionPercentage); } void RobotiqModelC::setSpeedPercentage(const ::rl::math::Real& speedPercentage) { - this->out[11] = static_cast< ::std::uint8_t>(0xFF * speedPercentage); + this->out[11] = static_cast<::std::uint8_t>(0xFF * speedPercentage); } void diff --git a/src/rl/hal/RobotiqModelC.h b/src/rl/hal/RobotiqModelC.h index cc28403f..af3773e0 100644 --- a/src/rl/hal/RobotiqModelC.h +++ b/src/rl/hal/RobotiqModelC.h @@ -158,9 +158,9 @@ namespace rl void send(::std::uint8_t* buf, const ::std::size_t& len); - ::std::array< ::std::uint8_t, 32> in; + ::std::array<::std::uint8_t, 32> in; - ::std::array< ::std::uint8_t, 32> out; + ::std::array<::std::uint8_t, 32> out; Serial serial; }; diff --git a/src/rl/hal/SchmersalLss300.cpp b/src/rl/hal/SchmersalLss300.cpp index 5c0bb0e7..5cbbdc0e 100644 --- a/src/rl/hal/SchmersalLss300.cpp +++ b/src/rl/hal/SchmersalLss300.cpp @@ -122,7 +122,7 @@ namespace rl ::rl::math::Vector distances(this->getDistancesCount()); - ::rl::math::Real scale = static_cast< ::rl::math::Real>(0.01); + ::rl::math::Real scale = static_cast<::rl::math::Real>(0.01); ::std::uint16_t count = Endian::hostWord(this->data[8], this->data[7]); ::std::uint8_t mask = 0x1F; @@ -130,7 +130,7 @@ namespace rl { if (this->data[10 + i * 2] & 32) { - distances(i) = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); + distances(i) = ::std::numeric_limits<::rl::math::Real>::quiet_NaN(); } else { @@ -177,7 +177,7 @@ namespace rl { assert(this->isConnected()); - return static_cast< ::rl::math::Real>(0.36) * ::rl::math::DEG2RAD; + return static_cast<::rl::math::Real>(0.36) * ::rl::math::DEG2RAD; } ::rl::math::Real @@ -201,7 +201,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 1013> buf; + ::std::array<::std::uint8_t, 1013> buf; buf[4] = 0x00; @@ -235,7 +235,7 @@ namespace rl this->setConnected(true); - ::std::array< ::std::uint8_t, 1013> buf; + ::std::array<::std::uint8_t, 1013> buf; // synchronize baud rates @@ -345,7 +345,7 @@ namespace rl ::std::uint16_t length = Endian::hostWord(buf[3], buf[2]); - if (len != static_cast< ::std::size_t>(length) + 6) + if (len != static_cast<::std::size_t>(length) + 6) { throw DeviceException("data length mismatch in command " + ::std::to_string(command)); } @@ -371,7 +371,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 1013> buf; + ::std::array<::std::uint8_t, 1013> buf; buf[4] = 0x10; @@ -416,7 +416,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 1013> buf; + ::std::array<::std::uint8_t, 1013> buf; buf[4] = 0x66; @@ -479,7 +479,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 1013> buf; + ::std::array<::std::uint8_t, 1013> buf; buf[4] = 0x20; diff --git a/src/rl/hal/SchmersalLss300.h b/src/rl/hal/SchmersalLss300.h index 288699fe..b9809434 100644 --- a/src/rl/hal/SchmersalLss300.h +++ b/src/rl/hal/SchmersalLss300.h @@ -132,7 +132,7 @@ namespace rl BaudRate baudRate; - ::std::array< ::std::uint8_t, 1013> data; + ::std::array<::std::uint8_t, 1013> data; BaudRate desired; diff --git a/src/rl/hal/SchunkFpsF5.cpp b/src/rl/hal/SchunkFpsF5.cpp index 6b1b6be8..786b4210 100644 --- a/src/rl/hal/SchunkFpsF5.cpp +++ b/src/rl/hal/SchunkFpsF5.cpp @@ -120,7 +120,7 @@ namespace rl SchunkFpsF5::getDistancesMaximum(const ::std::size_t& i) const { assert(i < this->getDistancesCount()); - return static_cast< ::rl::math::Real>(0.06); + return static_cast<::rl::math::Real>(0.06); } ::rl::math::Real @@ -278,7 +278,7 @@ namespace rl void SchunkFpsF5::start() { - ::std::array< ::std::uint8_t, 263> buf; + ::std::array<::std::uint8_t, 263> buf; // fulcrums @@ -297,8 +297,8 @@ namespace rl for (int i = 0; i < ::std::min(size, 31); ++i) { this->fulcrums.insert(::std::make_pair( - static_cast< ::rl::math::Real>(5) * (Endian::hostWord(~buf[9 + i * 4], ~buf[9 + i * 4 + 1]) - 0x0000) / (0xFFF0 - 0x0000), - Endian::hostWord(buf[11 + i * 4], buf[11 + i * 4 + 1]) / static_cast< ::rl::math::Real>(1000) / static_cast< ::rl::math::Real>(1000) + static_cast<::rl::math::Real>(5) * (Endian::hostWord(~buf[9 + i * 4], ~buf[9 + i * 4 + 1]) - 0x0000) / (0xFFF0 - 0x0000), + Endian::hostWord(buf[11 + i * 4], buf[11 + i * 4 + 1]) / static_cast<::rl::math::Real>(1000) / static_cast<::rl::math::Real>(1000) )); } @@ -315,8 +315,8 @@ namespace rl for (int i = 0; i < ::std::min(size - 31, 31); ++i) { this->fulcrums.insert(::std::make_pair( - static_cast< ::rl::math::Real>(5) * (Endian::hostWord(~buf[5 + i * 4], ~buf[5 + i * 4 + 1]) - 0x0000) / (0xFFF0 - 0x0000), - Endian::hostWord(buf[7 + i * 4], buf[7 + i * 4 + 1]) / static_cast< ::rl::math::Real>(1000) / static_cast< ::rl::math::Real>(1000) + static_cast<::rl::math::Real>(5) * (Endian::hostWord(~buf[5 + i * 4], ~buf[5 + i * 4 + 1]) - 0x0000) / (0xFFF0 - 0x0000), + Endian::hostWord(buf[7 + i * 4], buf[7 + i * 4 + 1]) / static_cast<::rl::math::Real>(1000) / static_cast<::rl::math::Real>(1000) )); } } @@ -326,7 +326,7 @@ namespace rl void SchunkFpsF5::step() { - ::std::array< ::std::uint8_t, 263> buf; + ::std::array<::std::uint8_t, 263> buf; buf[1] = 0x03; buf[2] = 0x06; @@ -347,9 +347,9 @@ namespace rl // 10000000 this->closed = (buf[5] & 128) ? true : false; - this->value = static_cast< ::rl::math::Real>(5) * (Endian::hostWord(~buf[31], ~buf[32]) - 0x0000) / (0xFFF0 - 0x0000); + this->value = static_cast<::rl::math::Real>(5) * (Endian::hostWord(~buf[31], ~buf[32]) - 0x0000) / (0xFFF0 - 0x0000); - ::std::set< ::std::pair< ::rl::math::Real, ::rl::math::Real>>::iterator lower = this->fulcrums.upper_bound(::std::make_pair(this->value, ::std::numeric_limits< ::rl::math::Real>::max())); + ::std::set<::std::pair<::rl::math::Real, ::rl::math::Real>>::iterator lower = this->fulcrums.upper_bound(::std::make_pair(this->value, ::std::numeric_limits<::rl::math::Real>::max())); if (!this->fulcrums.empty()) { @@ -363,17 +363,17 @@ namespace rl } else { - ::std::set< ::std::pair< ::rl::math::Real, ::rl::math::Real>>::iterator upper = lower--; + ::std::set<::std::pair<::rl::math::Real, ::rl::math::Real>>::iterator upper = lower--; this->interpolated = (this->value - (*lower).first) / ((*upper).first - (*lower).first) * ((*upper).second - (*lower).second) + (*lower).second; } } else { - this->interpolated = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); + this->interpolated = ::std::numeric_limits<::rl::math::Real>::quiet_NaN(); } - this->voltage = static_cast< ::rl::math::Real>(23) * (Endian::hostWord(buf[33], buf[34]) - 0x3D00) / (0xB700 - 0x3D00) + static_cast< ::rl::math::Real>(12); - this->temperature = static_cast< ::rl::math::Real>(90) * (Endian::hostWord(buf[35], 0x0) - 0x0A00) / (0xC300 - 0x0A00) - static_cast< ::rl::math::Real>(20); + this->voltage = static_cast<::rl::math::Real>(23) * (Endian::hostWord(buf[33], buf[34]) - 0x3D00) / (0xB700 - 0x3D00) + static_cast<::rl::math::Real>(12); + this->temperature = static_cast<::rl::math::Real>(90) * (Endian::hostWord(buf[35], 0x0) - 0x0A00) / (0xC300 - 0x0A00) - static_cast<::rl::math::Real>(20); // 00000001 this->area = (buf[36] & 1) ? true : false; diff --git a/src/rl/hal/SchunkFpsF5.h b/src/rl/hal/SchunkFpsF5.h index a2f4b9e1..0706be95 100644 --- a/src/rl/hal/SchunkFpsF5.h +++ b/src/rl/hal/SchunkFpsF5.h @@ -107,7 +107,7 @@ namespace rl bool closed; - ::std::set< ::std::pair< ::rl::math::Real, ::rl::math::Real>> fulcrums; + ::std::set<::std::pair<::rl::math::Real, ::rl::math::Real>> fulcrums; ::rl::math::Real interpolated; diff --git a/src/rl/hal/Serial.cpp b/src/rl/hal/Serial.cpp index d289e77c..b0164665 100644 --- a/src/rl/hal/Serial.cpp +++ b/src/rl/hal/Serial.cpp @@ -396,8 +396,8 @@ namespace rl return 0; #else ::timeval tv; - tv.tv_sec = ::std::chrono::duration_cast< ::std::chrono::seconds>(timeout).count(); - tv.tv_usec = ::std::chrono::duration_cast< ::std::chrono::microseconds>(timeout - ::std::chrono::duration_cast< ::std::chrono::seconds>(timeout)).count(); + tv.tv_sec = ::std::chrono::duration_cast<::std::chrono::seconds>(timeout).count(); + tv.tv_usec = ::std::chrono::duration_cast<::std::chrono::microseconds>(timeout - ::std::chrono::duration_cast<::std::chrono::seconds>(timeout)).count(); ::fd_set readfds; FD_ZERO(&readfds); diff --git a/src/rl/hal/SickLms200.cpp b/src/rl/hal/SickLms200.cpp index 9d4593de..850292da 100644 --- a/src/rl/hal/SickLms200.cpp +++ b/src/rl/hal/SickLms200.cpp @@ -132,7 +132,7 @@ namespace rl assert(this->isConnected()); - ::std::array< ::std::uint8_t, 812> buf; + ::std::array<::std::uint8_t, 812> buf; buf[4] = 0x74; @@ -199,7 +199,7 @@ namespace rl assert(this->isConnected()); - ::std::array< ::std::uint8_t, 812> buf; + ::std::array<::std::uint8_t, 812> buf; buf[4] = 0x31; @@ -312,10 +312,10 @@ namespace rl switch (this->data[6] & 192) { case 0: - scale = static_cast< ::rl::math::Real>(0.01); + scale = static_cast<::rl::math::Real>(0.01); break; case 64: - scale = static_cast< ::rl::math::Real>(0.001); + scale = static_cast<::rl::math::Real>(0.001); break; default: throw DeviceException("unknown scale"); @@ -369,11 +369,11 @@ ::std::cerr << "Operation overflow" << ::std::endl; ::std::cerr << "Signal-to-noise ratio too small" << ::std::endl; case 0x1FFA: ::std::cerr << "Error when reading channel 1" << ::std::endl; - distances(i) = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); + distances(i) = ::std::numeric_limits<::rl::math::Real>::quiet_NaN(); break; case 0x1FF7: ::std::cerr << "Measured value > Maximum value" << ::std::endl; - distances(i) = ::std::numeric_limits< ::rl::math::Real>::infinity(); + distances(i) = ::std::numeric_limits<::rl::math::Real>::infinity(); break; default: distances(i) = value; @@ -396,11 +396,11 @@ ::std::cerr << "Operation overflow" << ::std::endl; ::std::cerr << "Signal-to-noise ratio too small" << ::std::endl; case 0x3FFA: ::std::cerr << "Error when reading channel 1" << ::std::endl; - distances(i) = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); + distances(i) = ::std::numeric_limits<::rl::math::Real>::quiet_NaN(); break; case 0x3FF7: ::std::cerr << "Measured value > Maximum value" << ::std::endl; - distances(i) = ::std::numeric_limits< ::rl::math::Real>::infinity(); + distances(i) = ::std::numeric_limits<::rl::math::Real>::infinity(); break; default: distances(i) = value; @@ -421,11 +421,11 @@ ::std::cerr << "Operation overflow" << ::std::endl; ::std::cerr << "Signal-to-noise ratio too small" << ::std::endl; case 0x7FFA: ::std::cerr << "Error when reading channel 1" << ::std::endl; - distances(i) = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); + distances(i) = ::std::numeric_limits<::rl::math::Real>::quiet_NaN(); break; case 0x7FF7: ::std::cerr << "Measured value > Maximum value" << ::std::endl; - distances(i) = ::std::numeric_limits< ::rl::math::Real>::infinity(); + distances(i) = ::std::numeric_limits<::rl::math::Real>::infinity(); break; default: distances(i) = value; @@ -537,11 +537,11 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (this->variant) { case VARIANT_100_25: - return static_cast< ::rl::math::Real>(0.25) * ::rl::math::DEG2RAD; + return static_cast<::rl::math::Real>(0.25) * ::rl::math::DEG2RAD; break; case VARIANT_100_50: case VARIANT_180_50: - return static_cast< ::rl::math::Real>(0.5) * ::rl::math::DEG2RAD; + return static_cast<::rl::math::Real>(0.5) * ::rl::math::DEG2RAD; break; case VARIANT_100_100: case VARIANT_180_100: @@ -605,7 +605,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 812> buf; + ::std::array<::std::uint8_t, 812> buf; buf[4] = 0x3A; @@ -635,7 +635,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; this->setConnected(true); - ::std::array< ::std::uint8_t, 812> buf; + ::std::array<::std::uint8_t, 812> buf; // synchronize baud rates @@ -843,7 +843,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; ::std::uint16_t length = Endian::hostWord(buf[3], buf[2]); - if (len != static_cast< ::std::size_t>(length) + 6) + if (len != static_cast<::std::size_t>(length) + 6) { throw DeviceException("data length mismatch in command " + ::std::to_string(command)); } @@ -897,7 +897,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 812> buf; + ::std::array<::std::uint8_t, 812> buf; buf[4] = 0x10; @@ -946,7 +946,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 812> buf; + ::std::array<::std::uint8_t, 812> buf; buf[4] = 0x20; @@ -1020,7 +1020,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 812> buf; + ::std::array<::std::uint8_t, 812> buf; // transmit password @@ -1118,7 +1118,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 812> buf; + ::std::array<::std::uint8_t, 812> buf; buf[4] = 0x20; @@ -1162,7 +1162,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 812> buf; + ::std::array<::std::uint8_t, 812> buf; buf[4] = 0x3B; diff --git a/src/rl/hal/SickLms200.h b/src/rl/hal/SickLms200.h index c707b5df..f639bae6 100644 --- a/src/rl/hal/SickLms200.h +++ b/src/rl/hal/SickLms200.h @@ -168,7 +168,7 @@ namespace rl ::std::uint8_t configuration; - ::std::array< ::std::uint8_t, 812> data; + ::std::array<::std::uint8_t, 812> data; BaudRate desired; diff --git a/src/rl/hal/SickS300.cpp b/src/rl/hal/SickS300.cpp index d8614291..cb0950d4 100644 --- a/src/rl/hal/SickS300.cpp +++ b/src/rl/hal/SickS300.cpp @@ -124,7 +124,7 @@ namespace rl ::rl::math::Vector distances(this->getDistancesCount()); - ::rl::math::Real scale = static_cast< ::rl::math::Real>(0.01); + ::rl::math::Real scale = static_cast<::rl::math::Real>(0.01); for (::std::size_t i = 0; i < this->getDistancesCount(); ++i) { @@ -138,7 +138,7 @@ ::std::cerr << "Measured value detected within warning field" << ::std::endl; ::std::cerr << "Measured value detected within protective field" << ::std::endl; case 32: ::std::cerr << "Glare (dazzling) detected" << ::std::endl; - distances(i) = ::std::numeric_limits< ::rl::math::Real>::quiet_NaN(); + distances(i) = ::std::numeric_limits<::rl::math::Real>::quiet_NaN(); break; default: distances(i) = value * scale; diff --git a/src/rl/hal/SickS300.h b/src/rl/hal/SickS300.h index 8ebfe37a..c0e5bb55 100644 --- a/src/rl/hal/SickS300.h +++ b/src/rl/hal/SickS300.h @@ -87,7 +87,7 @@ namespace rl ::std::size_t recv(::std::uint8_t* buf); - ::std::array< ::std::uint8_t, 2048> data; + ::std::array<::std::uint8_t, 2048> data; Serial serial; }; diff --git a/src/rl/hal/Socket.cpp b/src/rl/hal/Socket.cpp index 4aea8e9c..a8a6b2ac 100644 --- a/src/rl/hal/Socket.cpp +++ b/src/rl/hal/Socket.cpp @@ -128,9 +128,9 @@ namespace rl ::socklen_t addrlen = sizeof(addr); #ifdef WIN32 - SOCKET fd = ::accept(this->fd, reinterpret_cast< ::sockaddr*>(&addr), &addrlen); + SOCKET fd = ::accept(this->fd, reinterpret_cast<::sockaddr*>(&addr), &addrlen); #else // WIN32 - int fd = ::accept(this->fd, reinterpret_cast< ::sockaddr*>(&addr), &addrlen); + int fd = ::accept(this->fd, reinterpret_cast<::sockaddr*>(&addr), &addrlen); #endif // WIN32 #ifdef WIN32 @@ -403,7 +403,7 @@ namespace rl #ifdef WIN32 int numbytes = ::recvfrom(this->fd, static_cast(buf), count, 0, reinterpret_cast<::sockaddr*>(&addr), &addrlen); #else // WIN32 - ::ssize_t numbytes = ::recvfrom(this->fd, buf, count, 0, reinterpret_cast< ::sockaddr*>(&addr), reinterpret_cast< ::socklen_t*>(&addrlen)); + ::ssize_t numbytes = ::recvfrom(this->fd, buf, count, 0, reinterpret_cast<::sockaddr*>(&addr), reinterpret_cast<::socklen_t*>(&addrlen)); #endif // WIN32 address = Address(addr); @@ -427,8 +427,8 @@ namespace rl Socket::select(const bool& read, const bool& write, const ::std::chrono::nanoseconds& timeout) { ::timeval tv; - tv.tv_sec = ::std::chrono::duration_cast< ::std::chrono::seconds>(timeout).count(); - tv.tv_usec = ::std::chrono::duration_cast< ::std::chrono::microseconds>(timeout - ::std::chrono::duration_cast< ::std::chrono::seconds>(timeout)).count(); + tv.tv_sec = ::std::chrono::duration_cast<::std::chrono::seconds>(timeout).count(); + tv.tv_usec = ::std::chrono::duration_cast<::std::chrono::microseconds>(timeout - ::std::chrono::duration_cast<::std::chrono::seconds>(timeout)).count(); ::fd_set readfds; FD_ZERO(&readfds); @@ -746,11 +746,11 @@ namespace rl { case AF_INET: hexadecimal.resize(4); - ::std::memcpy(hexadecimal.data(), &reinterpret_cast< ::sockaddr_in*>(&this->addr)->sin_addr.s_addr, hexadecimal.size()); + ::std::memcpy(hexadecimal.data(), &reinterpret_cast<::sockaddr_in*>(&this->addr)->sin_addr.s_addr, hexadecimal.size()); break; case AF_INET6: hexadecimal.resize(16); - ::std::memcpy(hexadecimal.data(), &reinterpret_cast< ::sockaddr_in6*>(&this->addr)->sin6_addr.s6_addr, hexadecimal.size()); + ::std::memcpy(hexadecimal.data(), &reinterpret_cast<::sockaddr_in6*>(&this->addr)->sin6_addr.s6_addr, hexadecimal.size()); break; default: break; @@ -801,7 +801,7 @@ namespace rl void Socket::Address::setInfo(const ::std::string& string, const unsigned short int& port, const bool& asNumeric) { - this->setInfo(string, ::boost::lexical_cast< ::std::string>(port), asNumeric); + this->setInfo(string, ::boost::lexical_cast<::std::string>(port), asNumeric); } void diff --git a/src/rl/hal/UniversalRobotsDashboard.cpp b/src/rl/hal/UniversalRobotsDashboard.cpp index 9658d2a5..e154f968 100644 --- a/src/rl/hal/UniversalRobotsDashboard.cpp +++ b/src/rl/hal/UniversalRobotsDashboard.cpp @@ -60,7 +60,7 @@ namespace rl { this->send("addToLog " + message + "\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -83,7 +83,7 @@ namespace rl { this->send("brake release\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -102,7 +102,7 @@ namespace rl { this->send("close popup\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -121,7 +121,7 @@ namespace rl { this->send("close safety popup\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -140,7 +140,7 @@ namespace rl { this->send("get loaded program\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -163,7 +163,7 @@ namespace rl { this->send("isProgramSaved\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -186,7 +186,7 @@ namespace rl { this->send("load " + program + "\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -213,7 +213,7 @@ namespace rl { this->send("load installation " + installation + "\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -240,7 +240,7 @@ namespace rl { this->send("pause\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -263,7 +263,7 @@ namespace rl { this->send("play\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -286,7 +286,7 @@ namespace rl { this->send("PolyscopeVersion\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -298,7 +298,7 @@ namespace rl { this->send("popup " + text + "\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -317,7 +317,7 @@ namespace rl { this->send("power off\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -336,7 +336,7 @@ namespace rl { this->send("power on\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -355,7 +355,7 @@ namespace rl { this->send("programState\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -382,7 +382,7 @@ namespace rl { this->send("robotmode\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -433,7 +433,7 @@ namespace rl { this->send("running\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -456,7 +456,7 @@ namespace rl { this->send("safetymode\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -507,7 +507,7 @@ namespace rl { this->send("shutdown\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -526,7 +526,7 @@ namespace rl { this->send("stop\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -549,7 +549,7 @@ namespace rl { this->send("quit\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -568,7 +568,7 @@ namespace rl { this->send("unlock protective stop\n"); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); @@ -590,7 +590,7 @@ namespace rl this->socket.setOption(::rl::hal::Socket::OPTION_NODELAY, 1); this->setConnected(true); - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket.recv(buffer.data(), buffer.size()); ::std::string reply(reinterpret_cast(buffer.data()), size); } diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index a1156559..64068148 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -100,7 +100,7 @@ namespace rl ::rl::math::Vector3 orientation(this->in.toolVectorActual[3], this->in.toolVectorActual[4], this->in.toolVectorActual[5]); ::rl::math::Real norm = orientation.norm(); - if (::std::abs(norm) <= ::std::numeric_limits< ::rl::math::Real>::epsilon()) + if (::std::abs(norm) <= ::std::numeric_limits<::rl::math::Real>::epsilon()) { x.linear().setIdentity(); } @@ -252,7 +252,7 @@ namespace rl void UniversalRobotsRealtime::step() { - ::std::array< ::std::uint8_t, 1116> buffer; + ::std::array<::std::uint8_t, 1116> buffer; this->socket.recv(buffer.data(), sizeof(this->in.messageSize)); #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index a2632133..4e6ee14b 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -100,7 +100,7 @@ namespace rl return this->output.toolAnalogInput1; break; default: - return ::std::numeric_limits< ::rl::math::Real>::signaling_NaN(); + return ::std::numeric_limits<::rl::math::Real>::signaling_NaN(); } } @@ -128,7 +128,7 @@ namespace rl return 0 == (this->output.toolAnalogInputTypes & 2) ? 1 : 24; break; default: - return ::std::numeric_limits< ::rl::math::Real>::signaling_NaN(); + return ::std::numeric_limits<::rl::math::Real>::signaling_NaN(); break; } } @@ -139,10 +139,10 @@ namespace rl return 0; } - ::std::vector< ::rl::math::Unit> + ::std::vector<::rl::math::Unit> UniversalRobotsRtde::getAnalogInputUnit() const { - ::std::vector< ::rl::math::Unit> values; + ::std::vector<::rl::math::Unit> values; for (::std::size_t i = 0; i < this->getAnalogInputCount(); ++i) { @@ -193,7 +193,7 @@ namespace rl return this->output.toolOutputCurrent; break; default: - return ::std::numeric_limits< ::rl::math::Real>::signaling_NaN(); + return ::std::numeric_limits<::rl::math::Real>::signaling_NaN(); } } @@ -221,7 +221,7 @@ namespace rl return 1; break; default: - return ::std::numeric_limits< ::rl::math::Real>::signaling_NaN(); + return ::std::numeric_limits<::rl::math::Real>::signaling_NaN(); break; } } @@ -232,10 +232,10 @@ namespace rl return 0; } - ::std::vector< ::rl::math::Unit> + ::std::vector<::rl::math::Unit> UniversalRobotsRtde::getAnalogOutputUnit() const { - ::std::vector< ::rl::math::Unit> values; + ::std::vector<::rl::math::Unit> values; for (::std::size_t i = 0; i < this->getAnalogOutputCount(); ++i) { @@ -289,7 +289,7 @@ namespace rl ::rl::math::Vector3 orientation(this->output.actualTcpPose[3], this->output.actualTcpPose[4], this->output.actualTcpPose[5]); ::rl::math::Real norm = orientation.norm(); - if (::std::abs(norm) <= ::std::numeric_limits< ::rl::math::Real>::epsilon()) + if (::std::abs(norm) <= ::std::numeric_limits<::rl::math::Real>::epsilon()) { x.linear().setIdentity(); } @@ -313,7 +313,7 @@ namespace rl ::rl::math::Vector3 orientation(this->output.targetTcpPose[3], this->output.targetTcpPose[4], this->output.targetTcpPose[5]); ::rl::math::Real norm = orientation.norm(); - if (::std::abs(norm) <= ::std::numeric_limits< ::rl::math::Real>::epsilon()) + if (::std::abs(norm) <= ::std::numeric_limits<::rl::math::Real>::epsilon()) { x.linear().setIdentity(); } @@ -577,14 +577,14 @@ namespace rl "output_double_register_22", "output_double_register_23" }; - static const ::std::vector< ::std::string> outputs(::std::begin(outputsArray), ::std::end(outputsArray)); + static const ::std::vector<::std::string> outputs(::std::begin(outputsArray), ::std::end(outputsArray)); this->send(COMMAND_CONTROL_PACKAGE_SETUP_OUTPUTS, outputs); this->recv(); static const ::std::string inputs1Array[] = { "input_int_register_0" }; - static const ::std::vector< ::std::string> inputs1(::std::begin(inputs1Array), ::std::end(inputs1Array)); + static const ::std::vector<::std::string> inputs1(::std::begin(inputs1Array), ::std::end(inputs1Array)); this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs1); this->recv(); @@ -603,7 +603,7 @@ namespace rl "input_double_register_11", "input_double_register_12" }; - static const ::std::vector< ::std::string> inputs2(::std::begin(inputs2Array), ::std::end(inputs2Array)); + static const ::std::vector<::std::string> inputs2(::std::begin(inputs2Array), ::std::end(inputs2Array)); this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs2); this->recv(); @@ -613,7 +613,7 @@ namespace rl "standard_digital_output", "configurable_digital_output" }; - static const ::std::vector< ::std::string> inputs3(::std::begin(inputs3Array), ::std::end(inputs3Array)); + static const ::std::vector<::std::string> inputs3(::std::begin(inputs3Array), ::std::end(inputs3Array)); this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs3); this->recv(); @@ -623,7 +623,7 @@ namespace rl "standard_analog_output_0", "standard_analog_output_1" }; - static const ::std::vector< ::std::string> inputs4(::std::begin(inputs4Array), ::std::end(inputs4Array)); + static const ::std::vector<::std::string> inputs4(::std::begin(inputs4Array), ::std::end(inputs4Array)); this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs4); this->recv(); @@ -631,7 +631,7 @@ namespace rl "input_bit_registers0_to_31", "input_bit_registers32_to_63" }; - static const ::std::vector< ::std::string> inputs5(::std::begin(inputs5Array), ::std::end(inputs5Array)); + static const ::std::vector<::std::string> inputs5(::std::begin(inputs5Array), ::std::end(inputs5Array)); this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs5); this->recv(); } @@ -639,7 +639,7 @@ namespace rl void UniversalRobotsRtde::recv() { - ::std::array< ::std::uint8_t, 4096> buffer; + ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket4.recv(buffer.data(), buffer.size()); #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) this->socket4.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); @@ -792,12 +792,12 @@ namespace rl void UniversalRobotsRtde::send(::std::uint8_t* buffer, const ::std::size_t& size) { - if (size > ::std::numeric_limits< ::std::uint16_t>::max()) + if (size > ::std::numeric_limits<::std::uint16_t>::max()) { throw DeviceException("Package size too large"); } - ::std::uint16_t packageSize = static_cast< ::std::uint16_t>(size); + ::std::uint16_t packageSize = static_cast<::std::uint16_t>(size); buffer[0] = Endian::hostHighByte(packageSize); buffer[1] = Endian::hostLowByte(packageSize); @@ -808,7 +808,7 @@ namespace rl void UniversalRobotsRtde::send(const ::std::uint8_t& command) { - ::std::vector< ::std::uint8_t> buffer; + ::std::vector<::std::uint8_t> buffer; buffer.reserve(3); @@ -820,9 +820,9 @@ namespace rl } void - UniversalRobotsRtde::send(const ::std::uint8_t& command, const ::std::vector< ::std::string>& strings) + UniversalRobotsRtde::send(const ::std::uint8_t& command, const ::std::vector<::std::string>& strings) { - ::std::vector< ::std::uint8_t> buffer; + ::std::vector<::std::uint8_t> buffer; buffer.reserve(3); @@ -854,7 +854,7 @@ namespace rl void UniversalRobotsRtde::send(const ::std::uint8_t& command, const ::std::uint16_t& word) { - ::std::vector< ::std::uint8_t> buffer; + ::std::vector<::std::uint8_t> buffer; buffer.reserve(5); @@ -870,7 +870,7 @@ namespace rl void UniversalRobotsRtde::sendAnalogOutputs() { - ::std::vector< ::std::uint8_t> buffer; + ::std::vector<::std::uint8_t> buffer; buffer.reserve(4); @@ -894,7 +894,7 @@ namespace rl void UniversalRobotsRtde::sendBitRegisters() { - ::std::vector< ::std::uint8_t> buffer; + ::std::vector<::std::uint8_t> buffer; buffer.reserve(4); @@ -923,7 +923,7 @@ namespace rl void UniversalRobotsRtde::sendDigitalOutputs() { - ::std::vector< ::std::uint8_t> buffer; + ::std::vector<::std::uint8_t> buffer; buffer.reserve(4); @@ -947,7 +947,7 @@ namespace rl void UniversalRobotsRtde::sendDoubleRegister() { - ::std::vector< ::std::uint8_t> buffer; + ::std::vector<::std::uint8_t> buffer; buffer.reserve(4); @@ -971,7 +971,7 @@ namespace rl void UniversalRobotsRtde::sendIntegerRegister() { - ::std::vector< ::std::uint8_t> buffer; + ::std::vector<::std::uint8_t> buffer; buffer.reserve(4); @@ -1026,7 +1026,7 @@ namespace rl } void - UniversalRobotsRtde::setAnalogOutputUnit(const ::std::vector< ::rl::math::Unit>& values) + UniversalRobotsRtde::setAnalogOutputUnit(const ::std::vector<::rl::math::Unit>& values) { for (::std::size_t i = 0; i < this->getAnalogOutputCount(); ++i) { @@ -1184,9 +1184,9 @@ namespace rl program << '\t' << '\t' << "qd[5] = read_input_float_register(11)" << '\n'; program << '\t' << '\t' << "qdd = read_input_float_register(12)" << '\n'; #if 1 - program << '\t' << '\t' << "servoj(q, 0, 0, " << ::std::chrono::duration_cast< ::std::chrono::duration>(this->getUpdateRate()).count() << ", 0.03, 2000)" << '\n'; + program << '\t' << '\t' << "servoj(q, 0, 0, " << ::std::chrono::duration_cast<::std::chrono::duration>(this->getUpdateRate()).count() << ", 0.03, 2000)" << '\n'; #else - program << '\t' << '\t' << "speedj(qd, qdd, " << ::std::chrono::duration_cast< ::std::chrono::duration>(this->getUpdateRate()).count() << ")" << '\n'; + program << '\t' << '\t' << "speedj(qd, qdd, " << ::std::chrono::duration_cast<::std::chrono::duration>(this->getUpdateRate()).count() << ")" << '\n'; #endif program << '\t' << "end" << '\n'; program << "end" << '\n'; diff --git a/src/rl/hal/UniversalRobotsRtde.h b/src/rl/hal/UniversalRobotsRtde.h index ede3a9e6..b3fff278 100644 --- a/src/rl/hal/UniversalRobotsRtde.h +++ b/src/rl/hal/UniversalRobotsRtde.h @@ -169,7 +169,7 @@ namespace rl ::rl::math::Real getAnalogInputMinimum(const ::std::size_t& i) const; - ::std::vector< ::rl::math::Unit> getAnalogInputUnit() const; + ::std::vector<::rl::math::Unit> getAnalogInputUnit() const; ::rl::math::Unit getAnalogInputUnit(const ::std::size_t& i) const; @@ -183,7 +183,7 @@ namespace rl ::rl::math::Real getAnalogOutputMinimum(const ::std::size_t& i) const; - ::std::vector< ::rl::math::Unit> getAnalogOutputUnit() const; + ::std::vector<::rl::math::Unit> getAnalogOutputUnit() const; ::rl::math::Unit getAnalogOutputUnit(const ::std::size_t& i) const; @@ -235,7 +235,7 @@ namespace rl void setAnalogOutput(const ::std::size_t& i, const ::rl::math::Real& value); - void setAnalogOutputUnit(const ::std::vector< ::rl::math::Unit>& values); + void setAnalogOutputUnit(const ::std::vector<::rl::math::Unit>& values); void setAnalogOutputUnit(const ::std::size_t& i, const ::rl::math::Unit& value); @@ -272,29 +272,29 @@ namespace rl struct Input { - ::boost::optional< ::std::uint8_t> configurableDigitalOutput; + ::boost::optional<::std::uint8_t> configurableDigitalOutput; - ::boost::optional< ::std::uint8_t> configurableDigitalOutputMask; + ::boost::optional<::std::uint8_t> configurableDigitalOutputMask; - ::boost::optional< ::std::uint32_t> inputBitRegisters0; + ::boost::optional<::std::uint32_t> inputBitRegisters0; - ::boost::optional< ::std::uint32_t> inputBitRegisters1; + ::boost::optional<::std::uint32_t> inputBitRegisters1; ::std::vector inputDoubleRegister; - ::std::vector< ::std::int32_t> inputIntRegister; + ::std::vector<::std::int32_t> inputIntRegister; ::boost::optional standardAnalogOutput0; ::boost::optional standardAnalogOutput1; - ::boost::optional< ::std::uint8_t> standardAnalogOutputMask; + ::boost::optional<::std::uint8_t> standardAnalogOutputMask; ::std::uint8_t standardAnalogOutputType; - ::boost::optional< ::std::uint8_t> standardDigitalOutput; + ::boost::optional<::std::uint8_t> standardDigitalOutput; - ::boost::optional< ::std::uint8_t> standardDigitalOutputMask; + ::boost::optional<::std::uint8_t> standardDigitalOutputMask; }; struct Output @@ -381,7 +381,7 @@ namespace rl void send(const ::std::uint8_t& command); - void send(const ::std::uint8_t& command, const ::std::vector< ::std::string>& strings); + void send(const ::std::uint8_t& command, const ::std::vector<::std::string>& strings); void send(const ::std::uint8_t& command, const ::std::uint16_t& word); diff --git a/src/rl/hal/WeissKms40.cpp b/src/rl/hal/WeissKms40.cpp index 0186f0bd..a6646e04 100644 --- a/src/rl/hal/WeissKms40.cpp +++ b/src/rl/hal/WeissKms40.cpp @@ -88,7 +88,7 @@ namespace rl return frame; } - ::std::pair< ::std::chrono::system_clock::time_point, ::std::chrono::system_clock::duration> + ::std::pair<::std::chrono::system_clock::time_point, ::std::chrono::system_clock::duration> WeissKms40::doGetCalibrationDateLifetime() { ::std::string command = "CALDATE()\n"; @@ -243,8 +243,8 @@ namespace rl return ::std::stoi(reply.substr(3)); } - ::std::vector< ::std::string> - WeissKms40::doPrintVariable(const ::std::vector< ::std::string>& variables) + ::std::vector<::std::string> + WeissKms40::doPrintVariable(const ::std::vector<::std::string>& variables) { ::std::string command = "PRINT("; @@ -258,7 +258,7 @@ namespace rl ::std::string reply = this->recv("PRINT="); - ::std::vector< ::std::string> values(variables.size()); + ::std::vector<::std::string> values(variables.size()); for (::std::size_t i = 0, start = 6; i < 6; ++i) { @@ -401,7 +401,7 @@ namespace rl return 3; break; default: - return ::std::numeric_limits< ::rl::math::Real>::signaling_NaN(); + return ::std::numeric_limits<::rl::math::Real>::signaling_NaN(); break; } } @@ -422,7 +422,7 @@ namespace rl return -3; break; default: - return ::std::numeric_limits< ::rl::math::Real>::signaling_NaN(); + return ::std::numeric_limits<::rl::math::Real>::signaling_NaN(); break; } } diff --git a/src/rl/hal/WeissKms40.h b/src/rl/hal/WeissKms40.h index a0d49dbd..7b913458 100644 --- a/src/rl/hal/WeissKms40.h +++ b/src/rl/hal/WeissKms40.h @@ -92,7 +92,7 @@ namespace rl ::rl::math::Vector doAcquireSingleFrame(); - ::std::pair< ::std::chrono::system_clock::time_point, ::std::chrono::system_clock::duration> doGetCalibrationDateLifetime(); + ::std::pair<::std::chrono::system_clock::time_point, ::std::chrono::system_clock::duration> doGetCalibrationDateLifetime(); ::rl::math::Matrix doGetCalibrationMatrix(); @@ -121,7 +121,7 @@ namespace rl ::std::size_t doGetVerboseLevel(); - ::std::vector< ::std::string> doPrintVariable(const ::std::vector< ::std::string>& variables); + ::std::vector<::std::string> doPrintVariable(const ::std::vector<::std::string>& variables); ::boost::dynamic_bitset<> doSetDataAcquisitionMask(const ::boost::dynamic_bitset<>& mask); diff --git a/src/rl/hal/WeissWsg50.cpp b/src/rl/hal/WeissWsg50.cpp index 1e7fbabf..66a507bd 100644 --- a/src/rl/hal/WeissWsg50.cpp +++ b/src/rl/hal/WeissWsg50.cpp @@ -147,7 +147,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x24; buf[this->HEADER_SIZE] = 0x61; @@ -163,7 +163,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x36; @@ -179,7 +179,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x07; @@ -192,7 +192,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x23; @@ -205,7 +205,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x31; @@ -222,7 +222,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x45; buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doAutomaticUpdate << 1); @@ -238,7 +238,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x33; @@ -253,7 +253,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x41; buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); @@ -269,7 +269,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x42; buf[this->HEADER_SIZE] = 0x00 | doReset; @@ -287,7 +287,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x43; buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); @@ -303,7 +303,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x35; @@ -322,7 +322,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x44; buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); @@ -338,7 +338,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x50; @@ -356,7 +356,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x53; @@ -384,7 +384,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x40; buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); @@ -407,7 +407,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x46; @@ -429,7 +429,7 @@ namespace rl float widthMilli = width * static_cast(::rl::math::UNIT2MILLI); float speedMilli = speed * static_cast(::rl::math::UNIT2MILLI); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x25; ::std::memcpy(&buf[this->HEADER_SIZE], &widthMilli, sizeof(widthMilli)); @@ -447,7 +447,7 @@ namespace rl assert(this->isConnected()); assert(direction < 3); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x20; buf[this->HEADER_SIZE] = direction; @@ -462,7 +462,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x37; buf[4] = 0x00; @@ -486,7 +486,7 @@ namespace rl float widthMilli = width * static_cast(::rl::math::UNIT2MILLI); float speedMilli = speed * static_cast(::rl::math::UNIT2MILLI); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x21; buf[this->HEADER_SIZE] = 0x00; @@ -519,7 +519,7 @@ namespace rl float widthMilli = width * static_cast(::rl::math::UNIT2MILLI); float speedMilli = speed * static_cast(::rl::math::UNIT2MILLI); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x26; ::std::memcpy(&buf[this->HEADER_SIZE], &widthMilli, sizeof(widthMilli)); @@ -537,7 +537,7 @@ namespace rl float accelerationMilli = acceleration * static_cast(::rl::math::UNIT2MILLI); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x30; ::std::memcpy(&buf[this->HEADER_SIZE], &accelerationMilli, sizeof(accelerationMilli)); @@ -554,7 +554,7 @@ namespace rl assert(this->isConnected()); assert(force >= 5.0f && force <= 80.0f); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x32; ::std::memcpy(&buf[this->HEADER_SIZE], &force, sizeof(force)); @@ -573,7 +573,7 @@ namespace rl float limitMinusMilli = limitMinus * static_cast(::rl::math::UNIT2MILLI); float limitPlusMilli = limitPlus * static_cast(::rl::math::UNIT2MILLI); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x34; ::std::memcpy(&buf[this->HEADER_SIZE], &limitMinusMilli, sizeof(limitMinusMilli)); @@ -591,7 +591,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x22; @@ -604,7 +604,7 @@ namespace rl { assert(this->isConnected()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x38; @@ -909,7 +909,7 @@ namespace rl assert(this->isConnected()); assert(this->isRunning()); - ::std::array< ::std::uint8_t, 64> buf; + ::std::array<::std::uint8_t, 64> buf; this->recv(buf.data()); // doGetForce this->recv(buf.data()); // doGetGraspingState diff --git a/src/rl/kin/Joint.h b/src/rl/kin/Joint.h index 1d23af1e..a2d00b10 100644 --- a/src/rl/kin/Joint.h +++ b/src/rl/kin/Joint.h @@ -61,7 +61,7 @@ namespace rl ::rl::math::Real d; - ::std::unordered_set< ::std::size_t> leaves; + ::std::unordered_set<::std::size_t> leaves; ::rl::math::Real max; diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 36d94940..796e94fe 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -141,7 +141,7 @@ namespace rl ::rl::xml::Path path(document); - ::rl::xml::NodeSet instances = path.eval("(/rl/kin|/rlkin)/kinematics|(/rl/kin|/rlkin)/puma|(/rl/kin|/rlkin)/rhino").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet instances = path.eval("(/rl/kin|/rlkin)/kinematics|(/rl/kin|/rlkin)/puma|(/rl/kin|/rlkin)/rhino").getValue<::rl::xml::NodeSet>(); if (instances.empty()) { @@ -171,17 +171,17 @@ namespace rl // manufacturer - kinematics->manufacturer = path.eval("string(manufacturer)").getValue< ::std::string>(); + kinematics->manufacturer = path.eval("string(manufacturer)").getValue<::std::string>(); // name - kinematics->name = path.eval("string(name)").getValue< ::std::string>(); + kinematics->name = path.eval("string(name)").getValue<::std::string>(); // frames - ::rl::xml::NodeSet frames = path.eval("frame|link|world").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet frames = path.eval("frame|link|world").getValue<::rl::xml::NodeSet>(); - ::std::map< ::std::string, Vertex> id2vertex; + ::std::map<::std::string, Vertex> id2vertex; for (int j = 0; j < frames.size(); ++j) { @@ -193,24 +193,24 @@ namespace rl { Frame* f = new Frame(); - f->name = path.eval("string(@id)").getValue< ::std::string>(); + f->name = path.eval("string(@id)").getValue<::std::string>(); f->frame.setIdentity(); f->frame = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX() ); - f->frame.translation().x() = path.eval("number(translation/x)").getValue< ::rl::math::Real>(0); - f->frame.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); - f->frame.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); + f->frame.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); + f->frame.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); + f->frame.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); kinematics->tree[v].reset(f); } @@ -218,7 +218,7 @@ namespace rl { Link* l = new Link(); - l->name = path.eval("string(@id)").getValue< ::std::string>(); + l->name = path.eval("string(@id)").getValue<::std::string>(); kinematics->tree[v].reset(l); } @@ -226,31 +226,31 @@ namespace rl { Frame* f = new Frame(); - f->name = path.eval("string(@id)").getValue< ::std::string>(); + f->name = path.eval("string(@id)").getValue<::std::string>(); f->frame.setIdentity(); f->frame = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX() ); - f->frame.translation().x() = path.eval("number(translation/x)").getValue< ::rl::math::Real>(0); - f->frame.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); - f->frame.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); + f->frame.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); + f->frame.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); + f->frame.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); kinematics->root = v; kinematics->tree[v].reset(f); } - ::std::string id = path.eval("string(@id)").getValue< ::std::string>(); + ::std::string id = path.eval("string(@id)").getValue<::std::string>(); if (id2vertex.find(id) != id2vertex.end()) { @@ -266,7 +266,7 @@ namespace rl if ("link" == frames[j].getName()) { - ::std::string v1Id = path.eval("string(@id)").getValue< ::std::string>(); + ::std::string v1Id = path.eval("string(@id)").getValue<::std::string>(); if (id2vertex.find(v1Id) == id2vertex.end()) { @@ -276,7 +276,7 @@ namespace rl Vertex v1 = id2vertex[v1Id]; Link* l1 = dynamic_cast(kinematics->tree[v1].get()); - ::rl::xml::NodeSet ignores = path.eval("ignore").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet ignores = path.eval("ignore").getValue<::rl::xml::NodeSet>(); for (int k = 0; k < ignores.size(); ++k) { @@ -305,15 +305,15 @@ namespace rl // transforms - ::rl::xml::NodeSet transforms = path.eval("prismatic|revolute|transform").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet transforms = path.eval("prismatic|revolute|transform").getValue<::rl::xml::NodeSet>(); for (int j = 0; j < transforms.size(); ++j) { ::rl::xml::Path path(document, transforms[j]); - ::std::string name = path.eval("string(@id)").getValue< ::std::string>(); + ::std::string name = path.eval("string(@id)").getValue<::std::string>(); - ::std::string aIdRef = path.eval("string(frame/a/@idref)").getValue< ::std::string>(); + ::std::string aIdRef = path.eval("string(frame/a/@idref)").getValue<::std::string>(); if (id2vertex.find(aIdRef) == id2vertex.end()) { @@ -322,7 +322,7 @@ namespace rl Vertex a = id2vertex[aIdRef]; - ::std::string bIdRef = path.eval("string(frame/b/@idref)").getValue< ::std::string>(); + ::std::string bIdRef = path.eval("string(frame/b/@idref)").getValue<::std::string>(); if (id2vertex.find(bIdRef) == id2vertex.end()) { @@ -339,14 +339,14 @@ namespace rl p->name = name; - p->a = path.eval("number(dh/a)").getValue< ::rl::math::Real>(0); - p->alpha = path.eval("number(dh/alpha)").getValue< ::rl::math::Real>(0); - p->d = path.eval("number(dh/d)").getValue< ::rl::math::Real>(0); - p->max = path.eval("number(max)").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - p->min = path.eval("number(min)").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - p->offset = path.eval("number(offset)").getValue< ::rl::math::Real>(0); - p->speed = path.eval("number(speed)").getValue< ::rl::math::Real>(0); - p->theta = path.eval("number(dh/theta)").getValue< ::rl::math::Real>(0); + p->a = path.eval("number(dh/a)").getValue<::rl::math::Real>(0); + p->alpha = path.eval("number(dh/alpha)").getValue<::rl::math::Real>(0); + p->d = path.eval("number(dh/d)").getValue<::rl::math::Real>(0); + p->max = path.eval("number(max)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + p->min = path.eval("number(min)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + p->offset = path.eval("number(offset)").getValue<::rl::math::Real>(0); + p->speed = path.eval("number(speed)").getValue<::rl::math::Real>(0); + p->theta = path.eval("number(dh/theta)").getValue<::rl::math::Real>(0); p->wraparound = path.eval("count(wraparound) > 0").getValue(); p->alpha *= ::rl::math::DEG2RAD; @@ -360,14 +360,14 @@ namespace rl r->name = name; - r->a = path.eval("number(dh/a)").getValue< ::rl::math::Real>(0); - r->alpha = path.eval("number(dh/alpha)").getValue< ::rl::math::Real>(0); - r->d = path.eval("number(dh/d)").getValue< ::rl::math::Real>(0); - r->max = path.eval("number(max)").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - r->min = path.eval("number(min)").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - r->offset = path.eval("number(offset)").getValue< ::rl::math::Real>(0); - r->speed = path.eval("number(speed)").getValue< ::rl::math::Real>(0); - r->theta = path.eval("number(dh/theta)").getValue< ::rl::math::Real>(0); + r->a = path.eval("number(dh/a)").getValue<::rl::math::Real>(0); + r->alpha = path.eval("number(dh/alpha)").getValue<::rl::math::Real>(0); + r->d = path.eval("number(dh/d)").getValue<::rl::math::Real>(0); + r->max = path.eval("number(max)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + r->min = path.eval("number(min)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + r->offset = path.eval("number(offset)").getValue<::rl::math::Real>(0); + r->speed = path.eval("number(speed)").getValue<::rl::math::Real>(0); + r->theta = path.eval("number(dh/theta)").getValue<::rl::math::Real>(0); r->wraparound = path.eval("count(wraparound) > 0").getValue(); r->alpha *= ::rl::math::DEG2RAD; @@ -388,19 +388,19 @@ namespace rl t->transform.setIdentity(); t->transform = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX() ); - t->transform.translation().x() = path.eval("number(translation/x)").getValue< ::rl::math::Real>(0); - t->transform.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); - t->transform.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); + t->transform.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); + t->transform.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); + t->transform.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); kinematics->tree[e].reset(t); } @@ -657,7 +657,7 @@ namespace rl } void - Kinematics::getPositionUnits(::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const + Kinematics::getPositionUnits(::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const { for (::std::size_t i = 0; i < this->joints.size(); ++i) { @@ -675,7 +675,7 @@ namespace rl } void - Kinematics::getSpeedUnits(::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const + Kinematics::getSpeedUnits(::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const { for (::std::size_t i = 0; i < this->joints.size(); ++i) { @@ -847,8 +847,8 @@ namespace rl #if 0 return !(this->getManipulabilityMeasure() > 0); #else - ::Eigen::JacobiSVD< ::rl::math::Matrix> svd(this->jacobian); - return (::std::abs(svd.singularValues()(svd.singularValues().size() - 1)) > ::std::numeric_limits< ::rl::math::Real>::epsilon()) ? false : true; + ::Eigen::JacobiSVD<::rl::math::Matrix> svd(this->jacobian); + return (::std::abs(svd.singularValues()(svd.singularValues().size() - 1)) > ::std::numeric_limits<::rl::math::Real>::epsilon()) ? false : true; #endif } @@ -877,7 +877,7 @@ namespace rl } } - ::std::uniform_real_distribution< ::rl::math::Real>::result_type + ::std::uniform_real_distribution<::rl::math::Real>::result_type Kinematics::rand() { return this->randDistribution(this->randEngine); @@ -1118,10 +1118,10 @@ namespace rl { this->jacobianInverse.setZero(); - ::Eigen::JacobiSVD< ::rl::math::Matrix> svd(this->jacobian, ::Eigen::ComputeFullU | ::Eigen::ComputeFullV); + ::Eigen::JacobiSVD<::rl::math::Matrix> svd(this->jacobian, ::Eigen::ComputeFullU | ::Eigen::ComputeFullV); ::rl::math::Real wMin = svd.singularValues().minCoeff(); - ::rl::math::Real lambdaSqr = wMin < static_cast< ::rl::math::Real>(1.0e-9) ? (1 - ::std::pow((wMin / static_cast< ::rl::math::Real>(1.0e-9)), 2)) * ::std::pow(lambda, 2) : 0; + ::rl::math::Real lambdaSqr = wMin < static_cast<::rl::math::Real>(1.0e-9) ? (1 - ::std::pow((wMin / static_cast<::rl::math::Real>(1.0e-9)), 2)) * ::std::pow(lambda, 2) : 0; for (::std::ptrdiff_t i = 0; i < svd.nonzeroSingularValues(); ++i) { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index c8699ece..894e3e3d 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -188,11 +188,11 @@ namespace rl */ void getPosition(::rl::math::Vector& q) const; - void getPositionUnits(::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const; + void getPositionUnits(::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const; void getSpeed(::rl::math::Vector& speed) const; - void getSpeedUnits(::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const; + void getSpeedUnits(::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const; void getWraparounds(::Eigen::Matrix& wraparounds) const; @@ -219,8 +219,8 @@ namespace rl const ::rl::math::Transform& x, ::rl::math::Vector& q, const ::std::size_t& leaf = 0, - const ::rl::math::Real& delta = ::std::numeric_limits< ::rl::math::Real>::infinity(), - const ::rl::math::Real& epsilon = static_cast< ::rl::math::Real>(1.0e-3), + const ::rl::math::Real& delta = ::std::numeric_limits<::rl::math::Real>::infinity(), + const ::rl::math::Real& epsilon = static_cast<::rl::math::Real>(1.0e-3), const ::std::size_t& iterations = 10000, const ::std::chrono::nanoseconds& duration = ::std::chrono::milliseconds(1000) ); @@ -384,9 +384,9 @@ namespace rl Tree tree; private: - ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + ::std::uniform_real_distribution<::rl::math::Real>::result_type rand(); - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; }; diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index 88d25edb..48fd7ab1 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -82,12 +82,12 @@ namespace rl && this->joints[4]->a == 0 && this->joints[5]->a == 0 && this->joints[4]->d == 0); - assert(::std::abs(this->joints[0]->alpha - (-static_cast< ::rl::math::Real>(M_PI)/2)) < 1e-3 - && ::std::abs(this->joints[1]->alpha ) < 1e-3 - && ::std::abs(this->joints[2]->alpha - (-static_cast< ::rl::math::Real>(M_PI)/2)) < 1e-3 - && ::std::abs(this->joints[3]->alpha - ( static_cast< ::rl::math::Real>(M_PI)/2)) < 1e-3 - && ::std::abs(this->joints[4]->alpha - ( static_cast< ::rl::math::Real>(M_PI)/2)) < 1e-3 - && ::std::abs(this->joints[5]->alpha ) < 1e-3); + assert(::std::abs(this->joints[0]->alpha - (-static_cast<::rl::math::Real>(M_PI)/2)) < 1e-3 + && ::std::abs(this->joints[1]->alpha ) < 1e-3 + && ::std::abs(this->joints[2]->alpha - (-static_cast<::rl::math::Real>(M_PI)/2)) < 1e-3 + && ::std::abs(this->joints[3]->alpha - ( static_cast<::rl::math::Real>(M_PI)/2)) < 1e-3 + && ::std::abs(this->joints[4]->alpha - ( static_cast<::rl::math::Real>(M_PI)/2)) < 1e-3 + && ::std::abs(this->joints[5]->alpha ) < 1e-3); ::rl::math::Real a1 = this->joints[0]->a; ::rl::math::Real a2 = this->joints[1]->a; @@ -174,7 +174,7 @@ namespace rl } // arm elbow configuration - ::rl::math::Real K = static_cast< ::rl::math::Real>(arm * elbow); + ::rl::math::Real K = static_cast<::rl::math::Real>(arm * elbow); // arm ::rl::math::Real theta2 = K * ::std::acos(cosalpha) + deltaWrist; @@ -194,10 +194,10 @@ namespace rl ::rl::math::Real theta3plusbeta = ::std::acos(costheta3plusbeta); // elbow - ::rl::math::Real theta3 = K * theta3plusbeta - beta - static_cast< ::rl::math::Real>(M_PI); + ::rl::math::Real theta3 = K * theta3plusbeta - beta - static_cast<::rl::math::Real>(M_PI); - ::rl::math::Real c23 = this->cos(theta2 + theta3 + static_cast< ::rl::math::Real>(M_PI)); - ::rl::math::Real s23 = this->sin(theta2 + theta3 + static_cast< ::rl::math::Real>(M_PI)); + ::rl::math::Real c23 = this->cos(theta2 + theta3 + static_cast<::rl::math::Real>(M_PI)); + ::rl::math::Real s23 = this->sin(theta2 + theta3 + static_cast<::rl::math::Real>(M_PI)); // forearm @@ -225,7 +225,7 @@ namespace rl c1 * s23 * a(0) + s1 * s23 * a(1) + c23 * a(2) - ) + static_cast< ::rl::math::Real>(M_PI); + ) + static_cast<::rl::math::Real>(M_PI); // flange @@ -260,7 +260,7 @@ namespace rl bool Puma::isSingular() const { - return (::std::abs(this->jacobian.determinant()) > static_cast< ::rl::math::Real>(1.0e-9)) ? false : true ; + return (::std::abs(this->jacobian.determinant()) > static_cast<::rl::math::Real>(1.0e-9)) ? false : true ; } void @@ -274,9 +274,9 @@ namespace rl { myq(i) = q(i) + this->joints[i]->theta + this->joints[i]->offset; myq(i) = ::std::fmod( - myq(i) + static_cast< ::rl::math::Real>(M_PI), - 2 * static_cast< ::rl::math::Real>(M_PI) - ) - static_cast< ::rl::math::Real>(M_PI); + myq(i) + static_cast<::rl::math::Real>(M_PI), + 2 * static_cast<::rl::math::Real>(M_PI) + ) - static_cast<::rl::math::Real>(M_PI); } if (myq(4) < 0) diff --git a/src/rl/kin/Puma.h b/src/rl/kin/Puma.h index d3ea8e22..a794c4ad 100644 --- a/src/rl/kin/Puma.h +++ b/src/rl/kin/Puma.h @@ -85,19 +85,19 @@ namespace rl template T atan2(const T& y, const T& x) const { T a = ::std::atan2(y, x); - return (::std::abs(a) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : a; + return (::std::abs(a) <= static_cast<::rl::math::Real>(1.0e-6)) ? 0 : a; } template T cos(const T& x) const { T c = ::std::cos(x); - return (::std::abs(c) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : c; + return (::std::abs(c) <= static_cast<::rl::math::Real>(1.0e-6)) ? 0 : c; } template T sin(const T& x) const { T s = ::std::sin(x); - return (::std::abs(s) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : s; + return (::std::abs(s) <= static_cast<::rl::math::Real>(1.0e-6)) ? 0 : s; } Arm arm; diff --git a/src/rl/kin/Revolute.cpp b/src/rl/kin/Revolute.cpp index a15bf1e9..dbc66963 100644 --- a/src/rl/kin/Revolute.cpp +++ b/src/rl/kin/Revolute.cpp @@ -79,15 +79,15 @@ namespace rl void Revolute::normalize(::rl::math::Real& q) { - q = ::std::remainder(q, 2 * static_cast< ::rl::math::Real>(M_PI)); + q = ::std::remainder(q, 2 * static_cast<::rl::math::Real>(M_PI)); if (q < this->min) { - q += 2 * static_cast< ::rl::math::Real>(M_PI); + q += 2 * static_cast<::rl::math::Real>(M_PI); } else if (q > this->max) { - q -= 2 * static_cast< ::rl::math::Real>(M_PI); + q -= 2 * static_cast<::rl::math::Real>(M_PI); } } diff --git a/src/rl/kin/Rhino.cpp b/src/rl/kin/Rhino.cpp index 838cc82d..51858246 100644 --- a/src/rl/kin/Rhino.cpp +++ b/src/rl/kin/Rhino.cpp @@ -109,7 +109,7 @@ namespace rl ::rl::math::Real py0_2 = ::std::pow(py0, 2); ::rl::math::Real pz0_2 = ::std::pow(pz0, 2); - ::rl::math::Real K = static_cast< ::rl::math::Real>(arm * elbow); + ::rl::math::Real K = static_cast<::rl::math::Real>(arm * elbow); ::rl::math::Real r_2 = px0_2 + py0_2; ::rl::math::Real r = ::std::sqrt(r_2); @@ -117,7 +117,7 @@ namespace rl ::rl::math::Real Q_2 = r_2 + pz0_2; ::rl::math::Real Q = ::std::sqrt(Q_2); - if (::std::abs(Q) <= ::std::numeric_limits< ::rl::math::Real>::epsilon()) + if (::std::abs(Q) <= ::std::numeric_limits<::rl::math::Real>::epsilon()) { return false; } @@ -138,13 +138,13 @@ namespace rl ::rl::math::Real c2 = cosAlpha * cosBeta - K * sinAlpha * sinBeta; // arm - ::rl::math::Real theta2 = this->atan2(s2, c2) + static_cast< ::rl::math::Real>(M_PI_2); + ::rl::math::Real theta2 = this->atan2(s2, c2) + static_cast<::rl::math::Real>(M_PI_2); ::rl::math::Real c3 = (a2_2 + a3_2 - Q_2) / (2 * a2 * a3); ::rl::math::Real s3 = K * ::std::sqrt(1 - ::std::pow(c3, 2)); // elbow - ::rl::math::Real theta3 = this->atan2(s3, c3) + static_cast< ::rl::math::Real>(M_PI); + ::rl::math::Real theta3 = this->atan2(s3, c3) + static_cast<::rl::math::Real>(M_PI); ::rl::math::Real c23 = this->cos(theta2 + theta3); ::rl::math::Real s23 = this->sin(theta2 + theta3); diff --git a/src/rl/kin/Rhino.h b/src/rl/kin/Rhino.h index c5eef4c5..8803d4bf 100644 --- a/src/rl/kin/Rhino.h +++ b/src/rl/kin/Rhino.h @@ -73,19 +73,19 @@ namespace rl template T atan2(const T& y, const T& x) const { T a = ::std::atan2(y, x); - return (::std::abs(a) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : a; + return (::std::abs(a) <= static_cast<::rl::math::Real>(1.0e-6)) ? 0 : a; } template T cos(const T& x) const { T c = ::std::cos(x); - return (::std::abs(c) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : c; + return (::std::abs(c) <= static_cast<::rl::math::Real>(1.0e-6)) ? 0 : c; } template T sin(const T& x) const { T s = ::std::sin(x); - return (::std::abs(s) <= static_cast< ::rl::math::Real>(1.0e-6)) ? 0 : s; + return (::std::abs(s) <= static_cast<::rl::math::Real>(1.0e-6)) ? 0 : s; } Arm arm; diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index 8dbf614c..ee731b2d 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -162,7 +162,7 @@ namespace rl return this->root.removed && this->root.data.empty() && this->root.children.empty(); } - ::boost::optional< ::std::size_t> getChecks() const + ::boost::optional<::std::size_t> getChecks() const { return this->checks; } @@ -231,7 +231,7 @@ namespace rl this->generator.seed(value); } - void setChecks(const ::boost::optional< ::std::size_t>& checks) + void setChecks(const ::boost::optional<::std::size_t>& checks) { this->checks = checks; } @@ -370,12 +370,12 @@ namespace rl bool removed; }; - void choose(const Node& node, ::std::vector< ::std::size_t>& centers, ::std::vector< ::std::vector>& distances) + void choose(const Node& node, ::std::vector<::std::size_t>& centers, ::std::vector<::std::vector>& distances) { ::std::size_t k = node.degree; ::std::vector min(node.data.size(), ::std::numeric_limits::infinity()); - ::std::uniform_int_distribution< ::std::size_t> distribution(0, node.data.size() - 1); + ::std::uniform_int_distribution<::std::size_t> distribution(0, node.data.size() - 1); centers[0] = distribution(this->generator); for (::std::size_t i = 0; i < k - 1; ++i) @@ -599,8 +599,8 @@ namespace rl void split(Node& node) { - ::std::vector< ::std::vector> distances(node.degree, ::std::vector(node.data.size())); - ::std::vector< ::std::size_t> centers(node.degree); + ::std::vector<::std::vector> distances(node.degree, ::std::vector(node.data.size())); + ::std::vector<::std::size_t> centers(node.degree); this->choose(node, centers, distances); for (::std::size_t i = 0; i < centers.size(); ++i) @@ -676,7 +676,7 @@ namespace rl } } - ::boost::optional< ::std::size_t> checks; + ::boost::optional<::std::size_t> checks; ::std::mt19937 generator; diff --git a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h index 3c3366bb..e079e3bf 100644 --- a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h @@ -151,7 +151,7 @@ namespace rl return this->root.data.empty() && nullptr == this->root.children[0] && nullptr == this->root.children[1]; } - ::boost::optional< ::std::size_t> getChecks() const + ::boost::optional<::std::size_t> getChecks() const { return this->checks; } @@ -233,7 +233,7 @@ namespace rl return this->search(query, nullptr, &radius, sorted); } - void setChecks(const ::boost::optional< ::std::size_t>& checks) + void setChecks(const ::boost::optional<::std::size_t>& checks) { this->checks = checks; } @@ -374,7 +374,7 @@ namespace rl lhs.swap(rhs); } - ::std::array< ::std::unique_ptr, 2> children; + ::std::array<::std::unique_ptr, 2> children; ::std::vector data; @@ -690,7 +690,7 @@ namespace rl BoundingBox boundingBox; - ::boost::optional< ::std::size_t> checks; + ::boost::optional<::std::size_t> checks; Metric metric; diff --git a/src/rl/math/KdtreeNearestNeighbors.h b/src/rl/math/KdtreeNearestNeighbors.h index 3fbdf06f..8c0f052e 100644 --- a/src/rl/math/KdtreeNearestNeighbors.h +++ b/src/rl/math/KdtreeNearestNeighbors.h @@ -153,7 +153,7 @@ namespace rl return !this->root.data && nullptr == this->root.children[0] && nullptr == this->root.children[1]; } - ::boost::optional< ::std::size_t> getChecks() const + ::boost::optional<::std::size_t> getChecks() const { return this->checks; } @@ -206,7 +206,7 @@ namespace rl return this->search(query, nullptr, &radius, sorted); } - void setChecks(const ::boost::optional< ::std::size_t>& checks) + void setChecks(const ::boost::optional<::std::size_t>& checks) { this->checks = checks; } @@ -318,7 +318,7 @@ namespace rl lhs.swap(rhs); } - ::std::array< ::std::unique_ptr, 2> children; + ::std::array<::std::unique_ptr, 2> children; Cut cut; @@ -558,7 +558,7 @@ namespace rl return cut; } - ::boost::optional< ::std::size_t> checks; + ::boost::optional<::std::size_t> checks; ::std::vector mean; diff --git a/src/rl/math/LinearNearestNeighbors.h b/src/rl/math/LinearNearestNeighbors.h index 3574dc3b..cfa3e65e 100644 --- a/src/rl/math/LinearNearestNeighbors.h +++ b/src/rl/math/LinearNearestNeighbors.h @@ -259,7 +259,7 @@ namespace rl } #ifdef _OPENMP - ::std::vector< ::std::vector> neighbors2(::omp_get_max_threads()); + ::std::vector<::std::vector> neighbors2(::omp_get_max_threads()); if (nullptr != k) { diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index aaf62211..a88ec20b 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -708,10 +708,10 @@ namespace rl */ template static Spline QuarticLinearQuarticAtRest( - const typename ::std::enable_if< ::std::is_floating_point::value, U>::type& q0, - const typename ::std::enable_if< ::std::is_floating_point::value, U>::type& q1, - const typename ::std::enable_if< ::std::is_floating_point::value, U>::type& vmax, - const typename ::std::enable_if< ::std::is_floating_point::value, U>::type& amax + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& q0, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& q1, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& vmax, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& amax ) { T xta = 3 * ::std::pow(vmax, 2) / (4 * amax); // travel distance during acceleration (or, deceleration) @@ -760,10 +760,10 @@ namespace rl */ template static Spline QuarticLinearQuarticAtRest( - const typename ::std::enable_if< ::std::is_class::value, U>::type& q0, - const typename ::std::enable_if< ::std::is_class::value, U>::type& q1, - const typename ::std::enable_if< ::std::is_class::value, U>::type& vmax, - const typename ::std::enable_if< ::std::is_class::value, U>::type& amax + const typename ::std::enable_if<::std::is_class::value, U>::type& q0, + const typename ::std::enable_if<::std::is_class::value, U>::type& q1, + const typename ::std::enable_if<::std::is_class::value, U>::type& vmax, + const typename ::std::enable_if<::std::is_class::value, U>::type& amax ) { assert(q0.size() >= 1 && q0.size() == q1.size() && q0.size() == vmax.size() && q0.size() == amax.size() && "QuarticLinearQuarticAtRest: parameters must have same dimension."); @@ -842,10 +842,10 @@ namespace rl */ template static Spline SexticLinearSexticAtRest( - const typename ::std::enable_if< ::std::is_floating_point::value, U>::type& q0, - const typename ::std::enable_if< ::std::is_floating_point::value, U>::type& q1, - const typename ::std::enable_if< ::std::is_floating_point::value, U>::type& vmax, - const typename ::std::enable_if< ::std::is_floating_point::value, U>::type& amax + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& q0, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& q1, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& vmax, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& amax ) { T xta = 15 * ::std::pow(vmax, 2) / (16 * amax); // travel distance during acceleration (or, deceleration) @@ -894,10 +894,10 @@ namespace rl */ template static Spline SexticLinearSexticAtRest( - const typename ::std::enable_if< ::std::is_class::value, U>::type& q0, - const typename ::std::enable_if< ::std::is_class::value, U>::type& q1, - const typename ::std::enable_if< ::std::is_class::value, U>::type& vmax, - const typename ::std::enable_if< ::std::is_class::value, U>::type& amax + const typename ::std::enable_if<::std::is_class::value, U>::type& q0, + const typename ::std::enable_if<::std::is_class::value, U>::type& q1, + const typename ::std::enable_if<::std::is_class::value, U>::type& vmax, + const typename ::std::enable_if<::std::is_class::value, U>::type& amax ) { assert(q0.size() >= 1 && q0.size() == q1.size() && q0.size() == vmax.size() && q0.size() == amax.size() && "SexticLinearSexticAtRest: parameters must have same dimension."); diff --git a/src/rl/math/TypeTraits.h b/src/rl/math/TypeTraits.h index 02091868..72393d4e 100644 --- a/src/rl/math/TypeTraits.h +++ b/src/rl/math/TypeTraits.h @@ -216,7 +216,7 @@ namespace rl }; template - class TypeTraits< ::Eigen::Array> + class TypeTraits<::Eigen::Array> { public: typedef Scalar value_type; @@ -263,7 +263,7 @@ namespace rl }; template - class TypeTraits< ::Eigen::Matrix> + class TypeTraits<::Eigen::Matrix> { public: typedef Scalar value_type; diff --git a/src/rl/math/metrics/L2.h b/src/rl/math/metrics/L2.h index 9faa61a8..da8df2b0 100644 --- a/src/rl/math/metrics/L2.h +++ b/src/rl/math/metrics/L2.h @@ -71,7 +71,7 @@ namespace rl }; template - struct L2< ::Eigen::Matrix> + struct L2<::Eigen::Matrix> { typedef Scalar Distance; @@ -91,7 +91,7 @@ namespace rl }; template - struct L2< ::Eigen::Matrix*> + struct L2<::Eigen::Matrix*> { typedef Scalar Distance; diff --git a/src/rl/math/metrics/L2Squared.h b/src/rl/math/metrics/L2Squared.h index ff7fdc48..c9514398 100644 --- a/src/rl/math/metrics/L2Squared.h +++ b/src/rl/math/metrics/L2Squared.h @@ -72,7 +72,7 @@ namespace rl }; template - struct L2Squared< ::Eigen::Matrix> + struct L2Squared<::Eigen::Matrix> { typedef Scalar Distance; @@ -93,7 +93,7 @@ namespace rl }; template - struct L2Squared< ::Eigen::Matrix*> + struct L2Squared<::Eigen::Matrix*> { typedef Scalar Distance; diff --git a/src/rl/mdl/AnalyticalInverseKinematics.cpp b/src/rl/mdl/AnalyticalInverseKinematics.cpp index c3272751..9237550b 100644 --- a/src/rl/mdl/AnalyticalInverseKinematics.cpp +++ b/src/rl/mdl/AnalyticalInverseKinematics.cpp @@ -40,7 +40,7 @@ namespace rl { } - const ::std::vector< ::rl::math::Vector>& + const ::std::vector<::rl::math::Vector>& AnalyticalInverseKinematics::getSolutions() const { return this->solutions; diff --git a/src/rl/mdl/AnalyticalInverseKinematics.h b/src/rl/mdl/AnalyticalInverseKinematics.h index 594ab407..fb1eab22 100644 --- a/src/rl/mdl/AnalyticalInverseKinematics.h +++ b/src/rl/mdl/AnalyticalInverseKinematics.h @@ -40,10 +40,10 @@ namespace rl virtual ~AnalyticalInverseKinematics(); - const ::std::vector< ::rl::math::Vector>& getSolutions() const; + const ::std::vector<::rl::math::Vector>& getSolutions() const; protected: - ::std::vector< ::rl::math::Vector> solutions; + ::std::vector<::rl::math::Vector> solutions; private: diff --git a/src/rl/mdl/InverseKinematics.h b/src/rl/mdl/InverseKinematics.h index 1c768e19..cd225dc5 100644 --- a/src/rl/mdl/InverseKinematics.h +++ b/src/rl/mdl/InverseKinematics.h @@ -40,7 +40,7 @@ namespace rl class RL_MDL_EXPORT InverseKinematics { public: - typedef ::std::pair< ::rl::math::Transform, ::std::size_t> Goal; + typedef ::std::pair<::rl::math::Transform, ::std::size_t> Goal; InverseKinematics(Kinematic* kinematic); diff --git a/src/rl/mdl/IterativeInverseKinematics.cpp b/src/rl/mdl/IterativeInverseKinematics.cpp index 7b1fa18b..f653292d 100644 --- a/src/rl/mdl/IterativeInverseKinematics.cpp +++ b/src/rl/mdl/IterativeInverseKinematics.cpp @@ -33,7 +33,7 @@ namespace rl IterativeInverseKinematics::IterativeInverseKinematics(Kinematic* kinematic) : InverseKinematics(kinematic), duration(::std::chrono::milliseconds(1000)), - epsilon(static_cast< ::rl::math::Real>(1.0e-6)), + epsilon(static_cast<::rl::math::Real>(1.0e-6)), iterations(10000) { } diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index 478c60db..bb7b99b6 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -33,7 +33,7 @@ namespace rl { JacobianInverseKinematics::JacobianInverseKinematics(Kinematic* kinematic) : IterativeInverseKinematics(kinematic), - delta(::std::numeric_limits< ::rl::math::Real>::infinity()), + delta(::std::numeric_limits<::rl::math::Real>::infinity()), method(METHOD_SVD), randDistribution(0, 1), randEngine(::std::random_device()()) diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index 82745b78..c104cfed 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -78,7 +78,7 @@ namespace rl Method method; - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; }; diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index 64bf3648..414adef4 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -37,8 +37,8 @@ namespace rl a(::rl::math::MotionVector::Zero()), c(::rl::math::MotionVector::Zero()), D(::rl::math::Matrix::Zero(dofVelocity, dofVelocity)), - max(::rl::math::Vector::Constant(dofPosition, ::std::numeric_limits< ::rl::math::Real>::max())), - min(::rl::math::Vector::Constant(dofPosition, -::std::numeric_limits< ::rl::math::Real>::max())), + max(::rl::math::Vector::Constant(dofPosition, ::std::numeric_limits<::rl::math::Real>::max())), + min(::rl::math::Vector::Constant(dofPosition, -::std::numeric_limits<::rl::math::Real>::max())), offset(::rl::math::Vector::Zero(dofPosition)), q(::rl::math::Vector::Zero(dofPosition)), qUnits(dofPosition), @@ -47,7 +47,7 @@ namespace rl qdd(::rl::math::Vector::Zero(dofVelocity)), qddUnits(dofVelocity), S(::rl::math::Matrix::Zero(6, dofVelocity)), - speed(::rl::math::Vector::Constant(dofVelocity, ::std::numeric_limits< ::rl::math::Real>::max())), + speed(::rl::math::Vector::Constant(dofVelocity, ::std::numeric_limits<::rl::math::Real>::max())), speedUnits(dofVelocity), tau(::rl::math::Vector::Zero(dofVelocity)), tauUnits(dofVelocity), @@ -183,7 +183,7 @@ namespace rl return this->qdd; } - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& Joint::getAccelerationUnits() const { return this->qddUnits; @@ -219,7 +219,7 @@ namespace rl return this->q; } - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& Joint::getPositionUnits() const { return this->qUnits; @@ -231,7 +231,7 @@ namespace rl return this->tau; } - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& Joint::getTorqueUnits() const { return this->tauUnits; @@ -243,7 +243,7 @@ namespace rl return this->speed; } - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& Joint::getSpeedUnits() const { return this->speedUnits; @@ -255,7 +255,7 @@ namespace rl return this->qd; } - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& Joint::getVelocityUnits() const { return this->qdUnits; diff --git a/src/rl/mdl/Joint.h b/src/rl/mdl/Joint.h index 5c0b8dd5..a6a42e21 100644 --- a/src/rl/mdl/Joint.h +++ b/src/rl/mdl/Joint.h @@ -65,7 +65,7 @@ namespace rl const ::rl::math::Vector& getAcceleration() const; - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& getAccelerationUnits() const; + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getAccelerationUnits() const; ::std::size_t getDof() const; @@ -77,19 +77,19 @@ namespace rl const ::rl::math::Vector& getPosition() const; - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& getPositionUnits() const; + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getPositionUnits() const; const ::rl::math::Vector& getTorque() const; - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& getTorqueUnits() const; + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getTorqueUnits() const; const ::rl::math::Vector& getSpeed() const; - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& getSpeedUnits() const; + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getSpeedUnits() const; const ::rl::math::Vector& getVelocity() const; - const ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1>& getVelocityUnits() const; + const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getVelocityUnits() const; virtual void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; @@ -125,25 +125,25 @@ namespace rl ::rl::math::Vector q; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> qUnits; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> qUnits; ::rl::math::Vector qd; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> qdUnits; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> qdUnits; ::rl::math::Vector qdd; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> qddUnits; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> qddUnits; ::rl::math::Matrix S; ::rl::math::Vector speed; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> speedUnits; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> speedUnits; ::rl::math::Vector tau; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> tauUnits; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> tauUnits; ::rl::math::Vector u; diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 72080e94..051de5bb 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -137,10 +137,10 @@ namespace rl { invJ.setZero(); - ::Eigen::JacobiSVD< ::rl::math::Matrix> svd(J, ::Eigen::ComputeFullU | ::Eigen::ComputeFullV); + ::Eigen::JacobiSVD<::rl::math::Matrix> svd(J, ::Eigen::ComputeFullU | ::Eigen::ComputeFullV); ::rl::math::Real wMin = svd.singularValues().minCoeff(); - ::rl::math::Real lambdaSqr = wMin < static_cast< ::rl::math::Real>(1.0e-9) ? (1 - ::std::pow((wMin / static_cast< ::rl::math::Real>(1.0e-9)), 2)) * ::std::pow(lambda, 2) : 0; + ::rl::math::Real lambdaSqr = wMin < static_cast<::rl::math::Real>(1.0e-9) ? (1 - ::std::pow((wMin / static_cast<::rl::math::Real>(1.0e-9)), 2)) * ::std::pow(lambda, 2) : 0; for (::std::ptrdiff_t i = 0; i < svd.nonzeroSingularValues(); ++i) { @@ -225,8 +225,8 @@ namespace rl bool Kinematic::isSingular(const ::rl::math::Matrix& J) const { - ::Eigen::JacobiSVD< ::rl::math::Matrix> svd(J); - return (::std::abs(svd.singularValues()(svd.singularValues().size() - 1)) > ::std::numeric_limits< ::rl::math::Real>::epsilon()) ? false : true; + ::Eigen::JacobiSVD<::rl::math::Matrix> svd(J); + return (::std::abs(svd.singularValues()(svd.singularValues().size() - 1)) > ::std::numeric_limits<::rl::math::Real>::epsilon()) ? false : true; } void diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index cd7d53b5..99472490 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -212,10 +212,10 @@ namespace rl return this->invGammaVelocity * qdd; } - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> Model::getAccelerationUnits() const { - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { @@ -420,10 +420,10 @@ namespace rl return this->invGammaPosition * q; } - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> Model::getPositionUnits() const { - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDofPosition()); + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDofPosition()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { @@ -446,10 +446,10 @@ namespace rl return speed; } - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> Model::getSpeedUnits() const { - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { @@ -472,10 +472,10 @@ namespace rl return tau; } - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> Model::getTorqueUnits() const { - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { @@ -512,10 +512,10 @@ namespace rl return this->invGammaVelocity * qd; } - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> Model::getVelocityUnits() const { - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { @@ -558,7 +558,7 @@ namespace rl return this->bodies[i]->collision; } - ::std::uniform_real_distribution< ::rl::math::Real>::result_type + ::std::uniform_real_distribution<::rl::math::Real>::result_type Model::rand() { return this->randDistribution(this->randEngine); @@ -625,12 +625,12 @@ namespace rl Model::setGammaPosition(const ::rl::math::Matrix& gammaPosition) { this->gammaPosition = gammaPosition; - ::Eigen::JacobiSVD< ::rl::math::Matrix> svd(this->gammaPosition, ::Eigen::ComputeThinU | ::Eigen::ComputeThinV); + ::Eigen::JacobiSVD<::rl::math::Matrix> svd(this->gammaPosition, ::Eigen::ComputeThinU | ::Eigen::ComputeThinV); ::rl::math::Vector singularValues(svd.singularValues().size()); for (::std::ptrdiff_t i = 0; i < svd.singularValues().size(); ++i) { - singularValues[i] = svd.singularValues()[i] > ::std::numeric_limits< ::rl::math::Real>::epsilon() ? 1 / svd.singularValues()[i] : 0; + singularValues[i] = svd.singularValues()[i] > ::std::numeric_limits<::rl::math::Real>::epsilon() ? 1 / svd.singularValues()[i] : 0; } this->invGammaPosition = svd.matrixV() * singularValues.asDiagonal() * svd.matrixU().transpose(); @@ -640,12 +640,12 @@ namespace rl Model::setGammaVelocity(const ::rl::math::Matrix& gammaVelocity) { this->gammaVelocity = gammaVelocity; - ::Eigen::JacobiSVD< ::rl::math::Matrix> svd(this->gammaVelocity, ::Eigen::ComputeThinU | ::Eigen::ComputeThinV); + ::Eigen::JacobiSVD<::rl::math::Matrix> svd(this->gammaVelocity, ::Eigen::ComputeThinU | ::Eigen::ComputeThinV); ::rl::math::Vector singularValues(svd.singularValues().size()); for (::std::ptrdiff_t i = 0; i < svd.singularValues().size(); ++i) { - singularValues[i] = svd.singularValues()[i] > ::std::numeric_limits< ::rl::math::Real>::epsilon() ? 1 / svd.singularValues()[i] : 0; + singularValues[i] = svd.singularValues()[i] > ::std::numeric_limits<::rl::math::Real>::epsilon() ? 1 / svd.singularValues()[i] : 0; } this->invGammaVelocity = svd.matrixV() * singularValues.asDiagonal() * svd.matrixU().transpose(); diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index d56d1987..2eb2a781 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -83,7 +83,7 @@ namespace rl ::rl::math::Vector getAcceleration() const; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getAccelerationUnits() const; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getAccelerationUnits() const; ::std::size_t getBodies() const; @@ -133,7 +133,7 @@ namespace rl ::rl::math::Vector getPosition() const; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getPositionUnits() const; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getPositionUnits() const; Transform* getTransform(const ::std::size_t& i) const; @@ -141,15 +141,15 @@ namespace rl ::rl::math::Vector getSpeed() const; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getSpeedUnits() const; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getSpeedUnits() const; ::rl::math::Vector getTorque() const; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getTorqueUnits() const; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getTorqueUnits() const; ::rl::math::Vector getVelocity() const; - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getVelocityUnits() const; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getVelocityUnits() const; World* getWorld() const; @@ -277,9 +277,9 @@ namespace rl Tree tree; private: - ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + ::std::uniform_real_distribution<::rl::math::Real>::result_type rand(); - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; }; diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 5bdaafbb..9e7d97f0 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -79,7 +79,7 @@ namespace rl if (nullptr != grad) { - ::Eigen::Map< ::Eigen::VectorXd> grad2(grad, n, 1); + ::Eigen::Map<::Eigen::VectorXd> grad2(grad, n, 1); ik->kinematic->calculateJacobian(); grad2 = -2 * ik->kinematic->getJacobian().transpose() * dx; } diff --git a/src/rl/mdl/NloptInverseKinematics.h b/src/rl/mdl/NloptInverseKinematics.h index 891215ee..8667a366 100644 --- a/src/rl/mdl/NloptInverseKinematics.h +++ b/src/rl/mdl/NloptInverseKinematics.h @@ -107,9 +107,9 @@ namespace rl ::rl::math::Vector lb; - ::std::unique_ptr< ::nlopt_opt_s, decltype(&::nlopt_destroy)> opt; + ::std::unique_ptr<::nlopt_opt_s, decltype(&::nlopt_destroy)> opt; - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; diff --git a/src/rl/mdl/Revolute.cpp b/src/rl/mdl/Revolute.cpp index 37adead4..efeeeb52 100644 --- a/src/rl/mdl/Revolute.cpp +++ b/src/rl/mdl/Revolute.cpp @@ -106,15 +106,15 @@ namespace rl void Revolute::normalize(::rl::math::VectorRef q) const { - q(0) = ::std::remainder(q(0), 2 * static_cast< ::rl::math::Real>(M_PI)); + q(0) = ::std::remainder(q(0), 2 * static_cast<::rl::math::Real>(M_PI)); if (q(0) < this->min(0)) { - q(0) += 2 * static_cast< ::rl::math::Real>(M_PI); + q(0) += 2 * static_cast<::rl::math::Real>(M_PI); } else if (q(0) > this->max(0)) { - q(0) -= 2 * static_cast< ::rl::math::Real>(M_PI); + q(0) -= 2 * static_cast<::rl::math::Real>(M_PI); } } diff --git a/src/rl/mdl/RungeKuttaNystromIntegrator.cpp b/src/rl/mdl/RungeKuttaNystromIntegrator.cpp index cf9193e8..916b3b4d 100644 --- a/src/rl/mdl/RungeKuttaNystromIntegrator.cpp +++ b/src/rl/mdl/RungeKuttaNystromIntegrator.cpp @@ -89,7 +89,7 @@ namespace rl // y_0 + dy_0 * dt + dt / 3 * (k_1 + k_2 + k_3) y = y0 + dy0 * dt + dt / 3 * (k1 + k2 + k3); // dy_0 + 1 / 3 * (k_1 + 2 * k_2 + 2 * k_3 + k_4) - dy = dy0 + static_cast< ::rl::math::Real>(1) / static_cast< ::rl::math::Real>(3) * (k1 + 2 * k2 + 2 * k3 + k4); + dy = dy0 + static_cast<::rl::math::Real>(1) / static_cast<::rl::math::Real>(3) * (k1 + 2 * k2 + 2 * k3 + k4); this->dynamic->setPosition(y); this->dynamic->setVelocity(dy); diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index 253171ec..5fa9c305 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -87,7 +87,7 @@ namespace rl q(i) = ::rl::std17::clamp(q(i), this->min(i), this->max(i)); } - ::Eigen::Map< ::rl::math::Quaternion>(q.tail<4>().data()).normalize(); + ::Eigen::Map<::rl::math::Quaternion>(q.tail<4>().data()).normalize(); } ::rl::math::Real @@ -149,13 +149,13 @@ namespace rl } } - return ::Eigen::internal::isApprox(q.tail<4>().norm(), static_cast< ::rl::math::Real>(1), static_cast< ::rl::math::Real>(1.0e-3)); + return ::Eigen::internal::isApprox(q.tail<4>().norm(), static_cast<::rl::math::Real>(1), static_cast<::rl::math::Real>(1.0e-3)); } void SixDof::normalize(::rl::math::VectorRef q) const { - ::Eigen::Map< ::rl::math::Quaternion> quaternion(q.tail<4>().data()); + ::Eigen::Map<::rl::math::Quaternion> quaternion(q.tail<4>().data()); if (quaternion.squaredNorm() > 0) { diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 3f95b523..1fa2b06f 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -65,7 +65,7 @@ namespace rl void Spherical::clamp(::rl::math::VectorRef q) const { - ::Eigen::Map< ::rl::math::Quaternion>(q.data()).normalize(); + ::Eigen::Map<::rl::math::Quaternion>(q.data()).normalize(); } ::rl::math::Real @@ -105,13 +105,13 @@ namespace rl bool Spherical::isValid(const ::rl::math::ConstVectorRef& q) const { - return ::Eigen::internal::isApprox(q.norm(), static_cast< ::rl::math::Real>(1), static_cast< ::rl::math::Real>(1.0e-3)); + return ::Eigen::internal::isApprox(q.norm(), static_cast<::rl::math::Real>(1), static_cast<::rl::math::Real>(1.0e-3)); } void Spherical::normalize(::rl::math::VectorRef q) const { - ::Eigen::Map< ::rl::math::Quaternion> quaternion(q.data()); + ::Eigen::Map<::rl::math::Quaternion> quaternion(q.data()); if (quaternion.squaredNorm() > 0) { diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 537843cf..298b1dfe 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -77,7 +77,7 @@ namespace rl ::rl::xml::Path path(document); - ::rl::xml::NodeSet robots = path.eval("/robot").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet robots = path.eval("/robot").getValue<::rl::xml::NodeSet>(); if (robots.empty()) { @@ -88,14 +88,14 @@ namespace rl // name - model->setName(path.eval("string(@name)").getValue< ::std::string>()); + model->setName(path.eval("string(@name)").getValue<::std::string>()); ::std::cout << model->getName() << ::std::endl; // links - ::rl::xml::NodeSet links = path.eval("link").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet links = path.eval("link").getValue<::rl::xml::NodeSet>(); - ::std::unordered_map< ::std::string, Frame*> name2frame; + ::std::unordered_map<::std::string, Frame*> name2frame; for (int j = 0; j < links.size(); ++j) { @@ -108,14 +108,14 @@ ::std::cout << "link: " << j << ::std::endl; if (path.eval("count(inertial/origin/@xyz) > 0").getValue()) { - ::std::vector< ::std::string> xyz; - ::std::string tmp = path.eval("string(inertial/origin/@xyz)").getValue< ::std::string>(); + ::std::vector<::std::string> xyz; + ::std::string tmp = path.eval("string(inertial/origin/@xyz)").getValue<::std::string>(); ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); b->setCenterOfMass( - ::boost::lexical_cast< ::rl::math::Real>(xyz[0]), - ::boost::lexical_cast< ::rl::math::Real>(xyz[1]), - ::boost::lexical_cast< ::rl::math::Real>(xyz[2]) + ::boost::lexical_cast<::rl::math::Real>(xyz[0]), + ::boost::lexical_cast<::rl::math::Real>(xyz[1]), + ::boost::lexical_cast<::rl::math::Real>(xyz[2]) ); } else @@ -130,41 +130,41 @@ ::std::cout << "\tcog: " << b->cm.transpose() << ::std::endl; } b->setInertia( - path.eval("number(inertial/inertia/@ixx)").getValue< ::rl::math::Real>(1), - path.eval("number(inertial/inertia/@iyy)").getValue< ::rl::math::Real>(1), - path.eval("number(inertial/inertia/@izz)").getValue< ::rl::math::Real>(1), - path.eval("number(inertial/inertia/@iyz)").getValue< ::rl::math::Real>(0), - path.eval("number(inertial/inertia/@ixz)").getValue< ::rl::math::Real>(0), - path.eval("number(inertial/inertia/@ixy)").getValue< ::rl::math::Real>(0) + path.eval("number(inertial/inertia/@ixx)").getValue<::rl::math::Real>(1), + path.eval("number(inertial/inertia/@iyy)").getValue<::rl::math::Real>(1), + path.eval("number(inertial/inertia/@izz)").getValue<::rl::math::Real>(1), + path.eval("number(inertial/inertia/@iyz)").getValue<::rl::math::Real>(0), + path.eval("number(inertial/inertia/@ixz)").getValue<::rl::math::Real>(0), + path.eval("number(inertial/inertia/@ixy)").getValue<::rl::math::Real>(0) ); ::std::cout << "\tinertia: " << b->ic.voigt6().transpose() << ::std::endl; b->setMass( - path.eval("number(inertial/mass/@value)").getValue< ::rl::math::Real>(1) + path.eval("number(inertial/mass/@value)").getValue<::rl::math::Real>(1) ); ::std::cout << "\tmass: " << b->m << ::std::endl; - b->setName(path.eval("string(@name)").getValue< ::std::string>()); + b->setName(path.eval("string(@name)").getValue<::std::string>()); ::std::cout << "\tname: " << b->getName() << ::std::endl; - name2frame[path.eval("string(@name)").getValue< ::std::string>()] = b; + name2frame[path.eval("string(@name)").getValue<::std::string>()] = b; } // joints - ::std::unordered_map< ::std::string, ::std::string> child2parent; + ::std::unordered_map<::std::string, ::std::string> child2parent; - ::rl::xml::NodeSet joints = path.eval("joint").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet joints = path.eval("joint").getValue<::rl::xml::NodeSet>(); for (int j = 0; j < joints.size(); ++j) { ::std::cout << "joint: " << j << ::std::endl; ::rl::xml::Path path(document, joints[j]); - child2parent[path.eval("string(child/@link)").getValue< ::std::string>()] = path.eval("string(parent/@link)").getValue< ::std::string>(); + child2parent[path.eval("string(child/@link)").getValue<::std::string>()] = path.eval("string(parent/@link)").getValue<::std::string>(); - Frame* parent = name2frame[path.eval("string(parent/@link)").getValue< ::std::string>()]; - Frame* child = name2frame[path.eval("string(child/@link)").getValue< ::std::string>()]; + Frame* parent = name2frame[path.eval("string(parent/@link)").getValue<::std::string>()]; + Frame* child = name2frame[path.eval("string(child/@link)").getValue<::std::string>()]; ::std::cout << "\tparent: " << parent->getName() << ::std::endl; ::std::cout << "\tchild: " << child->getName() << ::std::endl; @@ -184,44 +184,44 @@ ::std::cout << "\tchild: " << child->getName() << ::std::endl; if (path.eval("count(origin/@rpy) > 0").getValue()) { - ::std::vector< ::std::string> rpy; - ::std::string tmp = path.eval("string(origin/@rpy)").getValue< ::std::string>(); + ::std::vector<::std::string> rpy; + ::std::string tmp = path.eval("string(origin/@rpy)").getValue<::std::string>(); ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); fixed->x.linear() = ::rl::math::AngleAxis( - ::boost::lexical_cast< ::rl::math::Real>(rpy[2]), + ::boost::lexical_cast<::rl::math::Real>(rpy[2]), ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - ::boost::lexical_cast< ::rl::math::Real>(rpy[1]), + ::boost::lexical_cast<::rl::math::Real>(rpy[1]), ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - ::boost::lexical_cast< ::rl::math::Real>(rpy[0]), + ::boost::lexical_cast<::rl::math::Real>(rpy[0]), ::rl::math::Vector3::UnitX() ).toRotationMatrix(); } if (path.eval("count(origin/@xyz) > 0").getValue()) { - ::std::vector< ::std::string> xyz; - ::std::string tmp = path.eval("string(origin/@xyz)").getValue< ::std::string>(); + ::std::vector<::std::string> xyz; + ::std::string tmp = path.eval("string(origin/@xyz)").getValue<::std::string>(); ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); - fixed->x.translation().x() = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); - fixed->x.translation().y() = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); - fixed->x.translation().z() = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); + fixed->x.translation().x() = ::boost::lexical_cast<::rl::math::Real>(xyz[0]); + fixed->x.translation().y() = ::boost::lexical_cast<::rl::math::Real>(xyz[1]); + fixed->x.translation().z() = ::boost::lexical_cast<::rl::math::Real>(xyz[2]); } ::std::cout << "\torigin.translation: " << fixed->x.translation().transpose() << ::std::endl; ::std::cout << "\torigin.rotation: " << fixed->x.linear().eulerAngles(2, 1, 0).reverse().transpose() * ::rl::math::RAD2DEG << ::std::endl; // joint - ::std::string type = path.eval("string(@type)").getValue< ::std::string>(); + ::std::string type = path.eval("string(@type)").getValue<::std::string>(); ::std::cout << "\ttype: " << type << ::std::endl; if ("fixed" == type) { model->add(fixed, parent, child); - fixed->setName(path.eval("string(@name)").getValue< ::std::string>()); + fixed->setName(path.eval("string(@name)").getValue<::std::string>()); ::std::cout << "\tname: " << fixed->getName() << ::std::endl; } else if ("floating" == type) @@ -231,7 +231,7 @@ ::std::cout << "\tname: " << fixed->getName() << ::std::endl; model->add(fixed, parent, frame); model->add(s, frame, child); - s->setName(path.eval("string(@name)").getValue< ::std::string>()); + s->setName(path.eval("string(@name)").getValue<::std::string>()); ::std::cout << "\tname: " << s->getName() << ::std::endl; } else if ("planar" == type) @@ -245,24 +245,24 @@ ::std::cout << "\tname: " << s->getName() << ::std::endl; model->add(fixed, parent, frame); model->add(p, frame, child); - p->max(0) = path.eval("number(limit/@upper)").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); + p->max(0) = path.eval("number(limit/@upper)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); ::std::cout << "\tmax: " << p->max(0) << ::std::endl; - p->min(0) = path.eval("number(limit/@lower)").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); + p->min(0) = path.eval("number(limit/@lower)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); ::std::cout << "\tmin: " << p->min(0) << ::std::endl; p->offset(0) = 0; - p->speed(0) = path.eval("number(limit/@velocity)").getValue< ::rl::math::Real>(0); + p->speed(0) = path.eval("number(limit/@velocity)").getValue<::rl::math::Real>(0); ::std::cout << "\tspeed: " << p->speed(0) << ::std::endl; p->wraparound(0) = false; if (path.eval("count(axis/@xyz) > 0").getValue()) { - ::std::vector< ::std::string> xyz; - ::std::string tmp = path.eval("string(axis/@xyz)").getValue< ::std::string>(); + ::std::vector<::std::string> xyz; + ::std::string tmp = path.eval("string(axis/@xyz)").getValue<::std::string>(); ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); - p->S(3, 0) = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); - p->S(4, 0) = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); - p->S(5, 0) = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); + p->S(3, 0) = ::boost::lexical_cast<::rl::math::Real>(xyz[0]); + p->S(4, 0) = ::boost::lexical_cast<::rl::math::Real>(xyz[1]); + p->S(5, 0) = ::boost::lexical_cast<::rl::math::Real>(xyz[2]); } else { @@ -272,7 +272,7 @@ ::std::cout << "\tspeed: " << p->speed(0) << ::std::endl; } ::std::cout << "\taxis: " << p->S(3, 0) << " " << p->S(4, 0) << " " << p->S(5, 0) << ::std::endl; - p->setName(path.eval("string(@name)").getValue< ::std::string>()); + p->setName(path.eval("string(@name)").getValue<::std::string>()); ::std::cout << "\tname: " << p->getName() << ::std::endl; } else if ("revolute" == type || "continuous" == type) @@ -282,7 +282,7 @@ ::std::cout << "\tname: " << p->getName() << ::std::endl; model->add(fixed, parent, frame); model->add(r, frame, child); - if ("continuous" == path.eval("string(@type)").getValue< ::std::string>()) + if ("continuous" == path.eval("string(@type)").getValue<::std::string>()) { r->max(0) = 180 * ::rl::math::DEG2RAD; r->min(0) = -180 * ::rl::math::DEG2RAD; @@ -290,26 +290,26 @@ ::std::cout << "\tname: " << p->getName() << ::std::endl; } else { - r->max(0) = path.eval("number(limit/@upper)").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - r->min(0) = path.eval("number(limit/@lower)").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); + r->max(0) = path.eval("number(limit/@upper)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + r->min(0) = path.eval("number(limit/@lower)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); r->wraparound(0) = false; } ::std::cout << "\tmax: " << r->max(0) * ::rl::math::RAD2DEG << ::std::endl; ::std::cout << "\tmin: " << r->min(0) * ::rl::math::RAD2DEG << ::std::endl; r->offset(0) = 0; - r->speed(0) = path.eval("number(limit/@velocity)").getValue< ::rl::math::Real>(0); + r->speed(0) = path.eval("number(limit/@velocity)").getValue<::rl::math::Real>(0); ::std::cout << "\tspeed: " << r->speed(0) * ::rl::math::RAD2DEG << ::std::endl; if (path.eval("count(axis/@xyz) > 0").getValue()) { - ::std::vector< ::std::string> xyz; - ::std::string tmp = path.eval("string(axis/@xyz)").getValue< ::std::string>(); + ::std::vector<::std::string> xyz; + ::std::string tmp = path.eval("string(axis/@xyz)").getValue<::std::string>(); ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); - r->S(0, 0) = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); - r->S(1, 0) = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); - r->S(2, 0) = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); + r->S(0, 0) = ::boost::lexical_cast<::rl::math::Real>(xyz[0]); + r->S(1, 0) = ::boost::lexical_cast<::rl::math::Real>(xyz[1]); + r->S(2, 0) = ::boost::lexical_cast<::rl::math::Real>(xyz[2]); } else { @@ -319,7 +319,7 @@ ::std::cout << "\tspeed: " << r->speed(0) * ::rl::math::RAD2DEG << ::std::endl; } ::std::cout << "\taxis: " << r->S(0, 0) << " " << r->S(1, 0) << " " << r->S(2, 0) << ::std::endl; - r->setName(path.eval("string(@name)").getValue< ::std::string>()); + r->setName(path.eval("string(@name)").getValue<::std::string>()); ::std::cout << "\tname: " << r->getName() << ::std::endl; } } @@ -332,7 +332,7 @@ ::std::cout << "\tname: " << r->getName() << ::std::endl; Frame* root = nullptr; - for (::std::unordered_map< ::std::string, Frame*>::const_iterator frame = name2frame.begin(); frame != name2frame.end(); ++frame) + for (::std::unordered_map<::std::string, Frame*>::const_iterator frame = name2frame.begin(); frame != name2frame.end(); ++frame) { if (child2parent.end() == child2parent.find(frame->first)) { diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index 0583eb82..5d8e6d2a 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -87,7 +87,7 @@ namespace rl ::rl::xml::Path path(document); - ::rl::xml::NodeSet models = path.eval("(/rl/mdl|/rlmdl)/model").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet models = path.eval("(/rl/mdl|/rlmdl)/model").getValue<::rl::xml::NodeSet>(); if (models.empty()) { @@ -100,17 +100,17 @@ namespace rl // manufacturer - model->setManufacturer(path.eval("string(manufacturer)").getValue< ::std::string>()); + model->setManufacturer(path.eval("string(manufacturer)").getValue<::std::string>()); // name - model->setName(path.eval("string(name)").getValue< ::std::string>()); + model->setName(path.eval("string(name)").getValue<::std::string>()); // frame - ::rl::xml::NodeSet frames = path.eval("body|frame|world").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet frames = path.eval("body|frame|world").getValue<::rl::xml::NodeSet>(); - ::std::unordered_map< ::std::string, Frame*> id2frame; + ::std::unordered_map<::std::string, Frame*> id2frame; for (int j = 0; j < frames.size(); ++j) { @@ -125,22 +125,22 @@ namespace rl model->add(b); b->setCenterOfMass( - path.eval("number(cm/x)").getValue< ::rl::math::Real>(0), - path.eval("number(cm/y)").getValue< ::rl::math::Real>(0), - path.eval("number(cm/z)").getValue< ::rl::math::Real>(0) + path.eval("number(cm/x)").getValue<::rl::math::Real>(0), + path.eval("number(cm/y)").getValue<::rl::math::Real>(0), + path.eval("number(cm/z)").getValue<::rl::math::Real>(0) ); b->setInertia( - path.eval("number(i/xx)").getValue< ::rl::math::Real>(1), - path.eval("number(i/yy)").getValue< ::rl::math::Real>(1), - path.eval("number(i/zz)").getValue< ::rl::math::Real>(1), - path.eval("number(i/yz)").getValue< ::rl::math::Real>(0), - path.eval("number(i/xz)").getValue< ::rl::math::Real>(0), - path.eval("number(i/xy)").getValue< ::rl::math::Real>(0) + path.eval("number(i/xx)").getValue<::rl::math::Real>(1), + path.eval("number(i/yy)").getValue<::rl::math::Real>(1), + path.eval("number(i/zz)").getValue<::rl::math::Real>(1), + path.eval("number(i/yz)").getValue<::rl::math::Real>(0), + path.eval("number(i/xz)").getValue<::rl::math::Real>(0), + path.eval("number(i/xy)").getValue<::rl::math::Real>(0) ); b->setMass( - path.eval("number(m)").getValue< ::rl::math::Real>(1) + path.eval("number(m)").getValue<::rl::math::Real>(1) ); frame = b; @@ -160,25 +160,25 @@ namespace rl model->add(w); w->x.linear() = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX() ).toRotationMatrix(); - w->x.translation().x() = path.eval("number(translation/x)").getValue< ::rl::math::Real>(0); - w->x.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); - w->x.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); + w->x.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); + w->x.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); + w->x.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); w->setGravity( ::rl::math::Vector3( - path.eval("number(g/x)").getValue< ::rl::math::Real>(0), - path.eval("number(g/y)").getValue< ::rl::math::Real>(0), - path.eval("number(g/z)").getValue< ::rl::math::Real>(0) + path.eval("number(g/x)").getValue<::rl::math::Real>(0), + path.eval("number(g/y)").getValue<::rl::math::Real>(0), + path.eval("number(g/z)").getValue<::rl::math::Real>(0) ) ); @@ -187,7 +187,7 @@ namespace rl if (nullptr != frame) { - frame->setName(path.eval("string(@id)").getValue< ::std::string>()); + frame->setName(path.eval("string(@id)").getValue<::std::string>()); if (id2frame.find(frame->getName()) != id2frame.end()) { @@ -206,7 +206,7 @@ namespace rl if ("body" == frames[j].getName()) { - ::std::string b1Id = path.eval("string(@id)").getValue< ::std::string>(); + ::std::string b1Id = path.eval("string(@id)").getValue<::std::string>(); if (id2frame.find(b1Id) == id2frame.end()) { @@ -215,7 +215,7 @@ namespace rl Body* b1 = dynamic_cast(id2frame[b1Id]); - ::rl::xml::NodeSet ignores = path.eval("ignore").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet ignores = path.eval("ignore").getValue<::rl::xml::NodeSet>(); for (int k = 0; k < ignores.size(); ++k) { @@ -243,15 +243,15 @@ namespace rl // transforms - ::rl::xml::NodeSet transforms = path.eval("cylindrical|fixed|helical|prismatic|revolute|sixDof|spherical").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet transforms = path.eval("cylindrical|fixed|helical|prismatic|revolute|sixDof|spherical").getValue<::rl::xml::NodeSet>(); for (int j = 0; j < transforms.size(); ++j) { ::rl::xml::Path path(document, transforms[j]); - ::std::string name = path.eval("string(@id)").getValue< ::std::string>(); + ::std::string name = path.eval("string(@id)").getValue<::std::string>(); - ::std::string aIdRef = path.eval("string(frame/a/@idref)").getValue< ::std::string>(); + ::std::string aIdRef = path.eval("string(frame/a/@idref)").getValue<::std::string>(); if (id2frame.find(aIdRef) == id2frame.end()) { @@ -260,7 +260,7 @@ namespace rl Frame* a = id2frame[aIdRef]; - ::std::string bIdRef = path.eval("string(frame/b/@idref)").getValue< ::std::string>(); + ::std::string bIdRef = path.eval("string(frame/b/@idref)").getValue<::std::string>(); if (id2frame.find(bIdRef) == id2frame.end()) { @@ -277,25 +277,25 @@ namespace rl model->add(c, a, b); - c->max(0) = path.eval("number(max[1])").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - c->min(0) = path.eval("number(min[1])").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - c->offset(0) = path.eval("number(offset[1])").getValue< ::rl::math::Real>(0); - c->speed(0) = path.eval("number(speed[1])").getValue< ::rl::math::Real>(0); + c->max(0) = path.eval("number(max[1])").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + c->min(0) = path.eval("number(min[1])").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + c->offset(0) = path.eval("number(offset[1])").getValue<::rl::math::Real>(0); + c->speed(0) = path.eval("number(speed[1])").getValue<::rl::math::Real>(0); c->wraparound(0) = path.eval("count(wraparound[1]) > 0").getValue(); - c->max(1) = path.eval("number(max[2])").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - c->min(1) = path.eval("number(min[2])").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - c->offset(1) = path.eval("number(offset[2])").getValue< ::rl::math::Real>(0); - c->speed(1) = path.eval("number(speed[2])").getValue< ::rl::math::Real>(0); + c->max(1) = path.eval("number(max[2])").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + c->min(1) = path.eval("number(min[2])").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + c->offset(1) = path.eval("number(offset[2])").getValue<::rl::math::Real>(0); + c->speed(1) = path.eval("number(speed[2])").getValue<::rl::math::Real>(0); c->wraparound(1) = path.eval("count(wraparound[2]) > 0").getValue(); - c->S(0, 0) = path.eval("number(axis[1]/x)").getValue< ::rl::math::Real>(0); - c->S(1, 0) = path.eval("number(axis[1]/y)").getValue< ::rl::math::Real>(0); - c->S(2, 0) = path.eval("number(axis[1]/z)").getValue< ::rl::math::Real>(1); + c->S(0, 0) = path.eval("number(axis[1]/x)").getValue<::rl::math::Real>(0); + c->S(1, 0) = path.eval("number(axis[1]/y)").getValue<::rl::math::Real>(0); + c->S(2, 0) = path.eval("number(axis[1]/z)").getValue<::rl::math::Real>(1); - c->S(3, 1) = path.eval("number(axis[2]/x)").getValue< ::rl::math::Real>(0); - c->S(4, 1) = path.eval("number(axis[2]/y)").getValue< ::rl::math::Real>(0); - c->S(5, 1) = path.eval("number(axis[2]/z)").getValue< ::rl::math::Real>(1); + c->S(3, 1) = path.eval("number(axis[2]/x)").getValue<::rl::math::Real>(0); + c->S(4, 1) = path.eval("number(axis[2]/y)").getValue<::rl::math::Real>(0); + c->S(5, 1) = path.eval("number(axis[2]/z)").getValue<::rl::math::Real>(1); transform = c; } @@ -306,19 +306,19 @@ namespace rl model->add(f, a, b); f->x.linear() = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue< ::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX() ).toRotationMatrix(); - f->x.translation().x() = path.eval("number(translation/x)").getValue< ::rl::math::Real>(0); - f->x.translation().y() = path.eval("number(translation/y)").getValue< ::rl::math::Real>(0); - f->x.translation().z() = path.eval("number(translation/z)").getValue< ::rl::math::Real>(0); + f->x.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); + f->x.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); + f->x.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); transform = f; } @@ -328,21 +328,21 @@ namespace rl model->add(h, a, b); - h->max(0) = path.eval("number(max)").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - h->min(0) = path.eval("number(min)").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - h->offset(0) = path.eval("number(offset)").getValue< ::rl::math::Real>(0); - h->speed(0) = path.eval("number(speed)").getValue< ::rl::math::Real>(0); + h->max(0) = path.eval("number(max)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + h->min(0) = path.eval("number(min)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + h->offset(0) = path.eval("number(offset)").getValue<::rl::math::Real>(0); + h->speed(0) = path.eval("number(speed)").getValue<::rl::math::Real>(0); h->wraparound(0) = path.eval("count(wraparound) > 0").getValue(); - h->S(0, 0) = path.eval("number(axis[1]/x)").getValue< ::rl::math::Real>(0); - h->S(1, 0) = path.eval("number(axis[1]/y)").getValue< ::rl::math::Real>(0); - h->S(2, 0) = path.eval("number(axis[1]/z)").getValue< ::rl::math::Real>(1); + h->S(0, 0) = path.eval("number(axis[1]/x)").getValue<::rl::math::Real>(0); + h->S(1, 0) = path.eval("number(axis[1]/y)").getValue<::rl::math::Real>(0); + h->S(2, 0) = path.eval("number(axis[1]/z)").getValue<::rl::math::Real>(1); - h->S(3, 0) = path.eval("number(axis[2]/x)").getValue< ::rl::math::Real>(0); - h->S(4, 0) = path.eval("number(axis[2]/y)").getValue< ::rl::math::Real>(0); - h->S(5, 0) = path.eval("number(axis[2]/z)").getValue< ::rl::math::Real>(1); + h->S(3, 0) = path.eval("number(axis[2]/x)").getValue<::rl::math::Real>(0); + h->S(4, 0) = path.eval("number(axis[2]/y)").getValue<::rl::math::Real>(0); + h->S(5, 0) = path.eval("number(axis[2]/z)").getValue<::rl::math::Real>(1); - h->setPitch(path.eval("number(pitch)").getValue< ::rl::math::Real>(1)); + h->setPitch(path.eval("number(pitch)").getValue<::rl::math::Real>(1)); transform = h; } @@ -352,15 +352,15 @@ namespace rl model->add(p, a, b); - p->max(0) = path.eval("number(max)").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - p->min(0) = path.eval("number(min)").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - p->offset(0) = path.eval("number(offset)").getValue< ::rl::math::Real>(0); - p->speed(0) = path.eval("number(speed)").getValue< ::rl::math::Real>(0); + p->max(0) = path.eval("number(max)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + p->min(0) = path.eval("number(min)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + p->offset(0) = path.eval("number(offset)").getValue<::rl::math::Real>(0); + p->speed(0) = path.eval("number(speed)").getValue<::rl::math::Real>(0); p->wraparound(0) = path.eval("count(wraparound) > 0").getValue(); - p->S(3, 0) = path.eval("number(axis/x)").getValue< ::rl::math::Real>(0); - p->S(4, 0) = path.eval("number(axis/y)").getValue< ::rl::math::Real>(0); - p->S(5, 0) = path.eval("number(axis/z)").getValue< ::rl::math::Real>(1); + p->S(3, 0) = path.eval("number(axis/x)").getValue<::rl::math::Real>(0); + p->S(4, 0) = path.eval("number(axis/y)").getValue<::rl::math::Real>(0); + p->S(5, 0) = path.eval("number(axis/z)").getValue<::rl::math::Real>(1); transform = p; } @@ -370,15 +370,15 @@ namespace rl model->add(r, a, b); - r->max(0) = path.eval("number(max)").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - r->min(0) = path.eval("number(min)").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - r->offset(0) = path.eval("number(offset)").getValue< ::rl::math::Real>(0); - r->speed(0) = path.eval("number(speed)").getValue< ::rl::math::Real>(0); + r->max(0) = path.eval("number(max)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + r->min(0) = path.eval("number(min)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + r->offset(0) = path.eval("number(offset)").getValue<::rl::math::Real>(0); + r->speed(0) = path.eval("number(speed)").getValue<::rl::math::Real>(0); r->wraparound(0) = path.eval("count(wraparound) > 0").getValue(); - r->S(0, 0) = path.eval("number(axis/x)").getValue< ::rl::math::Real>(0); - r->S(1, 0) = path.eval("number(axis/y)").getValue< ::rl::math::Real>(0); - r->S(2, 0) = path.eval("number(axis/z)").getValue< ::rl::math::Real>(1); + r->S(0, 0) = path.eval("number(axis/x)").getValue<::rl::math::Real>(0); + r->S(1, 0) = path.eval("number(axis/y)").getValue<::rl::math::Real>(0); + r->S(2, 0) = path.eval("number(axis/z)").getValue<::rl::math::Real>(1); r->max *= ::rl::math::DEG2RAD; r->min *= ::rl::math::DEG2RAD; @@ -393,18 +393,18 @@ namespace rl model->add(s, a, b); - s->max(0) = path.eval("number(max[1])").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - s->max(1) = path.eval("number(max[2])").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - s->max(2) = path.eval("number(max[3])").getValue< ::rl::math::Real>(::std::numeric_limits< ::rl::math::Real>::max()); - s->min(0) = path.eval("number(min[1])").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - s->min(1) = path.eval("number(min[2])").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - s->min(2) = path.eval("number(min[3])").getValue< ::rl::math::Real>(-::std::numeric_limits< ::rl::math::Real>::max()); - s->offset(0) = path.eval("number(offset[1])").getValue< ::rl::math::Real>(0); - s->offset(1) = path.eval("number(offset[2])").getValue< ::rl::math::Real>(0); - s->offset(2) = path.eval("number(offset[3])").getValue< ::rl::math::Real>(0); - s->speed(0) = path.eval("number(speed[1])").getValue< ::rl::math::Real>(0); - s->speed(1) = path.eval("number(speed[2])").getValue< ::rl::math::Real>(0); - s->speed(2) = path.eval("number(speed[3])").getValue< ::rl::math::Real>(0); + s->max(0) = path.eval("number(max[1])").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + s->max(1) = path.eval("number(max[2])").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + s->max(2) = path.eval("number(max[3])").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + s->min(0) = path.eval("number(min[1])").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + s->min(1) = path.eval("number(min[2])").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + s->min(2) = path.eval("number(min[3])").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + s->offset(0) = path.eval("number(offset[1])").getValue<::rl::math::Real>(0); + s->offset(1) = path.eval("number(offset[2])").getValue<::rl::math::Real>(0); + s->offset(2) = path.eval("number(offset[3])").getValue<::rl::math::Real>(0); + s->speed(0) = path.eval("number(speed[1])").getValue<::rl::math::Real>(0); + s->speed(1) = path.eval("number(speed[2])").getValue<::rl::math::Real>(0); + s->speed(2) = path.eval("number(speed[3])").getValue<::rl::math::Real>(0); transform = s; } @@ -425,7 +425,7 @@ namespace rl model->update(); - ::rl::xml::NodeSet home = path.eval("home/q").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet home = path.eval("home/q").getValue<::rl::xml::NodeSet>(); if (home.size() > 0) { @@ -438,7 +438,7 @@ namespace rl for (int j = 0; j < home.size(); ++j) { - q(j) = ::boost::lexical_cast< ::rl::math::Real>(home[j].getContent().c_str()); + q(j) = ::boost::lexical_cast<::rl::math::Real>(home[j].getContent().c_str()); if ("deg" == home[j].getProperty("unit")) { @@ -449,14 +449,14 @@ namespace rl model->setHomePosition(q); } - ::rl::xml::NodeSet gammaPosition = path.eval("gammaPosition").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet gammaPosition = path.eval("gammaPosition").getValue<::rl::xml::NodeSet>(); for (int j = 0; j < gammaPosition.size(); ++j) { ::rl::xml::Path path(document, gammaPosition[j]); - ::std::size_t m = path.eval("count(row)").getValue< ::std::size_t>(0); - ::std::size_t n = path.eval("count(row[1]/col)").getValue< ::std::size_t>(0); + ::std::size_t m = path.eval("count(row)").getValue<::std::size_t>(0); + ::std::size_t n = path.eval("count(row[1]/col)").getValue<::std::size_t>(0); if (m != model->getDofPosition()) { @@ -465,36 +465,36 @@ namespace rl ::rl::math::Matrix G(m, n); - ::rl::xml::NodeSet rows = path.eval("row").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet rows = path.eval("row").getValue<::rl::xml::NodeSet>(); for (int k = 0; k < rows.size(); ++k) { ::rl::xml::Path path(document, rows[k]); - if (path.eval("count(col)").getValue< ::std::size_t>(0) != model->getDofPosition()) + if (path.eval("count(col)").getValue<::std::size_t>(0) != model->getDofPosition()) { throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of columns in gamma position matrix in file '" + filename + "'"); } - ::rl::xml::NodeSet cols = path.eval("col").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet cols = path.eval("col").getValue<::rl::xml::NodeSet>(); for (int l = 0; l < cols.size(); ++l) { - G(k, l) = boost::lexical_cast< ::rl::math::Real>(cols[l].getContent().c_str()); + G(k, l) = boost::lexical_cast<::rl::math::Real>(cols[l].getContent().c_str()); } } model->setGammaPosition(G); } - ::rl::xml::NodeSet gammaVelocity = path.eval("gammaVelocity").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet gammaVelocity = path.eval("gammaVelocity").getValue<::rl::xml::NodeSet>(); for (int j = 0; j < gammaVelocity.size(); ++j) { ::rl::xml::Path path(document, gammaVelocity[j]); - ::std::size_t m = path.eval("count(row)").getValue< ::std::size_t>(0); - ::std::size_t n = path.eval("count(row[1]/col)").getValue< ::std::size_t>(0); + ::std::size_t m = path.eval("count(row)").getValue<::std::size_t>(0); + ::std::size_t n = path.eval("count(row[1]/col)").getValue<::std::size_t>(0); if (m != model->getDof()) { @@ -503,22 +503,22 @@ namespace rl ::rl::math::Matrix G(m, n); - ::rl::xml::NodeSet rows = path.eval("row").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet rows = path.eval("row").getValue<::rl::xml::NodeSet>(); for (int k = 0; k < rows.size(); ++k) { ::rl::xml::Path path(document, rows[k]); - if (path.eval("count(col)").getValue< ::std::size_t>(0) != model->getDof()) + if (path.eval("count(col)").getValue<::std::size_t>(0) != model->getDof()) { throw Exception("rl::mdl::XmlFactory::load() - Incorrect number of columns in gamma velocity matrix in file '" + filename + "'"); } - ::rl::xml::NodeSet cols = path.eval("col").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet cols = path.eval("col").getValue<::rl::xml::NodeSet>(); for (int l = 0; l < cols.size(); ++l) { - G(k, l) = boost::lexical_cast< ::rl::math::Real>(cols[l].getContent().c_str()); + G(k, l) = boost::lexical_cast<::rl::math::Real>(cols[l].getContent().c_str()); } } diff --git a/src/rl/plan/AddRrtConCon.cpp b/src/rl/plan/AddRrtConCon.cpp index be5cad0d..afdc0b04 100644 --- a/src/rl/plan/AddRrtConCon.cpp +++ b/src/rl/plan/AddRrtConCon.cpp @@ -34,7 +34,7 @@ namespace rl { AddRrtConCon::AddRrtConCon() : RrtConCon(), - alpha(static_cast< ::rl::math::Real>(0.05)), + alpha(static_cast<::rl::math::Real>(0.05)), lower(2), radius(20) { @@ -50,7 +50,7 @@ namespace rl ::std::shared_ptr bundle = ::std::make_shared(); bundle->index = ::boost::num_vertices(tree) - 1; bundle->q = q; - bundle->radius = ::std::numeric_limits< ::rl::math::Real>::max(); + bundle->radius = ::std::numeric_limits<::rl::math::Real>::max(); Vertex v = ::boost::add_vertex(tree); tree[v] = bundle; @@ -82,8 +82,8 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared< ::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); Tree* a = &this->tree[0]; Tree* b = &this->tree[1]; @@ -107,7 +107,7 @@ namespace rl if (nullptr != aConnected) { - if (get(*a, aNearest.second)->radius < ::std::numeric_limits< ::rl::math::Real>::max()) + if (get(*a, aNearest.second)->radius < ::std::numeric_limits<::rl::math::Real>::max()) { get(*a, aNearest.second)->radius *= (1 + this->alpha); } @@ -127,7 +127,7 @@ namespace rl } else { - if (get(*a, aNearest.second)->radius < ::std::numeric_limits< ::rl::math::Real>::max()) + if (get(*a, aNearest.second)->radius < ::std::numeric_limits<::rl::math::Real>::max()) { get(*a, aNearest.second)->radius *= (1 - this->alpha); get(*a, aNearest.second)->radius = ::std::max(this->lower, get(*a, aNearest.second)->radius); diff --git a/src/rl/plan/AdvancedOptimizer.cpp b/src/rl/plan/AdvancedOptimizer.cpp index 9f492403..d79278b0 100644 --- a/src/rl/plan/AdvancedOptimizer.cpp +++ b/src/rl/plan/AdvancedOptimizer.cpp @@ -36,7 +36,7 @@ namespace rl AdvancedOptimizer::AdvancedOptimizer() : SimpleOptimizer(), length(1), - ratio(static_cast< ::rl::math::Real>(0.1)) + ratio(static_cast<::rl::math::Real>(0.1)) { } @@ -117,7 +117,7 @@ namespace rl { if (this->model->distance(*i, *j) > this->length) { - this->model->interpolate(*i, *j, static_cast< ::rl::math::Real>(0.5), inter); + this->model->interpolate(*i, *j, static_cast<::rl::math::Real>(0.5), inter); j = path.insert(j, inter); diff --git a/src/rl/plan/BridgeSampler.cpp b/src/rl/plan/BridgeSampler.cpp index af327b87..ff74038d 100644 --- a/src/rl/plan/BridgeSampler.cpp +++ b/src/rl/plan/BridgeSampler.cpp @@ -33,7 +33,7 @@ namespace rl { BridgeSampler::BridgeSampler() : GaussianSampler(), - ratio(static_cast< ::rl::math::Real>(5) / static_cast< ::rl::math::Real>(6)) + ratio(static_cast<::rl::math::Real>(5) / static_cast<::rl::math::Real>(6)) { } @@ -68,7 +68,7 @@ namespace rl if (this->model->isColliding(q3)) { - this->model->interpolate(q2, q3, static_cast< ::rl::math::Real>(0.5), q); + this->model->interpolate(q2, q3, static_cast<::rl::math::Real>(0.5), q); if (!this->model->isColliding(q)) { diff --git a/src/rl/plan/DistanceModel.cpp b/src/rl/plan/DistanceModel.cpp index f944cc58..dc66e305 100644 --- a/src/rl/plan/DistanceModel.cpp +++ b/src/rl/plan/DistanceModel.cpp @@ -45,7 +45,7 @@ namespace rl ::rl::math::Real DistanceModel::distance(const ::rl::math::Vector3& point) { - ::rl::math::Real distance = ::std::numeric_limits< ::rl::math::Real>::max(); + ::rl::math::Real distance = ::std::numeric_limits<::rl::math::Real>::max(); ::rl::math::Vector3 point1; ::rl::math::Vector3 point2; @@ -53,7 +53,7 @@ namespace rl { if (*i != this->model) { - distance = ::std::min(distance, dynamic_cast< ::rl::sg::DistanceScene*>(this->scene)->distance(*i, point, point1, point2)); + distance = ::std::min(distance, dynamic_cast<::rl::sg::DistanceScene*>(this->scene)->distance(*i, point, point1, point2)); } } @@ -65,7 +65,7 @@ namespace rl { assert(body < this->model->getNumBodies()); - ::rl::math::Real distance = ::std::numeric_limits< ::rl::math::Real>::max(); + ::rl::math::Real distance = ::std::numeric_limits<::rl::math::Real>::max(); ::rl::math::Vector3 tmpPoint1; ::rl::math::Vector3 tmpPoint2; @@ -78,7 +78,7 @@ namespace rl { for (::rl::sg::Model::Iterator j = (*i)->begin(); j != (*i)->end(); ++j) { - ::rl::math::Real tmpDistance = dynamic_cast< ::rl::sg::DistanceScene*>(this->scene)->distance(this->model->getBody(body), *j, tmpPoint1, tmpPoint2); + ::rl::math::Real tmpDistance = dynamic_cast<::rl::sg::DistanceScene*>(this->scene)->distance(this->model->getBody(body), *j, tmpPoint1, tmpPoint2); if (tmpDistance < distance) { @@ -96,7 +96,7 @@ namespace rl { if (this->areColliding(body, i)) { - ::rl::math::Real tmpDistance = dynamic_cast< ::rl::sg::DistanceScene*>(this->scene)->distance(this->model->getBody(body), this->model->getBody(i), tmpPoint1, tmpPoint2); + ::rl::math::Real tmpDistance = dynamic_cast<::rl::sg::DistanceScene*>(this->scene)->distance(this->model->getBody(body), this->model->getBody(i), tmpPoint1, tmpPoint2); if (tmpDistance < distance) { @@ -139,7 +139,7 @@ namespace rl ::rl::math::Vector3 tmpPoint1; ::rl::math::Vector3 tmpPoint2; - ::rl::math::Real tmpDistance = dynamic_cast< ::rl::sg::DistanceScene*>(this->scene)->distance( + ::rl::math::Real tmpDistance = dynamic_cast<::rl::sg::DistanceScene*>(this->scene)->distance( *k, *l, tmpPoint1, @@ -168,7 +168,7 @@ namespace rl ::rl::math::Vector3 tmpPoint1; ::rl::math::Vector3 tmpPoint2; - ::rl::math::Real tmpDistance = dynamic_cast< ::rl::sg::DistanceScene*>(this->scene)->distance( + ::rl::math::Real tmpDistance = dynamic_cast<::rl::sg::DistanceScene*>(this->scene)->distance( *k, *l, tmpPoint1, diff --git a/src/rl/plan/Eet.cpp b/src/rl/plan/Eet.cpp index 50727dc2..b42436df 100644 --- a/src/rl/plan/Eet.cpp +++ b/src/rl/plan/Eet.cpp @@ -52,14 +52,14 @@ namespace rl { Eet::Eet() : RrtCon(), - alpha(static_cast< ::rl::math::Real>(0.01)), + alpha(static_cast<::rl::math::Real>(0.01)), alternativeDistanceComputation(false), beta(0), - distanceWeight(static_cast< ::rl::math::Real>(0.1)), + distanceWeight(static_cast<::rl::math::Real>(0.1)), explorers(), explorersSetup(), - gamma(static_cast< ::rl::math::Real>(1) / static_cast< ::rl::math::Real>(3)), - goalEpsilon(static_cast< ::rl::math::Real>(0.1)), + gamma(static_cast<::rl::math::Real>(1) / static_cast<::rl::math::Real>(3)), + goalEpsilon(static_cast<::rl::math::Real>(0.1)), goalEpsilonUseOrientation(false), max(::rl::math::Vector3::Zero()), min(::rl::math::Vector3::Zero()), @@ -120,8 +120,8 @@ namespace rl do { VertexBundle best; - best.q = ::std::make_shared< ::rl::math::Vector>(this->model->getDofPosition()); - best.t = ::std::make_shared< ::rl::math::Transform>(); + best.q = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); + best.t = ::std::make_shared<::rl::math::Transform>(); state = this->expand(get(tree, n), *get(tree, nearest.second)->t, chosen, distance, best); // TODO @@ -201,7 +201,7 @@ namespace rl this->model->step(*nearest->q, qdot, *expanded.q); - if (this->model->getManipulabilityMeasure() < static_cast< ::rl::math::Real>(1.0e-3)) // within singularity + if (this->model->getManipulabilityMeasure() < static_cast<::rl::math::Real>(1.0e-3)) // within singularity { *expanded.q = this->sampler->generate(); // uniform sampling for singularities ::rl::math::Real tmp = this->model->distance(*nearest->q, *expanded.q); @@ -236,8 +236,8 @@ namespace rl Vertex extended = nullptr; VertexBundle best; - best.q = ::std::make_shared< ::rl::math::Vector>(this->model->getDofPosition()); - best.t = ::std::make_shared< ::rl::math::Transform>(); + best.q = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); + best.t = ::std::make_shared<::rl::math::Transform>(); if (this->expand(get(tree, nearest.second), *get(tree, nearest.second)->t, chosen, distance, best) >= 0) { @@ -249,7 +249,7 @@ namespace rl return extended; } - ::std::normal_distribution< ::rl::math::Real>::result_type + ::std::normal_distribution<::rl::math::Real>::result_type Eet::gauss() { return this->gaussDistribution(this->gaussEngine); @@ -294,11 +294,11 @@ namespace rl Rrt::Neighbor Eet::nearest(const Tree& tree, const ::rl::math::Transform& chosen) { - ::std::vector< ::rl::math::GnatNearestNeighbors::Neighbor> neighbors = this->nn.nearest(WorkspaceMetric::Value(&chosen, Vertex()), 1); + ::std::vector<::rl::math::GnatNearestNeighbors::Neighbor> neighbors = this->nn.nearest(WorkspaceMetric::Value(&chosen, Vertex()), 1); return Neighbor(neighbors.front().first, neighbors.front().second.second); } - ::std::uniform_real_distribution< ::rl::math::Real>::result_type + ::std::uniform_real_distribution<::rl::math::Real>::result_type Eet::rand() { return this->randDistribution(this->randEngine); @@ -391,10 +391,10 @@ namespace rl // tree initialization with start configuration - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector>(*this->start)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); this->model->setPosition(*this->start); this->model->updateFrames(); - get(this->tree[0], this->begin[0])->t = ::std::make_shared< ::rl::math::Transform>(this->model->forwardPosition()); + get(this->tree[0], this->begin[0])->t = ::std::make_shared<::rl::math::Transform>(this->model->forwardPosition()); this->nn.push(WorkspaceMetric::Value(get(this->tree[0], this->begin[0])->t.get(), begin[0])); ::rl::math::Transform chosen; @@ -413,7 +413,7 @@ namespace rl { Neighbor nearest; - if (path.end() == i + 1 && this->rand() < static_cast< ::rl::math::Real>(0.5)) // within last sphere + if (path.end() == i + 1 && this->rand() < static_cast<::rl::math::Real>(0.5)) // within last sphere { chosen = goal; // select goal position and orientation nearest = this->nearest(this->tree[0], chosen); // nearest vertex in tree @@ -477,7 +477,7 @@ namespace rl } sigma *= 1 - this->alpha; // increase exploitation - sigma = ::std::max(static_cast< ::rl::math::Real>(0.1), sigma); + sigma = ::std::max(static_cast<::rl::math::Real>(0.1), sigma); for (WorkspaceSphereVector::reverse_iterator k = ++path.rbegin(); k.base() != i; ++k) // search spheres backwards { diff --git a/src/rl/plan/Eet.h b/src/rl/plan/Eet.h index 8526c87b..0da240a0 100644 --- a/src/rl/plan/Eet.h +++ b/src/rl/plan/Eet.h @@ -140,7 +140,7 @@ namespace rl Vertex extend(Tree& tree, const Neighbor& nearest, const ::rl::math::Transform& chosen); - ::std::normal_distribution< ::rl::math::Real>::result_type gauss(); + ::std::normal_distribution<::rl::math::Real>::result_type gauss(); static VertexBundle* get(const Tree& tree, const Vertex& v); @@ -148,13 +148,13 @@ namespace rl Neighbor nearest(const Tree& tree, const ::rl::math::Transform& chosen); - ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + ::std::uniform_real_distribution<::rl::math::Real>::result_type rand(); - ::std::normal_distribution< ::rl::math::Real> gaussDistribution; + ::std::normal_distribution<::rl::math::Real> gaussDistribution; ::std::mt19937 gaussEngine; - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; diff --git a/src/rl/plan/GaussianSampler.cpp b/src/rl/plan/GaussianSampler.cpp index 832bc36f..f15a69c8 100644 --- a/src/rl/plan/GaussianSampler.cpp +++ b/src/rl/plan/GaussianSampler.cpp @@ -45,7 +45,7 @@ namespace rl { } - ::std::normal_distribution< ::rl::math::Real>::result_type + ::std::normal_distribution<::rl::math::Real>::result_type GaussianSampler::gauss() { return this->gaussDistribution(this->gaussEngine); diff --git a/src/rl/plan/GaussianSampler.h b/src/rl/plan/GaussianSampler.h index b71e2b65..98d59147 100644 --- a/src/rl/plan/GaussianSampler.h +++ b/src/rl/plan/GaussianSampler.h @@ -57,9 +57,9 @@ namespace rl ::rl::math::Vector* sigma; protected: - ::std::normal_distribution< ::rl::math::Real>::result_type gauss(); + ::std::normal_distribution<::rl::math::Real>::result_type gauss(); - ::std::normal_distribution< ::rl::math::Real> gaussDistribution; + ::std::normal_distribution<::rl::math::Real> gaussDistribution; ::std::mt19937 gaussEngine; diff --git a/src/rl/plan/GnatNearestNeighbors.cpp b/src/rl/plan/GnatNearestNeighbors.cpp index 9654f618..552abb0b 100644 --- a/src/rl/plan/GnatNearestNeighbors.cpp +++ b/src/rl/plan/GnatNearestNeighbors.cpp @@ -53,7 +53,7 @@ namespace rl return this->container.empty(); } - ::boost::optional< ::std::size_t> + ::boost::optional<::std::size_t> GnatNearestNeighbors::getChecks() const { return this->container.getChecks(); @@ -108,7 +108,7 @@ namespace rl } void - GnatNearestNeighbors::setChecks(const ::boost::optional< ::std::size_t>& checks) + GnatNearestNeighbors::setChecks(const ::boost::optional<::std::size_t>& checks) { this->container.setChecks(checks); } diff --git a/src/rl/plan/GnatNearestNeighbors.h b/src/rl/plan/GnatNearestNeighbors.h index 1f49a7e4..3f00955b 100644 --- a/src/rl/plan/GnatNearestNeighbors.h +++ b/src/rl/plan/GnatNearestNeighbors.h @@ -48,7 +48,7 @@ namespace rl bool empty() const; - ::boost::optional< ::std::size_t> getChecks() const; + ::boost::optional<::std::size_t> getChecks() const; ::std::size_t getNodeDataMax() const; @@ -66,7 +66,7 @@ namespace rl void seed(const ::std::mt19937::result_type& value); - void setChecks(const ::boost::optional< ::std::size_t>& checks); + void setChecks(const ::boost::optional<::std::size_t>& checks); void setNodeDataMax(const ::std::size_t& nodeDataMax); diff --git a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.cpp b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.cpp index 48e6c56b..f4d99650 100644 --- a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.cpp +++ b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.cpp @@ -53,7 +53,7 @@ namespace rl return this->container.empty(); } - ::boost::optional< ::std::size_t> + ::boost::optional<::std::size_t> KdtreeBoundingBoxNearestNeighbors::getChecks() const { return this->container.getChecks(); @@ -84,7 +84,7 @@ namespace rl } void - KdtreeBoundingBoxNearestNeighbors::setChecks(const ::boost::optional< ::std::size_t>& checks) + KdtreeBoundingBoxNearestNeighbors::setChecks(const ::boost::optional<::std::size_t>& checks) { this->container.setChecks(checks); } diff --git a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h index 87d065a2..95da1fcb 100644 --- a/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/plan/KdtreeBoundingBoxNearestNeighbors.h @@ -48,7 +48,7 @@ namespace rl bool empty() const; - ::boost::optional< ::std::size_t> getChecks() const; + ::boost::optional<::std::size_t> getChecks() const; ::std::size_t getNodeDataMax() const; @@ -58,7 +58,7 @@ namespace rl ::std::vector radius(const Value& query, const Distance& radius, const bool& sorted = true) const; - void setChecks(const ::boost::optional< ::std::size_t>& checks); + void setChecks(const ::boost::optional<::std::size_t>& checks); void setNodeDataMax(const ::std::size_t& nodeDataMax); diff --git a/src/rl/plan/KdtreeNearestNeighbors.cpp b/src/rl/plan/KdtreeNearestNeighbors.cpp index 4dedb16a..ea78484d 100644 --- a/src/rl/plan/KdtreeNearestNeighbors.cpp +++ b/src/rl/plan/KdtreeNearestNeighbors.cpp @@ -53,7 +53,7 @@ namespace rl return this->container.empty(); } - ::boost::optional< ::std::size_t> + ::boost::optional<::std::size_t> KdtreeNearestNeighbors::getChecks() const { return this->container.getChecks(); @@ -84,7 +84,7 @@ namespace rl } void - KdtreeNearestNeighbors::setChecks(const ::boost::optional< ::std::size_t>& checks) + KdtreeNearestNeighbors::setChecks(const ::boost::optional<::std::size_t>& checks) { this->container.setChecks(checks); } diff --git a/src/rl/plan/KdtreeNearestNeighbors.h b/src/rl/plan/KdtreeNearestNeighbors.h index cf28c5ef..3946c7d7 100644 --- a/src/rl/plan/KdtreeNearestNeighbors.h +++ b/src/rl/plan/KdtreeNearestNeighbors.h @@ -48,7 +48,7 @@ namespace rl bool empty() const; - ::boost::optional< ::std::size_t> getChecks() const; + ::boost::optional<::std::size_t> getChecks() const; ::std::size_t getSamples() const; @@ -58,7 +58,7 @@ namespace rl ::std::vector radius(const Value& query, const Distance& radius, const bool& sorted = true) const; - void setChecks(const ::boost::optional< ::std::size_t>& checks); + void setChecks(const ::boost::optional<::std::size_t>& checks); void setSamples(const ::std::size_t& samples); diff --git a/src/rl/plan/MatrixPtr.h b/src/rl/plan/MatrixPtr.h index 1a7538da..f60f7d94 100644 --- a/src/rl/plan/MatrixPtr.h +++ b/src/rl/plan/MatrixPtr.h @@ -34,7 +34,7 @@ namespace rl { namespace plan { - typedef ::std::shared_ptr< ::rl::math::Matrix> MatrixPtr; + typedef ::std::shared_ptr<::rl::math::Matrix> MatrixPtr; } } diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index 6166a2b5..e2221d74 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -307,12 +307,12 @@ namespace rl } } - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> Model::getPositionUnits() const { if (nullptr != this->kin) { - ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDofPosition());; + ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDofPosition());; this->kin->getPositionUnits(units); return units; } diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index e5dd9591..a4426dc7 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -88,7 +88,7 @@ namespace rl virtual ::std::size_t getOperationalDof() const; - virtual ::Eigen::Matrix< ::rl::math::Unit, ::Eigen::Dynamic, 1> getPositionUnits() const; + virtual ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getPositionUnits() const; virtual ::Eigen::Matrix getWraparounds() const; diff --git a/src/rl/plan/Prm.cpp b/src/rl/plan/Prm.cpp index 07099088..3ae53dba 100644 --- a/src/rl/plan/Prm.cpp +++ b/src/rl/plan/Prm.cpp @@ -43,9 +43,9 @@ namespace rl Prm::Prm() : Planner(), astar(true), - degree(::std::numeric_limits< ::std::size_t>::max()), + degree(::std::numeric_limits<::std::size_t>::max()), k(30), - radius(::std::numeric_limits< ::rl::math::Real>::max()), + radius(::std::numeric_limits<::rl::math::Real>::max()), sampler(nullptr), verifier(nullptr), begin(nullptr), @@ -99,7 +99,7 @@ namespace rl { for (::std::size_t i = 0; i < steps; ++i) { - VectorPtr q = ::std::make_shared< ::rl::math::Vector>(this->model->getDofPosition()); + VectorPtr q = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); *q = this->sampler->generateCollisionFree(); Vertex v = this->addVertex(q); this->insert(v); @@ -209,10 +209,10 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin = this->addVertex(::std::make_shared< ::rl::math::Vector>(*this->start)); + this->begin = this->addVertex(::std::make_shared<::rl::math::Vector>(*this->start)); this->insert(this->begin); - this->end = this->addVertex(::std::make_shared< ::rl::math::Vector>(*this->goal)); + this->end = this->addVertex(::std::make_shared<::rl::math::Vector>(*this->goal)); this->insert(this->end); while ((::std::chrono::steady_clock::now() - this->time) < this->duration && !::boost::same_component(this->begin, this->end, this->ds)) @@ -238,9 +238,9 @@ namespace rl ::boost::get(&EdgeBundle::weight, this->graph), ::boost::get(&VertexBundle::index, this->graph), ::boost::get(&VertexBundle::color, this->graph), - ::std::less< ::rl::math::Real>(), - ::std::plus< ::rl::math::Real>(), - ::std::numeric_limits< ::rl::math::Real>::max(), + ::std::less<::rl::math::Real>(), + ::std::plus<::rl::math::Real>(), + ::std::numeric_limits<::rl::math::Real>::max(), 0 ); } @@ -253,9 +253,9 @@ namespace rl ::boost::get(&VertexBundle::distance, this->graph), ::boost::get(&EdgeBundle::weight, this->graph), ::boost::get(&VertexBundle::index, this->graph), - ::std::less< ::rl::math::Real>(), - ::boost::closed_plus< ::rl::math::Real>(), - ::std::numeric_limits< ::rl::math::Real>::max(), + ::std::less<::rl::math::Real>(), + ::boost::closed_plus<::rl::math::Real>(), + ::std::numeric_limits<::rl::math::Real>::max(), 0, ::boost::default_dijkstra_visitor() ); diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index 8ae7c4e6..183b920e 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -81,7 +81,7 @@ namespace rl } #else // This works better in our examples. Here we define entropy by using samples where we are unsure, if they are colliding. - if (::std::abs(pFree - static_cast< ::rl::math::Real>(0.5)) < ::std::abs(pBest - static_cast< ::rl::math::Real>(0.5))) + if (::std::abs(pFree - static_cast<::rl::math::Real>(0.5)) < ::std::abs(pBest - static_cast<::rl::math::Real>(0.5))) { pBest = pFree; bestSample = sample; @@ -94,7 +94,7 @@ namespace rl { // store the sample in the graph bestSample.isColliding = false; - Vertex v = this->addVertex(::std::make_shared< ::rl::math::Vector>(bestSample.q)); + Vertex v = this->addVertex(::std::make_shared<::rl::math::Vector>(bestSample.q)); this->insert(v); } @@ -109,13 +109,13 @@ namespace rl // indices for two random vertices // the first sample uses the start ot the end component #ifdef ORIGINAL_VERSION - ::std::size_t randIndex1 = static_cast< ::std::size_t>(::std::floor(this->rand() * this->getNumVertices())); + ::std::size_t randIndex1 = static_cast<::std::size_t>(::std::floor(this->rand() * this->getNumVertices())); #else // here we always pick a component containing the beginning or end vertex // this prevents roadmap building in remote areas. - ::std::size_t randIndex1 = static_cast< ::std::size_t>(::std::floor(this->rand() * 2)); + ::std::size_t randIndex1 = static_cast<::std::size_t>(::std::floor(this->rand() * 2)); #endif - ::std::size_t randIndex2 = static_cast< ::std::size_t>(::std::floor(this->rand() * this->getNumVertices())); + ::std::size_t randIndex2 = static_cast<::std::size_t>(::std::floor(this->rand() * this->getNumVertices())); // two random vertices Vertex sample1 = ::boost::vertex(randIndex1, this->graph); @@ -137,7 +137,7 @@ namespace rl while (::boost::same_component(sample1, sample2, this->ds)); // The point in the middle of the two samples. - ::rl::math::Vector midPoint = static_cast< ::rl::math::Real>(0.5) * (*this->graph[sample1].q + *this->graph[sample2].q); + ::rl::math::Vector midPoint = static_cast<::rl::math::Real>(0.5) * (*this->graph[sample1].q + *this->graph[sample2].q); // add variance drawn randomly from [-variance, variance] to the point for (::std::ptrdiff_t i = 0; i < midPoint.size(); ++i) @@ -176,7 +176,7 @@ namespace rl queue.pop(); } - return 1 - static_cast< ::rl::math::Real>(collisionCount) / static_cast< ::rl::math::Real>(count); + return 1 - static_cast<::rl::math::Real>(collisionCount) / static_cast<::rl::math::Real>(count); } ::std::string @@ -185,7 +185,7 @@ namespace rl return "PRM Utility Guided"; } - ::std::uniform_real_distribution< ::rl::math::Real>::result_type + ::std::uniform_real_distribution<::rl::math::Real>::result_type PrmUtilityGuided::rand() { return this->randDistribution(this->randEngine); diff --git a/src/rl/plan/PrmUtilityGuided.h b/src/rl/plan/PrmUtilityGuided.h index e4efb32d..74f02322 100644 --- a/src/rl/plan/PrmUtilityGuided.h +++ b/src/rl/plan/PrmUtilityGuided.h @@ -103,13 +103,13 @@ namespace rl */ ::rl::math::Real getFreeProbability(const Sample& sample); - ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + ::std::uniform_real_distribution<::rl::math::Real>::result_type rand(); ::std::size_t numNeighbors; ::std::size_t numSamples; - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; diff --git a/src/rl/plan/RealList.h b/src/rl/plan/RealList.h index 375e0bbd..eec531dc 100644 --- a/src/rl/plan/RealList.h +++ b/src/rl/plan/RealList.h @@ -34,7 +34,7 @@ namespace rl { namespace plan { - typedef ::std::list< ::rl::math::Real> RealList; + typedef ::std::list<::rl::math::Real> RealList; } } diff --git a/src/rl/plan/RecursiveVerifier.cpp b/src/rl/plan/RecursiveVerifier.cpp index 36265cbd..3e4eb95d 100644 --- a/src/rl/plan/RecursiveVerifier.cpp +++ b/src/rl/plan/RecursiveVerifier.cpp @@ -52,7 +52,7 @@ namespace rl if (steps > 1) { - ::std::queue< ::std::pair< ::std::size_t, ::std::size_t>> queue; + ::std::queue<::std::pair<::std::size_t, ::std::size_t>> queue; queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(1), ::std::forward_as_tuple(steps - 1)); @@ -62,7 +62,7 @@ namespace rl { ::std::size_t midpoint = (queue.front().first + queue.front().second) / 2; - this->model->interpolate(u, v, static_cast< ::rl::math::Real>(midpoint) / static_cast< ::rl::math::Real>(steps), inter); + this->model->interpolate(u, v, static_cast<::rl::math::Real>(midpoint) / static_cast<::rl::math::Real>(steps), inter); if (this->model->isColliding(inter)) { diff --git a/src/rl/plan/Rrt.cpp b/src/rl/plan/Rrt.cpp index 519f4bd8..30a6f397 100644 --- a/src/rl/plan/Rrt.cpp +++ b/src/rl/plan/Rrt.cpp @@ -36,7 +36,7 @@ namespace rl Rrt::Rrt(const ::std::size_t& trees) : Planner(), delta(1), - epsilon(static_cast< ::rl::math::Real>(1.0e-3)), + epsilon(static_cast<::rl::math::Real>(1.0e-3)), sampler(nullptr), begin(trees, nullptr), end(trees, nullptr), @@ -117,7 +117,7 @@ namespace rl step = this->delta; } - VectorPtr last = ::std::make_shared< ::rl::math::Vector>(this->model->getDofPosition()); + VectorPtr last = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); this->model->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, *last); @@ -169,7 +169,7 @@ namespace rl ::rl::math::Real distance = nearest.first; ::rl::math::Real step = ::std::min(distance, this->delta); - VectorPtr next = ::std::make_shared< ::rl::math::Vector>(this->model->getDofPosition()); + VectorPtr next = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); this->model->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, *next); @@ -278,7 +278,7 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector>(*this->start)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); while ((::std::chrono::steady_clock::now() - this->time) < this->duration) { diff --git a/src/rl/plan/Rrt.h b/src/rl/plan/Rrt.h index 4a0df4f1..b4ee139d 100644 --- a/src/rl/plan/Rrt.h +++ b/src/rl/plan/Rrt.h @@ -119,7 +119,7 @@ namespace rl typedef ::std::pair EdgeIteratorPair; - typedef ::std::pair< ::rl::math::Real, Vertex> Neighbor; + typedef ::std::pair<::rl::math::Real, Vertex> Neighbor; typedef ::boost::graph_traits::vertex_iterator VertexIterator; diff --git a/src/rl/plan/RrtCon.cpp b/src/rl/plan/RrtCon.cpp index f27b1696..7633e8fb 100644 --- a/src/rl/plan/RrtCon.cpp +++ b/src/rl/plan/RrtCon.cpp @@ -51,7 +51,7 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector>(*this->start)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); while ((::std::chrono::steady_clock::now() - this->time) < this->duration) { diff --git a/src/rl/plan/RrtConCon.cpp b/src/rl/plan/RrtConCon.cpp index 15ead9cd..0091d01b 100644 --- a/src/rl/plan/RrtConCon.cpp +++ b/src/rl/plan/RrtConCon.cpp @@ -51,8 +51,8 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared< ::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); Tree* a = &this->tree[0]; Tree* b = &this->tree[1]; diff --git a/src/rl/plan/RrtDual.cpp b/src/rl/plan/RrtDual.cpp index b21d4904..13057aca 100644 --- a/src/rl/plan/RrtDual.cpp +++ b/src/rl/plan/RrtDual.cpp @@ -79,8 +79,8 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared< ::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); while ((::std::chrono::steady_clock::now() - this->time) < this->duration) { diff --git a/src/rl/plan/RrtExtCon.cpp b/src/rl/plan/RrtExtCon.cpp index dbd45110..aa95b027 100644 --- a/src/rl/plan/RrtExtCon.cpp +++ b/src/rl/plan/RrtExtCon.cpp @@ -51,8 +51,8 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared< ::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); Tree* a = &this->tree[0]; Tree* b = &this->tree[1]; diff --git a/src/rl/plan/RrtExtExt.cpp b/src/rl/plan/RrtExtExt.cpp index 55fb1e67..039e39ce 100644 --- a/src/rl/plan/RrtExtExt.cpp +++ b/src/rl/plan/RrtExtExt.cpp @@ -51,8 +51,8 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared< ::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared< ::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); Tree* a = &this->tree[0]; Tree* b = &this->tree[1]; diff --git a/src/rl/plan/RrtGoalBias.cpp b/src/rl/plan/RrtGoalBias.cpp index 1224a832..f9680c3e 100644 --- a/src/rl/plan/RrtGoalBias.cpp +++ b/src/rl/plan/RrtGoalBias.cpp @@ -35,7 +35,7 @@ namespace rl { RrtGoalBias::RrtGoalBias() : Rrt(), - probability(static_cast< ::rl::math::Real>(0.05)), + probability(static_cast<::rl::math::Real>(0.05)), randDistribution(0, 1), randEngine(::std::random_device()()) { @@ -64,7 +64,7 @@ namespace rl return "RRT Goal Bias"; } - ::std::uniform_real_distribution< ::rl::math::Real>::result_type + ::std::uniform_real_distribution<::rl::math::Real>::result_type RrtGoalBias::rand() { return this->randDistribution(this->randEngine); diff --git a/src/rl/plan/RrtGoalBias.h b/src/rl/plan/RrtGoalBias.h index e974be12..e7027e42 100644 --- a/src/rl/plan/RrtGoalBias.h +++ b/src/rl/plan/RrtGoalBias.h @@ -52,9 +52,9 @@ namespace rl protected: virtual ::rl::math::Vector choose(); - ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + ::std::uniform_real_distribution<::rl::math::Real>::result_type rand(); - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; diff --git a/src/rl/plan/SequentialVerifier.cpp b/src/rl/plan/SequentialVerifier.cpp index 3da97f63..1fcec426 100644 --- a/src/rl/plan/SequentialVerifier.cpp +++ b/src/rl/plan/SequentialVerifier.cpp @@ -52,7 +52,7 @@ namespace rl for (::std::size_t i = 0; i < steps - 1; ++i) { - this->model->interpolate(u, v, static_cast< ::rl::math::Real>(i + 1) / static_cast< ::rl::math::Real>(steps), inter); + this->model->interpolate(u, v, static_cast<::rl::math::Real>(i + 1) / static_cast<::rl::math::Real>(steps), inter); if (this->model->isColliding(inter)) { diff --git a/src/rl/plan/SimpleModel.cpp b/src/rl/plan/SimpleModel.cpp index 11dd2298..ef34d6e8 100644 --- a/src/rl/plan/SimpleModel.cpp +++ b/src/rl/plan/SimpleModel.cpp @@ -78,7 +78,7 @@ namespace rl { for (::rl::sg::Model::Iterator k = (*j)->begin(); k != (*j)->end(); ++k) { - if (dynamic_cast< ::rl::sg::SimpleScene*>(this->scene)->areColliding(this->model->getBody(i), *k)) + if (dynamic_cast<::rl::sg::SimpleScene*>(this->scene)->areColliding(this->model->getBody(i), *k)) { this->body = i; return true; @@ -92,7 +92,7 @@ namespace rl { if (this->areColliding(i, j)) { - if (dynamic_cast< ::rl::sg::SimpleScene*>(this->scene)->areColliding(this->model->getBody(i), this->model->getBody(j))) + if (dynamic_cast<::rl::sg::SimpleScene*>(this->scene)->areColliding(this->model->getBody(i), this->model->getBody(j))) { this->body = i; return true; diff --git a/src/rl/plan/TransformPtr.h b/src/rl/plan/TransformPtr.h index 1d2e05f9..11f93e15 100644 --- a/src/rl/plan/TransformPtr.h +++ b/src/rl/plan/TransformPtr.h @@ -34,7 +34,7 @@ namespace rl { namespace plan { - typedef ::std::shared_ptr< ::rl::math::Transform> TransformPtr; + typedef ::std::shared_ptr<::rl::math::Transform> TransformPtr; } } diff --git a/src/rl/plan/UniformSampler.cpp b/src/rl/plan/UniformSampler.cpp index 092f70cf..fec759f4 100644 --- a/src/rl/plan/UniformSampler.cpp +++ b/src/rl/plan/UniformSampler.cpp @@ -57,7 +57,7 @@ namespace rl return this->model->generatePositionUniform(rand); } - ::std::uniform_real_distribution< ::rl::math::Real>::result_type + ::std::uniform_real_distribution<::rl::math::Real>::result_type UniformSampler::rand() { return this->randDistribution(this->randEngine); diff --git a/src/rl/plan/UniformSampler.h b/src/rl/plan/UniformSampler.h index 58f0da24..578faf83 100644 --- a/src/rl/plan/UniformSampler.h +++ b/src/rl/plan/UniformSampler.h @@ -50,9 +50,9 @@ namespace rl virtual void seed(const ::std::mt19937::result_type& value); protected: - ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + ::std::uniform_real_distribution<::rl::math::Real>::result_type rand(); - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; diff --git a/src/rl/plan/Vector3List.h b/src/rl/plan/Vector3List.h index c41b93f4..e9791d5c 100644 --- a/src/rl/plan/Vector3List.h +++ b/src/rl/plan/Vector3List.h @@ -34,7 +34,7 @@ namespace rl { namespace plan { - typedef ::std::list< ::rl::math::Vector3> Vector3List; + typedef ::std::list<::rl::math::Vector3> Vector3List; } } diff --git a/src/rl/plan/Vector3Ptr.h b/src/rl/plan/Vector3Ptr.h index e47c007e..8f157308 100644 --- a/src/rl/plan/Vector3Ptr.h +++ b/src/rl/plan/Vector3Ptr.h @@ -34,7 +34,7 @@ namespace rl { namespace plan { - typedef ::std::shared_ptr< ::rl::math::Vector3> Vector3Ptr; + typedef ::std::shared_ptr<::rl::math::Vector3> Vector3Ptr; } } diff --git a/src/rl/plan/VectorList.h b/src/rl/plan/VectorList.h index 254817d0..654cab73 100644 --- a/src/rl/plan/VectorList.h +++ b/src/rl/plan/VectorList.h @@ -34,7 +34,7 @@ namespace rl { namespace plan { - typedef ::std::list< ::rl::math::Vector> VectorList; + typedef ::std::list<::rl::math::Vector> VectorList; } } diff --git a/src/rl/plan/VectorPtr.h b/src/rl/plan/VectorPtr.h index 947aaf28..0ffbc516 100644 --- a/src/rl/plan/VectorPtr.h +++ b/src/rl/plan/VectorPtr.h @@ -34,7 +34,7 @@ namespace rl { namespace plan { - typedef ::std::shared_ptr< ::rl::math::Vector> VectorPtr; + typedef ::std::shared_ptr<::rl::math::Vector> VectorPtr; } } diff --git a/src/rl/plan/Verifier.cpp b/src/rl/plan/Verifier.cpp index 16776e53..9efba6da 100644 --- a/src/rl/plan/Verifier.cpp +++ b/src/rl/plan/Verifier.cpp @@ -43,7 +43,7 @@ namespace rl ::std::size_t Verifier::getSteps(const ::rl::math::Real& d) { - return static_cast< ::std::size_t>(::std::ceil(d / this->delta)); + return static_cast<::std::size_t>(::std::ceil(d / this->delta)); } } } diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index e24149d3..8fd6930b 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -38,14 +38,14 @@ namespace rl { WorkspaceSphereExplorer::WorkspaceSphereExplorer() : boundingBox( - ::rl::math::Vector3::Constant(-::std::numeric_limits< ::rl::math::Real>::max()), - ::rl::math::Vector3::Constant(::std::numeric_limits< ::rl::math::Real>::max()) + ::rl::math::Vector3::Constant(-::std::numeric_limits<::rl::math::Real>::max()), + ::rl::math::Vector3::Constant(::std::numeric_limits<::rl::math::Real>::max()) ), goal(), greedy(GREEDY_SPACE), model(nullptr), radius(0), - range(::std::numeric_limits< ::rl::math::Real>::max()), + range(::std::numeric_limits<::rl::math::Real>::max()), samples(10), start(), viewer(nullptr), @@ -96,7 +96,7 @@ namespace rl WorkspaceSphereExplorer::explore() { WorkspaceSphere start; - start.center = ::std::make_shared< ::rl::math::Vector3>(*this->start); + start.center = ::std::make_shared<::rl::math::Vector3>(*this->start); start.radius = ::std::min( this->model->distance(*start.center), this->boundingBox.interiorDistance(*start.center) @@ -130,7 +130,7 @@ namespace rl if ((*this->goal - *top.center).norm() < top.radius) { WorkspaceSphere goal; - goal.center = ::std::make_shared< ::rl::math::Vector3>(*this->goal); + goal.center = ::std::make_shared<::rl::math::Vector3>(*this->goal); goal.radius = this->model->distance(*goal.center); goal.parent = vertex; goal.priority = (*this->goal - *goal.center).norm() - goal.radius; @@ -170,7 +170,7 @@ namespace rl //for (::std::size_t i = 0; i < this->samples; ++i) // TODO { WorkspaceSphere sphere; - sphere.center = ::std::make_shared< ::rl::math::Vector3>( + sphere.center = ::std::make_shared<::rl::math::Vector3>( top.radius * ::rl::math::Vector3::RandomOnSphere(::rl::math::Vector2(this->rand(), this->rand())) + *top.center ); sphere.parent = vertex; @@ -279,7 +279,7 @@ namespace rl return false; } - ::std::uniform_real_distribution< ::rl::math::Real>::result_type + ::std::uniform_real_distribution<::rl::math::Real>::result_type WorkspaceSphereExplorer::rand() { return this->randDistribution(this->randEngine); diff --git a/src/rl/plan/WorkspaceSphereExplorer.h b/src/rl/plan/WorkspaceSphereExplorer.h index 8b85af71..30de7203 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.h +++ b/src/rl/plan/WorkspaceSphereExplorer.h @@ -127,7 +127,7 @@ namespace rl bool isCovered(const Vertex& parent, const ::rl::math::Vector3& point) const; - ::std::uniform_real_distribution< ::rl::math::Real>::result_type rand(); + ::std::uniform_real_distribution<::rl::math::Real>::result_type rand(); Vertex begin; @@ -137,7 +137,7 @@ namespace rl ::std::multiset queue; - ::std::uniform_real_distribution< ::rl::math::Real> randDistribution; + ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; diff --git a/src/rl/sg/Body.cpp b/src/rl/sg/Body.cpp index a1e41727..4a608826 100644 --- a/src/rl/sg/Body.cpp +++ b/src/rl/sg/Body.cpp @@ -74,7 +74,7 @@ namespace rl } void - Body::getBoundingBoxPoints(const ::rl::math::Transform& frame, ::std::vector< ::rl::math::Vector3>& p) const + Body::getBoundingBoxPoints(const ::rl::math::Transform& frame, ::std::vector<::rl::math::Vector3>& p) const { p.resize(8); @@ -110,7 +110,7 @@ namespace rl } void - Body::getPoints(const ::rl::math::Transform& frame, ::std::vector< ::rl::math::Vector3>& p) const + Body::getPoints(const ::rl::math::Transform& frame, ::std::vector<::rl::math::Vector3>& p) const { p.resize(this->points.size()); diff --git a/src/rl/sg/Body.h b/src/rl/sg/Body.h index 3db9b9f6..d8ab626c 100644 --- a/src/rl/sg/Body.h +++ b/src/rl/sg/Body.h @@ -60,7 +60,7 @@ namespace rl Iterator end(); - void getBoundingBoxPoints(const ::rl::math::Transform& frame, ::std::vector< ::rl::math::Vector3>& p) const; + void getBoundingBoxPoints(const ::rl::math::Transform& frame, ::std::vector<::rl::math::Vector3>& p) const; Model* getModel() const; @@ -68,7 +68,7 @@ namespace rl ::std::size_t getNumShapes() const; - void getPoints(const ::rl::math::Transform& frame, ::std::vector< ::rl::math::Vector3>& p) const; + void getPoints(const ::rl::math::Transform& frame, ::std::vector<::rl::math::Vector3>& p) const; Shape* getShape(const ::std::size_t& i) const; @@ -86,7 +86,7 @@ namespace rl ::rl::math::Vector3 min; - ::std::vector< ::rl::math::Vector3> points; + ::std::vector<::rl::math::Vector3> points; protected: Model* model; diff --git a/src/rl/sg/DistanceScene.cpp b/src/rl/sg/DistanceScene.cpp index c83a37fc..e1a66637 100644 --- a/src/rl/sg/DistanceScene.cpp +++ b/src/rl/sg/DistanceScene.cpp @@ -44,7 +44,7 @@ namespace rl ::rl::math::Real DistanceScene::distance(const ::rl::math::Vector3& point, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) { - ::rl::math::Real distance = ::std::numeric_limits< ::rl::math::Real>::max(); + ::rl::math::Real distance = ::std::numeric_limits<::rl::math::Real>::max(); for (Scene::Iterator i = this->begin(); i != this->end(); ++i) { @@ -72,7 +72,7 @@ namespace rl ::rl::math::Real DistanceScene::distance(Body* first, Body* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) { - ::rl::math::Real distance = ::std::numeric_limits< ::rl::math::Real>::max(); + ::rl::math::Real distance = ::std::numeric_limits<::rl::math::Real>::max(); for (Body::Iterator i = first->begin(); i != first->end(); ++i) { @@ -103,7 +103,7 @@ namespace rl ::rl::math::Real DistanceScene::distance(Body* body, const ::rl::math::Vector3& point, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) { - ::rl::math::Real distance = ::std::numeric_limits< ::rl::math::Real>::max(); + ::rl::math::Real distance = ::std::numeric_limits<::rl::math::Real>::max(); for (Body::Iterator i = body->begin(); i != body->end(); ++i) { @@ -131,7 +131,7 @@ namespace rl ::rl::math::Real DistanceScene::distance(Model* first, Model* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) { - ::rl::math::Real distance = ::std::numeric_limits< ::rl::math::Real>::max(); + ::rl::math::Real distance = ::std::numeric_limits<::rl::math::Real>::max(); for (Model::Iterator i = first->begin(); i != first->end(); ++i) { @@ -162,7 +162,7 @@ namespace rl ::rl::math::Real DistanceScene::distance(Model* model, const ::rl::math::Vector3& point, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) { - ::rl::math::Real distance = ::std::numeric_limits< ::rl::math::Real>::max(); + ::rl::math::Real distance = ::std::numeric_limits<::rl::math::Real>::max(); for (Model::Iterator i = model->begin(); i != model->end(); ++i) { diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 99801730..22b96ce2 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -83,7 +83,7 @@ namespace rl ::rl::xml::Path path(document); - ::rl::xml::NodeSet robots = path.eval("/robot").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet robots = path.eval("/robot").getValue<::rl::xml::NodeSet>(); if (robots.empty()) { @@ -98,14 +98,14 @@ namespace rl // name - model->setName(path.eval("string(@name)").getValue< ::std::string>()); + model->setName(path.eval("string(@name)").getValue<::std::string>()); ::std::cout << model->getName() << ::std::endl; // materials - ::rl::xml::NodeSet materials = path.eval("material").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet materials = path.eval("material").getValue<::rl::xml::NodeSet>(); - ::std::unordered_map< ::std::string, ::SoVRMLMaterial*> name2material; + ::std::unordered_map<::std::string, ::SoVRMLMaterial*> name2material; for (int j = 0; j < materials.size(); ++j) { @@ -114,8 +114,8 @@ ::std::cout << "material: " << j << ::std::endl; if (path.eval("count(color/@rgba) > 0").getValue()) { - ::std::vector< ::std::string> rgba; - ::std::string tmp = path.eval("string(color/@rgba)").getValue< ::std::string>(); + ::std::vector<::std::string> rgba; + ::std::string tmp = path.eval("string(color/@rgba)").getValue<::std::string>(); ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\trgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; @@ -123,43 +123,43 @@ ::std::cout << "\trgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " vrmlMaterial->ref(); vrmlMaterial->diffuseColor.setValue( - ::boost::lexical_cast< ::rl::math::Real>(rgba[0]), - ::boost::lexical_cast< ::rl::math::Real>(rgba[1]), - ::boost::lexical_cast< ::rl::math::Real>(rgba[2]) + ::boost::lexical_cast<::rl::math::Real>(rgba[0]), + ::boost::lexical_cast<::rl::math::Real>(rgba[1]), + ::boost::lexical_cast<::rl::math::Real>(rgba[2]) ); vrmlMaterial->transparency.setValue( - 1 - ::boost::lexical_cast< ::rl::math::Real>(rgba[3]) + 1 - ::boost::lexical_cast<::rl::math::Real>(rgba[3]) ); - name2material[path.eval("string(@name)").getValue< ::std::string>()] = vrmlMaterial; -::std::cout << "\tname: " << path.eval("string(@name)").getValue< ::std::string>() << ::std::endl; + name2material[path.eval("string(@name)").getValue<::std::string>()] = vrmlMaterial; +::std::cout << "\tname: " << path.eval("string(@name)").getValue<::std::string>() << ::std::endl; } } // joints - ::std::unordered_map< ::std::string, ::std::string> child2parent; - ::std::unordered_map< ::std::string, ::rl::xml::Node> name2link; - ::std::multimap< ::std::string, ::std::string> parent2child; + ::std::unordered_map<::std::string, ::std::string> child2parent; + ::std::unordered_map<::std::string, ::rl::xml::Node> name2link; + ::std::multimap<::std::string, ::std::string> parent2child; - ::rl::xml::NodeSet joints = path.eval("joint").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet joints = path.eval("joint").getValue<::rl::xml::NodeSet>(); for (int j = 0; j < joints.size(); ++j) { ::std::cout << "joint: " << j << ::std::endl; ::rl::xml::Path path(document, joints[j]); - ::std::string child = path.eval("string(child/@link)").getValue< ::std::string>(); - ::std::string parent = path.eval("string(parent/@link)").getValue< ::std::string>(); + ::std::string child = path.eval("string(child/@link)").getValue<::std::string>(); + ::std::string parent = path.eval("string(parent/@link)").getValue<::std::string>(); child2parent[child] = parent; - parent2child.insert(::std::pair< ::std::string, ::std::string>(parent, child)); + parent2child.insert(::std::pair<::std::string, ::std::string>(parent, child)); ::std::cout << "\tconnect: " << parent << " -> " << child << ::std::endl; } // links - ::rl::xml::NodeSet links = path.eval("link").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet links = path.eval("link").getValue<::rl::xml::NodeSet>(); ::std::string root; @@ -167,7 +167,7 @@ ::std::cout << "\tconnect: " << parent << " -> " << child << ::std::endl; { ::rl::xml::Path path(document, links[j]); - ::std::string name = path.eval("string(@name)").getValue< ::std::string>(); + ::std::string name = path.eval("string(@name)").getValue<::std::string>(); name2link[name] = links[j]; @@ -204,22 +204,22 @@ ::std::cout << "\tname: " << body->getName() << ::std::endl; { if (path.eval("count(collision) > 0").getValue()) { - path.setNode(path.eval("collision").getValue< ::rl::xml::NodeSet>()[0]); + path.setNode(path.eval("collision").getValue<::rl::xml::NodeSet>()[0]); } else if (path.eval("count(visual) > 0").getValue()) { - path.setNode(path.eval("visual").getValue< ::rl::xml::NodeSet>()[0]); + path.setNode(path.eval("visual").getValue<::rl::xml::NodeSet>()[0]); } } else { if (path.eval("count(visual) > 0").getValue()) { - path.setNode(path.eval("visual").getValue< ::rl::xml::NodeSet>()[0]); + path.setNode(path.eval("visual").getValue<::rl::xml::NodeSet>()[0]); } else if (path.eval("count(collision) > 0").getValue()) { - path.setNode(path.eval("collision").getValue< ::rl::xml::NodeSet>()[0]); + path.setNode(path.eval("collision").getValue<::rl::xml::NodeSet>()[0]); } } @@ -231,28 +231,28 @@ ::std::cout << "\tname: " << body->getName() << ::std::endl; if (path.eval("count(material/color/@rgba) > 0").getValue()) { - ::std::vector< ::std::string> rgba; - ::std::string tmp = path.eval("string(material/color/@rgba)").getValue< ::std::string>(); + ::std::vector<::std::string> rgba; + ::std::string tmp = path.eval("string(material/color/@rgba)").getValue<::std::string>(); ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\tmaterial rgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); vrmlMaterial->diffuseColor.setValue( - ::boost::lexical_cast< ::rl::math::Real>(rgba[0]), - ::boost::lexical_cast< ::rl::math::Real>(rgba[1]), - ::boost::lexical_cast< ::rl::math::Real>(rgba[2]) + ::boost::lexical_cast<::rl::math::Real>(rgba[0]), + ::boost::lexical_cast<::rl::math::Real>(rgba[1]), + ::boost::lexical_cast<::rl::math::Real>(rgba[2]) ); vrmlMaterial->transparency.setValue( - 1 - ::boost::lexical_cast< ::rl::math::Real>(rgba[3]) + 1 - ::boost::lexical_cast<::rl::math::Real>(rgba[3]) ); vrmlAppearance->material = vrmlMaterial; } else if (path.eval("count(material/@name) > 0").getValue()) { -::std::cout << "\tmaterial name: " << path.eval("string(material/@name)").getValue< ::std::string>() << ::std::endl; - vrmlAppearance->material = name2material[path.eval("string(material/@name)").getValue< ::std::string>()]; +::std::cout << "\tmaterial name: " << path.eval("string(material/@name)").getValue<::std::string>() << ::std::endl; + vrmlAppearance->material = name2material[path.eval("string(material/@name)").getValue<::std::string>()]; } else { @@ -260,7 +260,7 @@ ::std::cout << "\tmaterial name: " << path.eval("string(material/@name)").getVal vrmlAppearance->material = vrmlMaterial; } - ::rl::xml::NodeSet shapes = path.eval("geometry/box|geometry/cylinder|geometry/mesh|geometry/sphere").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet shapes = path.eval("geometry/box|geometry/cylinder|geometry/mesh|geometry/sphere").getValue<::rl::xml::NodeSet>(); for (int k = 0; k < shapes.size(); ++k) { @@ -270,14 +270,14 @@ ::std::cout << "\tmaterial name: " << path.eval("string(material/@name)").getVal if (!shapes[k].getProperty("size").empty()) { - ::std::vector< ::std::string> size; + ::std::vector<::std::string> size; ::std::string tmp = shapes[k].getProperty("size"); ::boost::split(size, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); box->size.setValue( - ::boost::lexical_cast< ::rl::math::Real>(size[0]), - ::boost::lexical_cast< ::rl::math::Real>(size[1]), - ::boost::lexical_cast< ::rl::math::Real>(size[2]) + ::boost::lexical_cast<::rl::math::Real>(size[0]), + ::boost::lexical_cast<::rl::math::Real>(size[1]), + ::boost::lexical_cast<::rl::math::Real>(size[2]) ); } @@ -291,14 +291,14 @@ ::std::cout << "\tbox size: " << box->size.getValue()[0] << " " << box->size.get if (!shapes[k].getProperty("length").empty()) { cylinder->height.setValue( - ::boost::lexical_cast< ::rl::math::Real>(shapes[k].getProperty("length")) + ::boost::lexical_cast<::rl::math::Real>(shapes[k].getProperty("length")) ); } if (!shapes[k].getProperty("radius").empty()) { cylinder->radius.setValue( - ::boost::lexical_cast< ::rl::math::Real>(shapes[k].getProperty("radius")) + ::boost::lexical_cast<::rl::math::Real>(shapes[k].getProperty("radius")) ); } @@ -344,7 +344,7 @@ ::std::cout << "\tmesh filename: " << meshFilename << ::std::endl; for (int l = 0; l < searchAction.getPaths().getLength(); ++l) { - vrmlShape->geometry = static_cast< ::SoVRMLShape*>(static_cast< ::SoFullPath*>(searchAction.getPaths()[l])->getTail())->geometry; + vrmlShape->geometry = static_cast<::SoVRMLShape*>(static_cast<::SoFullPath*>(searchAction.getPaths()[l])->getTail())->geometry; if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLIndexedFaceSet::getClassTypeId())) { @@ -366,7 +366,7 @@ ::std::cout << "\tmesh filename: " << meshFilename << ::std::endl; if (!shapes[k].getProperty("radius").empty()) { sphere->radius.setValue( - ::boost::lexical_cast< ::rl::math::Real>(shapes[k].getProperty("radius")) + ::boost::lexical_cast<::rl::math::Real>(shapes[k].getProperty("radius")) ); } @@ -383,19 +383,19 @@ ::std::cout << "\tsphere radius: " << sphere->radius.getValue() << ::std::endl; if (path.eval("count(origin/@rpy) > 0").getValue()) { - ::std::vector< ::std::string> rpy; - ::std::string tmp = path.eval("string(origin/@rpy)").getValue< ::std::string>(); + ::std::vector<::std::string> rpy; + ::std::string tmp = path.eval("string(origin/@rpy)").getValue<::std::string>(); ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\torigin rpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << ::std::endl; origin.linear() = ::rl::math::AngleAxis( - ::boost::lexical_cast< ::rl::math::Real>(rpy[2]), + ::boost::lexical_cast<::rl::math::Real>(rpy[2]), ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - ::boost::lexical_cast< ::rl::math::Real>(rpy[1]), + ::boost::lexical_cast<::rl::math::Real>(rpy[1]), ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - ::boost::lexical_cast< ::rl::math::Real>(rpy[0]), + ::boost::lexical_cast<::rl::math::Real>(rpy[0]), ::rl::math::Vector3::UnitX() ).toRotationMatrix(); } @@ -407,14 +407,14 @@ ::std::cout << "\torigin rpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << : if (path.eval("count(origin/@xyz) > 0").getValue()) { - ::std::vector< ::std::string> xyz; - ::std::string tmp = path.eval("string(origin/@xyz)").getValue< ::std::string>(); + ::std::vector<::std::string> xyz; + ::std::string tmp = path.eval("string(origin/@xyz)").getValue<::std::string>(); ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\torigin xyz: " << xyz[0] << " " << xyz[1] << " " << xyz[2] << ::std::endl; - origin.translation().x() = ::boost::lexical_cast< ::rl::math::Real>(xyz[0]); - origin.translation().y() = ::boost::lexical_cast< ::rl::math::Real>(xyz[1]); - origin.translation().z() = ::boost::lexical_cast< ::rl::math::Real>(xyz[2]); + origin.translation().x() = ::boost::lexical_cast<::rl::math::Real>(xyz[0]); + origin.translation().y() = ::boost::lexical_cast<::rl::math::Real>(xyz[1]); + origin.translation().z() = ::boost::lexical_cast<::rl::math::Real>(xyz[2]); } shape->setTransform(origin); @@ -427,22 +427,22 @@ ::std::cout << "\torigin xyz: " << xyz[0] << " " << xyz[1] << " " << xyz[2] << : dfs.pop_front(); ::std::pair< - ::std::multimap< ::std::string, ::std::string>::const_iterator, - ::std::multimap< ::std::string, ::std::string>::const_iterator + ::std::multimap<::std::string, ::std::string>::const_iterator, + ::std::multimap<::std::string, ::std::string>::const_iterator > range = parent2child.equal_range(name); // reverse order - ::std::multimap< ::std::string, ::std::string>::const_iterator first = --range.second; - ::std::multimap< ::std::string, ::std::string>::const_iterator second = --range.first; + ::std::multimap<::std::string, ::std::string>::const_iterator first = --range.second; + ::std::multimap<::std::string, ::std::string>::const_iterator second = --range.first; - for (::std::multimap< ::std::string, ::std::string>::const_iterator k = first; k != second; --k) + for (::std::multimap<::std::string, ::std::string>::const_iterator k = first; k != second; --k) { dfs.push_front(k->second); } } - for (::std::unordered_map< ::std::string, ::SoVRMLMaterial*>::iterator j = name2material.begin(); j != name2material.end(); ++j) + for (::std::unordered_map<::std::string, ::SoVRMLMaterial*>::iterator j = name2material.begin(); j != name2material.end(); ++j) { j->second->unref(); } diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp index 2a50649d..96cce547 100644 --- a/src/rl/sg/XmlFactory.cpp +++ b/src/rl/sg/XmlFactory.cpp @@ -73,7 +73,7 @@ namespace rl ::rl::xml::Path path(document); - ::rl::xml::NodeSet scenes = path.eval("(/rl/sg|/rlsg)/scene").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet scenes = path.eval("(/rl/sg|/rlsg)/scene").getValue<::rl::xml::NodeSet>(); if (scenes.empty()) { @@ -102,7 +102,7 @@ namespace rl // model - ::rl::xml::NodeSet models = ::rl::xml::Path(document, scenes[i]).eval("model").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet models = ::rl::xml::Path(document, scenes[i]).eval("model").getValue<::rl::xml::NodeSet>(); for (int j = 0; j < models.size(); ++j) { @@ -123,13 +123,13 @@ namespace rl // body - ::rl::xml::NodeSet bodies = path.eval("body").getValue< ::rl::xml::NodeSet>(); + ::rl::xml::NodeSet bodies = path.eval("body").getValue<::rl::xml::NodeSet>(); for (int k = 0; k < bodies.size(); ++k) { ::SoSearchAction bodySearchAction; bodySearchAction.setName(bodies[k].getProperty("name").c_str()); - bodySearchAction.apply(static_cast< ::SoFullPath*>(modelSearchAction.getPath())->getTail()); + bodySearchAction.apply(static_cast<::SoFullPath*>(modelSearchAction.getPath())->getTail()); if (nullptr == bodySearchAction.getPath()) { @@ -141,11 +141,11 @@ namespace rl body->setName(bodies[k].getProperty("name")); ::SoSearchAction pathSearchAction; - pathSearchAction.setNode(static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()); + pathSearchAction.setNode(static_cast<::SoFullPath*>(bodySearchAction.getPath())->getTail()); pathSearchAction.apply(root); ::SoGetMatrixAction bodyGetMatrixAction(viewportRegion); - bodyGetMatrixAction.apply(static_cast< ::SoFullPath*>(pathSearchAction.getPath())); + bodyGetMatrixAction.apply(static_cast<::SoFullPath*>(pathSearchAction.getPath())); ::SbMatrix bodyMatrix = bodyGetMatrixAction.getMatrix(); if (!scene->isScalingSupported()) @@ -159,7 +159,7 @@ namespace rl for (int l = 0; l < 3; ++l) { - if (::std::abs(bodyScaleFactor[l] - 1) > static_cast< ::rl::math::Real>(1.0e-6)) + if (::std::abs(bodyScaleFactor[l] - 1) > static_cast<::rl::math::Real>(1.0e-6)) { throw Exception("rl::sg::XmlFactory::load() - bodyScaleFactor not supported in body '" + body->getName() + "'"); } @@ -178,9 +178,9 @@ namespace rl body->setFrame(frame); - if (static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()->isOfType(::SoVRMLTransform::getClassTypeId())) + if (static_cast<::SoFullPath*>(bodySearchAction.getPath())->getTail()->isOfType(::SoVRMLTransform::getClassTypeId())) { - ::SoVRMLTransform* bodyVrmlTransform = static_cast< ::SoVRMLTransform*>(static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()); + ::SoVRMLTransform* bodyVrmlTransform = static_cast<::SoVRMLTransform*>(static_cast<::SoFullPath*>(bodySearchAction.getPath())->getTail()); for (int l = 0; l < 3; ++l) { @@ -195,15 +195,15 @@ namespace rl ::SoSearchAction shapeSearchAction; shapeSearchAction.setInterest(::SoSearchAction::ALL); shapeSearchAction.setType(::SoVRMLShape::getClassTypeId()); - shapeSearchAction.apply(static_cast< ::SoFullPath*>(bodySearchAction.getPath())->getTail()); + shapeSearchAction.apply(static_cast<::SoFullPath*>(bodySearchAction.getPath())->getTail()); for (int l = 0; l < shapeSearchAction.getPaths().getLength(); ++l) { - ::SoFullPath* path = static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l]); + ::SoFullPath* path = static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l]); if (path->getLength() > 1) { - path = static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l]->copy(1, static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l])->getLength() - 1)); + path = static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l]->copy(1, static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l])->getLength() - 1)); } pathList.append(path); @@ -223,14 +223,14 @@ namespace rl for (int m = 0; m < 3; ++m) { - if (::std::abs(shapeScaleFactor[m] - 1) > static_cast< ::rl::math::Real>(1.0e-6)) + if (::std::abs(shapeScaleFactor[m] - 1) > static_cast<::rl::math::Real>(1.0e-6)) { throw Exception("rl::sg::XmlFactory::load() - shapeScaleFactor not supported"); } } } - ::SoVRMLShape* shapeVrmlShape = static_cast< ::SoVRMLShape*>(static_cast< ::SoFullPath*>(shapeSearchAction.getPaths()[l])->getTail()); + ::SoVRMLShape* shapeVrmlShape = static_cast<::SoVRMLShape*>(static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l])->getTail()); Shape* shape = body->create(shapeVrmlShape); @@ -282,7 +282,7 @@ namespace rl void XmlFactory::triangleCallback(void* userData, SoCallbackAction* action, const SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const SoPrimitiveVertex* v3) { - ::std::vector< ::rl::math::Vector3>* points = static_cast< ::std::vector< ::rl::math::Vector3>*>(userData); + ::std::vector<::rl::math::Vector3>* points = static_cast<::std::vector<::rl::math::Vector3>*>(userData); ::rl::math::Vector3 p1; p1(0) = v1->getPoint()[0]; diff --git a/src/rl/sg/bullet/Body.cpp b/src/rl/sg/bullet/Body.cpp index 596bd80c..14609b28 100644 --- a/src/rl/sg/bullet/Body.cpp +++ b/src/rl/sg/bullet/Body.cpp @@ -90,15 +90,15 @@ namespace rl Body::setFrame(const ::rl::math::Transform& frame) { this->object.getWorldTransform().getOrigin().setValue( - static_cast< ::btScalar>(frame(0, 3)), - static_cast< ::btScalar>(frame(1, 3)), - static_cast< ::btScalar>(frame(2, 3)) + static_cast<::btScalar>(frame(0, 3)), + static_cast<::btScalar>(frame(1, 3)), + static_cast<::btScalar>(frame(2, 3)) ); this->object.getWorldTransform().getBasis().setValue( - static_cast< ::btScalar>(frame(0, 0)), static_cast< ::btScalar>(frame(0, 1)), static_cast< ::btScalar>(frame(0, 2)), - static_cast< ::btScalar>(frame(1, 0)), static_cast< ::btScalar>(frame(1, 1)), static_cast< ::btScalar>(frame(1, 2)), - static_cast< ::btScalar>(frame(2, 0)), static_cast< ::btScalar>(frame(2, 1)), static_cast< ::btScalar>(frame(2, 2)) + static_cast<::btScalar>(frame(0, 0)), static_cast<::btScalar>(frame(0, 1)), static_cast<::btScalar>(frame(0, 2)), + static_cast<::btScalar>(frame(1, 0)), static_cast<::btScalar>(frame(1, 1)), static_cast<::btScalar>(frame(1, 2)), + static_cast<::btScalar>(frame(2, 0)), static_cast<::btScalar>(frame(2, 1)), static_cast<::btScalar>(frame(2, 2)) ); } } diff --git a/src/rl/sg/bullet/Scene.cpp b/src/rl/sg/bullet/Scene.cpp index df8bf736..0b1268d5 100644 --- a/src/rl/sg/bullet/Scene.cpp +++ b/src/rl/sg/bullet/Scene.cpp @@ -129,8 +129,8 @@ namespace rl ::btVoronoiSimplexSolver simplexSolver; ::btGjkEpaPenetrationDepthSolver penetrationDepthSolver; ::btGjkPairDetector pairDetector( - static_cast< ::btConvexShape*>(shape1->shape), - static_cast< ::btConvexShape*>(shape2->shape), + static_cast<::btConvexShape*>(shape1->shape), + static_cast<::btConvexShape*>(shape2->shape), &simplexSolver, &penetrationDepthSolver ); @@ -163,8 +163,8 @@ namespace rl ::btGjkEpaPenetrationDepthSolver epa; ::btGjkPairDetector convexConvex( - static_cast< ::btConvexShape*>(static_cast(shape)->shape), - static_cast< ::btConvexShape*>(&sphere), + static_cast<::btConvexShape*>(static_cast(shape)->shape), + static_cast<::btConvexShape*>(&sphere), &sGjkSimplexSolver, &epa ); @@ -176,9 +176,9 @@ namespace rl input.m_transformA = body->object.getWorldTransform() * static_cast(shape)->transform; input.m_transformB.setIdentity(); input.m_transformB.getOrigin().setValue( - static_cast< ::btScalar>(point.x()), - static_cast< ::btScalar>(point.y()), - static_cast< ::btScalar>(point.z()) + static_cast<::btScalar>(point.x()), + static_cast<::btScalar>(point.y()), + static_cast<::btScalar>(point.z()) ); convexConvex.getClosestPoints(input, gjkOutput, 0); @@ -222,15 +222,15 @@ namespace rl Scene::raycast(const ::rl::math::Vector3& source, const ::rl::math::Vector3& target, ::rl::math::Real& distance) { ::btVector3 rayFromWorld( - static_cast< ::btScalar>(source.x()), - static_cast< ::btScalar>(source.y()), - static_cast< ::btScalar>(source.z()) + static_cast<::btScalar>(source.x()), + static_cast<::btScalar>(source.y()), + static_cast<::btScalar>(source.z()) ); ::btVector3 rayToWorld( - static_cast< ::btScalar>(target.x()), - static_cast< ::btScalar>(target.y()), - static_cast< ::btScalar>(target.z()) + static_cast<::btScalar>(target.x()), + static_cast<::btScalar>(target.y()), + static_cast<::btScalar>(target.z()) ); RayResultCallback resultCallback; @@ -246,7 +246,7 @@ namespace rl } else { - distance = ::std::numeric_limits< ::btScalar>::quiet_NaN(); + distance = ::std::numeric_limits<::btScalar>::quiet_NaN(); return nullptr; } } @@ -257,9 +257,9 @@ namespace rl Body* body = static_cast(shape->getBody()); ::btVector3 rayFromWorld( - static_cast< ::btScalar>(source.x()), - static_cast< ::btScalar>(source.y()), - static_cast< ::btScalar>(source.z()) + static_cast<::btScalar>(source.x()), + static_cast<::btScalar>(source.y()), + static_cast<::btScalar>(source.z()) ); ::btTransform rayFromTrans; @@ -267,9 +267,9 @@ namespace rl rayFromTrans.setOrigin(rayFromWorld); ::btVector3 rayToWorld( - static_cast< ::btScalar>(target.x()), - static_cast< ::btScalar>(target.y()), - static_cast< ::btScalar>(target.z()) + static_cast<::btScalar>(target.x()), + static_cast<::btScalar>(target.y()), + static_cast<::btScalar>(target.z()) ); ::btTransform rayToTrans; @@ -296,7 +296,7 @@ namespace rl } else { - distance = ::std::numeric_limits< ::btScalar>::quiet_NaN(); + distance = ::std::numeric_limits<::btScalar>::quiet_NaN(); return false; } } diff --git a/src/rl/sg/bullet/Shape.cpp b/src/rl/sg/bullet/Shape.cpp index 51027bb2..8e436fa9 100644 --- a/src/rl/sg/bullet/Shape.cpp +++ b/src/rl/sg/bullet/Shape.cpp @@ -53,27 +53,27 @@ namespace rl triangleIndexVertexArray(nullptr), vertices() { - ::SoVRMLGeometry* geometry = static_cast< ::SoVRMLGeometry*>(shape->geometry.getValue()); + ::SoVRMLGeometry* geometry = static_cast<::SoVRMLGeometry*>(shape->geometry.getValue()); if (geometry->isOfType(::SoVRMLBox::getClassTypeId())) { - ::SoVRMLBox* box = static_cast< ::SoVRMLBox*>(geometry); + ::SoVRMLBox* box = static_cast<::SoVRMLBox*>(geometry); ::btVector3 boxHalfExtents(box->size.getValue()[0] / 2, box->size.getValue()[1] / 2, box->size.getValue()[2] / 2); this->shape = new ::btBoxShape(boxHalfExtents); } else if (geometry->isOfType(::SoVRMLCone::getClassTypeId())) { - ::SoVRMLCone* cone = static_cast< ::SoVRMLCone*>(geometry); + ::SoVRMLCone* cone = static_cast<::SoVRMLCone*>(geometry); this->shape = new ::btConeShape(cone->bottomRadius.getValue(), cone->height.getValue()); } else if (geometry->isOfType(::SoVRMLCylinder::getClassTypeId())) { - ::SoVRMLCylinder* cylinder = static_cast< ::SoVRMLCylinder*>(geometry); + ::SoVRMLCylinder* cylinder = static_cast<::SoVRMLCylinder*>(geometry); this->shape = new ::btCylinderShape(::btVector3(cylinder->radius.getValue(), cylinder->height.getValue() / 2, cylinder->radius.getValue())); } else if (geometry->isOfType(::SoVRMLIndexedFaceSet::getClassTypeId())) { - ::SoVRMLIndexedFaceSet* indexedFaceSet = static_cast< ::SoVRMLIndexedFaceSet*>(geometry); + ::SoVRMLIndexedFaceSet* indexedFaceSet = static_cast<::SoVRMLIndexedFaceSet*>(geometry); ::SoCallbackAction callbackAction; callbackAction.addTriangleCallback(geometry->getTypeId(), Shape::triangleCallback, this); @@ -103,7 +103,7 @@ namespace rl } else if (geometry->isOfType(::SoVRMLSphere::getClassTypeId())) { - ::SoVRMLSphere* sphere = static_cast< ::SoVRMLSphere*>(geometry); + ::SoVRMLSphere* sphere = static_cast<::SoVRMLSphere*>(geometry); this->shape = new ::btSphereShape(sphere->radius.getValue()); } else @@ -175,15 +175,15 @@ namespace rl if (this->shape == body->shape.getChildList()[i].m_childShape) { this->transform.getOrigin().setValue( - static_cast< ::btScalar>(transform(0, 3)), - static_cast< ::btScalar>(transform(1, 3)), - static_cast< ::btScalar>(transform(2, 3)) + static_cast<::btScalar>(transform(0, 3)), + static_cast<::btScalar>(transform(1, 3)), + static_cast<::btScalar>(transform(2, 3)) ); this->transform.getBasis().setValue( - static_cast< ::btScalar>(transform(0, 0)), static_cast< ::btScalar>(transform(0, 1)), static_cast< ::btScalar>(transform(0, 2)), - static_cast< ::btScalar>(transform(1, 0)), static_cast< ::btScalar>(transform(1, 1)), static_cast< ::btScalar>(transform(1, 2)), - static_cast< ::btScalar>(transform(2, 0)), static_cast< ::btScalar>(transform(2, 1)), static_cast< ::btScalar>(transform(2, 2)) + static_cast<::btScalar>(transform(0, 0)), static_cast<::btScalar>(transform(0, 1)), static_cast<::btScalar>(transform(0, 2)), + static_cast<::btScalar>(transform(1, 0)), static_cast<::btScalar>(transform(1, 1)), static_cast<::btScalar>(transform(1, 2)), + static_cast<::btScalar>(transform(2, 0)), static_cast<::btScalar>(transform(2, 1)), static_cast<::btScalar>(transform(2, 2)) ); body->shape.updateChildTransform(i, this->transform); diff --git a/src/rl/sg/bullet/Shape.h b/src/rl/sg/bullet/Shape.h index bb0faf81..c5aa20d3 100644 --- a/src/rl/sg/bullet/Shape.h +++ b/src/rl/sg/bullet/Shape.h @@ -62,7 +62,7 @@ namespace rl ::btTriangleIndexVertexArray* triangleIndexVertexArray; - ::std::vector< ::btScalar> vertices; + ::std::vector<::btScalar> vertices; }; } } diff --git a/src/rl/sg/fcl/Body.h b/src/rl/sg/fcl/Body.h index dd8358cf..21d9c036 100644 --- a/src/rl/sg/fcl/Body.h +++ b/src/rl/sg/fcl/Body.h @@ -57,7 +57,7 @@ namespace rl void setFrame(const ::rl::math::Transform& frame); - ::std::vector< ::fcl::CollisionObject*> collisionObjects; + ::std::vector<::fcl::CollisionObject*> collisionObjects; ::fcl::DynamicAABBTreeCollisionManager manager; diff --git a/src/rl/sg/fcl/Scene.h b/src/rl/sg/fcl/Scene.h index 1e7e88f7..f9039569 100644 --- a/src/rl/sg/fcl/Scene.h +++ b/src/rl/sg/fcl/Scene.h @@ -92,7 +92,7 @@ namespace rl private: struct CollisionData { - CollisionData(const ::std::unordered_map< ::fcl::CollisionObject*, Body*>& bodyForObj) : + CollisionData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj) : bodyForObj(bodyForObj), done(false), request(), @@ -100,7 +100,7 @@ namespace rl { } - const ::std::unordered_map< ::fcl::CollisionObject*, Body*>& bodyForObj; + const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj; bool done; @@ -111,7 +111,7 @@ namespace rl struct DistanceData { - DistanceData(const ::std::unordered_map< ::fcl::CollisionObject*, Body*>& bodyForObj) : + DistanceData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj) : bodyForObj(bodyForObj), done(false), request(true), @@ -119,7 +119,7 @@ namespace rl { } - const ::std::unordered_map< ::fcl::CollisionObject*, Body*>& bodyForObj; + const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj; bool done; @@ -132,7 +132,7 @@ namespace rl static bool defaultDistanceFunction(::fcl::CollisionObject* o1, ::fcl::CollisionObject* o2, void* data, ::fcl::FCL_REAL& dist); - ::std::unordered_map< ::fcl::CollisionObject*, Body*> bodyForObj; + ::std::unordered_map<::fcl::CollisionObject*, Body*> bodyForObj; }; } } diff --git a/src/rl/sg/fcl/Shape.h b/src/rl/sg/fcl/Shape.h index ec8d9a88..8e10bb16 100644 --- a/src/rl/sg/fcl/Shape.h +++ b/src/rl/sg/fcl/Shape.h @@ -52,7 +52,7 @@ namespace rl void update(const ::rl::math::Transform& frame); - ::std::shared_ptr< ::fcl::CollisionObject> collisionObject; + ::std::shared_ptr<::fcl::CollisionObject> collisionObject; protected: @@ -63,23 +63,23 @@ namespace rl ::rl::math::Transform currentFrame; - ::std::vector< ::fcl::FCL_REAL> distances; + ::std::vector<::fcl::FCL_REAL> distances; #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - ::boost::shared_ptr< ::fcl::CollisionGeometry> geometry; + ::boost::shared_ptr<::fcl::CollisionGeometry> geometry; #else - ::std::shared_ptr< ::fcl::CollisionGeometry> geometry; + ::std::shared_ptr<::fcl::CollisionGeometry> geometry; #endif ::std::vector indices; - ::std::vector< ::fcl::Vec3f> normals; + ::std::vector<::fcl::Vec3f> normals; ::std::vector polygons; ::rl::math::Transform transform; - ::std::vector< ::fcl::Vec3f> vertices; + ::std::vector<::fcl::Vec3f> vertices; }; } } diff --git a/src/rl/sg/ode/Body.cpp b/src/rl/sg/ode/Body.cpp index bec1bca5..825812e7 100644 --- a/src/rl/sg/ode/Body.cpp +++ b/src/rl/sg/ode/Body.cpp @@ -87,9 +87,9 @@ namespace rl { ::dBodySetPosition( this->body, - static_cast< ::dReal>(frame(0, 3)), - static_cast< ::dReal>(frame(1, 3)), - static_cast< ::dReal>(frame(2, 3)) + static_cast<::dReal>(frame(0, 3)), + static_cast<::dReal>(frame(1, 3)), + static_cast<::dReal>(frame(2, 3)) ); ::dMatrix3 rotation; @@ -98,7 +98,7 @@ namespace rl { for (::std::size_t j = 0; j < 3; ++j) { - rotation[i * 4 + j] = static_cast< ::dReal>(frame(i, j)); + rotation[i * 4 + j] = static_cast<::dReal>(frame(i, j)); } } diff --git a/src/rl/sg/ode/Scene.cpp b/src/rl/sg/ode/Scene.cpp index 36691055..f4daa5b3 100644 --- a/src/rl/sg/ode/Scene.cpp +++ b/src/rl/sg/ode/Scene.cpp @@ -63,8 +63,8 @@ namespace rl bool data = false; ::dSpaceCollide2( - reinterpret_cast< ::dGeomID>(static_cast(first)->space), - reinterpret_cast< ::dGeomID>(static_cast(second)->space), + reinterpret_cast<::dGeomID>(static_cast(first)->space), + reinterpret_cast<::dGeomID>(static_cast(second)->space), &data, &Scene::shapeSimpleCallback ); @@ -78,8 +78,8 @@ namespace rl bool data = false; ::dSpaceCollide2( - reinterpret_cast< ::dGeomID>(static_cast(first)->space), - reinterpret_cast< ::dGeomID>(static_cast(second)->space), + reinterpret_cast<::dGeomID>(static_cast(first)->space), + reinterpret_cast<::dGeomID>(static_cast(second)->space), &data, &Scene::bodySimpleCallback ); @@ -159,47 +159,47 @@ namespace rl return; } - ::dSpaceCollide(reinterpret_cast< ::dSpaceID>(o1), data, &Scene::bodySimpleCallback); + ::dSpaceCollide(reinterpret_cast<::dSpaceID>(o1), data, &Scene::bodySimpleCallback); if (*static_cast(data)) { return; } - ::dSpaceCollide(reinterpret_cast< ::dSpaceID>(o2), data, &Scene::bodySimpleCallback); + ::dSpaceCollide(reinterpret_cast<::dSpaceID>(o2), data, &Scene::bodySimpleCallback); } ::rl::sg::Shape* Scene::raycast(const ::rl::math::Vector3& source, const ::rl::math::Vector3& target, ::rl::math::Real& distance) { - ::dGeomID ray = ::dCreateRay(nullptr, ::std::numeric_limits< ::dReal>::max()); + ::dGeomID ray = ::dCreateRay(nullptr, ::std::numeric_limits<::dReal>::max()); ::dGeomRaySet( ray, - static_cast< ::dReal>(source.x()), - static_cast< ::dReal>(source.y()), - static_cast< ::dReal>(source.z()), - static_cast< ::dReal>(target.x() - source.x()), - static_cast< ::dReal>(target.y() - source.y()), - static_cast< ::dReal>(target.z() - source.z()) + static_cast<::dReal>(source.x()), + static_cast<::dReal>(source.y()), + static_cast<::dReal>(source.z()), + static_cast<::dReal>(target.x() - source.x()), + static_cast<::dReal>(target.y() - source.y()), + static_cast<::dReal>(target.z() - source.z()) ); ::dContactGeom contact; - contact.depth = ::std::numeric_limits< ::dReal>::max(); + contact.depth = ::std::numeric_limits<::dReal>::max(); contact.g1 = nullptr; contact.g2 = nullptr; - ::dSpaceCollide2(ray, reinterpret_cast< ::dGeomID>(this->space), &contact, &Scene::rayNearCallback); + ::dSpaceCollide2(ray, reinterpret_cast<::dGeomID>(this->space), &contact, &Scene::rayNearCallback); distance = contact.depth; if (nullptr != contact.g1 && ray != contact.g1) { - return static_cast< ::rl::sg::Shape*>(::dGeomGetData(contact.g1)); + return static_cast<::rl::sg::Shape*>(::dGeomGetData(contact.g1)); } else if (nullptr != contact.g2 && ray != contact.g2) { - return static_cast< ::rl::sg::Shape*>(::dGeomGetData(contact.g2)); + return static_cast<::rl::sg::Shape*>(::dGeomGetData(contact.g2)); } else { @@ -210,16 +210,16 @@ namespace rl bool Scene::raycast(::rl::sg::Shape* shape, const ::rl::math::Vector3& source, const ::rl::math::Vector3& target, ::rl::math::Real& distance) { - ::dGeomID ray = ::dCreateRay(nullptr, ::std::numeric_limits< ::dReal>::max()); + ::dGeomID ray = ::dCreateRay(nullptr, ::std::numeric_limits<::dReal>::max()); ::dGeomRaySet( ray, - static_cast< ::dReal>(source.x()), - static_cast< ::dReal>(source.y()), - static_cast< ::dReal>(source.z()), - static_cast< ::dReal>(target.x() - source.x()), - static_cast< ::dReal>(target.y() - source.y()), - static_cast< ::dReal>(target.z() - source.z()) + static_cast<::dReal>(source.x()), + static_cast<::dReal>(source.y()), + static_cast<::dReal>(source.z()), + static_cast<::dReal>(target.x() - source.x()), + static_cast<::dReal>(target.y() - source.y()), + static_cast<::dReal>(target.z() - source.z()) ); ::dContactGeom contacts[1]; @@ -231,7 +231,7 @@ namespace rl } else { - distance = ::std::numeric_limits< ::dReal>::quiet_NaN(); + distance = ::std::numeric_limits<::dReal>::quiet_NaN(); return false; } } @@ -245,12 +245,12 @@ namespace rl if (::dGeomIsSpace(o1)) { - ::dSpaceCollide(reinterpret_cast< ::dSpaceID>(o1), data, &Scene::rayNearCallback); + ::dSpaceCollide(reinterpret_cast<::dSpaceID>(o1), data, &Scene::rayNearCallback); } if (::dGeomIsSpace(o2)) { - ::dSpaceCollide(reinterpret_cast< ::dSpaceID>(o2), data, &Scene::rayNearCallback); + ::dSpaceCollide(reinterpret_cast<::dSpaceID>(o2), data, &Scene::rayNearCallback); } } else @@ -259,11 +259,11 @@ namespace rl if (::dCollide(o1, o2, 1, contacts, sizeof(::dContactGeom)) > 0) { - if (contacts[0].depth < static_cast< ::dContactGeom*>(data)->depth) + if (contacts[0].depth < static_cast<::dContactGeom*>(data)->depth) { - static_cast< ::dContactGeom*>(data)->depth = contacts[0].depth; - static_cast< ::dContactGeom*>(data)->g1 = o1; - static_cast< ::dContactGeom*>(data)->g2 = o2; + static_cast<::dContactGeom*>(data)->depth = contacts[0].depth; + static_cast<::dContactGeom*>(data)->g1 = o1; + static_cast<::dContactGeom*>(data)->g2 = o2; } } } @@ -272,7 +272,7 @@ namespace rl void Scene::shapeDepthCallback(void* data, ::dGeomID o1, ::dGeomID o2) { - ::dCollide(o1, o2, 1, static_cast< ::dContactGeom*>(data), sizeof(::dContactGeom)); + ::dCollide(o1, o2, 1, static_cast<::dContactGeom*>(data), sizeof(::dContactGeom)); } void diff --git a/src/rl/sg/ode/Shape.cpp b/src/rl/sg/ode/Shape.cpp index 006c5a19..0b4c7901 100644 --- a/src/rl/sg/ode/Shape.cpp +++ b/src/rl/sg/ode/Shape.cpp @@ -53,11 +53,11 @@ namespace rl transform(::rl::math::Transform::Identity()), vertices() { - ::SoVRMLGeometry* geometry = static_cast< ::SoVRMLGeometry*>(shape->geometry.getValue()); + ::SoVRMLGeometry* geometry = static_cast<::SoVRMLGeometry*>(shape->geometry.getValue()); if (geometry->isOfType(::SoVRMLBox::getClassTypeId())) { - ::SoVRMLBox* box = static_cast< ::SoVRMLBox*>(geometry); + ::SoVRMLBox* box = static_cast<::SoVRMLBox*>(geometry); this->geom = ::dCreateBox(static_cast(this->getBody())->space, box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); } else if (geometry->isOfType(::SoVRMLCone::getClassTypeId())) @@ -66,7 +66,7 @@ namespace rl } else if (geometry->isOfType(::SoVRMLCylinder::getClassTypeId())) { - ::SoVRMLCylinder* cylinder = static_cast< ::SoVRMLCylinder*>(geometry); + ::SoVRMLCylinder* cylinder = static_cast<::SoVRMLCylinder*>(geometry); this->geom = ::dCreateCylinder(static_cast(this->getBody())->space, cylinder->radius.getValue(), cylinder->height.getValue()); this->baseTransform(0, 0) = 1; @@ -98,7 +98,7 @@ namespace rl } else if (geometry->isOfType(::SoVRMLSphere::getClassTypeId())) { - ::SoVRMLSphere* sphere = static_cast< ::SoVRMLSphere*>(geometry); + ::SoVRMLSphere* sphere = static_cast<::SoVRMLSphere*>(geometry); this->geom = ::dCreateSphere(static_cast(this->getBody())->space, sphere->radius.getValue()); } else @@ -165,9 +165,9 @@ namespace rl ::dGeomSetOffsetPosition( this->geom, - static_cast< ::dReal>(totalTransform(0, 3)), - static_cast< ::dReal>(totalTransform(1, 3)), - static_cast< ::dReal>(totalTransform(2, 3)) + static_cast<::dReal>(totalTransform(0, 3)), + static_cast<::dReal>(totalTransform(1, 3)), + static_cast<::dReal>(totalTransform(2, 3)) ); ::dMatrix3 rotation; @@ -176,7 +176,7 @@ namespace rl { for (::std::size_t j = 0; j < 3; ++j) { - rotation[i * 4 + j] = static_cast< ::dReal>(totalTransform(i, j)); + rotation[i * 4 + j] = static_cast<::dReal>(totalTransform(i, j)); } } diff --git a/src/rl/sg/ode/Shape.h b/src/rl/sg/ode/Shape.h index 945e16ce..aeae1ade 100644 --- a/src/rl/sg/ode/Shape.h +++ b/src/rl/sg/ode/Shape.h @@ -60,11 +60,11 @@ namespace rl ::rl::math::Transform baseTransform; - ::std::vector< ::dTriIndex> indices; + ::std::vector<::dTriIndex> indices; ::rl::math::Transform transform; - ::std::vector< ::dReal> vertices; + ::std::vector<::dReal> vertices; }; } } diff --git a/src/rl/sg/pqp/Scene.cpp b/src/rl/sg/pqp/Scene.cpp index 6b920dff..80a661a3 100644 --- a/src/rl/sg/pqp/Scene.cpp +++ b/src/rl/sg/pqp/Scene.cpp @@ -93,8 +93,8 @@ namespace rl shape2->rotation, shape2->translation, &shape2->model, - ::std::numeric_limits< ::rl::math::Real>::epsilon(), - ::std::numeric_limits< ::rl::math::Real>::epsilon() + ::std::numeric_limits<::rl::math::Real>::epsilon(), + ::std::numeric_limits<::rl::math::Real>::epsilon() ); point1(0) = result.P1()[0]; @@ -142,8 +142,8 @@ namespace rl rotation, translation, &model, - ::std::numeric_limits< ::rl::math::Real>::epsilon(), - ::std::numeric_limits< ::rl::math::Real>::epsilon() + ::std::numeric_limits<::rl::math::Real>::epsilon(), + ::std::numeric_limits<::rl::math::Real>::epsilon() ); point1(0) = result.P1()[0]; diff --git a/src/rl/sg/pqp/Shape.cpp b/src/rl/sg/pqp/Shape.cpp index c780bcc5..107971c3 100644 --- a/src/rl/sg/pqp/Shape.cpp +++ b/src/rl/sg/pqp/Shape.cpp @@ -62,7 +62,7 @@ namespace rl this->translation[i] = static_cast(this->frame(i, 3)); } - ::SoVRMLGeometry* geometry = static_cast< ::SoVRMLGeometry*>(shape->geometry.getValue()); + ::SoVRMLGeometry* geometry = static_cast<::SoVRMLGeometry*>(shape->geometry.getValue()); ::SoGetPrimitiveCountAction* primitiveCountAction = new ::SoGetPrimitiveCountAction(); primitiveCountAction->apply(geometry); diff --git a/src/rl/sg/pqp/Shape.h b/src/rl/sg/pqp/Shape.h index 372e5577..733612ad 100644 --- a/src/rl/sg/pqp/Shape.h +++ b/src/rl/sg/pqp/Shape.h @@ -67,7 +67,7 @@ namespace rl protected: private: - typedef ::std::pair< ::PQP_Model*, ::std::size_t> Model; + typedef ::std::pair<::PQP_Model*, ::std::size_t> Model; static void triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3); diff --git a/src/rl/sg/solid/Scene.cpp b/src/rl/sg/solid/Scene.cpp index 728331a9..8c185c82 100644 --- a/src/rl/sg/solid/Scene.cpp +++ b/src/rl/sg/solid/Scene.cpp @@ -237,7 +237,7 @@ namespace rl distance = ::std::sqrt(::std::pow(hit[0] - source[0], 2) + ::std::pow(hit[1] - source[1], 2) + ::std::pow(hit[2] - source[2], 2));; - return static_cast< ::rl::sg::Shape*>(object); + return static_cast<::rl::sg::Shape*>(object); } bool diff --git a/src/rl/sg/solid/Shape.h b/src/rl/sg/solid/Shape.h index 33d7a97b..fc58f810 100644 --- a/src/rl/sg/solid/Shape.h +++ b/src/rl/sg/solid/Shape.h @@ -77,7 +77,7 @@ namespace rl DT_ShapeHandle create(const SoMFVec3f& point, const SoMFInt32& coordIndex); - ::Eigen::Transform< ::rl::math::Real, 3, ::Eigen::Affine, ::Eigen::ColMajor> frame; + ::Eigen::Transform<::rl::math::Real, 3, ::Eigen::Affine, ::Eigen::ColMajor> frame; DT_Vector3 max; diff --git a/src/rl/std/memory.h b/src/rl/std/memory.h index 593c4f41..b275c1e4 100644 --- a/src/rl/std/memory.h +++ b/src/rl/std/memory.h @@ -41,7 +41,7 @@ namespace rl using ::std::make_unique; #else template - typename ::std::enable_if< ::std::is_array::value, ::std::unique_ptr>::type + typename ::std::enable_if<::std::is_array::value, ::std::unique_ptr>::type make_unique(::std::size_t n) { return ::std::unique_ptr(new typename ::std::remove_extent::type[n]()); @@ -55,7 +55,7 @@ namespace rl } template - typename ::std::enable_if< ::std::extent::value != 0, ::std::unique_ptr>::type + typename ::std::enable_if<::std::extent::value != 0, ::std::unique_ptr>::type make_unique(Args&&...) = delete; #endif } diff --git a/src/rl/util/rtai/chrono.h b/src/rl/util/rtai/chrono.h index e245e9cc..51b84639 100644 --- a/src/rl/util/rtai/chrono.h +++ b/src/rl/util/rtai/chrono.h @@ -80,7 +80,7 @@ namespace rl static ::std::time_t to_time_t(const time_point& t) { return ::std::time_t( - ::std::chrono::duration_cast< ::std::chrono::seconds>( + ::std::chrono::duration_cast<::std::chrono::seconds>( t.time_since_epoch() ).count() ); diff --git a/src/rl/util/rtai/thread.h b/src/rl/util/rtai/thread.h index 0f24ae93..a75991b4 100644 --- a/src/rl/util/rtai/thread.h +++ b/src/rl/util/rtai/thread.h @@ -227,7 +227,7 @@ namespace rl template void set_periodic(const ::std::chrono::duration& period) { - ::std::chrono::nanoseconds period_ns = ::std::chrono::duration_cast< ::std::chrono::nanoseconds>(period); + ::std::chrono::nanoseconds period_ns = ::std::chrono::duration_cast<::std::chrono::nanoseconds>(period); int e = ::rt_task_make_periodic(this->M_id.M_task, ::rt_get_time(), ::nano2count(period_ns.count())); @@ -240,8 +240,8 @@ namespace rl template void set_periodic(const ::std::chrono::time_point& idate, const ::std::chrono::duration& period) { - ::std::chrono::time_point idate_ns = ::std::chrono::time_point_cast< ::std::chrono::nanoseconds>(idate); - ::std::chrono::nanoseconds period_ns = ::std::chrono::duration_cast< ::std::chrono::nanoseconds>(period); + ::std::chrono::time_point idate_ns = ::std::chrono::time_point_cast<::std::chrono::nanoseconds>(idate); + ::std::chrono::nanoseconds period_ns = ::std::chrono::duration_cast<::std::chrono::nanoseconds>(period); int e = ::rt_task_make_periodic(this->M_id.M_task, ::nano2count(idate_ns.time_since_epoch().count()), ::nano2count(period_ns.count())); @@ -416,7 +416,7 @@ namespace rl template inline void sleep_for(const ::std::chrono::duration& rtime) { - ::std::chrono::nanoseconds ns = ::std::chrono::duration_cast< ::std::chrono::nanoseconds>(rtime); + ::std::chrono::nanoseconds ns = ::std::chrono::duration_cast<::std::chrono::nanoseconds>(rtime); int e = ::rt_sleep(::nano2count(ns.count())); if (e) @@ -428,7 +428,7 @@ namespace rl template inline void sleep_until(const ::std::chrono::time_point& atime) { - ::std::chrono::time_point ns = ::std::chrono::time_point_cast< ::std::chrono::nanoseconds>(atime); + ::std::chrono::time_point ns = ::std::chrono::time_point_cast<::std::chrono::nanoseconds>(atime); int e = ::rt_sleep_until(::nano2count(ns.time_since_epoch().count())); if (e) @@ -481,11 +481,11 @@ namespace rl namespace std { template<> - struct hash< ::rl::util::rtai::thread::id> + struct hash<::rl::util::rtai::thread::id> { size_t operator()(const ::rl::util::rtai::thread::id& id) const { - return hash< ::rl::util::rtai::thread::native_handle_type>()(id.M_thread); + return hash<::rl::util::rtai::thread::native_handle_type>()(id.M_thread); } }; diff --git a/src/rl/util/xenomai/chrono.h b/src/rl/util/xenomai/chrono.h index b9252963..a9dbb5ec 100644 --- a/src/rl/util/xenomai/chrono.h +++ b/src/rl/util/xenomai/chrono.h @@ -80,7 +80,7 @@ namespace rl static ::std::time_t to_time_t(const time_point& t) { return ::std::time_t( - ::std::chrono::duration_cast< ::std::chrono::seconds>( + ::std::chrono::duration_cast<::std::chrono::seconds>( t.time_since_epoch() ).count() ); diff --git a/src/rl/util/xenomai/condition_variable.h b/src/rl/util/xenomai/condition_variable.h index 6e425113..981c15ba 100644 --- a/src/rl/util/xenomai/condition_variable.h +++ b/src/rl/util/xenomai/condition_variable.h @@ -122,7 +122,7 @@ namespace rl template ::std::cv_status wait_until(::std::unique_lock& lock, const ::std::chrono::time_point& atime) { - ::std::chrono::time_point ns = ::std::chrono::time_point_cast< ::std::chrono::nanoseconds>(atime); + ::std::chrono::time_point ns = ::std::chrono::time_point_cast<::std::chrono::nanoseconds>(atime); int e = ::rt_cond_wait_until(&this->M_cond, lock.mutex()->native_handle(), ::rt_timer_ns2ticks(ns.time_since_epoch().count())); if (e) diff --git a/src/rl/util/xenomai/mutex.h b/src/rl/util/xenomai/mutex.h index eb41e690..f1341e21 100644 --- a/src/rl/util/xenomai/mutex.h +++ b/src/rl/util/xenomai/mutex.h @@ -157,7 +157,7 @@ namespace rl ++rt; } - ::std::chrono::nanoseconds ns = ::std::chrono::duration_cast< ::std::chrono::nanoseconds>(rt); + ::std::chrono::nanoseconds ns = ::std::chrono::duration_cast<::std::chrono::nanoseconds>(rt); int e = ::rt_mutex_acquire(static_cast(this)->native_handle(), ::rt_timer_ns2ticks(ns.count())); switch (e) @@ -177,7 +177,7 @@ namespace rl template bool M_try_lock_until(const ::std::chrono::time_point& atime) { - ::std::chrono::time_point ns = ::std::chrono::time_point_cast< ::std::chrono::nanoseconds>(atime); + ::std::chrono::time_point ns = ::std::chrono::time_point_cast<::std::chrono::nanoseconds>(atime); int e = ::rt_mutex_acquire_until(static_cast(this)->native_handle(), ::rt_timer_ns2ticks(ns.time_since_epoch().count())); switch (e) diff --git a/src/rl/util/xenomai/thread.h b/src/rl/util/xenomai/thread.h index 8278d684..ab8f2a4a 100644 --- a/src/rl/util/xenomai/thread.h +++ b/src/rl/util/xenomai/thread.h @@ -214,7 +214,7 @@ namespace rl template void set_periodic(const ::std::chrono::duration& period) { - ::std::chrono::nanoseconds period_ns = ::std::chrono::duration_cast< ::std::chrono::nanoseconds>(period); + ::std::chrono::nanoseconds period_ns = ::std::chrono::duration_cast<::std::chrono::nanoseconds>(period); int e = ::rt_task_set_periodic(&this->M_id.M_thread, TM_NOW, ::rt_timer_ns2ticks(period_ns.count())); @@ -227,8 +227,8 @@ namespace rl template void set_periodic(const ::std::chrono::time_point& idate, const ::std::chrono::duration& period) { - ::std::chrono::time_point idate_ns = ::std::chrono::time_point_cast< ::std::chrono::nanoseconds>(idate); - ::std::chrono::nanoseconds period_ns = ::std::chrono::duration_cast< ::std::chrono::nanoseconds>(period); + ::std::chrono::time_point idate_ns = ::std::chrono::time_point_cast<::std::chrono::nanoseconds>(idate); + ::std::chrono::nanoseconds period_ns = ::std::chrono::duration_cast<::std::chrono::nanoseconds>(period); int e = ::rt_task_set_periodic(&this->M_id.M_thread, ::rt_timer_ns2ticks(idate_ns.time_since_epoch().count()), ::rt_timer_ns2ticks(period_ns.count())); @@ -429,7 +429,7 @@ namespace rl template inline void sleep_for(const ::std::chrono::duration& rtime) { - ::std::chrono::nanoseconds ns = ::std::chrono::duration_cast< ::std::chrono::nanoseconds>(rtime); + ::std::chrono::nanoseconds ns = ::std::chrono::duration_cast<::std::chrono::nanoseconds>(rtime); int e = ::rt_task_sleep(::rt_timer_ns2ticks(ns.count())); if (e) @@ -441,7 +441,7 @@ namespace rl template inline void sleep_until(const ::std::chrono::time_point& atime) { - ::std::chrono::time_point ns = ::std::chrono::time_point_cast< ::std::chrono::nanoseconds>(atime); + ::std::chrono::time_point ns = ::std::chrono::time_point_cast<::std::chrono::nanoseconds>(atime); int e = ::rt_task_sleep_until(::rt_timer_ns2ticks(ns.time_since_epoch().count())); if (e) @@ -486,11 +486,11 @@ namespace rl namespace std { template<> - struct hash< ::rl::util::xenomai::thread::id> + struct hash<::rl::util::xenomai::thread::id> { size_t operator()(const ::rl::util::xenomai::thread::id& id) const { - return hash< ::xnhandle_t>()(id.M_thread.opaque); + return hash<::xnhandle_t>()(id.M_thread.opaque); } }; diff --git a/src/rl/xml/Attribute.h b/src/rl/xml/Attribute.h index ea755c1e..7077abdf 100644 --- a/src/rl/xml/Attribute.h +++ b/src/rl/xml/Attribute.h @@ -100,7 +100,7 @@ namespace rl { if (nullptr != this->attr->ns) { - ::boost::shared_array< ::xmlChar> value( + ::boost::shared_array<::xmlChar> value( ::xmlGetNsProp( this->attr->parent, this->attr->name, @@ -113,7 +113,7 @@ namespace rl } else { - ::boost::shared_array< ::xmlChar> value( + ::boost::shared_array<::xmlChar> value( ::xmlGetProp( this->attr->parent, this->attr->name diff --git a/src/rl/xml/Document.h b/src/rl/xml/Document.h index 1e7df011..496e51de 100644 --- a/src/rl/xml/Document.h +++ b/src/rl/xml/Document.h @@ -71,7 +71,7 @@ namespace rl int size; ::xmlDocDumpFormatMemory(this->doc.get(), &mem, &size, format ? 1 : 0); - ::boost::shared_array< ::xmlChar> memory(mem, ::xmlFree); + ::boost::shared_array<::xmlChar> memory(mem, ::xmlFree); return nullptr != memory.get() ? reinterpret_cast(memory.get()) : ::std::string(); } @@ -82,7 +82,7 @@ namespace rl int size; ::xmlDocDumpMemory(this->doc.get(), &mem, &size); - ::boost::shared_array< ::xmlChar> memory(mem, ::xmlFree); + ::boost::shared_array<::xmlChar> memory(mem, ::xmlFree); return nullptr != memory.get() ? reinterpret_cast(memory.get()) : ::std::string(); } @@ -173,7 +173,7 @@ namespace rl protected: private: - ::std::unique_ptr< ::xmlDoc, decltype(&::xmlFreeDoc)> doc; + ::std::unique_ptr<::xmlDoc, decltype(&::xmlFreeDoc)> doc; }; } } diff --git a/src/rl/xml/DomParser.h b/src/rl/xml/DomParser.h index 0864c121..7008c08e 100644 --- a/src/rl/xml/DomParser.h +++ b/src/rl/xml/DomParser.h @@ -88,7 +88,7 @@ namespace rl protected: private: - ::std::shared_ptr< ::xmlParserCtxt> parser; + ::std::shared_ptr<::xmlParserCtxt> parser; }; } } diff --git a/src/rl/xml/Node.h b/src/rl/xml/Node.h index f81dc523..edfc42c0 100644 --- a/src/rl/xml/Node.h +++ b/src/rl/xml/Node.h @@ -110,7 +110,7 @@ namespace rl ::std::string getContent() const { - ::boost::shared_array< ::xmlChar> content( + ::boost::shared_array<::xmlChar> content( ::xmlNodeGetContent(this->node), ::xmlFree ); @@ -135,7 +135,7 @@ namespace rl ::std::string getLocalPath(const ::std::string& uri) const { - ::boost::shared_array< ::xmlChar> absolute( + ::boost::shared_array<::xmlChar> absolute( ::xmlBuildURI( reinterpret_cast(uri.c_str()), ::xmlNodeGetBase(this->node->doc, this->node) @@ -213,7 +213,7 @@ namespace rl ::std::string getProperty(const ::std::string& name) const { - ::boost::shared_array< ::xmlChar> prop( + ::boost::shared_array<::xmlChar> prop( ::xmlGetProp( this->node, reinterpret_cast(name.c_str()) @@ -226,7 +226,7 @@ namespace rl ::std::string getProperty(const ::std::string& name, const ::std::string& nameSpace) const { - ::boost::shared_array< ::xmlChar> prop( + ::boost::shared_array<::xmlChar> prop( ::xmlGetNsProp( this->node, reinterpret_cast(name.c_str()), @@ -240,7 +240,7 @@ namespace rl ::std::string getRelativeUri(const ::std::string& uri) const { - ::boost::shared_array< ::xmlChar> relative( + ::boost::shared_array<::xmlChar> relative( ::xmlBuildRelativeURI( reinterpret_cast(uri.c_str()), ::xmlNodeGetBase(this->node->doc, this->node) @@ -253,7 +253,7 @@ namespace rl ::std::string getUri(const ::std::string& uri) const { - ::boost::shared_array< ::xmlChar> absolute( + ::boost::shared_array<::xmlChar> absolute( ::xmlBuildURI( reinterpret_cast(uri.c_str()), ::xmlNodeGetBase(this->node->doc, this->node) diff --git a/src/rl/xml/NodeSet.h b/src/rl/xml/NodeSet.h index 420d9519..964d8362 100644 --- a/src/rl/xml/NodeSet.h +++ b/src/rl/xml/NodeSet.h @@ -45,7 +45,7 @@ namespace rl { } - explicit NodeSet(const ::std::shared_ptr< ::xmlNodeSet>& nodeSet) : + explicit NodeSet(const ::std::shared_ptr<::xmlNodeSet>& nodeSet) : nodeSet(nodeSet) { } @@ -97,7 +97,7 @@ namespace rl protected: private: - ::std::shared_ptr< ::xmlNodeSet> nodeSet; + ::std::shared_ptr<::xmlNodeSet> nodeSet; }; } } diff --git a/src/rl/xml/Object.h b/src/rl/xml/Object.h index a4dede01..466cd8f3 100644 --- a/src/rl/xml/Object.h +++ b/src/rl/xml/Object.h @@ -106,9 +106,9 @@ namespace rl protected: private: - ::std::shared_ptr< ::xmlXPathObject> object; + ::std::shared_ptr<::xmlXPathObject> object; - ::std::shared_ptr< ::xmlNodeSet> nodeSet; + ::std::shared_ptr<::xmlNodeSet> nodeSet; }; template<> @@ -267,7 +267,7 @@ namespace rl template<> inline - ::std::string Object::getValue< ::std::string>() const + ::std::string Object::getValue<::std::string>() const { return nullptr != this->object->stringval ? reinterpret_cast(this->object->stringval) : ::std::string(); } diff --git a/src/rl/xml/Path.h b/src/rl/xml/Path.h index c4ee5313..300d3051 100644 --- a/src/rl/xml/Path.h +++ b/src/rl/xml/Path.h @@ -105,7 +105,7 @@ namespace rl protected: private: - ::std::shared_ptr< ::xmlXPathContext> context; + ::std::shared_ptr<::xmlXPathContext> context; ::xmlDocPtr document; }; diff --git a/src/rl/xml/Schema.h b/src/rl/xml/Schema.h index 915a98ed..a78e3d20 100644 --- a/src/rl/xml/Schema.h +++ b/src/rl/xml/Schema.h @@ -70,11 +70,11 @@ namespace rl protected: private: - ::std::shared_ptr< ::xmlSchemaParserCtxt> parser; + ::std::shared_ptr<::xmlSchemaParserCtxt> parser; - ::std::shared_ptr< ::xmlSchema> schema; + ::std::shared_ptr<::xmlSchema> schema; - ::std::shared_ptr< ::xmlSchemaValidCtxt> valid; + ::std::shared_ptr<::xmlSchemaValidCtxt> valid; }; } } diff --git a/src/rl/xml/Stylesheet.h b/src/rl/xml/Stylesheet.h index 5996f4c5..a5774336 100644 --- a/src/rl/xml/Stylesheet.h +++ b/src/rl/xml/Stylesheet.h @@ -75,11 +75,11 @@ namespace rl return Document(::xsltApplyStylesheet(this->stylesheet.get(), this->stylesheet.get()->doc, nullptr)); } - Document apply(const ::std::map< ::std::string, ::std::string>& parameters) + Document apply(const ::std::map<::std::string, ::std::string>& parameters) { ::std::vector params; - for (::std::map< ::std::string, ::std::string>::const_iterator i = parameters.begin(); i != parameters.end(); ++i) + for (::std::map<::std::string, ::std::string>::const_iterator i = parameters.begin(); i != parameters.end(); ++i) { params.push_back(i->first.c_str()); params.push_back(i->second.c_str()); @@ -95,11 +95,11 @@ namespace rl return Document(::xsltApplyStylesheet(this->stylesheet.get(), document.get(), nullptr)); } - Document apply(const Document& document, const ::std::map< ::std::string, ::std::string>& parameters) + Document apply(const Document& document, const ::std::map<::std::string, ::std::string>& parameters) { ::std::vector params; - for (::std::map< ::std::string, ::std::string>::const_iterator i = parameters.begin(); i != parameters.end(); ++i) + for (::std::map<::std::string, ::std::string>::const_iterator i = parameters.begin(); i != parameters.end(); ++i) { params.push_back(i->first.c_str()); params.push_back(i->second.c_str()); @@ -116,7 +116,7 @@ namespace rl int size; ::xmlDocDumpFormatMemory(this->stylesheet.get()->doc, &mem, &size, format ? 1 : 0); - ::boost::shared_array< ::xmlChar> memory(mem, ::xmlFree); + ::boost::shared_array<::xmlChar> memory(mem, ::xmlFree); return nullptr != memory.get() ? reinterpret_cast(memory.get()) : ::std::string(); } @@ -127,7 +127,7 @@ namespace rl int size; ::xmlDocDumpMemory(this->stylesheet.get()->doc, &mem, &size); - ::boost::shared_array< ::xmlChar> memory(mem, ::xmlFree); + ::boost::shared_array<::xmlChar> memory(mem, ::xmlFree); return nullptr != memory.get() ? reinterpret_cast(memory.get()) : ::std::string(); } @@ -182,7 +182,7 @@ namespace rl protected: private: - ::std::shared_ptr< ::xsltStylesheet> stylesheet; + ::std::shared_ptr<::xsltStylesheet> stylesheet; }; } } diff --git a/tests/rlCollisionTest/rlCollisionTest.cpp b/tests/rlCollisionTest/rlCollisionTest.cpp index 2a4afb07..7d747cd7 100644 --- a/tests/rlCollisionTest/rlCollisionTest.cpp +++ b/tests/rlCollisionTest/rlCollisionTest.cpp @@ -69,7 +69,7 @@ collides(rl::sg::SimpleScene* scene, const rl::mdl::Kinematic* kinematic) { for (::rl::sg::Model::Iterator k = (*j)->begin(); k != (*j)->end(); ++k) { - if (dynamic_cast< ::rl::sg::SimpleScene*>(scene)->areColliding(robotModel->getBody(i), *k)) + if (dynamic_cast<::rl::sg::SimpleScene*>(scene)->areColliding(robotModel->getBody(i), *k)) { return true; } @@ -82,7 +82,7 @@ collides(rl::sg::SimpleScene* scene, const rl::mdl::Kinematic* kinematic) { if (kinematic->areColliding(i, j)) { - if (dynamic_cast< ::rl::sg::SimpleScene*>(scene)->areColliding(robotModel->getBody(i), robotModel->getBody(j))) + if (dynamic_cast<::rl::sg::SimpleScene*>(scene)->areColliding(robotModel->getBody(i), robotModel->getBody(j))) { return true; } diff --git a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp index 49bd917b..2efa7587 100644 --- a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp +++ b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp @@ -62,7 +62,7 @@ main(int argc, char** argv) t1, q3, 0, - std::numeric_limits< ::rl::math::Real>::infinity(), + std::numeric_limits<::rl::math::Real>::infinity(), static_cast(1.0e-6), 100000, std::chrono::nanoseconds::max() From 75617e178602f812394cb8cf695ecbbef14880a0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 21 May 2020 00:41:52 +0200 Subject: [PATCH 347/546] Use smart pointers for Bullet objects --- src/rl/sg/bullet/Scene.cpp | 8 ++++---- src/rl/sg/bullet/Shape.cpp | 30 ++++++++++++++---------------- src/rl/sg/bullet/Shape.h | 5 +++-- 3 files changed, 21 insertions(+), 22 deletions(-) diff --git a/src/rl/sg/bullet/Scene.cpp b/src/rl/sg/bullet/Scene.cpp index 0b1268d5..72aa019e 100644 --- a/src/rl/sg/bullet/Scene.cpp +++ b/src/rl/sg/bullet/Scene.cpp @@ -129,8 +129,8 @@ namespace rl ::btVoronoiSimplexSolver simplexSolver; ::btGjkEpaPenetrationDepthSolver penetrationDepthSolver; ::btGjkPairDetector pairDetector( - static_cast<::btConvexShape*>(shape1->shape), - static_cast<::btConvexShape*>(shape2->shape), + static_cast<::btConvexShape*>(shape1->shape.get()), + static_cast<::btConvexShape*>(shape2->shape.get()), &simplexSolver, &penetrationDepthSolver ); @@ -163,7 +163,7 @@ namespace rl ::btGjkEpaPenetrationDepthSolver epa; ::btGjkPairDetector convexConvex( - static_cast<::btConvexShape*>(static_cast(shape)->shape), + static_cast<::btConvexShape*>(static_cast(shape)->shape.get()), static_cast<::btConvexShape*>(&sphere), &sGjkSimplexSolver, &epa @@ -282,7 +282,7 @@ namespace rl rayFromTrans, rayToTrans, &body->object, - static_cast(shape)->shape, + static_cast(shape)->shape.get(), body->object.getWorldTransform() * static_cast(shape)->transform, // TODO resultCallback ); diff --git a/src/rl/sg/bullet/Shape.cpp b/src/rl/sg/bullet/Shape.cpp index 8e436fa9..41e4a5f2 100644 --- a/src/rl/sg/bullet/Shape.cpp +++ b/src/rl/sg/bullet/Shape.cpp @@ -32,6 +32,7 @@ #include #include #include +#include #include "../Exception.h" #include "Body.h" @@ -47,10 +48,10 @@ namespace rl { Shape::Shape(::SoVRMLShape* shape, Body* body) : ::rl::sg::Shape(shape, body), - shape(nullptr), + shape(), transform(), indices(), - triangleIndexVertexArray(nullptr), + triangleIndexVertexArray(), vertices() { ::SoVRMLGeometry* geometry = static_cast<::SoVRMLGeometry*>(shape->geometry.getValue()); @@ -59,17 +60,17 @@ namespace rl { ::SoVRMLBox* box = static_cast<::SoVRMLBox*>(geometry); ::btVector3 boxHalfExtents(box->size.getValue()[0] / 2, box->size.getValue()[1] / 2, box->size.getValue()[2] / 2); - this->shape = new ::btBoxShape(boxHalfExtents); + this->shape = ::rl::std14::make_unique<::btBoxShape>(boxHalfExtents); } else if (geometry->isOfType(::SoVRMLCone::getClassTypeId())) { ::SoVRMLCone* cone = static_cast<::SoVRMLCone*>(geometry); - this->shape = new ::btConeShape(cone->bottomRadius.getValue(), cone->height.getValue()); + this->shape = ::rl::std14::make_unique<::btConeShape>(cone->bottomRadius.getValue(), cone->height.getValue()); } else if (geometry->isOfType(::SoVRMLCylinder::getClassTypeId())) { ::SoVRMLCylinder* cylinder = static_cast<::SoVRMLCylinder*>(geometry); - this->shape = new ::btCylinderShape(::btVector3(cylinder->radius.getValue(), cylinder->height.getValue() / 2, cylinder->radius.getValue())); + this->shape = ::rl::std14::make_unique<::btCylinderShape>(::btVector3(cylinder->radius.getValue(), cylinder->height.getValue() / 2, cylinder->radius.getValue())); } else if (geometry->isOfType(::SoVRMLIndexedFaceSet::getClassTypeId())) { @@ -81,7 +82,7 @@ namespace rl if (indexedFaceSet->convex.getValue()) { - this->shape = new ::btConvexHullShape( + this->shape = ::rl::std14::make_unique<::btConvexHullShape>( &this->vertices[0], this->vertices.size() / 3, 3 * sizeof(btScalar) @@ -89,7 +90,7 @@ namespace rl } else { - this->triangleIndexVertexArray = new ::btTriangleIndexVertexArray( + this->triangleIndexVertexArray = ::rl::std14::make_unique<::btTriangleIndexVertexArray>( this->indices.size() / 3, &this->indices[0], 3 * sizeof(int), @@ -98,13 +99,13 @@ namespace rl 3 * sizeof(btScalar) ); - this->shape = new ::btBvhTriangleMeshShape(this->triangleIndexVertexArray, true); + this->shape = ::rl::std14::make_unique<::btBvhTriangleMeshShape>(this->triangleIndexVertexArray.get(), true); } } else if (geometry->isOfType(::SoVRMLSphere::getClassTypeId())) { ::SoVRMLSphere* sphere = static_cast<::SoVRMLSphere*>(geometry); - this->shape = new ::btSphereShape(sphere->radius.getValue()); + this->shape = ::rl::std14::make_unique<::btSphereShape>(sphere->radius.getValue()); } else { @@ -116,7 +117,7 @@ namespace rl if (nullptr != this->shape) { this->transform.setIdentity(); - dynamic_cast(this->getBody())->shape.addChildShape(this->transform, this->shape); + dynamic_cast(this->getBody())->shape.addChildShape(this->transform, this->shape.get()); this->shape->setMargin(0); this->shape->setUserPointer(this); } @@ -126,13 +127,10 @@ namespace rl { if (nullptr != this->shape) { - dynamic_cast(this->getBody())->shape.removeChildShape(this->shape); + dynamic_cast(this->getBody())->shape.removeChildShape(this->shape.get()); } this->getBody()->remove(this); - - delete this->triangleIndexVertexArray; - delete this->shape; } void @@ -142,7 +140,7 @@ namespace rl for (int i = 0; i < body->shape.getNumChildShapes(); ++i) { - if (this->shape == body->shape.getChildList()[i].m_childShape) + if (this->shape.get() == body->shape.getChildList()[i].m_childShape) { for (int j = 0; j < 3; ++j) { @@ -172,7 +170,7 @@ namespace rl for (int i = 0; i < body->shape.getNumChildShapes(); ++i) { - if (this->shape == body->shape.getChildList()[i].m_childShape) + if (this->shape.get() == body->shape.getChildList()[i].m_childShape) { this->transform.getOrigin().setValue( static_cast<::btScalar>(transform(0, 3)), diff --git a/src/rl/sg/bullet/Shape.h b/src/rl/sg/bullet/Shape.h index c5aa20d3..b113ade9 100644 --- a/src/rl/sg/bullet/Shape.h +++ b/src/rl/sg/bullet/Shape.h @@ -27,6 +27,7 @@ #ifndef RL_SG_BULLET_SHAPE_H #define RL_SG_BULLET_SHAPE_H +#include #include #include @@ -49,7 +50,7 @@ namespace rl void setTransform(const ::rl::math::Transform& transform); - ::btCollisionShape* shape; + ::std::unique_ptr<::btCollisionShape> shape; ::btTransform transform; @@ -60,7 +61,7 @@ namespace rl ::std::vector indices; - ::btTriangleIndexVertexArray* triangleIndexVertexArray; + ::std::unique_ptr<::btTriangleIndexVertexArray> triangleIndexVertexArray; ::std::vector<::btScalar> vertices; }; From 42a730b50e192e5e661f488a922b66b25acda148 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 29 May 2020 00:57:53 +0200 Subject: [PATCH 348/546] Update NLopt to 2.6.2 --- 3rdparty/nlopt/CMakeLists.txt | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/3rdparty/nlopt/CMakeLists.txt b/3rdparty/nlopt/CMakeLists.txt index dee075c1..89651557 100644 --- a/3rdparty/nlopt/CMakeLists.txt +++ b/3rdparty/nlopt/CMakeLists.txt @@ -6,11 +6,11 @@ include(ExternalProject) ExternalProject_Add( nlopt - #GIT_REPOSITORY git://github.com/stevengj/nlopt.git - #GIT_TAG 2.6.1 - URL https://github.com/stevengj/nlopt/archive/v2.6.1.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/nlopt-2.6.1.zip - URL_MD5 66ddf7088aeeef969972bc7061779805 + #GIT_REPOSITORY https://github.com/stevengj/nlopt.git + #GIT_TAG 2.6.2 + URL https://github.com/stevengj/nlopt/archive/v2.6.2.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/nlopt-2.6.2.zip + URL_MD5 3c7b0f560b6f1b547a1f71badc93db11 CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_DEBUG_POSTFIX=d -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_SHARED_LIBS=ON -DNLOPT_GUILE=OFF -DNLOPT_MATLAB=OFF -DNLOPT_OCTAVE=OFF -DNLOPT_PYTHON=OFF -DNLOPT_SWIG=OFF -DNLOPT_TESTS=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) From 743ee8bd1b4fb7fb60deb1e25a970c0a0700598f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 7 Jun 2020 23:23:36 +0200 Subject: [PATCH 349/546] Use Boost_INCLUDE_DIRS --- demos/rlDynamics1Demo/CMakeLists.txt | 2 +- demos/rlDynamics2Demo/CMakeLists.txt | 2 +- demos/rlEulerAnglesDemo/CMakeLists.txt | 2 +- demos/rlInversePositionDemo/CMakeLists.txt | 2 +- demos/rlJacobianDemo/CMakeLists.txt | 2 +- demos/rlPlanDemo/CMakeLists.txt | 2 +- demos/rlPolynomialRootsDemo/CMakeLists.txt | 2 +- demos/rlPrmDemo/CMakeLists.txt | 2 +- demos/rlPumaDemo/CMakeLists.txt | 2 +- demos/rlRrtDemo/CMakeLists.txt | 2 +- demos/rlSimulator/CMakeLists.txt | 2 +- demos/rlSocketDemo/CMakeLists.txt | 4 ++-- extras/tris2wrl/CMakeLists.txt | 2 +- src/rl/hal/CMakeLists.txt | 2 +- src/rl/kin/CMakeLists.txt | 2 +- src/rl/math/CMakeLists.txt | 2 +- src/rl/mdl/CMakeLists.txt | 2 +- src/rl/plan/CMakeLists.txt | 2 +- src/rl/xml/CMakeLists.txt | 2 +- tests/rlCollisionTest/CMakeLists.txt | 2 +- tests/rlEetTest/CMakeLists.txt | 2 +- tests/rlNearestNeighborsTest/CMakeLists.txt | 2 +- tests/rlPrmTest/CMakeLists.txt | 2 +- 23 files changed, 24 insertions(+), 24 deletions(-) diff --git a/demos/rlDynamics1Demo/CMakeLists.txt b/demos/rlDynamics1Demo/CMakeLists.txt index 7fdaf4fd..8c23e974 100644 --- a/demos/rlDynamics1Demo/CMakeLists.txt +++ b/demos/rlDynamics1Demo/CMakeLists.txt @@ -9,7 +9,7 @@ add_executable( target_include_directories( rlDynamics1Demo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/demos/rlDynamics2Demo/CMakeLists.txt b/demos/rlDynamics2Demo/CMakeLists.txt index 7c472b9c..8b6eb1ee 100644 --- a/demos/rlDynamics2Demo/CMakeLists.txt +++ b/demos/rlDynamics2Demo/CMakeLists.txt @@ -9,7 +9,7 @@ add_executable( target_include_directories( rlDynamics2Demo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/demos/rlEulerAnglesDemo/CMakeLists.txt b/demos/rlEulerAnglesDemo/CMakeLists.txt index 0ffce666..47fc2607 100644 --- a/demos/rlEulerAnglesDemo/CMakeLists.txt +++ b/demos/rlEulerAnglesDemo/CMakeLists.txt @@ -9,7 +9,7 @@ add_executable( target_include_directories( rlEulerAnglesDemo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/demos/rlInversePositionDemo/CMakeLists.txt b/demos/rlInversePositionDemo/CMakeLists.txt index 29f6b1b5..66229c44 100644 --- a/demos/rlInversePositionDemo/CMakeLists.txt +++ b/demos/rlInversePositionDemo/CMakeLists.txt @@ -9,7 +9,7 @@ add_executable( target_include_directories( rlInversePositionDemo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/demos/rlJacobianDemo/CMakeLists.txt b/demos/rlJacobianDemo/CMakeLists.txt index c34d4ab2..8ca61cbd 100644 --- a/demos/rlJacobianDemo/CMakeLists.txt +++ b/demos/rlJacobianDemo/CMakeLists.txt @@ -9,7 +9,7 @@ add_executable( target_include_directories( rlJacobianDemo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index 3eb84a29..293a791e 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -75,7 +75,7 @@ if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE target_include_directories( rlPlanDemo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ${OPENGL_INCLUDE_DIR} ${SoQt_INCLUDE_DIRS} ) diff --git a/demos/rlPolynomialRootsDemo/CMakeLists.txt b/demos/rlPolynomialRootsDemo/CMakeLists.txt index 4376900b..60f14426 100644 --- a/demos/rlPolynomialRootsDemo/CMakeLists.txt +++ b/demos/rlPolynomialRootsDemo/CMakeLists.txt @@ -9,7 +9,7 @@ add_executable( target_include_directories( rlPolynomialRootsDemo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/demos/rlPrmDemo/CMakeLists.txt b/demos/rlPrmDemo/CMakeLists.txt index b1942795..1e33a833 100644 --- a/demos/rlPrmDemo/CMakeLists.txt +++ b/demos/rlPrmDemo/CMakeLists.txt @@ -14,7 +14,7 @@ if(Bullet_FOUND OR ODE_FOUND OR SOLID3_FOUND) target_include_directories( rlPrmDemo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/demos/rlPumaDemo/CMakeLists.txt b/demos/rlPumaDemo/CMakeLists.txt index af1cd6b0..d28e3e71 100644 --- a/demos/rlPumaDemo/CMakeLists.txt +++ b/demos/rlPumaDemo/CMakeLists.txt @@ -9,7 +9,7 @@ add_executable( target_include_directories( rlPumaDemo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/demos/rlRrtDemo/CMakeLists.txt b/demos/rlRrtDemo/CMakeLists.txt index df21e9f8..3bc0945e 100644 --- a/demos/rlRrtDemo/CMakeLists.txt +++ b/demos/rlRrtDemo/CMakeLists.txt @@ -14,7 +14,7 @@ if(Bullet_FOUND OR ODE_FOUND OR SOLID3_FOUND) target_include_directories( rlRrtDemo PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index f3d6cf2f..f88c6da5 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -61,7 +61,7 @@ if(QT_FOUND AND SoQt_FOUND) target_include_directories( rlSimulator PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ${Coin_INCLUDE_DIRS} ${OPENGL_INCLUDE_DIR} ${SoQt_INCLUDE_DIRS} diff --git a/demos/rlSocketDemo/CMakeLists.txt b/demos/rlSocketDemo/CMakeLists.txt index 2e4ddea3..947c3f2c 100644 --- a/demos/rlSocketDemo/CMakeLists.txt +++ b/demos/rlSocketDemo/CMakeLists.txt @@ -9,7 +9,7 @@ add_executable( target_include_directories( rlSocketDemoClient PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( @@ -26,7 +26,7 @@ add_executable( target_include_directories( rlSocketDemoServer PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/extras/tris2wrl/CMakeLists.txt b/extras/tris2wrl/CMakeLists.txt index a9e94ce2..d20269d6 100644 --- a/extras/tris2wrl/CMakeLists.txt +++ b/extras/tris2wrl/CMakeLists.txt @@ -18,7 +18,7 @@ if(Coin_FOUND) target_include_directories( tris2wrl PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ${Coin_INCLUDE_DIRS} ) diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 33ddb842..4318ec96 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -197,7 +197,7 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) if(RL_BUILD_HAL_ATIDAQ) diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index b015cb70..30ca6892 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -47,7 +47,7 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index 0e32f026..6eca9f39 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -80,7 +80,7 @@ target_include_directories( INTERFACE $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS} ) diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index b13dbb73..66dac2f3 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -91,7 +91,7 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index 60ae3908..e4e97802 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -105,7 +105,7 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/src/rl/xml/CMakeLists.txt b/src/rl/xml/CMakeLists.txt index f6a4cf6d..ecffe8ee 100644 --- a/src/rl/xml/CMakeLists.txt +++ b/src/rl/xml/CMakeLists.txt @@ -37,7 +37,7 @@ target_include_directories( INTERFACE $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ${LIBXML2_INCLUDE_DIRS} ${LIBXSLT_INCLUDE_DIRS} ) diff --git a/tests/rlCollisionTest/CMakeLists.txt b/tests/rlCollisionTest/CMakeLists.txt index 0136d686..cf8a530e 100644 --- a/tests/rlCollisionTest/CMakeLists.txt +++ b/tests/rlCollisionTest/CMakeLists.txt @@ -17,7 +17,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 target_include_directories( rlCollisionTest PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index a1d5161d..367031dd 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -16,7 +16,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) target_include_directories( rlEetTest PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/tests/rlNearestNeighborsTest/CMakeLists.txt b/tests/rlNearestNeighborsTest/CMakeLists.txt index 582e5c6d..7d809dea 100644 --- a/tests/rlNearestNeighborsTest/CMakeLists.txt +++ b/tests/rlNearestNeighborsTest/CMakeLists.txt @@ -10,7 +10,7 @@ add_executable( target_include_directories( rlNearestNeighborsTest PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( diff --git a/tests/rlPrmTest/CMakeLists.txt b/tests/rlPrmTest/CMakeLists.txt index 1c81bf81..fb9276d6 100644 --- a/tests/rlPrmTest/CMakeLists.txt +++ b/tests/rlPrmTest/CMakeLists.txt @@ -17,7 +17,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 target_include_directories( rlPrmTest PUBLIC - ${Boost_INCLUDE_DIR} + ${Boost_INCLUDE_DIRS} ) target_link_libraries( From 37ef4e04369961542b895baba071907dca0fdf3b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 8 Jun 2020 00:51:07 +0200 Subject: [PATCH 350/546] Fix gmtime_s for MinGW --- .../rlSixAxisForceTorqueSensorDemo.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/demos/rlSixAxisForceTorqueSensorDemo/rlSixAxisForceTorqueSensorDemo.cpp b/demos/rlSixAxisForceTorqueSensorDemo/rlSixAxisForceTorqueSensorDemo.cpp index 7f59c5f3..82f66e62 100644 --- a/demos/rlSixAxisForceTorqueSensorDemo/rlSixAxisForceTorqueSensorDemo.cpp +++ b/demos/rlSixAxisForceTorqueSensorDemo/rlSixAxisForceTorqueSensorDemo.cpp @@ -64,8 +64,8 @@ toIsoString(const std::chrono::system_clock::time_point& timePoint) std::tm result; #ifdef __STDC_LIB_EXT1__ std::strftime(str.data(), str.size(), "%Y-%m-%d %H:%M:%S", gmtime_s(&time, &result)); -#elif _MSC_VER - if (NULL == gmtime_s(&result, &time)) +#elif defined(_MSC_VER) || defined(__MINGW32__) + if (0 == gmtime_s(&result, &time)) { std::strftime(str.data(), str.size(), "%Y-%m-%d %H:%M:%S", &result); } From a33742eb4555045f17eead38f5caf8e6700c97ca Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 8 Jun 2020 18:36:39 +0200 Subject: [PATCH 351/546] Add fixes for Cygwin --- src/rl/hal/Serial.cpp | 2 ++ src/rl/hal/Serial.h | 4 ++++ src/rl/hal/Socket.cpp | 8 ++++---- src/rl/hal/Socket.h | 6 +++--- src/rl/hal/UniversalRobotsRealtime.cpp | 8 ++++---- src/rl/hal/UniversalRobotsRtde.cpp | 4 ++-- src/rl/util/process.h | 8 ++++---- 7 files changed, 23 insertions(+), 17 deletions(-) diff --git a/src/rl/hal/Serial.cpp b/src/rl/hal/Serial.cpp index b0164665..2008dfe1 100644 --- a/src/rl/hal/Serial.cpp +++ b/src/rl/hal/Serial.cpp @@ -546,12 +546,14 @@ namespace rl case BAUDRATE_3000000BPS: speed = B3000000; break; +#ifndef __CYGWIN__ case BAUDRATE_3500000BPS: speed = B3500000; break; case BAUDRATE_4000000BPS: speed = B4000000; break; +#endif // __CYGWIN__ #endif // __APPLE__ #endif // __QNX__ default: diff --git a/src/rl/hal/Serial.h b/src/rl/hal/Serial.h index 26485593..ba443d7c 100644 --- a/src/rl/hal/Serial.h +++ b/src/rl/hal/Serial.h @@ -107,11 +107,15 @@ namespace rl /** 2,500,000 bps. */ BAUDRATE_2500000BPS, /** 3,000,000 bps. */ +#ifdef __CYGWIN__ + BAUDRATE_3000000BPS +#else // __CYGWIN__ BAUDRATE_3000000BPS, /** 3,500,000 bps. */ BAUDRATE_3500000BPS, /** 4,000,000 bps. */ BAUDRATE_4000000BPS +#endif // __CYGWIN__ #endif // __QNX__ #endif // WIN32 }; diff --git a/src/rl/hal/Socket.cpp b/src/rl/hal/Socket.cpp index a8a6b2ac..88682417 100644 --- a/src/rl/hal/Socket.cpp +++ b/src/rl/hal/Socket.cpp @@ -269,12 +269,12 @@ namespace rl level = IPPROTO_TCP; optname = TCP_NODELAY; break; -#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) +#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) case OPTION_QUICKACK: level = IPPROTO_TCP; optname = TCP_QUICKACK; break; -#endif // __APPLE__ || __QNX__ || WIN32 +#endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ default: break; } @@ -557,12 +557,12 @@ namespace rl level = IPPROTO_TCP; optname = TCP_NODELAY; break; -#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) +#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) case OPTION_QUICKACK: level = IPPROTO_TCP; optname = TCP_QUICKACK; break; -#endif // __APPLE__ || __QNX__ || WIN32 +#endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ default: break; } diff --git a/src/rl/hal/Socket.h b/src/rl/hal/Socket.h index d7f4ca32..5bf3853a 100644 --- a/src/rl/hal/Socket.h +++ b/src/rl/hal/Socket.h @@ -92,12 +92,12 @@ namespace rl OPTION_KEEPALIVE, OPTION_MULTICAST_LOOP, OPTION_MULTICAST_TTL, -#if defined(__APPLE__) || defined(__QNX__) || defined(WIN32) +#if defined(__APPLE__) || defined(__QNX__) || defined(WIN32) || defined(__CYGWIN__) OPTION_NODELAY -#else // __APPLE__ || __QNX__ || WIN32 +#else // __APPLE__ || __QNX__ || WIN32 || __CYGWIN__ OPTION_NODELAY, OPTION_QUICKACK -#endif // __APPLE__ || __QNX__ || WIN32 +#endif // __APPLE__ || __QNX__ || WIN32 || __CYGWIN__ }; Socket(const Socket& socket); diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index 64068148..a99576f3 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -255,9 +255,9 @@ namespace rl ::std::array<::std::uint8_t, 1116> buffer; this->socket.recv(buffer.data(), sizeof(this->in.messageSize)); -#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) +#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) this->socket.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); -#endif // __APPLE__ || __QNX__ || WIN32 +#endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ ::std::uint8_t* ptr = buffer.data(); this->in.unserialize(ptr, this->in.messageSize); @@ -272,9 +272,9 @@ namespace rl case 1108: case 1116: this->socket.recv(ptr, this->in.messageSize - sizeof(this->in.messageSize)); -#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) +#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) this->socket.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); -#endif // __APPLE__ || __QNX__ || WIN32 +#endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ this->in.unserialize(ptr); break; default: diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 4e6ee14b..6cd9d1ac 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -641,9 +641,9 @@ namespace rl { ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket4.recv(buffer.data(), buffer.size()); -#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) +#if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) this->socket4.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); -#endif // __APPLE__ || __QNX__ || WIN32 +#endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ // ::std::cout << "size: " << size << ::std::endl; ::std::uint8_t* ptr = buffer.data(); diff --git a/src/rl/util/process.h b/src/rl/util/process.h index f78b17b1..cb4332ef 100644 --- a/src/rl/util/process.h +++ b/src/rl/util/process.h @@ -64,12 +64,12 @@ namespace rl inline void memory_lock_all() { -#if !defined(WIN32) && !defined(__APPLE__) +#if !defined(WIN32) && !defined(__APPLE__) && !defined(__CYGWIN__) if (-1 == ::mlockall(MCL_CURRENT | MCL_FUTURE)) { throw ::std::system_error(::std::error_code(errno, ::std::generic_category())); } -#endif // !WIN32 && !__APPLE__ +#endif // !WIN32 && !__APPLE__ && !__CYGWIN__ } inline void memory_reserve(const ::std::size_t& size) @@ -89,12 +89,12 @@ namespace rl inline void memory_unlock_all() { -#if !defined(WIN32) && !defined(__APPLE__) +#if !defined(WIN32) && !defined(__APPLE__) && !defined(__CYGWIN__) if (-1 == ::munlockall()) { throw ::std::system_error(::std::error_code(errno, ::std::generic_category())); } -#endif // !WIN32 && !__APPLE__ +#endif // !WIN32 && !__APPLE__ && !__CYGWIN__ } inline void set_priority(const int& priority) From 79942d386f367985ddced618f23609f448ea1b92 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 8 Jun 2020 22:20:20 +0200 Subject: [PATCH 352/546] Use rl::mdl::Model::generatePositionUniform --- .../rlInversePositionDemo.cpp | 16 +--------------- 1 file changed, 1 insertion(+), 15 deletions(-) diff --git a/demos/rlInversePositionDemo/rlInversePositionDemo.cpp b/demos/rlInversePositionDemo/rlInversePositionDemo.cpp index fa53edb7..d83776ea 100644 --- a/demos/rlInversePositionDemo/rlInversePositionDemo.cpp +++ b/demos/rlInversePositionDemo/rlInversePositionDemo.cpp @@ -25,10 +25,8 @@ // #include -#include #include #include -#include #include #include #include @@ -55,11 +53,6 @@ main(int argc, char** argv) try { - std::function rand = std::bind( - std::uniform_real_distribution(0, 1), - std::mt19937(std::random_device()()) - ); - std::string filename(argv[1]); std::shared_ptr kinematic; @@ -99,14 +92,7 @@ main(int argc, char** argv) std::cout << " with timeout of " << std::chrono::duration_cast(ik.getDuration()).count() << " ms" << std::endl; ik.addGoal(kinematic->getOperationalPosition(0), 0); - rl::math::Vector min = kinematic->getMinimum(); - rl::math::Vector max = kinematic->getMaximum(); - - for (std::size_t i = 0; i < kinematic->getDofPosition(); ++i) - { - q(i) = min(i) + rand() * (max(i) - min(i)); - } - + q = kinematic->generatePositionUniform(); kinematic->setPosition(q); std::chrono::steady_clock::time_point start = std::chrono::steady_clock::now(); From 97edd6ea0cdcf5a10d79ae2b2ec72de7dee4ce81 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 9 Jun 2020 00:02:41 +0200 Subject: [PATCH 353/546] Remove doc target and option if Doxygen was not found --- CMakeLists.txt | 1 - doc/CMakeLists.txt | 21 +++++++++++++-------- 2 files changed, 13 insertions(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 759b3980..84ceef87 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -61,7 +61,6 @@ else() endif() option(RL_BUILD_DEMOS "Build demos" ON) -option(RL_BUILD_DOCUMENTATION "Build documentation" OFF) option(RL_BUILD_EXTRAS "Build extras" ON) option(RL_BUILD_MATH "Build mathematics component" ON) option(RL_BUILD_TESTS "Build tests" ON) diff --git a/doc/CMakeLists.txt b/doc/CMakeLists.txt index 5835a842..8a7609d9 100644 --- a/doc/CMakeLists.txt +++ b/doc/CMakeLists.txt @@ -1,12 +1,17 @@ find_package(Doxygen) -find_package(LATEX) -configure_file(Doxyfile.in Doxyfile) +cmake_dependent_option(RL_BUILD_DOCUMENTATION "Build documentation" OFF "DOXYGEN_FOUND" OFF) -if(RL_BUILD_DOCUMENTATION) - add_custom_target(doc ALL ${DOXYGEN_EXECUTABLE} ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile) -elseif(DOXYGEN_FOUND) - add_custom_target(doc ${DOXYGEN_EXECUTABLE} ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile) +if(DOXYGEN_FOUND) + find_package(LATEX) + + configure_file(Doxyfile.in Doxyfile) + + if(RL_BUILD_DOCUMENTATION) + add_custom_target(doc ALL ${DOXYGEN_EXECUTABLE} ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile) + else() + add_custom_target(doc ${DOXYGEN_EXECUTABLE} ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile) + endif() + + install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/html DESTINATION ${CMAKE_INSTALL_DATADIR}/doc/rl-${VERSION} OPTIONAL COMPONENT documentation) endif() - -install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/html DESTINATION ${CMAKE_INSTALL_DATADIR}/doc/rl-${VERSION} OPTIONAL COMPONENT documentation) From 87cfda2bacd592e6e3ccc580ead4b5e3e340f1cf Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 11 Jun 2020 22:24:24 +0200 Subject: [PATCH 354/546] Check for MSVC instead of WIN32 --- CMakeLists.txt | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 84ceef87..5e6b5999 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -44,17 +44,22 @@ else() endif() endif() -if(WIN32) +if(MSVC) add_definitions( -D_ENABLE_EXTENDED_ALIGNED_STORAGE -D_USE_MATH_DEFINES + ) +endif() + +if(WIN32) + add_definitions( -D_WIN32_WINNT=0x501 -DNOMINMAX -DWIN32_LEAN_AND_MEAN ) endif() -if(WIN32) +if(MSVC) option(BUILD_SHARED_LIBS "Build shared libraries" OFF) else() option(BUILD_SHARED_LIBS "Build shared libraries" ON) From c11f354a4a0cb74951db4a0b4f0cd68328315d92 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 11 Jun 2020 22:26:59 +0200 Subject: [PATCH 355/546] Add MSVC compiler definition for math constants to interface --- src/rl/math/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index 6eca9f39..f7252e2d 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -71,6 +71,10 @@ if(CMAKE_SIZEOF_VOID_P EQUAL 4) target_compile_definitions(math INTERFACE EIGEN_DONT_ALIGN_STATICALLY) endif() +if(MSVC) + target_compile_definitions(math INTERFACE _USE_MATH_DEFINES) +endif() + if(NOT CMAKE_VERSION VERSION_LESS 3.8) target_compile_features(math INTERFACE cxx_std_11) endif() From c4612abcf21d204042edd17894abf9f2d2daccae Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 11 Jun 2020 22:28:21 +0200 Subject: [PATCH 356/546] Remove windows.h from header files --- src/rl/hal/Serial.cpp | 309 ++++++++++++++++++++++++------------------ src/rl/hal/Serial.h | 47 +++---- src/rl/hal/Socket.cpp | 92 ++++++------- src/rl/hal/Socket.h | 43 +++--- 4 files changed, 265 insertions(+), 226 deletions(-) diff --git a/src/rl/hal/Serial.cpp b/src/rl/hal/Serial.cpp index 2008dfe1..a2fdc54f 100644 --- a/src/rl/hal/Serial.cpp +++ b/src/rl/hal/Serial.cpp @@ -24,23 +24,25 @@ // POSSIBILITY OF SUCH DAMAGE. // -#ifndef WIN32 +#ifdef WIN32 +#include +#else // WIN32 #include +#include +#include #include #include #ifdef __QNX__ #include #endif // __QNX__ #include -#ifdef __APPLE__ -#include -#endif // __APPLE__ #include #endif // WIN32 #include #include #include +#include #include "ComException.h" #include "Serial.h" @@ -54,6 +56,55 @@ namespace rl { namespace hal { + struct Serial::Impl + { +#ifdef WIN32 + DCB current; + + HANDLE fd; + + DCB restore; +#else // WIN32 + struct termios current; + + int fd; + + struct termios restore; +#endif // WIN32 + }; + + Serial::Serial( + const ::std::string& filename, + const BaudRate& baudRate, + const DataBits& dataBits, + const FlowControl& flowControl, + const Parity& parity, + const StopBits& stopBits + ) : + Com(), + baudRate(baudRate), + dataBits(dataBits), + filename(filename), +#ifdef WIN32 + flags(GENERIC_READ | GENERIC_WRITE), +#else // WIN32 + flags(O_RDWR | O_NOCTTY), +#endif // WIN32 + flowControl(flowControl), + impl(::rl::std14::make_unique()), + parity(parity), + stopBits(stopBits) + { +#ifndef WIN32 + ::cfmakeraw(&this->impl->current); +#endif // WIN32 + this->setBaudRate(this->baudRate); + this->setDataBits(this->dataBits); + this->setFlowControl(this->flowControl); + this->setParity(this->parity); + this->setStopBits(this->stopBits); + } + Serial::Serial( const ::std::string& filename, const BaudRate& baudRate, @@ -65,18 +116,16 @@ namespace rl ) : Com(), baudRate(baudRate), - current(), dataBits(dataBits), - fd(0), filename(filename), flags(flags), flowControl(flowControl), + impl(::rl::std14::make_unique()), parity(parity), - restore(), stopBits(stopBits) { #ifndef WIN32 - ::cfmakeraw(&this->current); + ::cfmakeraw(&this->impl->current); #endif // WIN32 this->setBaudRate(this->baudRate); this->setDataBits(this->dataBits); @@ -97,12 +146,12 @@ namespace rl Serial::changeParameters() { #ifdef WIN32 - if (0 == ::SetCommState(this->fd, &this->current)) + if (0 == ::SetCommState(this->impl->fd, &this->impl->current)) { throw ComException(::GetLastError()); } #else // WIN32 - if (-1 == ::tcsetattr(this->fd, TCSANOW, &this->current)) + if (-1 == ::tcsetattr(this->impl->fd, TCSANOW, &this->impl->current)) { throw ComException(errno); } @@ -115,26 +164,26 @@ namespace rl assert(this->isConnected()); #ifdef WIN32 - if (0 == ::SetCommState(this->fd, &this->restore)) + if (0 == ::SetCommState(this->impl->fd, &this->impl->restore)) { throw ComException(::GetLastError()); } this->flush(true, true); - if (0 == ::CloseHandle(this->fd)) + if (0 == ::CloseHandle(this->impl->fd)) { throw ComException(::GetLastError()); } #else // WIN32 - if (-1 == ::tcsetattr(this->fd, TCSANOW, &this->restore)) + if (-1 == ::tcsetattr(this->impl->fd, TCSANOW, &this->impl->restore)) { throw ComException(errno); } this->flush(true, true); - if (-1 == ::close(this->fd)) + if (-1 == ::close(this->impl->fd)) { throw ComException(errno); } @@ -147,12 +196,12 @@ namespace rl Serial::doBreak(const bool& doOn) { #ifdef WIN32 - if (0 == ::EscapeCommFunction(this->fd, doOn ? SETBREAK : CLRBREAK)) + if (0 == ::EscapeCommFunction(this->impl->fd, doOn ? SETBREAK : CLRBREAK)) { throw ComException(::GetLastError()); } #else // WIN32 - if (-1 == ::ioctl(this->fd, doOn ? TIOCSBRK : TIOCCBRK)) + if (-1 == ::ioctl(this->impl->fd, doOn ? TIOCSBRK : TIOCCBRK)) { throw ComException(errno); } @@ -163,12 +212,12 @@ namespace rl Serial::doDtr(const bool& doOn) { #ifdef WIN32 - if (0 == ::EscapeCommFunction(this->fd, doOn ? SETDTR : CLRDTR)) + if (0 == ::EscapeCommFunction(this->impl->fd, doOn ? SETDTR : CLRDTR)) { throw ComException(::GetLastError()); } #else // WIN32 - if (-1 == ::ioctl(this->fd, doOn ? TIOCMBIS : TIOCMBIC, TIOCM_DTR)) + if (-1 == ::ioctl(this->impl->fd, doOn ? TIOCMBIS : TIOCMBIC, TIOCM_DTR)) { throw ComException(errno); } @@ -181,7 +230,7 @@ namespace rl #ifdef WIN32 ::DWORD status; - if (0 == ::GetCommModemStatus(this->fd, &status)) + if (0 == ::GetCommModemStatus(this->impl->fd, &status)) { throw ComException(::GetLastError()); } @@ -193,7 +242,7 @@ namespace rl #else // WIN32 int status = 0; - if (-1 == ::ioctl(this->fd, TIOCMGET, status)) + if (-1 == ::ioctl(this->impl->fd, TIOCMGET, status)) { throw ComException(errno); } @@ -209,12 +258,12 @@ namespace rl Serial::doRts(const bool& doOn) { #ifdef WIN32 - if (0 == ::EscapeCommFunction(this->fd, doOn ? SETRTS : CLRRTS)) + if (0 == ::EscapeCommFunction(this->impl->fd, doOn ? SETRTS : CLRRTS)) { throw ComException(::GetLastError()); } #else // WIN32 - if (-1 == ::ioctl(this->fd, doOn ? TIOCMBIS : TIOCMBIC, TIOCM_RTS)) + if (-1 == ::ioctl(this->impl->fd, doOn ? TIOCMBIS : TIOCMBIC, TIOCM_RTS)) { throw ComException(errno); } @@ -229,21 +278,21 @@ namespace rl #ifdef WIN32 if (read && write) { - if (0 == ::PurgeComm(this->fd, PURGE_RXCLEAR | PURGE_TXCLEAR)) + if (0 == ::PurgeComm(this->impl->fd, PURGE_RXCLEAR | PURGE_TXCLEAR)) { throw ComException(::GetLastError()); } } else if (read) { - if (0 == ::PurgeComm(this->fd, PURGE_RXCLEAR)) + if (0 == ::PurgeComm(this->impl->fd, PURGE_RXCLEAR)) { throw ComException(::GetLastError()); } } else if (write) { - if (0 == ::PurgeComm(this->fd, PURGE_TXCLEAR)) + if (0 == ::PurgeComm(this->impl->fd, PURGE_TXCLEAR)) { throw ComException(::GetLastError()); } @@ -251,21 +300,21 @@ namespace rl #else // WIN32 if (read && write) { - if (-1 == ::tcflush(this->fd, TCIOFLUSH)) + if (-1 == ::tcflush(this->impl->fd, TCIOFLUSH)) { throw ComException(errno); } } else if (read) { - if (-1 == ::tcflush(this->fd, TCIFLUSH)) + if (-1 == ::tcflush(this->impl->fd, TCIFLUSH)) { throw ComException(errno); } } else if (write) { - if (-1 == ::tcflush(this->fd, TCOFLUSH)) + if (-1 == ::tcflush(this->impl->fd, TCOFLUSH)) { throw ComException(errno); } @@ -315,47 +364,47 @@ namespace rl assert(!this->isConnected()); #ifdef WIN32 - this->fd = ::CreateFile(this->filename.c_str(), this->flags, 0, nullptr, OPEN_EXISTING, 0, nullptr); + this->impl->fd = ::CreateFile(this->filename.c_str(), this->flags, 0, nullptr, OPEN_EXISTING, 0, nullptr); - if (INVALID_HANDLE_VALUE == this->fd) + if (INVALID_HANDLE_VALUE == this->impl->fd) { - this->fd = 0; + this->impl->fd = 0; throw ComException(::GetLastError()); } this->setConnected(true); - if (0 == GetCommState(this->fd, &this->restore)) + if (0 == GetCommState(this->impl->fd, &this->impl->restore)) { throw ComException(::GetLastError()); } this->flush(true, true); - if (0 == ::SetCommState(this->fd, &this->current)) + if (0 == ::SetCommState(this->impl->fd, &this->impl->current)) { throw ComException(::GetLastError()); } #else // WIN32 - this->fd = ::open(this->filename.c_str(), this->flags); + this->impl->fd = ::open(this->filename.c_str(), this->flags); - if (-1 == this->fd) + if (-1 == this->impl->fd) { throw ComException(errno); } this->setConnected(true); - if (-1 == ::tcgetattr(this->fd, &this->restore)) + if (-1 == ::tcgetattr(this->impl->fd, &this->impl->restore)) { throw ComException(errno); } this->flush(true, true); - this->current.c_cflag |= CREAD | CLOCAL; + this->impl->current.c_cflag |= CREAD | CLOCAL; - if (-1 == ::tcsetattr(this->fd, TCSANOW, &this->current)) + if (-1 == ::tcsetattr(this->impl->fd, TCSANOW, &this->impl->current)) { throw ComException(errno); } @@ -372,12 +421,12 @@ namespace rl #ifdef WIN32 ::DWORD numbytes; - if (0 == ::ReadFile(this->fd, buf, count, &numbytes, nullptr)) + if (0 == ::ReadFile(this->impl->fd, buf, count, &numbytes, nullptr)) { throw ComException(::GetLastError()); } #else // WIN32 - ::ssize_t numbytes = ::read(this->fd, buf, count); + ::ssize_t numbytes = ::read(this->impl->fd, buf, count); if (-1 == numbytes) { @@ -401,13 +450,13 @@ namespace rl ::fd_set readfds; FD_ZERO(&readfds); - FD_SET(this->fd, &readfds); + FD_SET(this->impl->fd, &readfds); ::fd_set writefds; FD_ZERO(&writefds); - FD_SET(this->fd, &writefds); + FD_SET(this->impl->fd, &writefds); - ::ssize_t numdescriptors = ::select(this->fd + 1, read ? &readfds : nullptr, write ? &writefds : nullptr, nullptr, &tv); + ::ssize_t numdescriptors = ::select(this->impl->fd + 1, read ? &readfds : nullptr, write ? &writefds : nullptr, nullptr, &tv); if (0 == numdescriptors) { @@ -429,46 +478,46 @@ namespace rl switch (baudRate) { case BAUDRATE_110BPS: - this->current.BaudRate = CBR_110; + this->impl->current.BaudRate = CBR_110; break; case BAUDRATE_300BPS: - this->current.BaudRate = CBR_300; + this->impl->current.BaudRate = CBR_300; break; case BAUDRATE_600BPS: - this->current.BaudRate = CBR_600; + this->impl->current.BaudRate = CBR_600; break; case BAUDRATE_1200BPS: - this->current.BaudRate = CBR_1200; + this->impl->current.BaudRate = CBR_1200; break; case BAUDRATE_2400BPS: - this->current.BaudRate = CBR_2400; + this->impl->current.BaudRate = CBR_2400; break; case BAUDRATE_4800BPS: - this->current.BaudRate = CBR_4800; + this->impl->current.BaudRate = CBR_4800; break; case BAUDRATE_9600BPS: - this->current.BaudRate = CBR_9600; + this->impl->current.BaudRate = CBR_9600; break; case BAUDRATE_14400BPS: - this->current.BaudRate = CBR_14400; + this->impl->current.BaudRate = CBR_14400; break; case BAUDRATE_19200BPS: - this->current.BaudRate = CBR_19200; + this->impl->current.BaudRate = CBR_19200; break; case BAUDRATE_38400BPS: - this->current.BaudRate = CBR_38400; + this->impl->current.BaudRate = CBR_38400; break; case BAUDRATE_57600BPS: - this->current.BaudRate = CBR_57600; + this->impl->current.BaudRate = CBR_57600; break; case BAUDRATE_115200BPS: - this->current.BaudRate = CBR_115200; + this->impl->current.BaudRate = CBR_115200; break; case BAUDRATE_128000BPS: - this->current.BaudRate = CBR_128000; + this->impl->current.BaudRate = CBR_128000; break; case BAUDRATE_256000BPS: - this->current.BaudRate = CBR_256000; + this->impl->current.BaudRate = CBR_256000; break; default: break; @@ -560,12 +609,12 @@ namespace rl break; } - if (-1 == ::cfsetispeed(&this->current, speed)) + if (-1 == ::cfsetispeed(&this->impl->current, speed)) { throw ComException(errno); } - if (-1 == ::cfsetospeed(&this->current, speed)) + if (-1 == ::cfsetospeed(&this->impl->current, speed)) { throw ComException(errno); } @@ -581,16 +630,16 @@ namespace rl switch (dataBits) { case DATABITS_5BITS: - this->current.ByteSize = 5; + this->impl->current.ByteSize = 5; break; case DATABITS_6BITS: - this->current.ByteSize = 6; + this->impl->current.ByteSize = 6; break; case DATABITS_7BITS: - this->current.ByteSize = 7; + this->impl->current.ByteSize = 7; break; case DATABITS_8BITS: - this->current.ByteSize = 8; + this->impl->current.ByteSize = 8; break; default: break; @@ -599,24 +648,24 @@ namespace rl switch (dataBits) { case DATABITS_5BITS: - this->current.c_cflag &= ~(CS6 | CS7 | CS8); - this->current.c_cflag |= CS5; - this->current.c_iflag |= ISTRIP; + this->impl->current.c_cflag &= ~(CS6 | CS7 | CS8); + this->impl->current.c_cflag |= CS5; + this->impl->current.c_iflag |= ISTRIP; break; case DATABITS_6BITS: - this->current.c_cflag &= ~(CS5 | CS7 | CS8); - this->current.c_cflag |= CS6; - this->current.c_iflag |= ISTRIP; + this->impl->current.c_cflag &= ~(CS5 | CS7 | CS8); + this->impl->current.c_cflag |= CS6; + this->impl->current.c_iflag |= ISTRIP; break; case DATABITS_7BITS: - this->current.c_cflag &= ~(CS5 | CS6 | CS8); - this->current.c_cflag |= CS7; - this->current.c_iflag |= ISTRIP; + this->impl->current.c_cflag &= ~(CS5 | CS6 | CS8); + this->impl->current.c_cflag |= CS7; + this->impl->current.c_iflag |= ISTRIP; break; case DATABITS_8BITS: - this->current.c_cflag &= ~(CS5 | CS6 | CS7); - this->current.c_cflag |= CS8; - this->current.c_iflag &= ~ISTRIP; + this->impl->current.c_cflag &= ~(CS5 | CS6 | CS7); + this->impl->current.c_cflag |= CS8; + this->impl->current.c_iflag &= ~ISTRIP; break; default: break; @@ -639,34 +688,34 @@ namespace rl switch (flowControl) { case FLOWCONTROL_OFF: - this->current.fOutxCtsFlow = false; - this->current.fOutxDsrFlow = false; - this->current.fDtrControl = DTR_CONTROL_DISABLE; - this->current.fOutX = false; - this->current.fInX = false; - this->current.fRtsControl = RTS_CONTROL_DISABLE; - this->current.XoffChar = 0x00; - this->current.XonChar = 0x00; + this->impl->current.fOutxCtsFlow = false; + this->impl->current.fOutxDsrFlow = false; + this->impl->current.fDtrControl = DTR_CONTROL_DISABLE; + this->impl->current.fOutX = false; + this->impl->current.fInX = false; + this->impl->current.fRtsControl = RTS_CONTROL_DISABLE; + this->impl->current.XoffChar = 0x00; + this->impl->current.XonChar = 0x00; break; case FLOWCONTROL_RTSCTS: - this->current.fOutxCtsFlow = true; - this->current.fOutxDsrFlow = true; - this->current.fDtrControl = DTR_CONTROL_HANDSHAKE; - this->current.fOutX = false; - this->current.fInX = false; - this->current.fRtsControl = RTS_CONTROL_HANDSHAKE; - this->current.XoffChar = 0x00; - this->current.XonChar = 0x00; + this->impl->current.fOutxCtsFlow = true; + this->impl->current.fOutxDsrFlow = true; + this->impl->current.fDtrControl = DTR_CONTROL_HANDSHAKE; + this->impl->current.fOutX = false; + this->impl->current.fInX = false; + this->impl->current.fRtsControl = RTS_CONTROL_HANDSHAKE; + this->impl->current.XoffChar = 0x00; + this->impl->current.XonChar = 0x00; break; case FLOWCONTROL_XONXOFF: - this->current.fOutxCtsFlow = false; - this->current.fOutxDsrFlow = false; - this->current.fDtrControl = DTR_CONTROL_DISABLE; - this->current.fOutX = true; - this->current.fInX = true; - this->current.fRtsControl = RTS_CONTROL_DISABLE; - this->current.XoffChar = 0x13; - this->current.XonChar = 0x11; + this->impl->current.fOutxCtsFlow = false; + this->impl->current.fOutxDsrFlow = false; + this->impl->current.fDtrControl = DTR_CONTROL_DISABLE; + this->impl->current.fOutX = true; + this->impl->current.fInX = true; + this->impl->current.fRtsControl = RTS_CONTROL_DISABLE; + this->impl->current.XoffChar = 0x13; + this->impl->current.XonChar = 0x11; break; default: break; @@ -675,22 +724,22 @@ namespace rl switch (flowControl) { case FLOWCONTROL_OFF: - this->current.c_cflag &= ~CRTSCTS; - this->current.c_iflag &= ~(IXANY | IXOFF | IXON); - this->current.c_cc[VSTART] = 0x00; - this->current.c_cc[VSTOP] = 0x00; + this->impl->current.c_cflag &= ~CRTSCTS; + this->impl->current.c_iflag &= ~(IXANY | IXOFF | IXON); + this->impl->current.c_cc[VSTART] = 0x00; + this->impl->current.c_cc[VSTOP] = 0x00; break; case FLOWCONTROL_RTSCTS: - this->current.c_cflag |= CRTSCTS; - this->current.c_iflag &= ~(IXANY | IXOFF | IXON); - this->current.c_cc[VSTART] = 0x00; - this->current.c_cc[VSTOP] = 0x00; + this->impl->current.c_cflag |= CRTSCTS; + this->impl->current.c_iflag &= ~(IXANY | IXOFF | IXON); + this->impl->current.c_cc[VSTART] = 0x00; + this->impl->current.c_cc[VSTOP] = 0x00; break; case FLOWCONTROL_XONXOFF: - this->current.c_cflag &= ~CRTSCTS; - this->current.c_iflag |= IXANY | IXOFF | IXON; - this->current.c_cc[VSTART] = 0x11; - this->current.c_cc[VSTOP] = 0x13; + this->impl->current.c_cflag &= ~CRTSCTS; + this->impl->current.c_iflag |= IXANY | IXOFF | IXON; + this->impl->current.c_cc[VSTART] = 0x11; + this->impl->current.c_cc[VSTOP] = 0x13; break; default: break; @@ -707,13 +756,13 @@ namespace rl switch (parity) { case PARITY_EVENPARITY: - this->current.Parity = EVENPARITY; + this->impl->current.Parity = EVENPARITY; break; case PARITY_NOPARITY: - this->current.Parity = NOPARITY; + this->impl->current.Parity = NOPARITY; break; case PARITY_ODDPARITY: - this->current.Parity = ODDPARITY; + this->impl->current.Parity = ODDPARITY; break; default: break; @@ -722,20 +771,20 @@ namespace rl switch (parity) { case PARITY_EVENPARITY: - this->current.c_cflag &= ~PARODD; - this->current.c_cflag |= PARENB; - this->current.c_iflag &= ~IGNPAR; - this->current.c_iflag |= INPCK; + this->impl->current.c_cflag &= ~PARODD; + this->impl->current.c_cflag |= PARENB; + this->impl->current.c_iflag &= ~IGNPAR; + this->impl->current.c_iflag |= INPCK; break; case PARITY_NOPARITY: - this->current.c_cflag &= ~(PARENB | PARODD); - this->current.c_iflag &= ~INPCK; - this->current.c_iflag |= IGNPAR; + this->impl->current.c_cflag &= ~(PARENB | PARODD); + this->impl->current.c_iflag &= ~INPCK; + this->impl->current.c_iflag |= IGNPAR; break; case PARITY_ODDPARITY: - this->current.c_cflag |= PARENB | PARODD; - this->current.c_iflag &= ~IGNPAR; - this->current.c_iflag |= INPCK; + this->impl->current.c_cflag |= PARENB | PARODD; + this->impl->current.c_iflag &= ~IGNPAR; + this->impl->current.c_iflag |= INPCK; break; default: break; @@ -752,10 +801,10 @@ namespace rl switch (stopBits) { case STOPBITS_1BIT: - this->current.StopBits = ONESTOPBIT; + this->impl->current.StopBits = ONESTOPBIT; break; case STOPBITS_2BITS: - this->current.StopBits = TWOSTOPBITS; + this->impl->current.StopBits = TWOSTOPBITS; break; default: break; @@ -764,10 +813,10 @@ namespace rl switch (stopBits) { case STOPBITS_1BIT: - this->current.c_cflag &= ~CSTOPB; + this->impl->current.c_cflag &= ~CSTOPB; break; case STOPBITS_2BITS: - this->current.c_cflag |= CSTOPB; + this->impl->current.c_cflag |= CSTOPB; break; default: break; @@ -785,12 +834,12 @@ namespace rl #ifdef WIN32 ::DWORD numbytes; - if (0 == ::WriteFile(this->fd, buf, count, &numbytes, nullptr)) + if (0 == ::WriteFile(this->impl->fd, buf, count, &numbytes, nullptr)) { throw ComException(::GetLastError()); } #else // WIN32 - ::ssize_t numbytes = ::write(this->fd, buf, count); + ::ssize_t numbytes = ::write(this->impl->fd, buf, count); if (-1 == numbytes) { diff --git a/src/rl/hal/Serial.h b/src/rl/hal/Serial.h index ba443d7c..7ff258d0 100644 --- a/src/rl/hal/Serial.h +++ b/src/rl/hal/Serial.h @@ -27,14 +27,8 @@ #ifndef RL_HAL_SERIAL_H #define RL_HAL_SERIAL_H -#ifdef WIN32 -#include -#else // WIN32 -#include -#include -#endif // WIN32 - #include +#include #include #include @@ -166,12 +160,17 @@ namespace rl const DataBits& dataBits = DATABITS_8BITS, const FlowControl& flowControl = FLOWCONTROL_OFF, const Parity& parity = PARITY_NOPARITY, - const StopBits& stopBits = STOPBITS_1BIT, -#ifdef WIN32 - const int& flags = GENERIC_READ | GENERIC_WRITE -#else // WIN32 - const int& flags = O_RDWR | O_NOCTTY -#endif // WIN32 + const StopBits& stopBits = STOPBITS_1BIT + ); + + Serial( + const ::std::string& filename, + const BaudRate& baudRate, + const DataBits& dataBits, + const FlowControl& flowControl, + const Parity& parity, + const StopBits& stopBits, + const int& flags ); virtual ~Serial(); @@ -225,35 +224,21 @@ namespace rl protected: private: - BaudRate baudRate; + struct Impl; -#ifdef WIN32 - DCB current; -#else // WIN32 - struct termios current; -#endif // WIN32 + BaudRate baudRate; DataBits dataBits; -#ifdef WIN32 - HANDLE fd; -#else // WIN32 - int fd; -#endif // WIN32 - ::std::string filename; int flags; FlowControl flowControl; - Parity parity; + ::std::unique_ptr impl; -#ifdef WIN32 - DCB restore; -#else // WIN32 - struct termios restore; -#endif // WIN32 + Parity parity; StopBits stopBits; }; diff --git a/src/rl/hal/Socket.cpp b/src/rl/hal/Socket.cpp index 88682417..4d0508e3 100644 --- a/src/rl/hal/Socket.cpp +++ b/src/rl/hal/Socket.cpp @@ -25,6 +25,7 @@ // #ifdef WIN32 +#include #include #include #else // WIN32 @@ -37,12 +38,14 @@ #ifdef __QNX__ #include #endif // __QNX__ +#include #include #endif // WIN32 #include #include #include +#include #include "ComException.h" #include "Socket.h" @@ -52,9 +55,14 @@ namespace rl { namespace hal { + struct Socket::Address::Impl + { + ::sockaddr_storage addr; + }; + Socket::Socket(const Socket& socket) : - fd(socket.fd), address(socket.address), + fd(socket.fd), protocol(socket.protocol), type(socket.type) { @@ -65,12 +73,12 @@ namespace rl Socket::Socket(const int& type, const int& protocol, const Address& address) : Com(), + address(address), #ifdef WIN32 fd(INVALID_SOCKET), #else // WIN32 fd(-1), #endif // WIN32 - address(address), protocol(protocol), type(type) { @@ -85,8 +93,8 @@ namespace rl Socket::Socket(const int& type, const int& protocol, const Address& address, const int& fd) : #endif // WIN32 Com(), - fd(fd), address(address), + fd(fd), protocol(protocol), type(type) { @@ -124,13 +132,13 @@ namespace rl Socket Socket::accept() { - ::sockaddr_storage addr; - ::socklen_t addrlen = sizeof(addr); + Address address; + ::socklen_t addrlen = address.getLength(); #ifdef WIN32 - SOCKET fd = ::accept(this->fd, reinterpret_cast<::sockaddr*>(&addr), &addrlen); + SOCKET fd = ::accept(this->fd, reinterpret_cast<::sockaddr*>(&address.get()->addr), &addrlen); #else // WIN32 - int fd = ::accept(this->fd, reinterpret_cast<::sockaddr*>(&addr), &addrlen); + int fd = ::accept(this->fd, reinterpret_cast<::sockaddr*>(&address.get()->addr), &addrlen); #endif // WIN32 #ifdef WIN32 @@ -145,13 +153,13 @@ namespace rl } #endif // WIN32 - return Socket(this->type, this->protocol, Address(addr), fd); + return Socket(this->type, this->protocol, address, fd); } void Socket::bind() { - int err = ::bind(this->fd, reinterpret_cast(&this->address.get()), this->address.getLength()); + int err = ::bind(this->fd, reinterpret_cast(&this->address.get()->addr), this->address.getLength()); #ifdef WIN32 if (SOCKET_ERROR == err) @@ -202,7 +210,7 @@ namespace rl void Socket::connect() { - int err = ::connect(this->fd, reinterpret_cast(&this->address.get()), this->address.getLength()); + int err = ::connect(this->fd, reinterpret_cast(&this->address.get()->addr), this->address.getLength()); #ifdef WIN32 if (SOCKET_ERROR == err) @@ -242,7 +250,7 @@ namespace rl optname = SO_KEEPALIVE; break; case OPTION_MULTICAST_LOOP: - if (AF_INET6 == this->address.get().ss_family) + if (AF_INET6 == this->address.get()->addr.ss_family) { level = IPPROTO_IPV6; optname = IPV6_MULTICAST_LOOP; @@ -254,7 +262,7 @@ namespace rl } break; case OPTION_MULTICAST_TTL: - if (AF_INET6 == this->address.get().ss_family) + if (AF_INET6 == this->address.get()->addr.ss_family) { level = IPPROTO_IPV6; optname = IPV6_MULTICAST_HOPS; @@ -276,6 +284,7 @@ namespace rl break; #endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ default: + throw ComException("Unsupported option"); break; } @@ -339,7 +348,7 @@ namespace rl void Socket::open() { - this->fd = ::socket(this->address.get().ss_family, this->type, this->protocol); + this->fd = ::socket(this->address.get()->addr.ss_family, this->type, this->protocol); #ifdef WIN32 if (INVALID_SOCKET == this->fd) @@ -395,19 +404,16 @@ namespace rl ::std::size_t Socket::recvfrom(void* buf, const ::std::size_t& count, Address& address) { - ::sockaddr_storage addr; - int addrlen = sizeof(addr); + int addrlen = address.getLength(); ::std::memset(buf, 0, count); #ifdef WIN32 - int numbytes = ::recvfrom(this->fd, static_cast(buf), count, 0, reinterpret_cast<::sockaddr*>(&addr), &addrlen); + int numbytes = ::recvfrom(this->fd, static_cast(buf), count, 0, reinterpret_cast<::sockaddr*>(&address.get()->addr), &addrlen); #else // WIN32 - ::ssize_t numbytes = ::recvfrom(this->fd, buf, count, 0, reinterpret_cast<::sockaddr*>(&addr), reinterpret_cast<::socklen_t*>(&addrlen)); + ::ssize_t numbytes = ::recvfrom(this->fd, buf, count, 0, reinterpret_cast<::sockaddr*>(&address.get()->addr), reinterpret_cast<::socklen_t*>(&addrlen)); #endif // WIN32 - address = Address(addr); - #ifdef WIN32 if (SOCKET_ERROR == numbytes) { @@ -491,9 +497,9 @@ namespace rl Socket::sendto(const void* buf, const ::std::size_t& count, const Address& address) { #ifdef WIN32 - int numbytes = ::sendto(this->fd, static_cast(buf), count, 0, reinterpret_cast(&address.get()), sizeof(address.get())); + int numbytes = ::sendto(this->fd, static_cast(buf), count, 0, reinterpret_cast(&address.get()->addr), address.getLength()); #else // WIN32 - ::ssize_t numbytes = ::sendto(this->fd, buf, count, 0, reinterpret_cast(&address.get()), sizeof(address.get())); + ::ssize_t numbytes = ::sendto(this->fd, buf, count, 0, reinterpret_cast(&address.get()->addr), address.getLength()); #endif // WIN32 #ifdef WIN32 @@ -530,7 +536,7 @@ namespace rl optname = SO_KEEPALIVE; break; case OPTION_MULTICAST_LOOP: - if (AF_INET6 == this->address.get().ss_family) + if (AF_INET6 == this->address.get()->addr.ss_family) { level = IPPROTO_IPV6; optname = IPV6_MULTICAST_LOOP; @@ -542,7 +548,7 @@ namespace rl } break; case OPTION_MULTICAST_TTL: - if (AF_INET6 == this->address.get().ss_family) + if (AF_INET6 == this->address.get()->addr.ss_family) { level = IPPROTO_IPV6; optname = IPV6_MULTICAST_HOPS; @@ -564,6 +570,7 @@ namespace rl break; #endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ default: + throw ComException("Unsupported option"); break; } @@ -659,7 +666,7 @@ namespace rl #endif // WIN32 Socket::Address::Address() : - addr() + impl(::rl::std14::make_unique()) { #ifdef WIN32 Socket::startup(); @@ -667,29 +674,22 @@ namespace rl } Socket::Address::Address(const Address& address) : - addr(address.addr) - { -#ifdef WIN32 - Socket::startup(); -#endif // WIN32 - } - - Socket::Address::Address(const ::sockaddr_storage& addr) : - addr(addr) + impl(::rl::std14::make_unique()) { + this->impl->addr = address.impl->addr; #ifdef WIN32 Socket::startup(); #endif // WIN32 } Socket::Address::Address(const int& family) : - addr() + impl(::rl::std14::make_unique()) { #ifdef WIN32 Socket::startup(); #endif // WIN32 - this->addr.ss_family = family; + this->impl->addr.ss_family = family; } Socket::Address::~Address() @@ -731,10 +731,10 @@ namespace rl return address; } - const ::sockaddr_storage& + Socket::Address::Impl* Socket::Address::get() const { - return this->addr; + return this->impl.get(); } ::std::vector @@ -742,15 +742,15 @@ namespace rl { ::std::vector hexadecimal; - switch (this->addr.ss_family) + switch (this->impl->addr.ss_family) { case AF_INET: hexadecimal.resize(4); - ::std::memcpy(hexadecimal.data(), &reinterpret_cast<::sockaddr_in*>(&this->addr)->sin_addr.s_addr, hexadecimal.size()); + ::std::memcpy(hexadecimal.data(), &reinterpret_cast<::sockaddr_in*>(&this->impl->addr)->sin_addr.s_addr, hexadecimal.size()); break; case AF_INET6: hexadecimal.resize(16); - ::std::memcpy(hexadecimal.data(), &reinterpret_cast<::sockaddr_in6*>(&this->addr)->sin6_addr.s6_addr, hexadecimal.size()); + ::std::memcpy(hexadecimal.data(), &reinterpret_cast<::sockaddr_in6*>(&this->impl->addr)->sin6_addr.s6_addr, hexadecimal.size()); break; default: break; @@ -762,7 +762,7 @@ namespace rl ::std::size_t Socket::Address::getLength() const { - switch (this->addr.ss_family) + switch (this->impl->addr.ss_family) { case AF_INET: return sizeof(::sockaddr_in); @@ -771,7 +771,7 @@ namespace rl return sizeof(::sockaddr_in6); break; default: - return 0; + return sizeof(this->impl->addr); break; } } @@ -781,7 +781,7 @@ namespace rl { char host[INET6_ADDRSTRLEN]; - int err = ::getnameinfo(reinterpret_cast(&this->addr), sizeof(this->addr), host, INET6_ADDRSTRLEN, nullptr, 0, asNumeric ? NI_NUMERICHOST : 0); + int err = ::getnameinfo(reinterpret_cast(&this->impl->addr), this->getLength(), host, INET6_ADDRSTRLEN, nullptr, 0, asNumeric ? NI_NUMERICHOST : 0); if (0 != err) { @@ -794,7 +794,7 @@ namespace rl Socket::Address& Socket::Address::operator=(const Socket::Address& other) { - this->addr = other.addr; + this->impl->addr = other.impl->addr; return *this; } @@ -809,7 +809,7 @@ namespace rl { ::addrinfo hints; ::std::memset(&hints, 0, sizeof(hints)); - hints.ai_family = this->addr.ss_family; + hints.ai_family = this->impl->addr.ss_family; hints.ai_flags = asNumeric ? AI_NUMERICHOST | AI_PASSIVE : AI_PASSIVE; hints.ai_socktype = 0; @@ -822,7 +822,7 @@ namespace rl throw ComException(::gai_strerror(err)); } - ::std::memcpy(&this->addr, res->ai_addr, res->ai_addrlen); + ::std::memcpy(&this->impl->addr, res->ai_addr, res->ai_addrlen); ::freeaddrinfo(res); } diff --git a/src/rl/hal/Socket.h b/src/rl/hal/Socket.h index 5bf3853a..d069c1f0 100644 --- a/src/rl/hal/Socket.h +++ b/src/rl/hal/Socket.h @@ -27,13 +27,8 @@ #ifndef RL_HAL_SOCKET_H #define RL_HAL_SOCKET_H -#ifdef WIN32 -#include -#else -#include -#endif // WIN32 - #include +#include #include #include #include @@ -50,12 +45,12 @@ namespace rl class RL_HAL_EXPORT Address { public: + struct Impl; + Address(); Address(const Address& address); - Address(const ::sockaddr_storage& addr); - virtual ~Address(); static Address Ipv4(const ::std::string& string, const unsigned short int& port, const bool& asNumeric = false); @@ -66,7 +61,7 @@ namespace rl static Address Ipv6(const ::std::string& string, const ::std::string& port, const bool& asNumeric = false); - const ::sockaddr_storage& get() const; + Impl* get() const; ::std::vector getHexadecimal(); @@ -81,10 +76,11 @@ namespace rl void setInfo(const ::std::string& string, const ::std::string& port, const bool& asNumeric = false); protected: - Address(const int& family); private: - ::sockaddr_storage addr; + Address(const int& family); + + ::std::unique_ptr impl; }; enum Option @@ -149,21 +145,20 @@ namespace rl void shutdown(const bool& read = true, const bool& write = true); protected: + + private: Socket(const int& type, const int& protocol, const Address& address); #ifdef WIN32 - Socket(const int& type, const int& protocol, const Address& address, const SOCKET& fd); +#ifdef _WIN64 + Socket(const int& type, const int& protocol, const Address& address, const unsigned __int64& fd); +#else // _WIN64 + Socket(const int& type, const int& protocol, const Address& address, const unsigned int& fd); +#endif // _WIN64 #else // WIN32 Socket(const int& type, const int& protocol, const Address& address, const int& fd); #endif // WIN32 -#ifdef WIN32 - SOCKET fd; -#else // WIN32 - int fd; -#endif // WIN32 - - private: #ifdef WIN32 static void cleanup(); @@ -172,6 +167,16 @@ namespace rl Address address; +#ifdef WIN32 +#ifdef _WIN64 + unsigned __int64 fd; +#else // _WIN64 + unsigned int fd; +#endif // _WIN64 +#else // WIN32 + int fd; +#endif // WIN32 + int protocol; int type; From 11c868eaeb737b430051149d8bc20f208742ac77 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 12 Jun 2020 00:40:00 +0200 Subject: [PATCH 357/546] Update deprecated Qt classes and functions --- demos/rlCoachKin/MainWindow.h | 2 +- demos/rlCoachKin/Socket.cpp | 8 ++++++ demos/rlCoachMdl/MainWindow.h | 2 +- demos/rlCoachMdl/Socket.cpp | 8 ++++++ demos/rlCollisionDemo/MainWindow.h | 2 +- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 28 +++++++++++--------- demos/rlPlanDemo/ConfigurationSpaceScene.h | 7 +++-- demos/rlPlanDemo/MainWindow.h | 2 +- demos/rlPlanDemo/Viewer.h | 2 +- demos/rlRotationConverterDemo/TableView.cpp | 4 +++ demos/rlSimulator/MainWindow.h | 2 +- demos/rlSimulator/Socket.cpp | 4 +++ extras/wrlview/MainWindow.h | 2 +- 13 files changed, 49 insertions(+), 24 deletions(-) diff --git a/demos/rlCoachKin/MainWindow.h b/demos/rlCoachKin/MainWindow.h index 22edccf7..0dcecc6f 100644 --- a/demos/rlCoachKin/MainWindow.h +++ b/demos/rlCoachKin/MainWindow.h @@ -73,7 +73,7 @@ public slots: void saveScene(); protected: - MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); + MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); private: void init(); diff --git a/demos/rlCoachKin/Socket.cpp b/demos/rlCoachKin/Socket.cpp index ec5fa2e4..da2de2c3 100644 --- a/demos/rlCoachKin/Socket.cpp +++ b/demos/rlCoachKin/Socket.cpp @@ -166,7 +166,11 @@ Socket::readClient() if (list.size() < 2) { +#if QT_VERSION >= 0x050E00 + textStream << Qt::endl; +#else // QT_VERSION textStream << endl; +#endif // QT_VERSION continue; } @@ -184,7 +188,11 @@ Socket::readClient() } } +#if QT_VERSION >= 0x050E00 + textStream << Qt::endl; +#else // QT_VERSION textStream << endl; +#endif // QT_VERSION } break; default: diff --git a/demos/rlCoachMdl/MainWindow.h b/demos/rlCoachMdl/MainWindow.h index d0982046..fae808d9 100644 --- a/demos/rlCoachMdl/MainWindow.h +++ b/demos/rlCoachMdl/MainWindow.h @@ -85,7 +85,7 @@ public slots: void saveScene(); protected: - MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); + MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); private: void init(); diff --git a/demos/rlCoachMdl/Socket.cpp b/demos/rlCoachMdl/Socket.cpp index 29fcdb7b..eda8897d 100644 --- a/demos/rlCoachMdl/Socket.cpp +++ b/demos/rlCoachMdl/Socket.cpp @@ -170,7 +170,11 @@ Socket::readClient() if (list.size() < 2) { +#if QT_VERSION >= 0x050E00 + textStream << Qt::endl; +#else // QT_VERSION textStream << endl; +#endif // QT_VERSION continue; } @@ -187,7 +191,11 @@ Socket::readClient() } } +#if QT_VERSION >= 0x050E00 + textStream << Qt::endl; +#else // QT_VERSION textStream << endl; +#endif // QT_VERSION } break; default: diff --git a/demos/rlCollisionDemo/MainWindow.h b/demos/rlCollisionDemo/MainWindow.h index f6ef5ac9..ea766cfc 100644 --- a/demos/rlCollisionDemo/MainWindow.h +++ b/demos/rlCollisionDemo/MainWindow.h @@ -55,7 +55,7 @@ class MainWindow : public QMainWindow std::shared_ptr viewScene; protected: - MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); + MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); private: std::size_t body; diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index f810529b..3647ae31 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -41,8 +41,8 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : delta0(1), delta1(1), model(nullptr), - edges(), - path(), + edges(nullptr), + path(nullptr), scene(nullptr), thread(new ConfigurationSpaceThread(this)) { @@ -86,9 +86,6 @@ ConfigurationSpaceScene::clear() { delete items.takeFirst(); } - - this->edges.clear(); - this->path.clear(); } void @@ -107,10 +104,9 @@ ConfigurationSpaceScene::drawConfigurationEdge(const rl::math::Vector& u, const free ? QPen(QBrush(QColor(0, 128, 0)), 0) : QPen(QBrush(QColor(128, 0, 0)), 0) ); - line->setParentItem(this->scene); line->setZValue(2); - this->edges.push_back(line); + this->edges->addToGroup(line); } void @@ -136,10 +132,9 @@ ConfigurationSpaceScene::drawConfigurationPath(const rl::plan::VectorList& path) QPen(QBrush(QColor(0, 255, 0)), 0) ); - line->setParentItem(this->scene); line->setZValue(3); - this->path.push_back(line); + this->path->addToGroup(line); ++i; ++j; @@ -239,6 +234,9 @@ ConfigurationSpaceScene::init() this->scene->setZValue(0); this->setSceneRect(this->scene->boundingRect()); + + this->edges = new QGraphicsItemGroup(this->scene); + this->path = new QGraphicsItemGroup(this->scene); } void @@ -297,9 +295,11 @@ ConfigurationSpaceScene::reset() void ConfigurationSpaceScene::resetEdges() { - while (!this->edges.isEmpty()) + QList items = this->edges->childItems(); + + while (!items.isEmpty()) { - delete this->edges.takeFirst(); + delete items.takeFirst(); } } @@ -311,9 +311,11 @@ ConfigurationSpaceScene::resetLines() void ConfigurationSpaceScene::resetPath() { - while (!this->path.isEmpty()) + QList items = this->path->childItems(); + + while (!items.isEmpty()) { - delete this->path.takeFirst(); + delete items.takeFirst(); } } diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.h b/demos/rlPlanDemo/ConfigurationSpaceScene.h index 4a0a50a0..7ac16d65 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.h +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.h @@ -27,9 +27,8 @@ #ifndef CONFIGURATIONSPACESCENE_H #define CONFIGURATIONSPACESCENE_H -#include +#include #include -#include #include #include @@ -109,9 +108,9 @@ public slots: void mousePressEvent(QGraphicsSceneMouseEvent* mouseEvent); private: - QLinkedList edges; + QGraphicsItemGroup* edges; - QLinkedList path; + QGraphicsItemGroup* path; QGraphicsRectItem* scene; diff --git a/demos/rlPlanDemo/MainWindow.h b/demos/rlPlanDemo/MainWindow.h index 6c955523..066818ea 100644 --- a/demos/rlPlanDemo/MainWindow.h +++ b/demos/rlPlanDemo/MainWindow.h @@ -178,7 +178,7 @@ public slots: void toggleViewActive(const bool& doOn); protected: - MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); + MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); private: void clear(); diff --git a/demos/rlPlanDemo/Viewer.h b/demos/rlPlanDemo/Viewer.h index 82f381d5..439797d0 100644 --- a/demos/rlPlanDemo/Viewer.h +++ b/demos/rlPlanDemo/Viewer.h @@ -51,7 +51,7 @@ class Viewer : public QWidget, public rl::plan::Viewer Q_OBJECT public: - Viewer(QWidget* parent = nullptr, Qt::WindowFlags f = 0); + Viewer(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); virtual ~Viewer(); diff --git a/demos/rlRotationConverterDemo/TableView.cpp b/demos/rlRotationConverterDemo/TableView.cpp index bb1ea082..817055f1 100644 --- a/demos/rlRotationConverterDemo/TableView.cpp +++ b/demos/rlRotationConverterDemo/TableView.cpp @@ -75,7 +75,11 @@ TableView::keyPressEvent(QKeyEvent* event) { QString text = QApplication::clipboard()->text(); +#if QT_VERSION >= 0x050E00 + QStringList rowContents = text.split("\n", Qt::SkipEmptyParts); +#else // QT_VERSION QStringList rowContents = text.split("\n", QString::SkipEmptyParts); +#endif // QT_VERSION if (!this->selectionModel()->hasSelection()) { diff --git a/demos/rlSimulator/MainWindow.h b/demos/rlSimulator/MainWindow.h index 4500bc30..f51ee38b 100644 --- a/demos/rlSimulator/MainWindow.h +++ b/demos/rlSimulator/MainWindow.h @@ -101,7 +101,7 @@ public slots: void saveScene(); protected: - MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); + MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); void timerEvent(QTimerEvent *event); diff --git a/demos/rlSimulator/Socket.cpp b/demos/rlSimulator/Socket.cpp index dc7693e0..5401e75c 100644 --- a/demos/rlSimulator/Socket.cpp +++ b/demos/rlSimulator/Socket.cpp @@ -195,6 +195,10 @@ Socket::readClient() break; } +#if QT_VERSION >= 0x050E00 + textStream << Qt::endl; +#else // QT_VERSION textStream << endl; +#endif // QT_VERSION } } diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index df063f78..0c7e523b 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -47,7 +47,7 @@ class MainWindow : public QMainWindow Q_OBJECT public: - MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = 0); + MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); virtual ~MainWindow(); From e36fe25cfbf4c1c48b4d45e4390f05be3e45a9c5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 12 Jun 2020 16:31:03 +0200 Subject: [PATCH 358/546] Add workaround for load function and mark as deprecated --- src/rl/sg/Scene.cpp | 8 ++++++++ src/rl/sg/Scene.h | 2 ++ 2 files changed, 10 insertions(+) diff --git a/src/rl/sg/Scene.cpp b/src/rl/sg/Scene.cpp index bc981561..5f4e0efc 100644 --- a/src/rl/sg/Scene.cpp +++ b/src/rl/sg/Scene.cpp @@ -27,6 +27,7 @@ #include #include "Scene.h" +#include "XmlFactory.h" namespace rl { @@ -85,6 +86,13 @@ namespace rl return true; } + void + Scene::load(const ::std::string& filename, const bool& doBoundingBoxPoints, const bool& doPoints) + { + XmlFactory factory; + factory.load(filename, this, doBoundingBoxPoints, doPoints); + } + void Scene::remove(Model* model) { diff --git a/src/rl/sg/Scene.h b/src/rl/sg/Scene.h index c8247a9b..3c647d12 100644 --- a/src/rl/sg/Scene.h +++ b/src/rl/sg/Scene.h @@ -66,6 +66,8 @@ namespace rl virtual bool isScalingSupported() const; + RL_SG_DEPRECATED void load(const ::std::string& filename, const bool& doBoundingBoxPoints = false, const bool& doPoints = false); + virtual void remove(Model* model); virtual void setName(const ::std::string& name); From d0b2712a8ef4e688072d1eecac1f91ba9171b151 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 12 Jun 2020 21:07:26 +0200 Subject: [PATCH 359/546] Add header with version information --- src/CMakeLists.txt | 3 +++ src/rl/math/CMakeLists.txt | 1 + src/rl/std/CMakeLists.txt | 8 ++++++++ src/rl/util/CMakeLists.txt | 1 + src/rl/version.h.in | 37 +++++++++++++++++++++++++++++++++++++ src/rl/xml/CMakeLists.txt | 1 + 6 files changed, 51 insertions(+) create mode 100644 src/rl/version.h.in diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index e7d58e75..6f5b20fa 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -1,3 +1,6 @@ +configure_file(rl/version.h.in rl/version.h) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/rl/version.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl COMPONENT development) + add_subdirectory(rl/std) list(APPEND TARGETS std) diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index f7252e2d..b83d60d8 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -82,6 +82,7 @@ endif() target_include_directories( math INTERFACE + $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> ${Boost_INCLUDE_DIRS} diff --git a/src/rl/std/CMakeLists.txt b/src/rl/std/CMakeLists.txt index 41f44eff..1a1eba0e 100644 --- a/src/rl/std/CMakeLists.txt +++ b/src/rl/std/CMakeLists.txt @@ -16,6 +16,14 @@ if(NOT CMAKE_VERSION VERSION_LESS 3.8) target_compile_features(std INTERFACE cxx_std_11) endif() +target_include_directories( + std + INTERFACE + $ + $ + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> +) + install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/std COMPONENT development) if(CMAKE_VERSION VERSION_LESS 3.0) diff --git a/src/rl/util/CMakeLists.txt b/src/rl/util/CMakeLists.txt index a5c1b325..0e0edd32 100644 --- a/src/rl/util/CMakeLists.txt +++ b/src/rl/util/CMakeLists.txt @@ -59,6 +59,7 @@ endif() target_include_directories( util INTERFACE + $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> ) diff --git a/src/rl/version.h.in b/src/rl/version.h.in new file mode 100644 index 00000000..990adf3c --- /dev/null +++ b/src/rl/version.h.in @@ -0,0 +1,37 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_VERSION_H +#define RL_VERSION_H + +#define RL_VERSION RL_VERSION_MACRO(RL_VERSION_MAJOR, RL_VERSION_MINOR, RL_VERSION_PATCH) +#define RL_VERSION_MACRO(major, minor, patch) ((major << 16) | (minor << 8) | patch) +#define RL_VERSION_MAJOR @VERSION_MAJOR@ +#define RL_VERSION_MINOR @VERSION_MINOR@ +#define RL_VERSION_PATCH @VERSION_PATCH@ +#define RL_VERSION_STRING "@VERSION@" + +#endif // RL_VERSION_H diff --git a/src/rl/xml/CMakeLists.txt b/src/rl/xml/CMakeLists.txt index ecffe8ee..648cb3f3 100644 --- a/src/rl/xml/CMakeLists.txt +++ b/src/rl/xml/CMakeLists.txt @@ -35,6 +35,7 @@ endif() target_include_directories( xml INTERFACE + $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> ${Boost_INCLUDE_DIRS} From 30f08e1ebb9e740a8cb22f58908f6ec02a4b4a1e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 12 Jun 2020 23:13:38 +0200 Subject: [PATCH 360/546] Replace rl::kin with rl::mdl in demos and tests --- demos/rlJacobianDemo/CMakeLists.txt | 2 +- demos/rlJacobianDemo/rlJacobianDemo.cpp | 44 +++++++----- demos/rlPlanDemo/CMakeLists.txt | 4 +- demos/rlPlanDemo/rlPlanDemo.desktop.in | 2 +- demos/rlPrmDemo/CMakeLists.txt | 2 +- demos/rlPrmDemo/rlPrmDemo.cpp | 45 ++++++++++--- demos/rlRrtDemo/CMakeLists.txt | 2 +- demos/rlRrtDemo/rlRrtDemo.cpp | 45 ++++++++++--- examples/rlmdl/box-6d-300505.sixDof.xml | 54 +++++++++++++++ .../box-6d-300505_maze_prm.mdl.sixDof.xml | 43 ++++++++++++ ...ox-6d-300505_maze_rrtConCon.mdl.sixDof.xml | 42 ++++++++++++ .../unimation-puma560_boxes_prm.mdl.xml | 67 +++++++++++++++++++ .../unimation-puma560_boxes_rrtConCon.mdl.xml | 65 ++++++++++++++++++ examples/rlsg/box-6d-300505_maze.mdl.xml | 12 ++++ tests/rlEetTest/CMakeLists.txt | 32 ++++----- tests/rlEetTest/rlEetTest.cpp | 25 +++---- tests/rlPrmTest/CMakeLists.txt | 20 +++--- tests/rlPrmTest/rlPrmTest.cpp | 24 ++++--- 18 files changed, 439 insertions(+), 91 deletions(-) create mode 100644 examples/rlmdl/box-6d-300505.sixDof.xml create mode 100644 examples/rlplan/box-6d-300505_maze_prm.mdl.sixDof.xml create mode 100644 examples/rlplan/box-6d-300505_maze_rrtConCon.mdl.sixDof.xml create mode 100644 examples/rlplan/unimation-puma560_boxes_prm.mdl.xml create mode 100644 examples/rlplan/unimation-puma560_boxes_rrtConCon.mdl.xml create mode 100644 examples/rlsg/box-6d-300505_maze.mdl.xml diff --git a/demos/rlJacobianDemo/CMakeLists.txt b/demos/rlJacobianDemo/CMakeLists.txt index 8ca61cbd..815553b3 100644 --- a/demos/rlJacobianDemo/CMakeLists.txt +++ b/demos/rlJacobianDemo/CMakeLists.txt @@ -14,5 +14,5 @@ target_include_directories( target_link_libraries( rlJacobianDemo - kin + mdl ) diff --git a/demos/rlJacobianDemo/rlJacobianDemo.cpp b/demos/rlJacobianDemo/rlJacobianDemo.cpp index 644168ed..a01844fc 100644 --- a/demos/rlJacobianDemo/rlJacobianDemo.cpp +++ b/demos/rlJacobianDemo/rlJacobianDemo.cpp @@ -28,8 +28,10 @@ #include #include #include -#include #include +#include +#include +#include int main(int argc, char** argv) @@ -42,46 +44,56 @@ main(int argc, char** argv) try { - std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[1])); + std::string filename(argv[1]); + std::shared_ptr kinematic; - rl::math::Vector q(kinematics->getDof()); + if ("urdf" == filename.substr(filename.length() - 4, 4)) + { + rl::mdl::UrdfFactory factory; + kinematic = std::dynamic_pointer_cast(factory.create(filename)); + } + else + { + rl::mdl::XmlFactory factory; + kinematic = std::dynamic_pointer_cast(factory.create(filename)); + } + + rl::math::Vector q(kinematic->getDofPosition()); for (std::ptrdiff_t i = 0; i < q.size(); ++i) { q(i) = boost::lexical_cast(argv[i + 2]); } - rl::math::Vector qdot(kinematics->getDof()); + rl::math::Vector qdot(kinematic->getDof()); for (std::ptrdiff_t i = 0; i < qdot.size(); ++i) { qdot(i) = boost::lexical_cast(argv[q.size() + i + 2]); } - kinematics->setPosition(q); - kinematics->updateFrames(); - kinematics->updateJacobian(); - - std::cout << "J=" << std::endl << kinematics->getJacobian() << std::endl; + kinematic->setPosition(q); + kinematic->forwardPosition(); + kinematic->calculateJacobian(); - rl::math::Vector xdot(kinematics->getOperationalDof() * 6); + std::cout << "J=" << std::endl << kinematic->getJacobian() << std::endl; - kinematics->forwardVelocity(qdot, xdot); + rl::math::Vector xdot = kinematic->getJacobian() * qdot; std::cout << "xdot=" << std::endl; - for (std::size_t i = 0; i < kinematics->getOperationalDof(); ++i) + for (std::size_t i = 0; i < kinematic->getOperationalDof(); ++i) { std::cout << i << " " << xdot.transpose() << std::endl; } - kinematics->updateJacobianInverse(static_cast(1.0e-9)); + kinematic->calculateJacobianInverse(); - std::cout << "invJ=" << std::endl << kinematics->getJacobianInverse() << std::endl; + std::cout << "invJ=" << std::endl << kinematic->getJacobianInverse() << std::endl; - kinematics->inverseVelocity(xdot, qdot); + rl::math::Vector qdot2 = kinematic->getJacobianInverse() * xdot; - std::cout << "qdot=" << std::endl << qdot.transpose() << std::endl; + std::cout << "qdot=" << std::endl << qdot2.transpose() << std::endl; } catch (const std::exception& e) { diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index 293a791e..522a0b8f 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -128,7 +128,7 @@ if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlPlanDemo.lnk\\\" \\\\ \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlPlanDemo.exe\\\" \\\\ \\\"\\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlplan\\\\unimation-puma560_boxes_rrtConCon.xml\\\$\\\\\\\"\\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlplan\\\\unimation-puma560_boxes_rrtConCon.mdl.xml\\\$\\\\\\\"\\\\ \\\" \\\\ \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ \\\"Path planning demo with Unimation Puma 560 and RRT algorithm\\\"" @@ -140,7 +140,7 @@ if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE WIX_SHORTCUTS ${WIX_SHORTCUTS} " #include #include -#include #include +#include +#include +#include #include #include #include #include #include +#include #include #if defined(RL_SG_SOLID) @@ -59,7 +62,7 @@ main(int argc, char** argv) try { - rl::sg::XmlFactory factory; + std::string scenefile(argv[1]); #if defined(RL_SG_SOLID) rl::sg::solid::Scene scene; #elif defined(RL_SG_BULLET) @@ -67,12 +70,34 @@ main(int argc, char** argv) #elif defined(RL_SG_ODE) rl::sg::ode::Scene scene; #endif - factory.load(argv[1], &scene); - std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[2])); + if ("urdf" == scenefile.substr(scenefile.length() - 4, 4)) + { + rl::sg::UrdfFactory factory; + factory.load(scenefile, &scene); + } + else + { + rl::sg::XmlFactory factory; + factory.load(scenefile, &scene); + } + + std::string kinematicsfile(argv[2]); + std::shared_ptr kinematic; + + if ("urdf" == kinematicsfile.substr(kinematicsfile.length() - 4, 4)) + { + rl::mdl::UrdfFactory factory; + kinematic = std::dynamic_pointer_cast(factory.create(kinematicsfile)); + } + else + { + rl::mdl::XmlFactory factory; + kinematic = std::dynamic_pointer_cast(factory.create(kinematicsfile)); + } rl::plan::SimpleModel model; - model.kin = kinematics.get(); + model.mdl = kinematic.get(); model.model = scene.getModel(0); model.scene = &scene; @@ -91,20 +116,20 @@ main(int argc, char** argv) verifier.delta = 1 * rl::math::DEG2RAD; verifier.model = &model; - rl::math::Vector start(kinematics->getDof()); + rl::math::Vector start(kinematic->getDofPosition()); - for (std::size_t i = 0; i < kinematics->getDof(); ++i) + for (std::ptrdiff_t i = 0; i < start.size(); ++i) { start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::DEG2RAD; } planner.start = &start; - rl::math::Vector goal(kinematics->getDof()); + rl::math::Vector goal(kinematic->getDofPosition()); - for (std::size_t i = 0; i < kinematics->getDof(); ++i) + for (std::ptrdiff_t i = 0; i < goal.size(); ++i) { - goal(i) = boost::lexical_cast(argv[kinematics->getDof() + i + 3]) * rl::math::DEG2RAD; + goal(i) = boost::lexical_cast(argv[start.size() + i + 3]) * rl::math::DEG2RAD; } planner.goal = &goal; diff --git a/demos/rlRrtDemo/CMakeLists.txt b/demos/rlRrtDemo/CMakeLists.txt index 3bc0945e..f061682a 100644 --- a/demos/rlRrtDemo/CMakeLists.txt +++ b/demos/rlRrtDemo/CMakeLists.txt @@ -19,8 +19,8 @@ if(Bullet_FOUND OR ODE_FOUND OR SOLID3_FOUND) target_link_libraries( rlRrtDemo + mdl plan - kin sg ) endif() diff --git a/demos/rlRrtDemo/rlRrtDemo.cpp b/demos/rlRrtDemo/rlRrtDemo.cpp index 72af4787..1614e23f 100644 --- a/demos/rlRrtDemo/rlRrtDemo.cpp +++ b/demos/rlRrtDemo/rlRrtDemo.cpp @@ -28,12 +28,15 @@ #include #include #include -#include #include +#include +#include +#include #include #include #include #include +#include #include #if defined(RL_SG_SOLID) @@ -58,7 +61,7 @@ main(int argc, char** argv) try { - rl::sg::XmlFactory factory; + std::string scenefile(argv[1]); #if defined(RL_SG_SOLID) rl::sg::solid::Scene scene; #elif defined(RL_SG_BULLET) @@ -66,12 +69,34 @@ main(int argc, char** argv) #elif defined(RL_SG_ODE) rl::sg::ode::Scene scene; #endif - factory.load(argv[1], &scene); - std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[2])); + if ("urdf" == scenefile.substr(scenefile.length() - 4, 4)) + { + rl::sg::UrdfFactory factory; + factory.load(scenefile, &scene); + } + else + { + rl::sg::XmlFactory factory; + factory.load(scenefile, &scene); + } + + std::string kinematicsfile(argv[2]); + std::shared_ptr kinematic; + + if ("urdf" == kinematicsfile.substr(kinematicsfile.length() - 4, 4)) + { + rl::mdl::UrdfFactory factory; + kinematic = std::dynamic_pointer_cast(factory.create(kinematicsfile)); + } + else + { + rl::mdl::XmlFactory factory; + kinematic = std::dynamic_pointer_cast(factory.create(kinematicsfile)); + } rl::plan::SimpleModel model; - model.kin = kinematics.get(); + model.mdl = kinematic.get(); model.model = scene.getModel(0); model.scene = &scene; @@ -89,20 +114,20 @@ main(int argc, char** argv) planner.delta = 1 * rl::math::DEG2RAD; - rl::math::Vector start(kinematics->getDof()); + rl::math::Vector start(kinematic->getDofPosition()); - for (std::size_t i = 0; i < kinematics->getDof(); ++i) + for (std::ptrdiff_t i = 0; i < start.size(); ++i) { start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::DEG2RAD; } planner.start = &start; - rl::math::Vector goal(kinematics->getDof()); + rl::math::Vector goal(kinematic->getDofPosition()); - for (std::size_t i = 0; i < kinematics->getDof(); ++i) + for (std::ptrdiff_t i = 0; i < goal.size(); ++i) { - goal(i) = boost::lexical_cast(argv[kinematics->getDof() + i + 3]) * rl::math::DEG2RAD; + goal(i) = boost::lexical_cast(argv[start.size() + i + 3]) * rl::math::DEG2RAD; } planner.goal = &goal; diff --git a/examples/rlmdl/box-6d-300505.sixDof.xml b/examples/rlmdl/box-6d-300505.sixDof.xml new file mode 100644 index 00000000..a5f66db4 --- /dev/null +++ b/examples/rlmdl/box-6d-300505.sixDof.xml @@ -0,0 +1,54 @@ + + + + + 6D Box (3.0m x 0.5m x 0.5m) + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + 0 + 0 + 9.86055 + + + + + + + + 30 + 30 + 2 + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + 1.5 + 0 + 0 + + + + + diff --git a/examples/rlplan/box-6d-300505_maze_prm.mdl.sixDof.xml b/examples/rlplan/box-6d-300505_maze_prm.mdl.sixDof.xml new file mode 100644 index 00000000..15abc5d0 --- /dev/null +++ b/examples/rlplan/box-6d-300505_maze_prm.mdl.sixDof.xml @@ -0,0 +1,43 @@ + + + + 1200 + + 9 + 11 + 1 + 0 + 0 + -0.70710678 + 0.70710678 + + + + 0 + + + + 2 + 1 + 1 + 0 + 0 + 0 + 1 + + + 1 + + + 0 + + + 100 + + + + + 1 + + + diff --git a/examples/rlplan/box-6d-300505_maze_rrtConCon.mdl.sixDof.xml b/examples/rlplan/box-6d-300505_maze_rrtConCon.mdl.sixDof.xml new file mode 100644 index 00000000..e651dfe7 --- /dev/null +++ b/examples/rlplan/box-6d-300505_maze_rrtConCon.mdl.sixDof.xml @@ -0,0 +1,42 @@ + + + + 1200 + + 9 + 11 + 1 + 0 + 0 + -0.70710678 + 0.70710678 + + + + 0 + + + + 2 + 1 + 1 + 0 + 0 + 0 + 1 + + + 1 + + + 0 + + + 100 + + 1 + 1e-9 + + + + diff --git a/examples/rlplan/unimation-puma560_boxes_prm.mdl.xml b/examples/rlplan/unimation-puma560_boxes_prm.mdl.xml new file mode 100644 index 00000000..8c279797 --- /dev/null +++ b/examples/rlplan/unimation-puma560_boxes_prm.mdl.xml @@ -0,0 +1,67 @@ + + + + 120 + + 0 + 0 + 90 + 0 + 0 + 0 + + + + + + 0 + 0 + 90 + + + 0 + 0 + 0 + + + + 0 + + + + 90 + -180 + 90 + 0 + 0 + 0 + + + 1 + + + + + 0 + 0 + 90 + + + 0 + 0 + 0 + + + + 0 + + + 100 + + + + + 1 + + + diff --git a/examples/rlplan/unimation-puma560_boxes_rrtConCon.mdl.xml b/examples/rlplan/unimation-puma560_boxes_rrtConCon.mdl.xml new file mode 100644 index 00000000..f2c540d8 --- /dev/null +++ b/examples/rlplan/unimation-puma560_boxes_rrtConCon.mdl.xml @@ -0,0 +1,65 @@ + + + + 120 + + 0 + 0 + 90 + 0 + 0 + 0 + + + + + + 0 + 0 + 90 + + + 0 + 0 + 0 + + + + 0 + + + + 90 + -180 + 90 + 0 + 0 + 0 + + + 1 + + + + + 0 + 0 + 90 + + + 0 + 0 + 0 + + + + 0 + + + 100 + + 1 + + + + diff --git a/examples/rlsg/box-6d-300505_maze.mdl.xml b/examples/rlsg/box-6d-300505_maze.mdl.xml new file mode 100644 index 00000000..9079aa4c --- /dev/null +++ b/examples/rlsg/box-6d-300505_maze.mdl.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index 367031dd..a80fc2ef 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -31,11 +31,11 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) NAME rlEetTestBulletBox6d300505Maze COMMAND rlEetTest bullet - ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml - ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml + ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.mdl.xml + ${rl_SOURCE_DIR}/examples/rlmdl/box-6d-300505.sixDof.xml 270 269 - 2 1 1 0 0 0 - 9 11 1 0 0 -90 + 2 1 1 0 0 0 1 + 9 11 1 0 0 -0.70710678 0.70710678 ) endif() @@ -44,11 +44,11 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) NAME rlEetTestFclBox6d300505Maze COMMAND rlEetTest fcl - ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml - ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml + ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.mdl.xml + ${rl_SOURCE_DIR}/examples/rlmdl/box-6d-300505.sixDof.xml 242 241 - 2 1 1 0 0 0 - 9 11 1 0 0 -90 + 2 1 1 0 0 0 1 + 9 11 1 0 0 -0.70710678 0.70710678 ) endif() @@ -57,11 +57,11 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) NAME rlEetTestPqpBox6d300505Maze COMMAND rlEetTest pqp - ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml - ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml + ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.mdl.xml + ${rl_SOURCE_DIR}/examples/rlmdl/box-6d-300505.sixDof.xml 239 238 - 2 1 1 0 0 0 - 9 11 1 0 0 -90 + 2 1 1 0 0 0 1 + 9 11 1 0 0 -0.70710678 0.70710678 ) endif() @@ -70,11 +70,11 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) NAME rlEetTestSolidBox6d300505Maze COMMAND rlEetTest solid - ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.xml - ${rl_SOURCE_DIR}/examples/rlkin/box-6d-300505.xml + ${rl_SOURCE_DIR}/examples/rlsg/box-6d-300505_maze.mdl.xml + ${rl_SOURCE_DIR}/examples/rlmdl/box-6d-300505.sixDof.xml 321 320 - 2 1 1 0 0 0 - 9 11 1 0 0 -90 + 2 1 1 0 0 0 1 + 9 11 1 0 0 -0.70710678 0.70710678 ) endif() endif() diff --git a/tests/rlEetTest/rlEetTest.cpp b/tests/rlEetTest/rlEetTest.cpp index a88114d8..af765b6b 100644 --- a/tests/rlEetTest/rlEetTest.cpp +++ b/tests/rlEetTest/rlEetTest.cpp @@ -28,8 +28,9 @@ #include #include #include -#include #include +#include +#include #include #include #include @@ -89,17 +90,17 @@ main(int argc, char** argv) } #endif // RL_SG_SOLID - rl::sg::XmlFactory factory; - factory.load(argv[2], scene.get()); + rl::sg::XmlFactory factory1; + factory1.load(argv[2], scene.get()); - std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[3])); + rl::mdl::XmlFactory factory2; + std::shared_ptr kinematic = std::dynamic_pointer_cast(factory2.create(argv[3])); - Eigen::Matrix qUnits(kinematics->getDof()); - kinematics->getPositionUnits(qUnits); + Eigen::Matrix qUnits = kinematic->getPositionUnits(); - rl::math::Vector start(kinematics->getDof()); + rl::math::Vector start(kinematic->getDofPosition()); - for (std::size_t i = 0; i < kinematics->getDof(); ++i) + for (std::ptrdiff_t i = 0; i < start.size(); ++i) { start(i) = boost::lexical_cast(argv[i + 6]); @@ -109,11 +110,11 @@ main(int argc, char** argv) } } - rl::math::Vector goal(kinematics->getDof()); + rl::math::Vector goal(kinematic->getDofPosition()); - for (std::size_t i = 0; i < kinematics->getDof(); ++i) + for (std::ptrdiff_t i = 0; i < goal.size(); ++i) { - goal(i) = boost::lexical_cast(argv[kinematics->getDof() + i + 6]); + goal(i) = boost::lexical_cast(argv[start.size() + i + 6]); if (rl::math::UNIT_RADIAN == qUnits(i)) { @@ -122,7 +123,7 @@ main(int argc, char** argv) } rl::plan::DistanceModel model; - model.kin = kinematics.get(); + model.mdl = kinematic.get(); model.model = scene->getModel(0); model.scene = scene.get(); diff --git a/tests/rlPrmTest/CMakeLists.txt b/tests/rlPrmTest/CMakeLists.txt index fb9276d6..e3577f0c 100644 --- a/tests/rlPrmTest/CMakeLists.txt +++ b/tests/rlPrmTest/CMakeLists.txt @@ -33,7 +33,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest bullet ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 110 -200 60 0 0 0 @@ -45,7 +45,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest bullet ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 90 -180 90 0 0 0 @@ -59,7 +59,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest fcl ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 110 -200 60 0 0 0 @@ -71,7 +71,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest fcl ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 90 -180 90 0 0 0 @@ -85,7 +85,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest ode ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 110 -200 60 0 0 0 @@ -97,7 +97,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest ode ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 90 -180 90 0 0 0 @@ -111,7 +111,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest pqp ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 110 -200 60 0 0 0 @@ -123,7 +123,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest pqp ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 90 -180 90 0 0 0 @@ -137,7 +137,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest solid ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 110 -200 60 0 0 0 @@ -149,7 +149,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 COMMAND rlPrmTest solid ${rl_SOURCE_DIR}/examples/rlsg/unimation-puma560_boxes.convex.xml - ${rl_SOURCE_DIR}/examples/rlkin/unimation-puma560.xml + ${rl_SOURCE_DIR}/examples/rlmdl/unimation-puma560.xml 17 16 0 0 0 0 0 90 90 -180 90 0 0 0 diff --git a/tests/rlPrmTest/rlPrmTest.cpp b/tests/rlPrmTest/rlPrmTest.cpp index dfb32769..e40c4c9d 100644 --- a/tests/rlPrmTest/rlPrmTest.cpp +++ b/tests/rlPrmTest/rlPrmTest.cpp @@ -28,8 +28,9 @@ #include #include #include -#include #include +#include +#include #include #include #include @@ -99,10 +100,11 @@ main(int argc, char** argv) } #endif // RL_SG_SOLID - rl::sg::XmlFactory factory; - factory.load(argv[2], scene.get()); + rl::sg::XmlFactory factory1; + factory1.load(argv[2], scene.get()); - std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[3])); + rl::mdl::XmlFactory factory2; + std::shared_ptr kinematic = std::dynamic_pointer_cast(factory2.create(argv[3])); rl::math::Transform world = rl::math::Transform::Identity(); @@ -121,10 +123,10 @@ main(int argc, char** argv) world.translation().y() = boost::lexical_cast(argv[7]); world.translation().z() = boost::lexical_cast(argv[8]); - kinematics->world() = world; + kinematic->world() = world; rl::plan::SimpleModel model; - model.kin = kinematics.get(); + model.mdl = kinematic.get(); model.model = scene->getModel(0); model.scene = scene.get(); @@ -145,20 +147,20 @@ main(int argc, char** argv) verifier.delta = 1 * rl::math::DEG2RAD; verifier.model = &model; - rl::math::Vector start(kinematics->getDof()); + rl::math::Vector start(kinematic->getDofPosition()); - for (std::size_t i = 0; i < kinematics->getDof(); ++i) + for (std::ptrdiff_t i = 0; i < start.size(); ++i) { start(i) = boost::lexical_cast(argv[i + 12]) * rl::math::DEG2RAD; } planner.start = &start; - rl::math::Vector goal(kinematics->getDof()); + rl::math::Vector goal(kinematic->getDofPosition()); - for (std::size_t i = 0; i < kinematics->getDof(); ++i) + for (std::ptrdiff_t i = 0; i < goal.size(); ++i) { - goal(i) = boost::lexical_cast(argv[kinematics->getDof() + i + 12]) * rl::math::DEG2RAD; + goal(i) = boost::lexical_cast(argv[start.size() + i + 12]) * rl::math::DEG2RAD; } planner.goal = &goal; From 15feafa5e9f60fe89c1f77f90ea3428881c6f7cb Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 13 Jun 2020 13:47:51 +0200 Subject: [PATCH 361/546] Remove extra whitespace required by older compilers --- src/rl/hal/Ati.cpp | 4 +-- src/rl/hal/Dc1394Camera.cpp | 72 ++++++++++++++++++------------------- src/rl/hal/Jr3.cpp | 2 +- src/rl/sg/UrdfFactory.cpp | 2 +- src/rl/sg/fcl/Model.cpp | 4 +-- src/rl/sg/fcl/Scene.cpp | 12 +++---- src/rl/sg/fcl/Shape.cpp | 30 ++++++++-------- 7 files changed, 63 insertions(+), 63 deletions(-) diff --git a/src/rl/hal/Ati.cpp b/src/rl/hal/Ati.cpp index eb7a01a4..29c89d81 100644 --- a/src/rl/hal/Ati.cpp +++ b/src/rl/hal/Ati.cpp @@ -57,8 +57,8 @@ namespace rl throw DeviceException("Could not load the desired calibration"); } - this->values.fill(::std::numeric_limits< ::rl::math::Real>::quiet_NaN()); - this->voltages.fill(::std::numeric_limits< ::rl::math::Real>::quiet_NaN()); + this->values.fill(::std::numeric_limits<::rl::math::Real>::quiet_NaN()); + this->voltages.fill(::std::numeric_limits<::rl::math::Real>::quiet_NaN()); } Ati::~Ati() diff --git a/src/rl/hal/Dc1394Camera.cpp b/src/rl/hal/Dc1394Camera.cpp index 2dffac7c..485cb166 100644 --- a/src/rl/hal/Dc1394Camera.cpp +++ b/src/rl/hal/Dc1394Camera.cpp @@ -274,7 +274,7 @@ namespace rl unsigned int width; unsigned int height; - ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast< ::dc1394video_mode_t>(this->videoMode), &width, &height); + ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast<::dc1394video_mode_t>(this->videoMode), &width, &height); if (::DC1394_SUCCESS != error) { @@ -293,7 +293,7 @@ namespace rl ::dc1394bool_t hasAbsoluteControl; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_has_absolute_control(this->camera, static_cast< ::dc1394feature_t>(feature), &hasAbsoluteControl); + ::dc1394error_t error = ::dc1394_feature_has_absolute_control(this->camera, static_cast<::dc1394feature_t>(feature), &hasAbsoluteControl); #else int error = ::dc1394_has_absolute_control(this->handle, this->nodes[this->node], feature, &hasAbsoluteControl); #endif @@ -310,7 +310,7 @@ namespace rl Dc1394Camera::getFeatureBoundaries(const Feature& feature, unsigned int& min, unsigned int& max) const { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_get_boundaries(this->camera, static_cast< ::dc1394feature_t>(feature), &min, &max); + ::dc1394error_t error = ::dc1394_feature_get_boundaries(this->camera, static_cast<::dc1394feature_t>(feature), &min, &max); if (::DC1394_SUCCESS != error) { @@ -337,7 +337,7 @@ namespace rl Dc1394Camera::getFeatureBoundariesAbsolute(const Feature& feature, float& min, float& max) const { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_get_absolute_boundaries(this->camera, static_cast< ::dc1394feature_t>(feature), &min, &max); + ::dc1394error_t error = ::dc1394_feature_get_absolute_boundaries(this->camera, static_cast<::dc1394feature_t>(feature), &min, &max); #else int error = ::dc1394_query_absolute_feature_min_max(this->handle, this->nodes[this->node], feature, &min, &max); #endif @@ -354,7 +354,7 @@ namespace rl #if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394feature_mode_t mode; - ::dc1394error_t error = ::dc1394_feature_get_mode(this->camera, static_cast< ::dc1394feature_t>(feature), &mode); + ::dc1394error_t error = ::dc1394_feature_get_mode(this->camera, static_cast<::dc1394feature_t>(feature), &mode); if (::DC1394_SUCCESS != error) { @@ -401,7 +401,7 @@ namespace rl #if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394feature_modes_t modes; - ::dc1394error_t error = ::dc1394_feature_get_modes(this->camera, static_cast< ::dc1394feature_t>(feature), &modes); + ::dc1394error_t error = ::dc1394_feature_get_modes(this->camera, static_cast<::dc1394feature_t>(feature), &modes); if (::DC1394_SUCCESS != error) { @@ -428,21 +428,21 @@ namespace rl } } #else - int error = ::dc1394_has_manual_mode(this->handle, this->nodes[this->node], feature, static_cast< ::dc1394bool_t*>(&hasManual)); + int error = ::dc1394_has_manual_mode(this->handle, this->nodes[this->node], feature, static_cast<::dc1394bool_t*>(&hasManual)); if (::DC1394_SUCCESS != error) { throw Exception(error); } - error = ::dc1394_has_auto_mode(this->handle, this->nodes[this->node], feature, stataic_cast< ::dc1394bool_t*>(&hasAuto)); + error = ::dc1394_has_auto_mode(this->handle, this->nodes[this->node], feature, static_cast<::dc1394bool_t*>(&hasAuto)); if (::DC1394_SUCCESS != error) { throw Exception(error); } - error = ::dc1394_has_one_push_auto(this->handle, this->nodes[this->node], feature, static_cast< ::dc1394bool_t*>(&hasOnePushAuto)); + error = ::dc1394_has_one_push_auto(this->handle, this->nodes[this->node], feature, static_cast<::dc1394bool_t*>(&hasOnePushAuto)); if (::DC1394_SUCCESS != error) { @@ -457,7 +457,7 @@ namespace rl unsigned int value; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_get_value(this->camera, static_cast< ::dc1394feature_t>(feature), &value); + ::dc1394error_t error = ::dc1394_feature_get_value(this->camera, static_cast<::dc1394feature_t>(feature), &value); #else int error = ::dc1394_get_feature_value(this->handle, this->nodes[this->node], feature, &value); #endif @@ -476,7 +476,7 @@ namespace rl float value; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_get_absolute_value(this->camera, static_cast< ::dc1394feature_t>(feature), &value); + ::dc1394error_t error = ::dc1394_feature_get_absolute_value(this->camera, static_cast<::dc1394feature_t>(feature), &value); #else int error = ::dc1394_query_absolute_feature_value(this->handle, this->nodes[this->node], feature, &value); #endif @@ -510,7 +510,7 @@ namespace rl Dc1394Camera::getFormat7MaximumImageSize(const unsigned int& mode, unsigned int& width, unsigned& height) const { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_format7_get_max_image_size(this->camera, static_cast< ::dc1394video_mode_t>(mode), &width, &height); + ::dc1394error_t error = ::dc1394_format7_get_max_image_size(this->camera, static_cast<::dc1394video_mode_t>(mode), &width, &height); #else int error = ::dc1394_query_format7_max_image_size(this->handle, this->nodes[this->node], mode, &width, &height); #endif @@ -527,7 +527,7 @@ namespace rl Framerate framerate; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_video_get_framerate(this->camera, reinterpret_cast< ::dc1394framerate_t*>(&framerate)); + ::dc1394error_t error = ::dc1394_video_get_framerate(this->camera, reinterpret_cast<::dc1394framerate_t*>(&framerate)); #else int error = ::dc1394_get_video_framerate(this->handle, this->nodes[this->node], reinterpret_cast(&framerate)); #endif @@ -558,7 +558,7 @@ namespace rl OperationMode operationMode; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_video_get_operation_mode(this->camera, reinterpret_cast< ::dc1394operation_mode_t*>(&operationMode)); + ::dc1394error_t error = ::dc1394_video_get_operation_mode(this->camera, reinterpret_cast<::dc1394operation_mode_t*>(&operationMode)); #else int error = ::dc1394_get_operation_mode(this->handle, this->nodes[this->node], reinterpret_cast(&operationMode)); #endif @@ -578,7 +578,7 @@ namespace rl unsigned int width; unsigned int height; - ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast< ::dc1394video_mode_t>(this->videoMode), &width, &height); + ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast<::dc1394video_mode_t>(this->videoMode), &width, &height); if (::DC1394_SUCCESS != error) { @@ -597,7 +597,7 @@ namespace rl IsoSpeed speed; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_video_get_iso_speed(this->camera, reinterpret_cast< ::dc1394speed_t*>(&speed)); + ::dc1394error_t error = ::dc1394_video_get_iso_speed(this->camera, reinterpret_cast<::dc1394speed_t*>(&speed)); #else unsigned int channel; int error = ::dc1394_get_iso_channel_and_speed(this->handle, this->nodes[this->node], &channel, reinterpret_cast(&speed)); @@ -647,7 +647,7 @@ namespace rl break; } - return ::std::chrono::duration_cast< ::std::chrono::nanoseconds>( + return ::std::chrono::duration_cast<::std::chrono::nanoseconds>( ::std::chrono::duration(1.0 / framerate * rl::math::UNIT2NANO) ); } @@ -658,7 +658,7 @@ namespace rl VideoMode videoMode; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_video_get_mode(this->camera, reinterpret_cast< ::dc1394video_mode_t*>(&videoMode)); + ::dc1394error_t error = ::dc1394_video_get_mode(this->camera, reinterpret_cast<::dc1394video_mode_t*>(&videoMode)); #else int error = ::dc1394_get_video_mode(this->handle, this->nodes[this->node], reinterpret_cast(&videoMode)); #endif @@ -678,7 +678,7 @@ namespace rl unsigned int width; unsigned int height; - ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast< ::dc1394video_mode_t>(this->videoMode), &width, &height); + ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast<::dc1394video_mode_t>(this->videoMode), &width, &height); if (::DC1394_SUCCESS != error) { @@ -735,7 +735,7 @@ namespace rl ::dc1394bool_t hasAbsoluteControl; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_has_absolute_control(this->camera, static_cast< ::dc1394feature_t>(feature), &hasAbsoluteControl); + ::dc1394error_t error = ::dc1394_feature_has_absolute_control(this->camera, static_cast<::dc1394feature_t>(feature), &hasAbsoluteControl); #else int error = ::dc1394_has_absolute_control(this->handle, this->nodes[this->node], feature, &hasAbsoluteControl); #endif @@ -754,7 +754,7 @@ namespace rl #if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394switch_t isFeatureOn; - ::dc1394error_t error = ::dc1394_feature_get_power(this->camera, static_cast< ::dc1394feature_t>(feature), &isFeatureOn); + ::dc1394error_t error = ::dc1394_feature_get_power(this->camera, static_cast<::dc1394feature_t>(feature), &isFeatureOn); #else ::dc1394bool_t isFeatureOn; @@ -775,7 +775,7 @@ namespace rl ::dc1394bool_t isFeaturePresent; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_is_present(this->camera, static_cast< ::dc1394feature_t>(feature), &isFeaturePresent); + ::dc1394error_t error = ::dc1394_feature_is_present(this->camera, static_cast<::dc1394feature_t>(feature), &isFeaturePresent); #else int error = ::dc1394_is_feature_present(this->handle, this->nodes[this->node], feature, &isFeaturePresent); #endif @@ -794,7 +794,7 @@ namespace rl ::dc1394bool_t canReadOut; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_is_readable(this->camera, static_cast< ::dc1394feature_t>(feature), &canReadOut); + ::dc1394error_t error = ::dc1394_feature_is_readable(this->camera, static_cast<::dc1394feature_t>(feature), &canReadOut); #else int error = ::dc1394_can_read_out(this->handle, this->nodes[this->node], feature, &canReadOut); #endif @@ -813,7 +813,7 @@ namespace rl ::dc1394bool_t canTurnOnOff; #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_is_switchable(this->camera, static_cast< ::dc1394feature_t>(feature), &canTurnOnOff); + ::dc1394error_t error = ::dc1394_feature_is_switchable(this->camera, static_cast<::dc1394feature_t>(feature), &canTurnOnOff); #else int error = ::dc1394_can_turn_on_off(this->handle, this->nodes[this->node], feature, &canTurnOnOff); #endif @@ -873,14 +873,14 @@ namespace rl throw Exception(error); } - error = ::dc1394_get_video_framerate(this->handle, this->nodes[this->node], static_cast< ::dc1394framerate_t*>(&this->framerate)); + error = ::dc1394_get_video_framerate(this->handle, this->nodes[this->node], static_cast<::dc1394framerate_t*>(&this->framerate)); if (::DC1394_SUCCESS != error) { throw Exception(error); } - error = ::dc1394_get_video_mode(this->handle, this->nodes[this->node], static_cast< ::dc1394video_mode_t*>(&this->videoMode)); + error = ::dc1394_get_video_mode(this->handle, this->nodes[this->node], static_cast<::dc1394video_mode_t*>(&this->videoMode)); if (::DC1394_SUCCESS != error) { @@ -922,7 +922,7 @@ namespace rl Dc1394Camera::setFeatureEnabled(const Feature& feature, const bool& doOn) { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_set_power(this->camera, static_cast< ::dc1394feature_t>(feature), static_cast< ::dc1394switch_t>(doOn)); + ::dc1394error_t error = ::dc1394_feature_set_power(this->camera, static_cast<::dc1394feature_t>(feature), static_cast<::dc1394switch_t>(doOn)); #else int error = ::dc1394_feature_on_off(this->handle, this->nodes[this->node], feature, doOn); #endif @@ -937,7 +937,7 @@ namespace rl Dc1394Camera::setFeatureMode(const Feature& feature, const FeatureMode& mode) { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_set_mode(this->camera, static_cast< ::dc1394feature_t>(feature), static_cast< ::dc1394feature_mode_t>(mode)); + ::dc1394error_t error = ::dc1394_feature_set_mode(this->camera, static_cast<::dc1394feature_t>(feature), static_cast<::dc1394feature_mode_t>(mode)); #else int error; @@ -967,7 +967,7 @@ namespace rl Dc1394Camera::setFeatureValue(const Feature& feature, const unsigned int& value) { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_set_value(this->camera, static_cast< ::dc1394feature_t>(feature), value); + ::dc1394error_t error = ::dc1394_feature_set_value(this->camera, static_cast<::dc1394feature_t>(feature), value); #else int error = ::dc1394_set_feature_value(this->handle, this->nodes[this->node], feature, value); #endif @@ -982,7 +982,7 @@ namespace rl Dc1394Camera::setFeatureValueAbsolute(const Feature& feature, const float& value) { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_feature_set_absolute_value(this->camera, static_cast< ::dc1394feature_t>(feature), value); + ::dc1394error_t error = ::dc1394_feature_set_absolute_value(this->camera, static_cast<::dc1394feature_t>(feature), value); #else int error = ::dc1394_set_absolute_feature_value(this->handle, this->nodes[this->node], feature, value); #endif @@ -1005,8 +1005,8 @@ namespace rl #if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_format7_set_roi( this->camera, - static_cast< ::dc1394video_mode_t>(videoMode), - static_cast< ::dc1394color_coding_t>(colorCoding), + static_cast<::dc1394video_mode_t>(videoMode), + static_cast<::dc1394color_coding_t>(colorCoding), DC1394_QUERY_FROM_CAMERA, left, top, @@ -1032,7 +1032,7 @@ namespace rl Dc1394Camera::setFramerate(const Framerate& framerate) { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_video_set_framerate(this->camera, static_cast< ::dc1394framerate_t>(framerate)); + ::dc1394error_t error = ::dc1394_video_set_framerate(this->camera, static_cast<::dc1394framerate_t>(framerate)); #else int error = ::dc1394_set_video_framerate(this->handle, this->nodes[node], framerate); #endif @@ -1055,7 +1055,7 @@ namespace rl Dc1394Camera::setOperationMode(const OperationMode& mode) { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_video_set_operation_mode(this->camera, static_cast< ::dc1394operation_mode_t>(mode)); + ::dc1394error_t error = ::dc1394_video_set_operation_mode(this->camera, static_cast<::dc1394operation_mode_t>(mode)); #else int error = ::dc1394_set_operation_mode(this->handle, this->nodes[this->node], mode); #endif @@ -1070,7 +1070,7 @@ namespace rl Dc1394Camera::setSpeed(const IsoSpeed& speed) { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_video_set_iso_speed(this->camera, static_cast< ::dc1394speed_t>(speed)); + ::dc1394error_t error = ::dc1394_video_set_iso_speed(this->camera, static_cast<::dc1394speed_t>(speed)); #else int error = ::dc1394_set_iso_channel_and_speed(this->handle, this->nodes[node], this->channel, speed); #endif @@ -1087,7 +1087,7 @@ namespace rl Dc1394Camera::setVideoMode(const VideoMode& videoMode) { #if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::dc1394_video_set_mode(this->camera, static_cast< ::dc1394video_mode_t>(videoMode)); + ::dc1394error_t error = ::dc1394_video_set_mode(this->camera, static_cast<::dc1394video_mode_t>(videoMode)); #else unsigned int format; diff --git a/src/rl/hal/Jr3.cpp b/src/rl/hal/Jr3.cpp index 3f183896..652c6be0 100644 --- a/src/rl/hal/Jr3.cpp +++ b/src/rl/hal/Jr3.cpp @@ -41,7 +41,7 @@ namespace rl values(), zeroes() { - this->values.fill(::std::numeric_limits< ::rl::math::Real>::quiet_NaN()); + this->values.fill(::std::numeric_limits<::rl::math::Real>::quiet_NaN()); this->zeroes.fill(0); } diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 22b96ce2..a4285793 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -185,7 +185,7 @@ ::std::cout << "root: " << name << ::std::endl; } } - ::std::deque< ::std::string> dfs; + ::std::deque<::std::string> dfs; dfs.push_front(root); while (!dfs.empty()) diff --git a/src/rl/sg/fcl/Model.cpp b/src/rl/sg/fcl/Model.cpp index bf09ae75..b468e695 100644 --- a/src/rl/sg/fcl/Model.cpp +++ b/src/rl/sg/fcl/Model.cpp @@ -56,7 +56,7 @@ namespace rl Model::add(Body* body) { this->bodies.push_back(body); - ::std::vector< ::fcl::CollisionObject*> objects; + ::std::vector<::fcl::CollisionObject*> objects; body->manager.getObjects(objects); if (objects.size() > 0) @@ -87,7 +87,7 @@ namespace rl if (found != this->bodies.end()) { this->bodies.erase(found); - ::std::vector< ::fcl::CollisionObject*> objects; + ::std::vector<::fcl::CollisionObject*> objects; body->manager.getObjects(objects); for (::std::size_t i = 0; i < objects.size(); ++i) diff --git a/src/rl/sg/fcl/Scene.cpp b/src/rl/sg/fcl/Scene.cpp index 71d8cc76..0d10855e 100644 --- a/src/rl/sg/fcl/Scene.cpp +++ b/src/rl/sg/fcl/Scene.cpp @@ -64,7 +64,7 @@ namespace rl { Model* modelFcl = static_cast(model); this->models.push_back(model); - ::std::vector< ::fcl::CollisionObject*> objects; + ::std::vector<::fcl::CollisionObject*> objects; modelFcl->manager.getObjects(objects); if (objects.size() > 0) @@ -281,15 +281,15 @@ namespace rl Scene::distance(::rl::sg::Shape* shape, const ::rl::math::Vector3& point, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) { #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - ::boost::shared_ptr< ::fcl::CollisionGeometry> geometry = ::boost::make_shared< ::fcl::Sphere>(0); + ::boost::shared_ptr<::fcl::CollisionGeometry> geometry = ::boost::make_shared<::fcl::Sphere>(0); #else - ::std::shared_ptr< ::fcl::CollisionGeometry> geometry = ::std::make_shared< ::fcl::Sphere>(0); + ::std::shared_ptr<::fcl::CollisionGeometry> geometry = ::std::make_shared<::fcl::Sphere>(0); #endif ::fcl::Vec3f translation(point(0), point(1), point(2)); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - ::boost::shared_ptr< ::fcl::CollisionObject> collisionObject = ::boost::make_shared< ::fcl::CollisionObject>(geometry, ::fcl::Transform3f(translation)); + ::boost::shared_ptr<::fcl::CollisionObject> collisionObject = ::boost::make_shared<::fcl::CollisionObject>(geometry, ::fcl::Transform3f(translation)); #else - ::std::shared_ptr< ::fcl::CollisionObject> collisionObject = ::std::make_shared< ::fcl::CollisionObject>(geometry, ::fcl::Transform3f(translation)); + ::std::shared_ptr<::fcl::CollisionObject> collisionObject = ::std::make_shared<::fcl::CollisionObject>(geometry, ::fcl::Transform3f(translation)); #endif ::fcl::DistanceRequest request; @@ -331,7 +331,7 @@ namespace rl if (found != this->models.end()) { this->models.erase(found); - ::std::vector< ::fcl::CollisionObject*> objects; + ::std::vector<::fcl::CollisionObject*> objects; static_cast(model)->manager.getObjects(objects); for (::std::size_t i = 0; i < objects.size(); ++i) diff --git a/src/rl/sg/fcl/Shape.cpp b/src/rl/sg/fcl/Shape.cpp index 8d049112..a9deae51 100644 --- a/src/rl/sg/fcl/Shape.cpp +++ b/src/rl/sg/fcl/Shape.cpp @@ -60,18 +60,18 @@ namespace rl { SoVRMLBox* box = static_cast(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared< ::fcl::Box>(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); + this->geometry = ::boost::make_shared<::fcl::Box>(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); #else - this->geometry = ::std::make_shared< ::fcl::Box>(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); + this->geometry = ::std::make_shared<::fcl::Box>(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); #endif } else if (vrmlGeometry->isOfType(SoVRMLCone::getClassTypeId())) { SoVRMLCone* cone = static_cast(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared< ::fcl::Cone>(cone->bottomRadius.getValue(), cone->height.getValue()); + this->geometry = ::boost::make_shared<::fcl::Cone>(cone->bottomRadius.getValue(), cone->height.getValue()); #else - this->geometry = ::std::make_shared< ::fcl::Cone>(cone->bottomRadius.getValue(), cone->height.getValue()); + this->geometry = ::std::make_shared<::fcl::Cone>(cone->bottomRadius.getValue(), cone->height.getValue()); #endif this->baseTransform(0, 0) = 1; @@ -95,9 +95,9 @@ namespace rl { SoVRMLCylinder* cylinder = static_cast(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared< ::fcl::Cylinder>(cylinder->radius.getValue(), cylinder->height.getValue()); + this->geometry = ::boost::make_shared<::fcl::Cylinder>(cylinder->radius.getValue(), cylinder->height.getValue()); #else - this->geometry = ::std::make_shared< ::fcl::Cylinder>(cylinder->radius.getValue(), cylinder->height.getValue()); + this->geometry = ::std::make_shared<::fcl::Cylinder>(cylinder->radius.getValue(), cylinder->height.getValue()); #endif this->baseTransform(0, 0) = 1; @@ -127,8 +127,8 @@ namespace rl if (indexedFaceSet->convex.getValue() && !indexedFaceSet->convex.isDefault()) { - this->normals = ::std::vector< ::fcl::Vec3f>(this->indices.size() / 3); - this->distances = ::std::vector< ::fcl::FCL_REAL>(this->indices.size() / 3); + this->normals = ::std::vector<::fcl::Vec3f>(this->indices.size() / 3); + this->distances = ::std::vector<::fcl::FCL_REAL>(this->indices.size() / 3); this->polygons = ::std::vector(this->indices.size() + this->indices.size() / 3); for (::std::size_t i = 0; i < this->indices.size() / 3; ++i) @@ -143,9 +143,9 @@ namespace rl } #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared< ::fcl::Convex>( + this->geometry = ::boost::make_shared<::fcl::Convex>( #else - this->geometry = ::std::make_shared< ::fcl::Convex>( + this->geometry = ::std::make_shared<::fcl::Convex>( #endif this->normals.data(), this->distances.data(), @@ -158,9 +158,9 @@ namespace rl else { #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - ::boost::shared_ptr< ::fcl::BVHModel< ::fcl::OBBRSS>> mesh = ::boost::make_shared< ::fcl::BVHModel< ::fcl::OBBRSS>>(); + ::boost::shared_ptr<::fcl::BVHModel<::fcl::OBBRSS>> mesh = ::boost::make_shared<::fcl::BVHModel<::fcl::OBBRSS>>(); #else - ::std::shared_ptr< ::fcl::BVHModel< ::fcl::OBBRSS>> mesh = ::std::make_shared< ::fcl::BVHModel< ::fcl::OBBRSS>>(); + ::std::shared_ptr<::fcl::BVHModel<::fcl::OBBRSS>> mesh = ::std::make_shared<::fcl::BVHModel<::fcl::OBBRSS>>(); #endif mesh->beginModel(this->indices.size() / 3, this->vertices.size()); @@ -181,13 +181,13 @@ namespace rl { SoVRMLSphere* sphere = static_cast(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared< ::fcl::Sphere>(sphere->radius.getValue()); + this->geometry = ::boost::make_shared<::fcl::Sphere>(sphere->radius.getValue()); #else - this->geometry = ::std::make_shared< ::fcl::Sphere>(sphere->radius.getValue()); + this->geometry = ::std::make_shared<::fcl::Sphere>(sphere->radius.getValue()); #endif } - this->collisionObject = ::std::make_shared< ::fcl::CollisionObject>(this->geometry, ::fcl::Transform3f()); + this->collisionObject = ::std::make_shared<::fcl::CollisionObject>(this->geometry, ::fcl::Transform3f()); this->getBody()->add(this); setTransform(::rl::math::Transform::Identity()); From 430e4ee8c1151083d6d22de11e06bb02e2bc94fc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 13 Jun 2020 21:05:36 +0200 Subject: [PATCH 362/546] Remove libdc1394 1.x API --- cmake/Findlibdc1394.cmake | 55 +-- demos/rlCameraDemo/rlCameraDemo.cpp | 2 +- src/rl/hal/CMakeLists.txt | 1 - src/rl/hal/Dc1394Camera.cpp | 502 +--------------------------- src/rl/hal/Dc1394Camera.h | 112 +------ 5 files changed, 9 insertions(+), 663 deletions(-) diff --git a/cmake/Findlibdc1394.cmake b/cmake/Findlibdc1394.cmake index 1fd81bd4..c1c00b4c 100644 --- a/cmake/Findlibdc1394.cmake +++ b/cmake/Findlibdc1394.cmake @@ -38,21 +38,7 @@ foreach(PATH $ENV{PATH}) endforeach() find_path( - libdc1394_V1_INCLUDE_DIRS - libdc1394/dc1394_control.h - HINTS - ${libdc1394_INCLUDE_HINTS} - PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include -) - -mark_as_advanced(libdc1394_V1_INCLUDE_DIRS) - -find_path( - libdc1394_V2_INCLUDE_DIRS + libdc1394_INCLUDE_DIRS dc1394/dc1394.h HINTS ${libdc1394_INCLUDE_HINTS} @@ -63,13 +49,7 @@ find_path( /usr/include ) -mark_as_advanced(libdc1394_V2_INCLUDE_DIRS) - -if(libdc1394_V1_INCLUDE_DIRS) - set(libdc1394_INCLUDE_DIRS ${libdc1394_V1_INCLUDE_DIRS}) -elseif(libdc1394_V2_INCLUDE_DIRS) - set(libdc1394_INCLUDE_DIRS ${libdc1394_V2_INCLUDE_DIRS}) -endif() +mark_as_advanced(libdc1394_INCLUDE_DIRS) foreach(PATH ${CMAKE_PREFIX_PATH}) file( @@ -107,19 +87,7 @@ foreach(PATH $ENV{PATH}) endforeach() find_library( - libdc1394_V1_LIBRARY_RELEASE - NAMES - dc1394_control - HINTS - ${libdc1394_LIBRARY_HINTS} - PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) -find_library( - libdc1394_V2_LIBRARY_RELEASE + libdc1394_LIBRARY_RELEASE NAMES dc1394 HINTS @@ -132,25 +100,10 @@ find_library( /usr/lib ) -mark_as_advanced(libdc1394_V1_LIBRARY_RELEASE) -mark_as_advanced(libdc1394_V2_LIBRARY_RELEASE) - -if(libdc1394_V1_LIBRARY_RELEASE) - set(libdc1394_LIBRARY_RELEASE ${libdc1394_V1_LIBRARY_RELEASE}) -elseif(libdc1394_V2_LIBRARY_RELEASE) - set(libdc1394_LIBRARY_RELEASE ${libdc1394_V2_LIBRARY_RELEASE}) -endif() +mark_as_advanced(libdc1394_LIBRARY_RELEASE) select_library_configurations(libdc1394) -if(libdc1394_V1_LIBRARY_RELEASE AND libdc1394_V1_INCLUDE_DIRS) - set(libdc1394_DEFINITIONS -DLIBDC1394_VERSION_MAJOR=10) -elseif(libdc1394_V2_LIBRARY_RELEASE AND libdc1394_V2_INCLUDE_DIRS) - set(libdc1394_DEFINITIONS -DLIBDC1394_VERSION_MAJOR=20) -endif() - -mark_as_advanced(libdc1394_DEFINITIONS) - find_package_handle_standard_args( libdc1394 FOUND_VAR libdc1394_FOUND diff --git a/demos/rlCameraDemo/rlCameraDemo.cpp b/demos/rlCameraDemo/rlCameraDemo.cpp index c183c9f2..46aed784 100644 --- a/demos/rlCameraDemo/rlCameraDemo.cpp +++ b/demos/rlCameraDemo/rlCameraDemo.cpp @@ -35,7 +35,7 @@ main(int argc, char** argv) { try { - rl::hal::Dc1394Camera dc1394(argc > 1 ? argv[1] : ""); + rl::hal::Dc1394Camera dc1394(argc > 1 ? std::stoi(argv[1]) : 0); dc1394.open(); dc1394.start(); diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 4318ec96..593b2c24 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -216,7 +216,6 @@ if(RL_BUILD_HAL_COMEDI) endif() if(RL_BUILD_HAL_LIBDC1394) - target_compile_definitions(hal PUBLIC ${libdc1394_DEFINITIONS}) target_include_directories(hal PUBLIC ${libdc1394_INCLUDE_DIRS}) target_link_libraries(hal ${libdc1394_LIBRARIES}) endif() diff --git a/src/rl/hal/Dc1394Camera.cpp b/src/rl/hal/Dc1394Camera.cpp index 485cb166..23930bf8 100644 --- a/src/rl/hal/Dc1394Camera.cpp +++ b/src/rl/hal/Dc1394Camera.cpp @@ -33,16 +33,14 @@ namespace rl { namespace hal { - Dc1394Camera::Dc1394Camera(const ::std::string& filename, const unsigned int& node) : + Dc1394Camera::Dc1394Camera(const unsigned int& node) : Camera(), CyclicDevice(::std::chrono::nanoseconds::zero()), -#if (LIBDC1394_VERSION_MAJOR > 10) buffer(8), camera(nullptr), cameras(0), colorCoding(COLOR_CODING_RAW8), dc1394(::dc1394_new()), - filename(filename), frame(), framerate(static_cast(DC1394_FRAMERATE_MIN)), height(DC1394_USE_MAX_AVAIL), @@ -52,73 +50,24 @@ namespace rl top(0), videoMode(VIDEO_MODE_640x480_RGB8), width(DC1394_USE_MAX_AVAIL) -#else - buffer(8), - camera(), - cameras(0), - channel(0), - colorCoding(COLOR_CODING_RAW8), - drop(1), - filename(filename), - framerate(FRAMERATE_MIN), - handle(nullptr), - height(USE_MAX_AVAIL), - info(), - left(0), - node(node), - nodes(nullptr), - port(0), - speed(::SPEED_400), - top(0), - videoMode(VIDEO_MODE_640x480_RGB8), - width(USE_MAX_AVAIL) -#endif { } Dc1394Camera::~Dc1394Camera() { -#if (LIBDC1394_VERSION_MAJOR > 10) if (nullptr != this->dc1394) { ::dc1394_free(this->dc1394); } -#else - if (nullptr != this->nodes) - { - ::dc1394_free_camera_nodes(this->nodes); - this->nodes = nullptr; - } - - if (nullptr != this->handle) - { - ::dc1394_destroy_handle(this->handle); - this->handle = nullptr; - } -#endif } void Dc1394Camera::close() { -#if (LIBDC1394_VERSION_MAJOR > 10) if (nullptr != this->camera) { ::dc1394_camera_free(this->camera); } -#else - if (nullptr != this->nodes) - { - ::dc1394_free_camera_nodes(this->nodes); - this->nodes = nullptr; - } - - if (nullptr != this->handle) - { - ::dc1394_destroy_handle(this->handle); - this->handle = nullptr; - } -#endif } unsigned int @@ -270,7 +219,6 @@ namespace rl unsigned int Dc1394Camera::getHeight() const { -#if (LIBDC1394_VERSION_MAJOR > 10) unsigned int width; unsigned int height; @@ -282,9 +230,6 @@ namespace rl } return height; -#else - return this->camera.frame_height; -#endif } bool @@ -292,11 +237,7 @@ namespace rl { ::dc1394bool_t hasAbsoluteControl; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_has_absolute_control(this->camera, static_cast<::dc1394feature_t>(feature), &hasAbsoluteControl); -#else - int error = ::dc1394_has_absolute_control(this->handle, this->nodes[this->node], feature, &hasAbsoluteControl); -#endif if (::DC1394_SUCCESS != error) { @@ -309,38 +250,18 @@ namespace rl void Dc1394Camera::getFeatureBoundaries(const Feature& feature, unsigned int& min, unsigned int& max) const { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_get_boundaries(this->camera, static_cast<::dc1394feature_t>(feature), &min, &max); if (::DC1394_SUCCESS != error) { throw Exception(error); } -#else - int error = ::dc1394_get_min_value(this->handle, this->nodes[this->node], feature, &min); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_get_max_value(this->handle, this->nodes[this->node], feature, &max); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } -#endif } void Dc1394Camera::getFeatureBoundariesAbsolute(const Feature& feature, float& min, float& max) const { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_get_absolute_boundaries(this->camera, static_cast<::dc1394feature_t>(feature), &min, &max); -#else - int error = ::dc1394_query_absolute_feature_min_max(this->handle, this->nodes[this->node], feature, &min, &max); -#endif if (::DC1394_SUCCESS != error) { @@ -351,7 +272,6 @@ namespace rl Dc1394Camera::FeatureMode Dc1394Camera::getFeatureMode(const Feature& feature) const { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394feature_mode_t mode; ::dc1394error_t error = ::dc1394_feature_get_mode(this->camera, static_cast<::dc1394feature_t>(feature), &mode); @@ -362,43 +282,11 @@ namespace rl } return static_cast(mode); -#else - ::dc1394bool_t isOnePushInOperation; - - int error = ::dc1394_is_one_push_in_operation(this->handle, this->nodes[this->node], feature, &isOnePushInOperation); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - if (isOnePushInOperation) - { - return FEATURE_MODE_ONE_PUSH_AUTO; - } - - ::dc1394bool_t isFeatureAuto; - - error = ::dc1394_is_feature_auto(this->handle, this->nodes[this->node], feature, &isFeatureAuto); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - if (isFeatureAuto) - { - return FEATURE_MODE_AUTO; - } - - return FEATURE_MODE_MANUAL; -#endif } void Dc1394Camera::getFeatureModes(const Feature& feature, bool& hasManual, bool& hasAuto, bool& hasOnePushAuto) const { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394feature_modes_t modes; ::dc1394error_t error = ::dc1394_feature_get_modes(this->camera, static_cast<::dc1394feature_t>(feature), &modes); @@ -427,28 +315,6 @@ namespace rl hasOnePushAuto = true; } } -#else - int error = ::dc1394_has_manual_mode(this->handle, this->nodes[this->node], feature, static_cast<::dc1394bool_t*>(&hasManual)); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_has_auto_mode(this->handle, this->nodes[this->node], feature, static_cast<::dc1394bool_t*>(&hasAuto)); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_has_one_push_auto(this->handle, this->nodes[this->node], feature, static_cast<::dc1394bool_t*>(&hasOnePushAuto)); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } -#endif } unsigned int @@ -456,11 +322,7 @@ namespace rl { unsigned int value; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_get_value(this->camera, static_cast<::dc1394feature_t>(feature), &value); -#else - int error = ::dc1394_get_feature_value(this->handle, this->nodes[this->node], feature, &value); -#endif if (::DC1394_SUCCESS != error) { @@ -475,11 +337,7 @@ namespace rl { float value; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_get_absolute_value(this->camera, static_cast<::dc1394feature_t>(feature), &value); -#else - int error = ::dc1394_query_absolute_feature_value(this->handle, this->nodes[this->node], feature, &value); -#endif if (::DC1394_SUCCESS != error) { @@ -489,12 +347,6 @@ namespace rl return value; } - ::std::string - Dc1394Camera::getFilename() const - { - return this->filename; - } - void Dc1394Camera::getFormat7(VideoMode& videoMode, ColorCoding& colorCoding, unsigned int& left, unsigned int& top, unsigned int& width, unsigned int& height) const { @@ -509,11 +361,7 @@ namespace rl void Dc1394Camera::getFormat7MaximumImageSize(const unsigned int& mode, unsigned int& width, unsigned& height) const { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_format7_get_max_image_size(this->camera, static_cast<::dc1394video_mode_t>(mode), &width, &height); -#else - int error = ::dc1394_query_format7_max_image_size(this->handle, this->nodes[this->node], mode, &width, &height); -#endif if (::DC1394_SUCCESS != error) { @@ -526,11 +374,7 @@ namespace rl { Framerate framerate; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_video_get_framerate(this->camera, reinterpret_cast<::dc1394framerate_t*>(&framerate)); -#else - int error = ::dc1394_get_video_framerate(this->handle, this->nodes[this->node], reinterpret_cast(&framerate)); -#endif if (::DC1394_SUCCESS != error) { @@ -557,11 +401,7 @@ namespace rl { OperationMode operationMode; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_video_get_operation_mode(this->camera, reinterpret_cast<::dc1394operation_mode_t*>(&operationMode)); -#else - int error = ::dc1394_get_operation_mode(this->handle, this->nodes[this->node], reinterpret_cast(&operationMode)); -#endif if (::DC1394_SUCCESS != error) { @@ -574,7 +414,6 @@ namespace rl unsigned int Dc1394Camera::getSize() const { -#if (LIBDC1394_VERSION_MAJOR > 10) unsigned int width; unsigned int height; @@ -586,9 +425,6 @@ namespace rl } return width * height * this->getBitsPerPixel() / 8; -#else - return this->getWidth() * this->getHeight() * this->getBitsPerPixel() / 8; -#endif } Dc1394Camera::IsoSpeed @@ -596,12 +432,7 @@ namespace rl { IsoSpeed speed; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_video_get_iso_speed(this->camera, reinterpret_cast<::dc1394speed_t*>(&speed)); -#else - unsigned int channel; - int error = ::dc1394_get_iso_channel_and_speed(this->handle, this->nodes[this->node], &channel, reinterpret_cast(&speed)); -#endif if (::DC1394_SUCCESS != error) { @@ -657,11 +488,7 @@ namespace rl { VideoMode videoMode; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_video_get_mode(this->camera, reinterpret_cast<::dc1394video_mode_t*>(&videoMode)); -#else - int error = ::dc1394_get_video_mode(this->handle, this->nodes[this->node], reinterpret_cast(&videoMode)); -#endif if (::DC1394_SUCCESS != error) { @@ -674,7 +501,6 @@ namespace rl unsigned int Dc1394Camera::getWidth() const { -#if (LIBDC1394_VERSION_MAJOR > 10) unsigned int width; unsigned int height; @@ -686,15 +512,11 @@ namespace rl } return width; -#else - return this->camera.frame_width; -#endif } void Dc1394Camera::grab(unsigned char* image) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_capture_dequeue(this->camera, ::DC1394_CAPTURE_POLICY_WAIT, &this->frame); if (::DC1394_SUCCESS != error) @@ -710,23 +532,6 @@ namespace rl { throw Exception(error); } -#else - int error = ::dc1394_dma_multi_capture(&this->camera, 1); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - ::std::memcpy(image, this->camera.capture_buffer, this->getSize()); - - error = ::dc1394_dma_done_with_buffer(&this->camera); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } -#endif } bool @@ -734,11 +539,7 @@ namespace rl { ::dc1394bool_t hasAbsoluteControl; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_has_absolute_control(this->camera, static_cast<::dc1394feature_t>(feature), &hasAbsoluteControl); -#else - int error = ::dc1394_has_absolute_control(this->handle, this->nodes[this->node], feature, &hasAbsoluteControl); -#endif if (::DC1394_SUCCESS != error) { @@ -751,15 +552,9 @@ namespace rl bool Dc1394Camera::isFeatureEnabled(const Feature& feature) const { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394switch_t isFeatureOn; ::dc1394error_t error = ::dc1394_feature_get_power(this->camera, static_cast<::dc1394feature_t>(feature), &isFeatureOn); -#else - ::dc1394bool_t isFeatureOn; - - int error = ::dc1394_is_feature_on(this->handle, this->nodes[this->node], feature, &isFeatureOn); -#endif if (::DC1394_SUCCESS != error) { @@ -774,11 +569,7 @@ namespace rl { ::dc1394bool_t isFeaturePresent; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_is_present(this->camera, static_cast<::dc1394feature_t>(feature), &isFeaturePresent); -#else - int error = ::dc1394_is_feature_present(this->handle, this->nodes[this->node], feature, &isFeaturePresent); -#endif if (::DC1394_SUCCESS != error) { @@ -793,11 +584,7 @@ namespace rl { ::dc1394bool_t canReadOut; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_is_readable(this->camera, static_cast<::dc1394feature_t>(feature), &canReadOut); -#else - int error = ::dc1394_can_read_out(this->handle, this->nodes[this->node], feature, &canReadOut); -#endif if (::DC1394_SUCCESS != error) { @@ -812,11 +599,7 @@ namespace rl { ::dc1394bool_t canTurnOnOff; -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_is_switchable(this->camera, static_cast<::dc1394feature_t>(feature), &canTurnOnOff); -#else - int error = ::dc1394_can_turn_on_off(this->handle, this->nodes[this->node], feature, &canTurnOnOff); -#endif if (::DC1394_SUCCESS != error) { @@ -829,7 +612,6 @@ namespace rl void Dc1394Camera::open() { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394camera_list_t* list; ::dc1394error_t error = ::dc1394_camera_enumerate(this->dc1394, &list); @@ -844,59 +626,12 @@ namespace rl this->camera = ::dc1394_camera_new(this->dc1394, list->ids[this->node].guid); ::dc1394_camera_free_list(list); -#else - this->handle = ::dc1394_create_handle(0); - - if (nullptr == this->handle) - { - throw Exception("Handle creation failure."); - } - - this->nodes = ::dc1394_get_camera_nodes(handle, &this->cameras, this->port); - - if (nullptr == this->nodes || 1 > this->cameras) - { - throw Exception("No cameras found."); - } - - int error = ::dc1394_get_camera_info(this->handle, this->nodes[this->node], &this->info); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_get_iso_channel_and_speed(this->handle, this->nodes[this->node], &this->channel, &this->speed); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_get_video_framerate(this->handle, this->nodes[this->node], static_cast<::dc1394framerate_t*>(&this->framerate)); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_get_video_mode(this->handle, this->nodes[this->node], static_cast<::dc1394video_mode_t*>(&this->videoMode)); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } -#endif } void Dc1394Camera::reset() { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_camera_reset(this->camera); -#else - int error = ::dc1394_init_camera(this->handle, this->nodes[this->node]); -#endif if (::DC1394_SUCCESS != error) { @@ -907,25 +642,12 @@ namespace rl void Dc1394Camera::setFeatureAbsoluteControl(const Feature& feature, const bool& doOn) { -#if (LIBDC1394_VERSION_MAJOR > 10) -#else - int error = ::dc1394_absolute_setting_on_off(this->handle, this->nodes[this->node], feature, doOn); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } -#endif } void Dc1394Camera::setFeatureEnabled(const Feature& feature, const bool& doOn) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_set_power(this->camera, static_cast<::dc1394feature_t>(feature), static_cast<::dc1394switch_t>(doOn)); -#else - int error = ::dc1394_feature_on_off(this->handle, this->nodes[this->node], feature, doOn); -#endif if (::DC1394_SUCCESS != error) { @@ -936,26 +658,7 @@ namespace rl void Dc1394Camera::setFeatureMode(const Feature& feature, const FeatureMode& mode) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_set_mode(this->camera, static_cast<::dc1394feature_t>(feature), static_cast<::dc1394feature_mode_t>(mode)); -#else - int error; - - switch (mode) - { - case FEATURE_MODE_MANUAL: - error = ::dc1394_auto_on_off(this->handle, this->nodes[this->node], feature, false); - break; - case FEATURE_MODE_AUTO: - error = ::dc1394_auto_on_off(this->handle, this->nodes[this->node], feature, true); - break; - case FEATURE_MODE_ONE_PUSH_AUTO: - error = ::dc1394_start_one_push_operation(this->handle, this->nodes[this->node], feature); - break; - default: - break; - } -#endif if (::DC1394_SUCCESS != error) { @@ -966,11 +669,7 @@ namespace rl void Dc1394Camera::setFeatureValue(const Feature& feature, const unsigned int& value) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_set_value(this->camera, static_cast<::dc1394feature_t>(feature), value); -#else - int error = ::dc1394_set_feature_value(this->handle, this->nodes[this->node], feature, value); -#endif if (::DC1394_SUCCESS != error) { @@ -981,11 +680,7 @@ namespace rl void Dc1394Camera::setFeatureValueAbsolute(const Feature& feature, const float& value) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_feature_set_absolute_value(this->camera, static_cast<::dc1394feature_t>(feature), value); -#else - int error = ::dc1394_set_absolute_feature_value(this->handle, this->nodes[this->node], feature, value); -#endif if (::DC1394_SUCCESS != error) { @@ -993,16 +688,9 @@ namespace rl } } - void - Dc1394Camera::setFilename(const ::std::string& filename) - { - this->filename = filename; - } - void Dc1394Camera::setFormat7(const VideoMode& videoMode, const ColorCoding& colorCoding, const unsigned int& left, const unsigned int& top, const unsigned int& width, const unsigned int& height) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_format7_set_roi( this->camera, static_cast<::dc1394video_mode_t>(videoMode), @@ -1018,7 +706,6 @@ namespace rl { throw Exception(error); } -#endif this->colorCoding = colorCoding; this->height = height; @@ -1031,11 +718,7 @@ namespace rl void Dc1394Camera::setFramerate(const Framerate& framerate) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_video_set_framerate(this->camera, static_cast<::dc1394framerate_t>(framerate)); -#else - int error = ::dc1394_set_video_framerate(this->handle, this->nodes[node], framerate); -#endif if (::DC1394_SUCCESS != error) { @@ -1054,11 +737,7 @@ namespace rl void Dc1394Camera::setOperationMode(const OperationMode& mode) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_video_set_operation_mode(this->camera, static_cast<::dc1394operation_mode_t>(mode)); -#else - int error = ::dc1394_set_operation_mode(this->handle, this->nodes[this->node], mode); -#endif if (::DC1394_SUCCESS != error) { @@ -1069,11 +748,7 @@ namespace rl void Dc1394Camera::setSpeed(const IsoSpeed& speed) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_video_set_iso_speed(this->camera, static_cast<::dc1394speed_t>(speed)); -#else - int error = ::dc1394_set_iso_channel_and_speed(this->handle, this->nodes[node], this->channel, speed); -#endif if (::DC1394_SUCCESS != error) { @@ -1086,37 +761,7 @@ namespace rl void Dc1394Camera::setVideoMode(const VideoMode& videoMode) { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_video_set_mode(this->camera, static_cast<::dc1394video_mode_t>(videoMode)); -#else - unsigned int format; - - if (static_cast(MODE_FORMAT0_MIN) <= this->videoMode && static_cast(MODE_FORMAT0_MAX) >= this->videoMode) - { - format = FORMAT_VGA_NONCOMPRESSED; - } - else if (static_cast(MODE_FORMAT1_MIN) <= this->videoMode && static_cast(MODE_FORMAT1_MAX) >= this->videoMode) - { - format = FORMAT_SVGA_NONCOMPRESSED_1; - } - else if (static_cast(MODE_FORMAT2_MIN) <= this->videoMode && static_cast(MODE_FORMAT2_MAX) >= this->videoMode) - { - format = FORMAT_SVGA_NONCOMPRESSED_2; - } - else if (static_cast(MODE_FORMAT6_MIN) <= this->videoMode && static_cast(MODE_FORMAT6_MAX) >= this->videoMode) - { - format = FORMAT_STILL_IMAGE; - } - - int error = ::dc1394_set_video_format(this->handle, this->nodes[this->node], format); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_set_video_mode(this->handle, this->nodes[this->node], videoMode); -#endif if (::DC1394_SUCCESS != error) { @@ -1129,15 +774,7 @@ namespace rl void Dc1394Camera::start() { -#if (LIBDC1394_VERSION_MAJOR > 10) - ::dc1394error_t error = ::DC1394_SUCCESS;// = ::dc1394_capture_set_device_filename(this->camera, this->filename.c_str()); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_capture_setup(this->camera, this->buffer, 0); + ::dc1394error_t error = ::dc1394_capture_setup(this->camera, this->buffer, 0); if (::DC1394_SUCCESS != error) { @@ -1157,90 +794,6 @@ namespace rl { throw Exception(error); } -#else - int error; - - if (static_cast(MODE_FORMAT7_MIN) <= this->videoMode && static_cast(MODE_FORMAT7_MAX) >= this->videoMode) - { - error = ::dc1394_set_format7_color_coding_id(this->handle, this->nodes[this->node], this->videoMode, this->colorCoding); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_dma_setup_format7_capture( - this->handle, - this->nodes[this->node], - this->channel, - this->videoMode, - this->speed, - QUERY_FROM_CAMERA, - this->left, - this->top, - this->width, - this->height, - this->buffer, - this->drop, - this->filename.c_str(), - &this->camera - ); - } - else - { - unsigned int format; - - if (static_cast(MODE_FORMAT0_MIN) <= this->videoMode && static_cast(MODE_FORMAT0_MAX) >= this->videoMode) - { - format = FORMAT_VGA_NONCOMPRESSED; - } - else if (static_cast(MODE_FORMAT1_MIN) <= this->videoMode && static_cast(MODE_FORMAT1_MAX) >= this->videoMode) - { - format = FORMAT_SVGA_NONCOMPRESSED_1; - } - else if (static_cast(MODE_FORMAT2_MIN) <= this->videoMode && static_cast(MODE_FORMAT2_MAX) >= this->videoMode) - { - format = FORMAT_SVGA_NONCOMPRESSED_2; - } - else if (static_cast(MODE_FORMAT6_MIN) <= this->videoMode && static_cast(MODE_FORMAT6_MAX) >= this->videoMode) - { - format = FORMAT_STILL_IMAGE; - } - - error = ::dc1394_dma_setup_capture( - this->handle, - this->nodes[this->node], - this->channel, - format, - this->videoMode, - this->speed, - this->framerate, - this->buffer, - this->drop, - this->filename.c_str(), - &this->camera - ); - } - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_camera_on(this->handle, this->nodes[this->node]); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_start_iso_transmission(this->handle, this->nodes[this->node]); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } -#endif } void @@ -1251,7 +804,6 @@ namespace rl void Dc1394Camera::stop() { -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error = ::dc1394_video_set_transmission(this->camera, ::DC1394_OFF); if (::DC1394_SUCCESS != error) @@ -1272,42 +824,9 @@ namespace rl { throw Exception(error); } -#else - int error = ::dc1394_stop_iso_transmission(this->handle, this->nodes[this->node]); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_camera_off(this->handle, this->nodes[this->node]); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_dma_unlisten(this->handle, &this->camera); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } - - error = ::dc1394_dma_release_camera(this->handle, &this->camera); - - if (::DC1394_SUCCESS != error) - { - throw Exception(error); - } -#endif } -#if (LIBDC1394_VERSION_MAJOR > 10) Dc1394Camera::Exception::Exception(const ::dc1394error_t& error) : -#else - Dc1394Camera::Exception::Exception(const int& error) : -#endif DeviceException(""), error(error) { @@ -1317,11 +836,7 @@ namespace rl { } -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t -#else - int -#endif Dc1394Camera::Exception::getError() const { return this->error; @@ -1335,23 +850,10 @@ namespace rl case ::DC1394_FAILURE: return "Failure."; break; -#if (LIBDC1394_VERSION_MAJOR > 10) default: return ::dc1394_error_get_string(this->error); break; } -#else - case ::DC1394_NO_FRAME: - return "No frame."; - break; - case ::DC1394_NO_CAMERA: - return "No camera."; - break; - default: - return "Unknown error."; - break; - } -#endif } } } diff --git a/src/rl/hal/Dc1394Camera.h b/src/rl/hal/Dc1394Camera.h index 2f6f4016..23134947 100644 --- a/src/rl/hal/Dc1394Camera.h +++ b/src/rl/hal/Dc1394Camera.h @@ -27,14 +27,8 @@ #ifndef RL_HAL_DC1394CAMERA_H #define RL_HAL_DC1394CAMERA_H -#if (LIBDC1394_VERSION_MAJOR > 10) -#include -#else -#include -#include -#endif - #include +#include #include "Camera.h" #include "CyclicDevice.h" @@ -52,11 +46,7 @@ namespace rl public: enum ColorCoding { -#if (LIBDC1394_VERSION_MAJOR > 10) COLOR_CODING_MONO8 = ::DC1394_COLOR_CODING_MONO8, -#else - COLOR_CODING_MONO8 = ::COLOR_FORMAT7_MONO8, -#endif COLOR_CODING_YUV411, COLOR_CODING_YUV422, COLOR_CODING_YUV444, @@ -71,11 +61,7 @@ namespace rl enum Feature { -#if (LIBDC1394_VERSION_MAJOR > 10) FEATURE_BRIGHTNESS = ::DC1394_FEATURE_BRIGHTNESS, -#else - FEATURE_BRIGHTNESS = ::FEATURE_BRIGHTNESS, -#endif FEATURE_EXPOSURE, FEATURE_SHARPNESS, FEATURE_WHITE_BALANCE, @@ -101,22 +87,14 @@ namespace rl enum FeatureMode { -#if (LIBDC1394_VERSION_MAJOR > 10) FEATURE_MODE_MANUAL = ::DC1394_FEATURE_MODE_MANUAL, -#else - FEATURE_MODE_MANUAL, -#endif FEATURE_MODE_AUTO, FEATURE_MODE_ONE_PUSH_AUTO }; enum Framerate { -#if (LIBDC1394_VERSION_MAJOR > 10) FRAMERATE_1_875 = ::DC1394_FRAMERATE_1_875, -#else - FRAMERATE_1_875 = ::FRAMERATE_1_875, -#endif FRAMERATE_3_75, FRAMERATE_7_5, FRAMERATE_15, @@ -128,11 +106,7 @@ namespace rl enum IsoSpeed { -#if (LIBDC1394_VERSION_MAJOR > 10) ISO_SPEED_100 = ::DC1394_ISO_SPEED_100, -#else - ISO_SPEED_100 = ::SPEED_100, -#endif ISO_SPEED_200, ISO_SPEED_400, ISO_SPEED_800, @@ -142,32 +116,20 @@ namespace rl enum OperationMode { -#if (LIBDC1394_VERSION_MAJOR > 10) OPERATION_MODE_LEGACY = ::DC1394_OPERATION_MODE_LEGACY, -#else - OPERATION_MODE_LEGACY = ::OPERATION_MODE_LEGACY, -#endif OPERATION_MODE_1394B }; enum VideoMode { -#if (LIBDC1394_VERSION_MAJOR > 10) VIDEO_MODE_160x120_YUV444 = ::DC1394_VIDEO_MODE_160x120_YUV444, -#else - VIDEO_MODE_160x120_YUV444 = ::MODE_160x120_YUV444, -#endif VIDEO_MODE_320x240_YUV422, VIDEO_MODE_640x480_YUV411, VIDEO_MODE_640x480_YUV422, VIDEO_MODE_640x480_RGB8, VIDEO_MODE_640x480_MONO8, VIDEO_MODE_640x480_MONO16, -#if (LIBDC1394_VERSION_MAJOR > 10) VIDEO_MODE_800x600_YUV422, -#else - VIDEO_MODE_800x600_YUV422 = ::MODE_800x600_YUV422, -#endif VIDEO_MODE_800x600_RGB8, VIDEO_MODE_800x600_MONO8, VIDEO_MODE_1024x768_YUV422, @@ -175,11 +137,7 @@ namespace rl VIDEO_MODE_1024x768_MONO8, VIDEO_MODE_800x600_MONO16, VIDEO_MODE_1024x768_MONO16, -#if (LIBDC1394_VERSION_MAJOR > 10) VIDEO_MODE_1280x960_YUV422, -#else - VIDEO_MODE_1280x960_YUV422 = ::MODE_1280x960_YUV422, -#endif VIDEO_MODE_1280x960_RGB8, VIDEO_MODE_1280x960_MONO8, VIDEO_MODE_1600x1200_YUV422, @@ -187,16 +145,8 @@ namespace rl VIDEO_MODE_1600x1200_MONO8, VIDEO_MODE_1280x960_MONO16, VIDEO_MODE_1600x1200_MONO16, -#if (LIBDC1394_VERSION_MAJOR > 10) VIDEO_MODE_EXIF, -#else - VIDEO_MODE_EXIF = ::MODE_EXIF, -#endif -#if (LIBDC1394_VERSION_MAJOR > 10) VIDEO_MODE_FORMAT7_0, -#else - VIDEO_MODE_FORMAT7_0 = ::MODE_FORMAT7_0, -#endif VIDEO_MODE_FORMAT7_1, VIDEO_MODE_FORMAT7_2, VIDEO_MODE_FORMAT7_3, @@ -209,33 +159,21 @@ namespace rl class Exception : public DeviceException { public: -#if (LIBDC1394_VERSION_MAJOR > 10) Exception(const ::dc1394error_t& error); -#else - Exception(const int& error); -#endif virtual ~Exception() throw(); -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t getError() const; -#else - int getError() const; -#endif virtual const char* what() const throw(); protected: private: -#if (LIBDC1394_VERSION_MAJOR > 10) ::dc1394error_t error; -#else - int error; -#endif }; - Dc1394Camera(const ::std::string& filename = "", const unsigned int& node = 0); + Dc1394Camera(const unsigned int& node = 0); virtual ~Dc1394Camera(); @@ -261,8 +199,6 @@ namespace rl float getFeatureValueAbsolute(const Feature& feature) const; - ::std::string getFilename() const; - void getFormat7(VideoMode& videoMode, ColorCoding& colorCoding, unsigned int& left, unsigned int& top, unsigned int& width, unsigned int& height) const; void getFormat7MaximumImageSize(const unsigned int& mode, unsigned int& width, unsigned& height) const; @@ -313,8 +249,6 @@ namespace rl void setFeatureValueAbsolute(const Feature& feature, const float& value); - void setFilename(const ::std::string& filename); - void setFormat7(const VideoMode& videoMode, const ColorCoding& colorCoding, const unsigned int& left, const unsigned int& top, const unsigned int& width, const unsigned int& height); void setFramerate(const Framerate& framerate); @@ -338,7 +272,6 @@ namespace rl protected: private: -#if (LIBDC1394_VERSION_MAJOR > 10) unsigned int buffer; ::dc1394camera_t* camera; @@ -349,8 +282,6 @@ namespace rl ::dc1394_t* dc1394; - ::std::string filename; - ::dc1394video_frame_t* frame; Framerate framerate; @@ -368,45 +299,6 @@ namespace rl VideoMode videoMode; unsigned int width; -#else - unsigned int buffer; - - ::dc1394_cameracapture camera; - - int cameras; - - unsigned int channel; - - ColorCoding colorCoding; - - unsigned int drop; - - ::std::string filename; - - Framerate framerate; - - ::raw1394handle_t handle; - - unsigned int height; - - ::dc1394_camerainfo info; - - unsigned int left; - - unsigned int node; - - nodeid_t* nodes; - - unsigned int port; - - unsigned int speed; - - unsigned int top; - - VideoMode videoMode; - - unsigned int width; -#endif }; } } From 326fe85a9c60171c43df097e1cb5e1c9412fdf33 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 13 Jun 2020 23:33:49 +0200 Subject: [PATCH 363/546] Add item group for collisions --- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 44 ++++++++++++-------- demos/rlPlanDemo/ConfigurationSpaceScene.h | 2 + 2 files changed, 28 insertions(+), 18 deletions(-) diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 3647ae31..2ab61dd9 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -41,6 +41,7 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : delta0(1), delta1(1), model(nullptr), + collisions(nullptr), edges(nullptr), path(nullptr), scene(nullptr), @@ -73,19 +74,17 @@ ConfigurationSpaceScene::addCollision(const qreal& x, const qreal& y, const qrea QBrush(QColor(rgb, rgb, rgb)) ); - rect->setParentItem(this->scene); - rect->setZValue(1); + this->collisions->addToGroup(rect); } void ConfigurationSpaceScene::clear() { - QList items = this->items(); - - while (!items.isEmpty()) - { - delete items.takeFirst(); - } + QGraphicsScene::clear(); + this->collisions = nullptr; + this->edges = nullptr; + this->path = nullptr; + this->scene = nullptr; } void @@ -104,8 +103,6 @@ ConfigurationSpaceScene::drawConfigurationEdge(const rl::math::Vector& u, const free ? QPen(QBrush(QColor(0, 128, 0)), 0) : QPen(QBrush(QColor(128, 0, 0)), 0) ); - line->setZValue(2); - this->edges->addToGroup(line); } @@ -122,7 +119,7 @@ ConfigurationSpaceScene::drawConfigurationPath(const rl::plan::VectorList& path) rl::plan::VectorList::const_iterator i = path.begin(); rl::plan::VectorList::const_iterator j = ++path.begin(); - while (i != path.end() && j != path.end()) + for (; i != path.end() && j != path.end(); ++i, ++j) { QGraphicsLineItem* line = this->addLine( (*i)(this->axis0), @@ -132,12 +129,7 @@ ConfigurationSpaceScene::drawConfigurationPath(const rl::plan::VectorList& path) QPen(QBrush(QColor(0, 255, 0)), 0) ); - line->setZValue(3); - this->path->addToGroup(line); - - ++i; - ++j; } } @@ -235,8 +227,14 @@ ConfigurationSpaceScene::init() this->setSceneRect(this->scene->boundingRect()); - this->edges = new QGraphicsItemGroup(this->scene); - this->path = new QGraphicsItemGroup(this->scene); + this->collisions = this->createItemGroup(QList()); + this->collisions->setZValue(1); + + this->edges = this->createItemGroup(QList()); + this->edges->setZValue(2); + + this->path = this->createItemGroup(QList()); + this->path->setZValue(3); } void @@ -295,6 +293,11 @@ ConfigurationSpaceScene::reset() void ConfigurationSpaceScene::resetEdges() { + if (nullptr == this->edges) + { + return; + } + QList items = this->edges->childItems(); while (!items.isEmpty()) @@ -311,6 +314,11 @@ ConfigurationSpaceScene::resetLines() void ConfigurationSpaceScene::resetPath() { + if (nullptr == this->path) + { + return; + } + QList items = this->path->childItems(); while (!items.isEmpty()) diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.h b/demos/rlPlanDemo/ConfigurationSpaceScene.h index 7ac16d65..323adbbe 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.h +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.h @@ -108,6 +108,8 @@ public slots: void mousePressEvent(QGraphicsSceneMouseEvent* mouseEvent); private: + QGraphicsItemGroup* collisions; + QGraphicsItemGroup* edges; QGraphicsItemGroup* path; From e829de61533b95c4ab9fcc42a49c49f15b9a05f6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 14 Jun 2020 00:32:07 +0200 Subject: [PATCH 364/546] Fix whitespace --- cmake/FindODE.cmake | 2 +- cmake/FindSoQt.cmake | 2 +- cmake/FindXenomai.cmake | 2 +- demos/rlCoachKin/ConfigurationDelegate.cpp | 2 +- demos/rlCoachKin/ConfigurationModel.h | 4 +- demos/rlCoachKin/OperationalDelegate.cpp | 2 +- demos/rlCoachKin/OperationalModel.h | 2 +- demos/rlCoachMdl/ConfigurationDelegate.cpp | 2 +- demos/rlCoachMdl/ConfigurationModel.h | 4 +- demos/rlCoachMdl/OperationalDelegate.cpp | 2 +- demos/rlCoachMdl/OperationalModel.h | 2 +- demos/rlCollisionDemo/BodyDelegate.cpp | 2 +- demos/rlCollisionDemo/BodyModel.h | 2 +- demos/rlPlanDemo/ConfigurationDelegate.cpp | 2 +- demos/rlPlanDemo/ConfigurationModel.h | 2 +- demos/rlPlanDemo/ConfigurationSpaceModel.h | 2 +- demos/rlPlanDemo/PlannerModel.h | 2 +- .../rlRotationConverterDemo/AngleAxisModel.h | 2 +- .../EulerAnglesModel.h | 2 +- .../rlRotationConverterDemo/QuaternionModel.h | 2 +- .../RotationMatrixModel.h | 2 +- demos/rlSimulator/ConfigurationDelegate.cpp | 2 +- demos/rlSimulator/ConfigurationModel.h | 4 +- demos/rlSimulator/MainWindow.cpp | 10 +- demos/rlSimulator/OperationalDelegate.cpp | 2 +- demos/rlSimulator/OperationalModel.h | 2 +- demos/rlThreadsDemo/rlThreadsDemo.cpp | 2 +- src/rl/hal/Dc1394Camera.cpp | 64 +++++------ src/rl/hal/Dc1394Camera.h | 2 +- src/rl/hal/LeuzeRs4.cpp | 2 +- src/rl/hal/MitsubishiH7.h | 2 +- src/rl/hal/MitsubishiR3.h | 40 +++---- src/rl/hal/RobotiqModelC.cpp | 2 +- src/rl/hal/SchmersalLss300.cpp | 2 +- src/rl/hal/Serial.cpp | 4 +- src/rl/hal/SickLms200.cpp | 2 +- src/rl/hal/UniversalRobotsRealtime.h | 2 +- src/rl/hal/WeissKms40.h | 2 +- src/rl/hal/WeissWsg50.h | 8 +- src/rl/kin/Kinematics.h | 60 +++++------ src/rl/kin/Puma.cpp | 4 +- src/rl/mainpage.dox | 6 +- src/rl/math/Circular.h | 1 - src/rl/math/CircularVector2.h | 12 +-- src/rl/math/CircularVector3.h | 10 +- src/rl/math/Function.h | 12 +-- src/rl/math/GnatNearestNeighbors.h | 4 +- src/rl/math/Kalman.h | 14 +-- .../math/KdtreeBoundingBoxNearestNeighbors.h | 4 +- src/rl/math/KdtreeNearestNeighbors.h | 4 +- src/rl/math/MatrixBaseAddons.h | 16 +-- src/rl/math/Pid.h | 4 +- src/rl/math/Polynomial.h | 16 +-- src/rl/math/QuaternionBaseAddons.h | 8 +- src/rl/math/Spline.h | 74 ++++++------- src/rl/math/TransformAddons.h | 4 +- src/rl/math/Unit.h | 6 +- src/rl/math/spatial/PlueckerTransform.h | 2 +- src/rl/mdl/Dynamic.h | 102 +++++++++--------- src/rl/mdl/EulerCauchyIntegrator.h | 6 +- src/rl/mdl/JacobianInverseKinematics.h | 4 +- src/rl/mdl/Kinematic.h | 82 +++++++------- src/rl/mdl/Model.h | 2 +- src/rl/mdl/RungeKuttaNystromIntegrator.h | 6 +- src/rl/mdl/UrdfFactory.cpp | 2 +- src/rl/plan/AddRrtConCon.h | 4 +- src/rl/plan/BridgeSampler.h | 4 +- src/rl/plan/Eet.h | 4 +- src/rl/plan/GaussianSampler.h | 4 +- src/rl/plan/Planner.h | 4 +- src/rl/plan/Prm.h | 10 +- src/rl/plan/PrmUtilityGuided.cpp | 6 +- src/rl/plan/PrmUtilityGuided.h | 4 +- src/rl/plan/Rrt.h | 6 +- src/rl/plan/RrtCon.h | 4 +- src/rl/plan/RrtConCon.h | 4 +- src/rl/plan/WorkspaceSphere.h | 2 +- src/rl/plan/WorkspaceSphereExplorer.h | 4 +- src/rl/sg/bullet/Scene.cpp | 2 +- src/rl/sg/bullet/Scene.h | 4 +- src/rl/sg/fcl/Body.cpp | 2 +- src/rl/sg/fcl/Model.cpp | 4 +- src/rl/sg/fcl/Scene.cpp | 4 +- src/rl/sg/fcl/Scene.h | 2 +- src/rl/sg/ode/Scene.cpp | 4 +- src/rl/sg/ode/Scene.h | 2 +- src/rl/sg/pqp/Scene.h | 2 +- src/rl/sg/solid/Scene.h | 2 +- src/rl/xml/Attribute.h | 2 +- tests/rlCollisionTest/rlCollisionTest.cpp | 2 +- tests/rlJacobianKinTest/rlJacobianKinTest.cpp | 4 +- tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp | 4 +- .../rlSplineTest/rlPolynomialExtremaTest.cpp | 2 +- tests/rlSplineTest/rlSplineTest.cpp | 2 +- 94 files changed, 382 insertions(+), 387 deletions(-) diff --git a/cmake/FindODE.cmake b/cmake/FindODE.cmake index 4cddb193..6056ce6c 100644 --- a/cmake/FindODE.cmake +++ b/cmake/FindODE.cmake @@ -162,7 +162,7 @@ if(ODE_INCLUDE_DIRS AND ODE_LIBRARIES) endif() endif() -mark_as_advanced(ODE_DEFINITIONS) +mark_as_advanced(ODE_DEFINITIONS) find_package_handle_standard_args( ODE diff --git a/cmake/FindSoQt.cmake b/cmake/FindSoQt.cmake index 05e7cea7..69af1329 100644 --- a/cmake/FindSoQt.cmake +++ b/cmake/FindSoQt.cmake @@ -122,7 +122,7 @@ select_library_configurations(SoQt) set(SoQt_DEFINITIONS -DSOQT_DLL) -mark_as_advanced(SoQt_DEFINITIONS) +mark_as_advanced(SoQt_DEFINITIONS) if(EXISTS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h") file(STRINGS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h" GUI_TOOLKIT_VERSION_DEFINE REGEX "#define GUI_TOOLKIT_VERSION.*[0-9]+.*") diff --git a/cmake/FindXenomai.cmake b/cmake/FindXenomai.cmake index 708e84e0..ea6c8675 100644 --- a/cmake/FindXenomai.cmake +++ b/cmake/FindXenomai.cmake @@ -153,7 +153,7 @@ set(Xenomai_LIBRARIES ${Xenomai_NATIVE_LIBRARIES} ${Xenomai_XENOMAI_LIBRARIES} p set(Xenomai_DEFINITIONS -D__XENO__ -D_GNU_SOURCE -D_REENTRANT) -mark_as_advanced(Xenomai_DEFINITIONS) +mark_as_advanced(Xenomai_DEFINITIONS) find_package_handle_standard_args( Xenomai diff --git a/demos/rlCoachKin/ConfigurationDelegate.cpp b/demos/rlCoachKin/ConfigurationDelegate.cpp index dee7c273..2d0101da 100644 --- a/demos/rlCoachKin/ConfigurationDelegate.cpp +++ b/demos/rlCoachKin/ConfigurationDelegate.cpp @@ -99,7 +99,7 @@ void ConfigurationDelegate::updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const { editor->setGeometry(option.rect); -} +} void ConfigurationDelegate::valueChanged(double d) diff --git a/demos/rlCoachKin/ConfigurationModel.h b/demos/rlCoachKin/ConfigurationModel.h index dc09e3d2..8ab8c2f2 100644 --- a/demos/rlCoachKin/ConfigurationModel.h +++ b/demos/rlCoachKin/ConfigurationModel.h @@ -49,9 +49,9 @@ class ConfigurationModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); - bool setData(const rl::math::Vector& q); + bool setData(const rl::math::Vector& q); std::size_t id; diff --git a/demos/rlCoachKin/OperationalDelegate.cpp b/demos/rlCoachKin/OperationalDelegate.cpp index a33a5b61..f537bd77 100644 --- a/demos/rlCoachKin/OperationalDelegate.cpp +++ b/demos/rlCoachKin/OperationalDelegate.cpp @@ -93,7 +93,7 @@ void OperationalDelegate::updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const { editor->setGeometry(option.rect); -} +} void OperationalDelegate::valueChanged(double d) diff --git a/demos/rlCoachKin/OperationalModel.h b/demos/rlCoachKin/OperationalModel.h index b24153dd..d5c31810 100644 --- a/demos/rlCoachKin/OperationalModel.h +++ b/demos/rlCoachKin/OperationalModel.h @@ -48,7 +48,7 @@ class OperationalModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); std::size_t id; diff --git a/demos/rlCoachMdl/ConfigurationDelegate.cpp b/demos/rlCoachMdl/ConfigurationDelegate.cpp index 46fc3bbd..65953e8b 100644 --- a/demos/rlCoachMdl/ConfigurationDelegate.cpp +++ b/demos/rlCoachMdl/ConfigurationDelegate.cpp @@ -98,7 +98,7 @@ void ConfigurationDelegate::updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const { editor->setGeometry(option.rect); -} +} void ConfigurationDelegate::valueChanged(double d) diff --git a/demos/rlCoachMdl/ConfigurationModel.h b/demos/rlCoachMdl/ConfigurationModel.h index dc09e3d2..8ab8c2f2 100644 --- a/demos/rlCoachMdl/ConfigurationModel.h +++ b/demos/rlCoachMdl/ConfigurationModel.h @@ -49,9 +49,9 @@ class ConfigurationModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); - bool setData(const rl::math::Vector& q); + bool setData(const rl::math::Vector& q); std::size_t id; diff --git a/demos/rlCoachMdl/OperationalDelegate.cpp b/demos/rlCoachMdl/OperationalDelegate.cpp index a33a5b61..f537bd77 100644 --- a/demos/rlCoachMdl/OperationalDelegate.cpp +++ b/demos/rlCoachMdl/OperationalDelegate.cpp @@ -93,7 +93,7 @@ void OperationalDelegate::updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const { editor->setGeometry(option.rect); -} +} void OperationalDelegate::valueChanged(double d) diff --git a/demos/rlCoachMdl/OperationalModel.h b/demos/rlCoachMdl/OperationalModel.h index b24153dd..d5c31810 100644 --- a/demos/rlCoachMdl/OperationalModel.h +++ b/demos/rlCoachMdl/OperationalModel.h @@ -48,7 +48,7 @@ class OperationalModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); std::size_t id; diff --git a/demos/rlCollisionDemo/BodyDelegate.cpp b/demos/rlCollisionDemo/BodyDelegate.cpp index f3efa20c..7f48504c 100644 --- a/demos/rlCollisionDemo/BodyDelegate.cpp +++ b/demos/rlCollisionDemo/BodyDelegate.cpp @@ -94,7 +94,7 @@ void BodyDelegate::updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const { editor->setGeometry(option.rect); -} +} void BodyDelegate::valueChanged(double d) diff --git a/demos/rlCollisionDemo/BodyModel.h b/demos/rlCollisionDemo/BodyModel.h index 8ca36c07..938f4465 100644 --- a/demos/rlCollisionDemo/BodyModel.h +++ b/demos/rlCollisionDemo/BodyModel.h @@ -51,7 +51,7 @@ class BodyModel : public QAbstractTableModel void setBody(rl::sg::Body* collision, rl::sg::Body* view); - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); protected: diff --git a/demos/rlPlanDemo/ConfigurationDelegate.cpp b/demos/rlPlanDemo/ConfigurationDelegate.cpp index d4c93bc5..e3989576 100644 --- a/demos/rlPlanDemo/ConfigurationDelegate.cpp +++ b/demos/rlPlanDemo/ConfigurationDelegate.cpp @@ -90,7 +90,7 @@ void ConfigurationDelegate::updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const { editor->setGeometry(option.rect); -} +} void ConfigurationDelegate::valueChanged(double d) diff --git a/demos/rlPlanDemo/ConfigurationModel.h b/demos/rlPlanDemo/ConfigurationModel.h index cba8a4e4..6ddc96ec 100644 --- a/demos/rlPlanDemo/ConfigurationModel.h +++ b/demos/rlPlanDemo/ConfigurationModel.h @@ -48,7 +48,7 @@ class ConfigurationModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); protected: diff --git a/demos/rlPlanDemo/ConfigurationSpaceModel.h b/demos/rlPlanDemo/ConfigurationSpaceModel.h index 9cae8ce3..2ed66177 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceModel.h +++ b/demos/rlPlanDemo/ConfigurationSpaceModel.h @@ -50,7 +50,7 @@ class ConfigurationSpaceModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); ConfigurationSpaceScene* configurationSpaceScene; diff --git a/demos/rlPlanDemo/PlannerModel.h b/demos/rlPlanDemo/PlannerModel.h index e713ac57..d3ed5997 100644 --- a/demos/rlPlanDemo/PlannerModel.h +++ b/demos/rlPlanDemo/PlannerModel.h @@ -48,7 +48,7 @@ class PlannerModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); protected: diff --git a/demos/rlRotationConverterDemo/AngleAxisModel.h b/demos/rlRotationConverterDemo/AngleAxisModel.h index 1969f78e..1faa3581 100644 --- a/demos/rlRotationConverterDemo/AngleAxisModel.h +++ b/demos/rlRotationConverterDemo/AngleAxisModel.h @@ -51,7 +51,7 @@ class AngleAxisModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); rl::math::AngleAxis* angleAxis; diff --git a/demos/rlRotationConverterDemo/EulerAnglesModel.h b/demos/rlRotationConverterDemo/EulerAnglesModel.h index f100d678..c19c734c 100644 --- a/demos/rlRotationConverterDemo/EulerAnglesModel.h +++ b/demos/rlRotationConverterDemo/EulerAnglesModel.h @@ -52,7 +52,7 @@ class EulerAnglesModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); rl::math::Vector3* eulerAngles; diff --git a/demos/rlRotationConverterDemo/QuaternionModel.h b/demos/rlRotationConverterDemo/QuaternionModel.h index c8c6f857..59b16712 100644 --- a/demos/rlRotationConverterDemo/QuaternionModel.h +++ b/demos/rlRotationConverterDemo/QuaternionModel.h @@ -51,7 +51,7 @@ class QuaternionModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); rl::math::Quaternion* quaternion; diff --git a/demos/rlRotationConverterDemo/RotationMatrixModel.h b/demos/rlRotationConverterDemo/RotationMatrixModel.h index 7bee1124..b4b5a056 100644 --- a/demos/rlRotationConverterDemo/RotationMatrixModel.h +++ b/demos/rlRotationConverterDemo/RotationMatrixModel.h @@ -51,7 +51,7 @@ class RotationMatrixModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); rl::math::Matrix33* rotation; diff --git a/demos/rlSimulator/ConfigurationDelegate.cpp b/demos/rlSimulator/ConfigurationDelegate.cpp index 48c156f1..017c685c 100644 --- a/demos/rlSimulator/ConfigurationDelegate.cpp +++ b/demos/rlSimulator/ConfigurationDelegate.cpp @@ -65,7 +65,7 @@ void ConfigurationDelegate::updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const { editor->setGeometry(option.rect); -} +} void ConfigurationDelegate::valueChanged(double d) diff --git a/demos/rlSimulator/ConfigurationModel.h b/demos/rlSimulator/ConfigurationModel.h index 076ca5db..8cd300a9 100644 --- a/demos/rlSimulator/ConfigurationModel.h +++ b/demos/rlSimulator/ConfigurationModel.h @@ -49,9 +49,9 @@ class ConfigurationModel : public QAbstractTableModel virtual int rowCount(const QModelIndex& parent = QModelIndex()) const = 0; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); - bool setData(const rl::math::Vector& q); + bool setData(const rl::math::Vector& q); public slots: void operationalChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index 8138e593..39c843d2 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -363,19 +363,19 @@ MainWindow::~MainWindow() MainWindow::singleton = nullptr; } -void +void MainWindow::changeSimulationGravity(double value) { this->simulationGravityValue = value; } -void +void MainWindow::changeSimulationDampingFactor(double value) { this->simulationDampingValue = value; } -void +void MainWindow::clickSimulationStart() { this->simulationIsRunning = true; @@ -451,7 +451,7 @@ MainWindow::timerEvent(QTimerEvent *event) rl::math::Vector torque(this->dynamicModel->getDof()); rl::math::Matrix M(this->dynamicModel->getDof(), this->dynamicModel->getDof()); -#if 1 +#if 1 for (int i = 0; i < this->simulationStepsPerFrame; ++i) { this->dynamicModel->setTorque(this->externalTorque); @@ -468,7 +468,7 @@ MainWindow::timerEvent(QTimerEvent *event) this->dynamicModel->setVelocity(qd); this->dynamicModel->setAcceleration(qdd); #else - this->dynamicModel->rungeKuttaNystrom(simulationTimeStep); // its side effects do not work with damping + this->dynamicModel->rungeKuttaNystrom(simulationTimeStep); // its side effects do not work with damping #endif } diff --git a/demos/rlSimulator/OperationalDelegate.cpp b/demos/rlSimulator/OperationalDelegate.cpp index 29a074fb..6b1daf68 100644 --- a/demos/rlSimulator/OperationalDelegate.cpp +++ b/demos/rlSimulator/OperationalDelegate.cpp @@ -91,7 +91,7 @@ void OperationalDelegate::updateEditorGeometry(QWidget* editor, const QStyleOptionViewItem& option, const QModelIndex& index) const { editor->setGeometry(option.rect); -} +} void OperationalDelegate::valueChanged(double d) diff --git a/demos/rlSimulator/OperationalModel.h b/demos/rlSimulator/OperationalModel.h index b52ec802..cc774be9 100644 --- a/demos/rlSimulator/OperationalModel.h +++ b/demos/rlSimulator/OperationalModel.h @@ -47,7 +47,7 @@ class OperationalModel : public QAbstractTableModel int rowCount(const QModelIndex& parent = QModelIndex()) const; - bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); + bool setData(const QModelIndex& index, const QVariant& value, int role = Qt::EditRole); public slots: void configurationChanged(const QModelIndex& topLeft, const QModelIndex& bottomRight); diff --git a/demos/rlThreadsDemo/rlThreadsDemo.cpp b/demos/rlThreadsDemo/rlThreadsDemo.cpp index be4aa92f..75b6f077 100644 --- a/demos/rlThreadsDemo/rlThreadsDemo.cpp +++ b/demos/rlThreadsDemo/rlThreadsDemo.cpp @@ -37,7 +37,7 @@ void run(const std::size_t& i) for (std::size_t j = 0; j < 5; ++j) { - double seconds = rand(); + double seconds = rand(); std::this_thread::sleep_for(std::chrono::duration(seconds)); std::cout << "Thread[" << i << "] - " << j << " - " << seconds << " seconds" << std::endl; } diff --git a/src/rl/hal/Dc1394Camera.cpp b/src/rl/hal/Dc1394Camera.cpp index 23930bf8..dfb1fba5 100644 --- a/src/rl/hal/Dc1394Camera.cpp +++ b/src/rl/hal/Dc1394Camera.cpp @@ -222,7 +222,7 @@ namespace rl unsigned int width; unsigned int height; - ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast<::dc1394video_mode_t>(this->videoMode), &width, &height); + ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast<::dc1394video_mode_t>(this->videoMode), &width, &height); if (::DC1394_SUCCESS != error) { @@ -250,7 +250,7 @@ namespace rl void Dc1394Camera::getFeatureBoundaries(const Feature& feature, unsigned int& min, unsigned int& max) const { - ::dc1394error_t error = ::dc1394_feature_get_boundaries(this->camera, static_cast<::dc1394feature_t>(feature), &min, &max); + ::dc1394error_t error = ::dc1394_feature_get_boundaries(this->camera, static_cast<::dc1394feature_t>(feature), &min, &max); if (::DC1394_SUCCESS != error) { @@ -261,7 +261,7 @@ namespace rl void Dc1394Camera::getFeatureBoundariesAbsolute(const Feature& feature, float& min, float& max) const { - ::dc1394error_t error = ::dc1394_feature_get_absolute_boundaries(this->camera, static_cast<::dc1394feature_t>(feature), &min, &max); + ::dc1394error_t error = ::dc1394_feature_get_absolute_boundaries(this->camera, static_cast<::dc1394feature_t>(feature), &min, &max); if (::DC1394_SUCCESS != error) { @@ -274,7 +274,7 @@ namespace rl { ::dc1394feature_mode_t mode; - ::dc1394error_t error = ::dc1394_feature_get_mode(this->camera, static_cast<::dc1394feature_t>(feature), &mode); + ::dc1394error_t error = ::dc1394_feature_get_mode(this->camera, static_cast<::dc1394feature_t>(feature), &mode); if (::DC1394_SUCCESS != error) { @@ -322,7 +322,7 @@ namespace rl { unsigned int value; - ::dc1394error_t error = ::dc1394_feature_get_value(this->camera, static_cast<::dc1394feature_t>(feature), &value); + ::dc1394error_t error = ::dc1394_feature_get_value(this->camera, static_cast<::dc1394feature_t>(feature), &value); if (::DC1394_SUCCESS != error) { @@ -337,7 +337,7 @@ namespace rl { float value; - ::dc1394error_t error = ::dc1394_feature_get_absolute_value(this->camera, static_cast<::dc1394feature_t>(feature), &value); + ::dc1394error_t error = ::dc1394_feature_get_absolute_value(this->camera, static_cast<::dc1394feature_t>(feature), &value); if (::DC1394_SUCCESS != error) { @@ -361,7 +361,7 @@ namespace rl void Dc1394Camera::getFormat7MaximumImageSize(const unsigned int& mode, unsigned int& width, unsigned& height) const { - ::dc1394error_t error = ::dc1394_format7_get_max_image_size(this->camera, static_cast<::dc1394video_mode_t>(mode), &width, &height); + ::dc1394error_t error = ::dc1394_format7_get_max_image_size(this->camera, static_cast<::dc1394video_mode_t>(mode), &width, &height); if (::DC1394_SUCCESS != error) { @@ -401,7 +401,7 @@ namespace rl { OperationMode operationMode; - ::dc1394error_t error = ::dc1394_video_get_operation_mode(this->camera, reinterpret_cast<::dc1394operation_mode_t*>(&operationMode)); + ::dc1394error_t error = ::dc1394_video_get_operation_mode(this->camera, reinterpret_cast<::dc1394operation_mode_t*>(&operationMode)); if (::DC1394_SUCCESS != error) { @@ -417,7 +417,7 @@ namespace rl unsigned int width; unsigned int height; - ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast<::dc1394video_mode_t>(this->videoMode), &width, &height); + ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast<::dc1394video_mode_t>(this->videoMode), &width, &height); if (::DC1394_SUCCESS != error) { @@ -488,7 +488,7 @@ namespace rl { VideoMode videoMode; - ::dc1394error_t error = ::dc1394_video_get_mode(this->camera, reinterpret_cast<::dc1394video_mode_t*>(&videoMode)); + ::dc1394error_t error = ::dc1394_video_get_mode(this->camera, reinterpret_cast<::dc1394video_mode_t*>(&videoMode)); if (::DC1394_SUCCESS != error) { @@ -504,7 +504,7 @@ namespace rl unsigned int width; unsigned int height; - ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast<::dc1394video_mode_t>(this->videoMode), &width, &height); + ::dc1394error_t error = ::dc1394_get_image_size_from_video_mode(this->camera, static_cast<::dc1394video_mode_t>(this->videoMode), &width, &height); if (::DC1394_SUCCESS != error) { @@ -517,7 +517,7 @@ namespace rl void Dc1394Camera::grab(unsigned char* image) { - ::dc1394error_t error = ::dc1394_capture_dequeue(this->camera, ::DC1394_CAPTURE_POLICY_WAIT, &this->frame); + ::dc1394error_t error = ::dc1394_capture_dequeue(this->camera, ::DC1394_CAPTURE_POLICY_WAIT, &this->frame); if (::DC1394_SUCCESS != error) { @@ -539,7 +539,7 @@ namespace rl { ::dc1394bool_t hasAbsoluteControl; - ::dc1394error_t error = ::dc1394_feature_has_absolute_control(this->camera, static_cast<::dc1394feature_t>(feature), &hasAbsoluteControl); + ::dc1394error_t error = ::dc1394_feature_has_absolute_control(this->camera, static_cast<::dc1394feature_t>(feature), &hasAbsoluteControl); if (::DC1394_SUCCESS != error) { @@ -554,7 +554,7 @@ namespace rl { ::dc1394switch_t isFeatureOn; - ::dc1394error_t error = ::dc1394_feature_get_power(this->camera, static_cast<::dc1394feature_t>(feature), &isFeatureOn); + ::dc1394error_t error = ::dc1394_feature_get_power(this->camera, static_cast<::dc1394feature_t>(feature), &isFeatureOn); if (::DC1394_SUCCESS != error) { @@ -569,7 +569,7 @@ namespace rl { ::dc1394bool_t isFeaturePresent; - ::dc1394error_t error = ::dc1394_feature_is_present(this->camera, static_cast<::dc1394feature_t>(feature), &isFeaturePresent); + ::dc1394error_t error = ::dc1394_feature_is_present(this->camera, static_cast<::dc1394feature_t>(feature), &isFeaturePresent); if (::DC1394_SUCCESS != error) { @@ -584,7 +584,7 @@ namespace rl { ::dc1394bool_t canReadOut; - ::dc1394error_t error = ::dc1394_feature_is_readable(this->camera, static_cast<::dc1394feature_t>(feature), &canReadOut); + ::dc1394error_t error = ::dc1394_feature_is_readable(this->camera, static_cast<::dc1394feature_t>(feature), &canReadOut); if (::DC1394_SUCCESS != error) { @@ -599,7 +599,7 @@ namespace rl { ::dc1394bool_t canTurnOnOff; - ::dc1394error_t error = ::dc1394_feature_is_switchable(this->camera, static_cast<::dc1394feature_t>(feature), &canTurnOnOff); + ::dc1394error_t error = ::dc1394_feature_is_switchable(this->camera, static_cast<::dc1394feature_t>(feature), &canTurnOnOff); if (::DC1394_SUCCESS != error) { @@ -631,7 +631,7 @@ namespace rl void Dc1394Camera::reset() { - ::dc1394error_t error = ::dc1394_camera_reset(this->camera); + ::dc1394error_t error = ::dc1394_camera_reset(this->camera); if (::DC1394_SUCCESS != error) { @@ -647,7 +647,7 @@ namespace rl void Dc1394Camera::setFeatureEnabled(const Feature& feature, const bool& doOn) { - ::dc1394error_t error = ::dc1394_feature_set_power(this->camera, static_cast<::dc1394feature_t>(feature), static_cast<::dc1394switch_t>(doOn)); + ::dc1394error_t error = ::dc1394_feature_set_power(this->camera, static_cast<::dc1394feature_t>(feature), static_cast<::dc1394switch_t>(doOn)); if (::DC1394_SUCCESS != error) { @@ -658,7 +658,7 @@ namespace rl void Dc1394Camera::setFeatureMode(const Feature& feature, const FeatureMode& mode) { - ::dc1394error_t error = ::dc1394_feature_set_mode(this->camera, static_cast<::dc1394feature_t>(feature), static_cast<::dc1394feature_mode_t>(mode)); + ::dc1394error_t error = ::dc1394_feature_set_mode(this->camera, static_cast<::dc1394feature_t>(feature), static_cast<::dc1394feature_mode_t>(mode)); if (::DC1394_SUCCESS != error) { @@ -669,7 +669,7 @@ namespace rl void Dc1394Camera::setFeatureValue(const Feature& feature, const unsigned int& value) { - ::dc1394error_t error = ::dc1394_feature_set_value(this->camera, static_cast<::dc1394feature_t>(feature), value); + ::dc1394error_t error = ::dc1394_feature_set_value(this->camera, static_cast<::dc1394feature_t>(feature), value); if (::DC1394_SUCCESS != error) { @@ -680,7 +680,7 @@ namespace rl void Dc1394Camera::setFeatureValueAbsolute(const Feature& feature, const float& value) { - ::dc1394error_t error = ::dc1394_feature_set_absolute_value(this->camera, static_cast<::dc1394feature_t>(feature), value); + ::dc1394error_t error = ::dc1394_feature_set_absolute_value(this->camera, static_cast<::dc1394feature_t>(feature), value); if (::DC1394_SUCCESS != error) { @@ -700,7 +700,7 @@ namespace rl top, width, height - ); + ); if (::DC1394_SUCCESS != error) { @@ -718,7 +718,7 @@ namespace rl void Dc1394Camera::setFramerate(const Framerate& framerate) { - ::dc1394error_t error = ::dc1394_video_set_framerate(this->camera, static_cast<::dc1394framerate_t>(framerate)); + ::dc1394error_t error = ::dc1394_video_set_framerate(this->camera, static_cast<::dc1394framerate_t>(framerate)); if (::DC1394_SUCCESS != error) { @@ -737,7 +737,7 @@ namespace rl void Dc1394Camera::setOperationMode(const OperationMode& mode) { - ::dc1394error_t error = ::dc1394_video_set_operation_mode(this->camera, static_cast<::dc1394operation_mode_t>(mode)); + ::dc1394error_t error = ::dc1394_video_set_operation_mode(this->camera, static_cast<::dc1394operation_mode_t>(mode)); if (::DC1394_SUCCESS != error) { @@ -748,7 +748,7 @@ namespace rl void Dc1394Camera::setSpeed(const IsoSpeed& speed) { - ::dc1394error_t error = ::dc1394_video_set_iso_speed(this->camera, static_cast<::dc1394speed_t>(speed)); + ::dc1394error_t error = ::dc1394_video_set_iso_speed(this->camera, static_cast<::dc1394speed_t>(speed)); if (::DC1394_SUCCESS != error) { @@ -761,7 +761,7 @@ namespace rl void Dc1394Camera::setVideoMode(const VideoMode& videoMode) { - ::dc1394error_t error = ::dc1394_video_set_mode(this->camera, static_cast<::dc1394video_mode_t>(videoMode)); + ::dc1394error_t error = ::dc1394_video_set_mode(this->camera, static_cast<::dc1394video_mode_t>(videoMode)); if (::DC1394_SUCCESS != error) { @@ -781,14 +781,14 @@ namespace rl throw Exception(error); } - error = ::dc1394_camera_set_power(this->camera, ::DC1394_ON); + error = ::dc1394_camera_set_power(this->camera, ::DC1394_ON); if (::DC1394_SUCCESS != error) { throw Exception(error); } - error = ::dc1394_video_set_transmission(this->camera, ::DC1394_ON); + error = ::dc1394_video_set_transmission(this->camera, ::DC1394_ON); if (::DC1394_SUCCESS != error) { @@ -804,7 +804,7 @@ namespace rl void Dc1394Camera::stop() { - ::dc1394error_t error = ::dc1394_video_set_transmission(this->camera, ::DC1394_OFF); + ::dc1394error_t error = ::dc1394_video_set_transmission(this->camera, ::DC1394_OFF); if (::DC1394_SUCCESS != error) { @@ -818,7 +818,7 @@ namespace rl throw Exception(error); } - error = ::dc1394_capture_stop(this->camera); + error = ::dc1394_capture_stop(this->camera); if (::DC1394_SUCCESS != error) { @@ -853,7 +853,7 @@ namespace rl default: return ::dc1394_error_get_string(this->error); break; - } + } } } } diff --git a/src/rl/hal/Dc1394Camera.h b/src/rl/hal/Dc1394Camera.h index 23134947..0f05ff76 100644 --- a/src/rl/hal/Dc1394Camera.h +++ b/src/rl/hal/Dc1394Camera.h @@ -39,7 +39,7 @@ namespace rl namespace hal { /** - * IEEE 1394 based cameras. + * IEEE 1394 based cameras. */ class RL_HAL_EXPORT Dc1394Camera : public Camera, public CyclicDevice { diff --git a/src/rl/hal/LeuzeRs4.cpp b/src/rl/hal/LeuzeRs4.cpp index 49eff015..b6fbf9e7 100644 --- a/src/rl/hal/LeuzeRs4.cpp +++ b/src/rl/hal/LeuzeRs4.cpp @@ -95,7 +95,7 @@ namespace rl ::std::uint8_t LeuzeRs4::crc(const ::std::uint8_t* buf, const ::std::size_t& len) const - { + { ::std::uint8_t checksum = buf[0]; for (::std::size_t i = 1; i < len; ++i) diff --git a/src/rl/hal/MitsubishiH7.h b/src/rl/hal/MitsubishiH7.h index 10351ab9..b1abd4b6 100644 --- a/src/rl/hal/MitsubishiH7.h +++ b/src/rl/hal/MitsubishiH7.h @@ -148,7 +148,7 @@ namespace rl }; struct Joint - { + { /** J1 axis angle [rad]. */ float j1; /** J2 axis angle [rad]. */ diff --git a/src/rl/hal/MitsubishiR3.h b/src/rl/hal/MitsubishiR3.h index c669adab..fec6bcb9 100644 --- a/src/rl/hal/MitsubishiR3.h +++ b/src/rl/hal/MitsubishiR3.h @@ -230,24 +230,24 @@ namespace rl /** * The install status is read. - * + * * @param[out] state Install state */ CalibState doCalib(); /** * Operation enable or disable. - * + * * When the command which needs the operation right such as program start, * servo ON and more is used, the operation right should be made effective. - * + * * @param[in] doOn OFF / ON */ void doCntl(const bool& doOn); /** * The origin is set by the data input. - * + * * @param[in] j1 Joint 1 data * @param[in] j2 Joint 2 data * @param[in] j3 Joint 3 data @@ -260,7 +260,7 @@ namespace rl /** * The origin is set by the data input. - * + * * @param[in] j1 Joint 1 data * @param[in] j2 Joint 2 data * @param[in] j3 Joint 3 data @@ -276,30 +276,30 @@ namespace rl /** * The stop state is read. - * + * * @param[out] state Stop state */ StopState doDstate(); /** * Clear program contents. - * + * * It is effective in the edit slot. */ void doEclr(); /** * More line and position are registered in the program. - * + * * It is effective in the edit slot. - * + * * @param[in] program Line data and positional data ([0b...]) */ void doEmdat(const ::std::string& program); /** * The content of the error is read. - * + * * @param[in] errorNo Error number * @return Content of the error */ @@ -307,14 +307,14 @@ namespace rl /** * The instruction is executed directly. - * + * * @param[in] instruction Instruction of MELFA-BASIC IV or MOVEMASTER commands */ void doExec(const ::std::string& instruction); /** * The hand is openend and closed. - * + * * @param[in] doOpen CLOSE / OPEN * @param[in] handNo Hand number (1 - 8) is specified */ @@ -322,14 +322,14 @@ namespace rl /** * The setting and the output of the hand are read. - * + * * @param[out] state Hand state */ ::std::array doHndsts(); /** * The input signal is pseudo-input. - * + * * @param[in] inNo Input signal number * @param[in] inVal Pseudo-input signal value by 4 hex number fixation */ @@ -337,7 +337,7 @@ namespace rl /** * Open the program for edit. - * + * * @param[in] programName Edit program name */ void doLoad(const ::std::string& programName); @@ -349,7 +349,7 @@ namespace rl /** * The output signal is compelling output. - * + * * @param[in] outNo Output signal number * @param[in] outVal Output signal value by 4 hex number fixation */ @@ -367,7 +367,7 @@ namespace rl /** * The program is started. - * + * * @param[in] programName Program name * @param[in] doModeCycle Repeat start / cycle start */ @@ -385,14 +385,14 @@ namespace rl /** * The servo power supply is turned on and off. - * + * * @param[in] doOn OFF / ON */ void doSrv(const bool& doOn); /** * The run state is read. - * + * * @param[out] state Run state */ RunState doState(); @@ -404,7 +404,7 @@ namespace rl /** * The state of the stop signal is read. - * + * * @param[out] state Stop signal state */ StopSignalState doStpsig(); diff --git a/src/rl/hal/RobotiqModelC.cpp b/src/rl/hal/RobotiqModelC.cpp index 3b59ebc1..2a15d15d 100644 --- a/src/rl/hal/RobotiqModelC.cpp +++ b/src/rl/hal/RobotiqModelC.cpp @@ -67,7 +67,7 @@ namespace rl ::std::uint16_t RobotiqModelC::crc(const ::std::uint8_t* buf, const ::std::size_t& len) const - { + { ::std::uint16_t checksum = 0xFFFF; for (::std::size_t i = 0; i < len; ++i) diff --git a/src/rl/hal/SchmersalLss300.cpp b/src/rl/hal/SchmersalLss300.cpp index 5cbbdc0e..a6cd887e 100644 --- a/src/rl/hal/SchmersalLss300.cpp +++ b/src/rl/hal/SchmersalLss300.cpp @@ -88,7 +88,7 @@ namespace rl ::std::uint16_t SchmersalLss300::crc(const ::std::uint8_t* buf, const ::std::size_t& len) const - { + { ::std::uint16_t checksum = buf[0]; for (::std::size_t i = 1; i < len; ++i) diff --git a/src/rl/hal/Serial.cpp b/src/rl/hal/Serial.cpp index a2fdc54f..701e73a5 100644 --- a/src/rl/hal/Serial.cpp +++ b/src/rl/hal/Serial.cpp @@ -49,7 +49,7 @@ #include "TimeoutException.h" #ifdef __QNX__ -#define CRTSCTS (IHFLOW | OHFLOW) +#define CRTSCTS (IHFLOW | OHFLOW) #endif // __QNX__ namespace rl @@ -396,7 +396,7 @@ namespace rl this->setConnected(true); if (-1 == ::tcgetattr(this->impl->fd, &this->impl->restore)) - { + { throw ComException(errno); } diff --git a/src/rl/hal/SickLms200.cpp b/src/rl/hal/SickLms200.cpp index 850292da..5ccd716d 100644 --- a/src/rl/hal/SickLms200.cpp +++ b/src/rl/hal/SickLms200.cpp @@ -104,7 +104,7 @@ namespace rl ::std::uint16_t SickLms200::crc(const ::std::uint8_t* buf, const ::std::size_t& len) const - { + { ::std::uint16_t checksum = buf[0]; for (::std::size_t i = 1; i < len; ++i) diff --git a/src/rl/hal/UniversalRobotsRealtime.h b/src/rl/hal/UniversalRobotsRealtime.h index f87076d5..e844e802 100644 --- a/src/rl/hal/UniversalRobotsRealtime.h +++ b/src/rl/hal/UniversalRobotsRealtime.h @@ -47,7 +47,7 @@ namespace rl { /** * Universal Robots realtime interface. - * + * * Supports versions 1.5, 1.6, 1.7, 1.8, 3.0, 3.1, 3.2, 3.3, 3.4, 3.5, 3.6, * 3.7, 3.8, 3.9, 3.10, 3.11, 3.12, 5.0, 5.1, 5.2, 5.3, 5.4, 5.5, 5.6. */ diff --git a/src/rl/hal/WeissKms40.h b/src/rl/hal/WeissKms40.h index 7b913458..823e28f3 100644 --- a/src/rl/hal/WeissKms40.h +++ b/src/rl/hal/WeissKms40.h @@ -43,7 +43,7 @@ namespace rl { /** * Weiss Robotics Force-Torque Sensor KMS 40. - * + * * See "KMS Command Set Reference Manual": * */ diff --git a/src/rl/hal/WeissWsg50.h b/src/rl/hal/WeissWsg50.h index 38ec9a8d..633be51a 100644 --- a/src/rl/hal/WeissWsg50.h +++ b/src/rl/hal/WeissWsg50.h @@ -41,10 +41,10 @@ namespace rl { /** * Weiss Robotics Universal Gripper WSG 50. - * + * * See "WSG Series of Intelligent Servo-Electric Grippers: Command Set Reference Manual": * - * + * * Important: Before use, you usually need to set "Part Width Tolerance" * and "Default Clamping Travel" to maximum in the web interface. * Otherwise, the gripper will not grasp if object width is different @@ -150,9 +150,9 @@ namespace rl /** * Perform necessary homing motion for calibration. - * + * * This function call is blocking until the calibration is complete. - * + * * @param[in] direction 0 = default from system configuration, 1 = positive movement, 2 = negative movement */ void doHomingMotion(const unsigned int& direction = 0); diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 894e3e3d..92470018 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -67,7 +67,7 @@ namespace rl /** * Clamp specified configuration to be within joint limits. - * + * * @param[out] q \f$\vec{q}\f$ */ virtual void clamp(::rl::math::Vector& q) const; @@ -76,7 +76,7 @@ namespace rl /** * Calculate distance measure between specified configuration. - * + * * @param[in] q1 \f$\vec{q}_{1}\f$ * @param[in] q2 \f$\vec{q}_{2}\f$ */ @@ -84,21 +84,21 @@ namespace rl /** * Get forward position kinematics. - * + * * @param[in] i End effector - * + * * @pre updateFrames() */ virtual const ::rl::math::Transform& forwardPosition(const ::std::size_t& i = 0) const; /** * Calculate forward force kinematics. - * + * * \f[ \vec{F} = \matr{J}^{-\mathrm{T}} \vec{\tau} \f] - * + * * @param[in] tau \f$\vec{\tau}\f$ * @param[out] f \f$\vec{F}\f$ - * + * * @pre updateJacobian() * @pre updateJacobianInverse() */ @@ -106,12 +106,12 @@ namespace rl /** * Calculate forward velocity kinematics. - * + * * \f[ \dot{\vec{x}} = \matr{J} \dot{\vec{q}} \f] - * + * * @param[in] qdot \f$\dot{\vec{q}}\f$ * @param[out] xdot \f$\dot{\vec{x}}\f$ - * + * * @pre updateJacobian() */ virtual void forwardVelocity(const ::rl::math::Vector& qdot, ::rl::math::Vector& xdot) const; @@ -136,21 +136,21 @@ namespace rl /** * Get link frame. - * + * * @pre updateFrames() */ const ::rl::math::Transform& getFrame(const ::std::size_t& i) const; /** * Get Jacobian. - * + * * @pre updateJacobian() */ const ::rl::math::Matrix& getJacobian() const; /** * Get Jacobian-Inverse. - * + * * @pre updateJacobianInverse() */ const ::rl::math::Matrix& getJacobianInverse() const; @@ -159,7 +159,7 @@ namespace rl /** * Get manipulability measure. - * + * * @pre updateJacobian() */ ::rl::math::Real getManipulabilityMeasure() const; @@ -183,7 +183,7 @@ namespace rl /** * Get current joint position. - * + * * @param[out] q \f$\vec{q}\f$ */ void getPosition(::rl::math::Vector& q) const; @@ -200,12 +200,12 @@ namespace rl /** * Calculate inverse force kinematics. - * + * * \f[ \vec{\tau} = \matr{J}^{\mathrm{T}} \vec{F} \f] - * + * * @param[in] f \f$\vec{F}\f$ * @param[out] tau \f$\vec{\tau}\f$ - * + * * @pre updateJacobian() */ virtual void inverseForce(const ::rl::math::Vector& f, ::rl::math::Vector& tau) const; @@ -227,12 +227,12 @@ namespace rl /** * Calculate inverse velocity kinematics. - * + * * \f[ \dot{\vec{q}} = \matr{J}^{\dagger} \dot{\vec{x}} \f] - * + * * @param[in] xdot \f$\dot{\vec{x}}\f$ * @param[out] qdot \f$\dot{\vec{q}}\f$ - * + * * @pre updateJacobianInverse() */ virtual void inverseVelocity(const ::rl::math::Vector& xdot, ::rl::math::Vector& qdot) const; @@ -249,7 +249,7 @@ namespace rl /** * Check if specified configuration is within joint limits. - * + * * @param[in] q \f$\vec{q}\f$ */ virtual bool isValid(const ::rl::math::Vector& q) const; @@ -270,7 +270,7 @@ namespace rl /** * Update current joint position. - * + * * @param[in] q \f$\vec{q}\f$ */ void setPosition(const ::rl::math::Vector& q); @@ -289,31 +289,31 @@ namespace rl /** * Update frames. - * + * * \f[ {_{0}^{n}\matr{T}} = {_{0}^{1}\matr{T}} \, {_{0}^{1}\matr{T}} \, \ldots \, {_{n-1}^{n}\matr{T}} \f] - * + * * @pre setPosition() */ virtual void updateFrames(); /** * Update Jacobian. - * + * * \f[ {^{0}\matr{J}} = \begin{pmatrix} {^{0}\matr{J}_{1}} & {^{0}\matr{J}_{2}} & \cdots & {^{0}\matr{J}_{n}} \end{pmatrix} \f] - * + * * @pre updateFrames() */ virtual void updateJacobian(); /** * Update Jacobian-Inverse. - * + * * \f[ \matr{J}^{\dagger}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \f] * \f[ \matr{J}^{\dagger}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \f] - * + * * @param[in] lambda Damping factor \f$\lambda\f$ * @param[in] doSvd Use singular value decomposition or damped least squares - * + * * @pre updateJacobian() */ virtual void updateJacobianInverse(const ::rl::math::Real& lambda = 0, const bool& doSvd = true); diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index 48fd7ab1..5e50eb51 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -133,7 +133,7 @@ namespace rl // shoulder (see Siegert p82) // FIXME: For a1 != 0, the configuration model deviates from the Puma 560 // In this case, Siegert's formula may give a (correct) solution with wrong arm handedness - // For instance, for the Mitsubishi RV-6SL robot with a1=50mm, poses near + // For instance, for the Mitsubishi RV-6SL robot with a1=50mm, poses near // the boundaries of one configuration will yield an inverse solution in the wrong // configuration space. // A fix would be to enumerate all (eight) solutions and pick the one thats best @@ -299,7 +299,7 @@ namespace rl ::rl::math::Real d4 = this->joints[3]->d; // z_1 component of the derivative of wrist location wrt to theta2 - ::rl::math::Real tmp = d4 * c2 * s3 + d4 * s2 * c3 + a3 * s2 * s3 - a3 * c2 * c3 - a2 * c2; + ::rl::math::Real tmp = d4 * c2 * s3 + d4 * s2 * c3 + a3 * s2 * s3 - a3 * c2 * c3 - a2 * c2; // y_2 component of wrist location ::rl::math::Real tmp2 = a3 * s3 + d4 * c3; diff --git a/src/rl/mainpage.dox b/src/rl/mainpage.dox index a0f442cf..290fb761 100644 --- a/src/rl/mainpage.dox +++ b/src/rl/mainpage.dox @@ -1,6 +1,6 @@ -namespace rl +namespace rl { -/** +/** \mainpage Robotics Library For first time users, please have a look at our website. Also, please refer to the website for tutorials, a high-level API description and answers on frequently asked questions (FAQ). @@ -64,5 +64,5 @@ For first time users, please have a look at our class Circular : public Function @@ -67,7 +66,7 @@ namespace rl /** * Generates a circular segment function in 2D through three given points. - * + * * The given points most not be (numerically close to) colinear. */ static Circular ThreePoints(const Vector2& y0, const Vector2& yi, const Vector2& y1, const Real& x1 = 1) @@ -81,7 +80,7 @@ namespace rl Matrix33 A; A << Matrix::Ones(3, 1), -points2d.transpose(); Vector3 b = - (points2d.transpose() * points2d).diagonal(); - Vector3 x = A.fullPivLu().solve(b); + Vector3 x = A.fullPivLu().solve(b); Vector2 center2d = x.bottomRows(2) / 2; //Real radiusSquared = center2d.transpose() * center2d - x(0); //Real radius = ::std::sqrt(radiusSquared); @@ -112,14 +111,13 @@ namespace rl /** * Generates a circular segment through three given points in 2D with * a given segment angle. - * + * * The given points must not be (numerically close to) colinear. * Contrary to ThreePoints, where the circular segment ends in y1, * the circular segments ends after a given angle. * With this, a full circle can be constructed, given an angle of 2*pi. * The given segment angle may be any real number, which allows * multiple rotations. - * */ static Circular ThreePointsAngle(const Vector2& y0, const Vector2& yi, const Vector2& y1, const Real& angle, const Real& x1 = 1) { @@ -155,7 +153,7 @@ namespace rl /** * Evaluates the circular segment function for a given x. - * + * * Note that only the first two derivatives are implemented, all higher * orders will return NaN. */ diff --git a/src/rl/math/CircularVector3.h b/src/rl/math/CircularVector3.h index 280a4852..ef18d1b1 100644 --- a/src/rl/math/CircularVector3.h +++ b/src/rl/math/CircularVector3.h @@ -40,7 +40,7 @@ #include "Circular.h" #include "CircularVector2.h" #include "Function.h" -#include "Matrix.h" +#include "Matrix.h" #include "Vector.h" namespace rl @@ -50,7 +50,6 @@ namespace rl /** * Circular segment function that maps from a time x to a point in 3D on * a circular trajectory. - * */ template<> class Circular : public Function @@ -68,7 +67,7 @@ namespace rl /** * Generates a circular segment through three given points in 3D. - * + * * The given points must not be (numerically close to) colinear. */ static Circular ThreePoints(const Vector3& y0, const Vector3& yi, const Vector3& y1, const Real& x1 = 1) @@ -119,14 +118,13 @@ namespace rl /** * Generates a circular segment through three given points in 3D with * a given segment angle. - * + * * The given points must not be (numerically close to) colinear. * Contrary to ThreePoints, where the circular segment ends in y1, * the circular segments ends after a given angle. * With this, a full circle can be constructed, given an angle of 2*pi. * The given segment angle may be any real number, which allows * multiple rotations. - * */ static Circular ThreePointsAngle(const Vector3& y0, const Vector3& yi, const Vector3& y1, const Real& angle, const Real& x1 = 1) { @@ -162,7 +160,7 @@ namespace rl /** * Evaluates the circular segment function for a given x. - * + * * Note that only the first two derivatives are implemented, all higher * orders will return NaN. */ diff --git a/src/rl/math/Function.h b/src/rl/math/Function.h index 2bbc3fe8..47527986 100644 --- a/src/rl/math/Function.h +++ b/src/rl/math/Function.h @@ -35,7 +35,7 @@ namespace rl { /** * A mathematical mapping from Real -> ArrayX. - * + * * A Function is guaranteed to be defined in the interval [lower() upper()], * and may be defined outside this interval. Its computation is expected * to be numerically stable, accurate and efficient. @@ -83,16 +83,16 @@ namespace rl /** * Evaluates the function or a derivative thereof for a given value x. - * + * * Some functions are only defined in the interval [lower(), upper()], - * and fail to evaluate outside of + * and fail to evaluate outside of * [lower() - FUNCTION_BOUNDARY, upper() + FUNCTION_BOUNDARY]. * In Debug mode, this is signaled by failing asserts. * In Release mode, the function is evaluated if algebraically possible, - * or will return an empty ArrayX otherwise. - * Some functions are not indefinitely often differentiable, + * or will return an empty ArrayX otherwise. + * Some functions are not indefinitely often differentiable, * and will return a NaN array for all higher orders. - * + * * @param[in] x Input value of the function or derivative * @param[in] derivative Order of the derivative to be evaluated */ diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index ee731b2d..d74c1257 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -42,11 +42,11 @@ namespace rl { /** * Geometric Near-Neighbor Access Tree (GNAT). - * + * * Sergey Brin. Near neighbor search in large metric spaces. In Proceedings of * the International Conference on Very Large Data Bases, pages 574-584, * Zurich, Switzerland, September, 1985. - * + * * http://www.vldb.org/conf/1995/P574.PDF */ template diff --git a/src/rl/math/Kalman.h b/src/rl/math/Kalman.h index 1935bdc6..905c2bb7 100644 --- a/src/rl/math/Kalman.h +++ b/src/rl/math/Kalman.h @@ -40,11 +40,11 @@ namespace rl { /** * Kalman filter. - * + * * Greg Welch and Gary Bishop. An introduction to the Kalman filter. Technical * Report TR 95-041, University of North Carolina at Chapel Hill, Chapel Hill, * NC, USA, July 2006. - * + * * http://www.cs.unc.edu/~welch/media/pdf/kalman_intro.pdf */ template @@ -86,14 +86,14 @@ namespace rl /** * Measurement update ("correct"). - * + * * Compute the Kalman gain * \f[ \matr{K}_{k} = \matr{P}^{-}_{k} \matr{H}^{\mathrm{T}} \left( \matr{H} \matr{P}^{-}_{k} \matr{H}^{\mathrm{T}} + \matr{R} \right)^{-1} \f] * Update estimate with measurement \f$\vec{z}_{k}\f$ * \f[ \hat{\vec{x}}_{k} = \hat{\vec{x}}^{-}_{k} + \matr{K}_{k} \left( \vec{z}_{k} - \matr{H} \hat{\vec{x}}^{-}_{k} \right) \f] * Update the error covariance * \f[ \matr{P}_{k} = \left( \matr{1} - \matr{K}_{k} \matr{H} \right) \matr{P}^{-}_{k} \f] - * + * * @param[in] z Measurement \f$\vec{z}_{k}\f$ */ VectorType correct(const VectorType& z) @@ -151,7 +151,7 @@ namespace rl /** * Time update ("predict") without control input. - * + * * Project the state ahead * \f[ \hat{\vec{x}}^{-}_{k} = \matr{A} \hat{\vec{x}}_{k - 1} \f] * Project the error covariance ahead @@ -168,12 +168,12 @@ namespace rl /** * Time update ("predict") with control input. - * + * * Project the state ahead * \f[ \hat{\vec{x}}^{-}_{k} = \matr{A} \hat{\vec{x}}_{k - 1} + \matr{B} \vec{u}_{k - 1} \f] * Project the error covariance ahead * \f[ \matr{P}^{-}_{k} = \matr{A} \matr{P}_{k - 1} \matr{A}^{\mathrm{T}} + \matr{Q} \f] - * + * * @param[in] u Control input \f$\vec{u}_{k - 1}\f$ */ VectorType predict(const VectorType& u) diff --git a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h index e079e3bf..11388f7b 100644 --- a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h @@ -47,11 +47,11 @@ namespace rl { /** * k-d tree. - * + * * Jon Louis Bentley. Multidimensional binary search trees used for * associative searching. Communications of the ACM, 18(9):509-517, * September 1975. - * + * * http://dx.doi.org/10.1145/361002.361007 */ template diff --git a/src/rl/math/KdtreeNearestNeighbors.h b/src/rl/math/KdtreeNearestNeighbors.h index 8c0f052e..709028d0 100644 --- a/src/rl/math/KdtreeNearestNeighbors.h +++ b/src/rl/math/KdtreeNearestNeighbors.h @@ -46,11 +46,11 @@ namespace rl { /** * k-d tree. - * + * * Jon Louis Bentley. Multidimensional binary search trees used for * associative searching. Communications of the ACM, 18(9):509-517, * September 1975. - * + * * http://dx.doi.org/10.1145/361002.361007 */ template diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index 1e9ef9ce..169dbb91 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -41,9 +41,9 @@ static CartesianFromPolar(const MatrixBase& polar) /** * Convert polar coordinates into Cartesian coordinates. - * + * * http://mathworld.wolfram.com/PolarCoordinates.html - * + * * @param[in] r Radial distance from the origin * @param[in] theta Counterclockwise angle from the x-axis */ @@ -73,9 +73,9 @@ static CartesianFromSpherical(const MatrixBase& spherical) /** * Convert spherical coordinates into Cartesian coordinates. - * + * * http://mathworld.wolfram.com/SphericalCoordinates.html - * + * * @param[in] r Radial distance from the origin * @param[in] theta Azimuthal angle in the xy-plane from the x-axis * @param[in] phi Polar angle (also known as the zenith angle and colatitude) from the positive z-axis @@ -109,7 +109,7 @@ static PolarFromCartesian(const MatrixBase& cartesian) /** * Convert Cartesian coordinates into polar coordinates. - * + * * http://mathworld.wolfram.com/PolarCoordinates.html */ Matrix @@ -135,7 +135,7 @@ static RandomOnCircle() /** * Generate random point on unit circle. - * + * * http://mathworld.wolfram.com/CirclePointPicking.html */ Matrix @@ -170,7 +170,7 @@ static RandomOnSphere() /** * Generate random point on unit sphere. - * + * * http://mathworld.wolfram.com/SpherePointPicking.html */ template @@ -211,7 +211,7 @@ static SphericalFromCartesian(const MatrixBase& cartesian) /** * Convert Cartesian coordinates into spherical coordinates. - * + * * http://mathworld.wolfram.com/SphericalCoordinates.html */ template diff --git a/src/rl/math/Pid.h b/src/rl/math/Pid.h index da22ab07..9de783d3 100644 --- a/src/rl/math/Pid.h +++ b/src/rl/math/Pid.h @@ -57,9 +57,9 @@ namespace rl /** * Calculate next step. - * + * * \f[ k_{\mathrm{p}} \, e(t) + k_{\mathrm{i}} \int_{0}^{t} e(\tau) \, \mathrm{d}\tau + k_{\mathrm{d}} \, \frac{\mathrm{d}}{\mathrm{d}t} \, e(t) \f] - * + * * @param[in] dt \f$\mathrm{d}t\f$ */ T operator()(const T& x, const Real& dt) diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index fb59bac9..f32ef695 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -53,7 +53,7 @@ namespace rl { /** * A polynomial function. - * + * * \f[ f(x) = c_0 + c_1 x + c_2 x^2 + \ldots + c_{n - 1} x^{n - 1} + c_n x^n \f] */ template @@ -229,13 +229,13 @@ namespace rl } /** - * Returns the array of the maximum function values of each dimension + * Returns the array of the maximum function values of each dimension * within the definition range, not regarding the sign of the function values. - * + * * For polynomials higher than cubics, Eigen::PolynomialSolver is required * and calculations become iterative, without guaranteeing convergence. * A common use case is to verify speed limits with the comparison - * (trajectory.derivate().getAbsoluteMaximum() < maximumSpeed).all() + * (trajectory.derivate().getAbsoluteMaximum() < maximumSpeed).all() */ T getAbsoluteMaximum() const { @@ -538,7 +538,7 @@ namespace rl if (det > 0) { - Real sqrtDet = ::std::sqrt(det); + Real sqrtDet = ::std::sqrt(det); ::std::vector roots(2); roots[0] = (-c[1] + sqrtDet) / (2 * c[2]); roots[1] = (-c[1] - sqrtDet) / (2 * c[2]); @@ -645,12 +645,12 @@ namespace rl } } - /** + /** * Stretches the x-axis of a polynomial by a given factor. - * + * * The returned, scaled polynomial p' of a given polynomial p fulfills * p'(x * factor) = p(x), and p'.duration() = factor * p.duration(). - * This is done by recalculating the underlying polynomial coefficients. + * This is done by recalculating the underlying polynomial coefficients. */ Polynomial scaledX(const Real& factor) const { diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 161f61c2..3b2ca28d 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -33,11 +33,11 @@ namespace Eigen { template class QuaternionBase { /** * QuTEM (Quaternion Tangent Ellipsoid at the Mean) sampling algorithm. - * + * * Michael Patrick Johnson. Exploiting Quaternions to Support Expressive * Interactive Character Motion. PhD Thesis, Massachusetts Institute of * Technology, Cambridge, MA, USA, February 2003. - * + * * http://characters.media.mit.edu/Theses/johnson_phd.pdf */ template @@ -72,11 +72,11 @@ static Quaternion Random() /** * Generate uniformly-distributed random unit quaternions. - * + * * James J. Kuffner. Effective Sampling and Distance Metrics for 3D Rigid Body * Path Planning. Proceedings of the IEEE International Conference on Robotics * and Automation, pages 3993-3998. New Orleans, LA, USA, April 2004. - * + * * https://doi.org/10.1109/ROBOT.2004.1308895 */ template diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index a88ec20b..1c1686b6 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -39,10 +39,10 @@ namespace rl { /** * A piecewise polynomial function. - * + * * A Spline is a function consisting of a list of polynomials, which * may have different degrees. - * + * * @see Polynomial */ template @@ -70,7 +70,7 @@ namespace rl /** * Generates a cubic spline that interpolates a set of data points * with known first derivatives at the endpoints. - * + * * A cubic spline interpolant \f$S\f$ for a function \f$f\f$ with a * set of nodes \f$x_0 < x_1 < \cdots < x_n\f$ is a piecewise cubic polynomial * \f$S_i\f$ on \f$[x_i, x_{i + 1}]\f$ for \f$i = 0, \ldots, n - 1\f$ @@ -80,7 +80,7 @@ namespace rl * S_i'(x) &= b_i + 2 c_i (x - x_i) + 3 d_i (x - x_i)^2 \, , \\ * S_i''(x) &= 2 c_i + 6 d_i (x - x_i) \, . * \f} - * + * * The spline matches the nodes and is continuous in the first and second * derivatives as defined by the properties * \f{align*}{ @@ -89,16 +89,16 @@ namespace rl * S'_i(x_{i + 1}) &= S'_{i + 1}(x_{i + 1}) \, , \\ * S''_i(x_{i + 1}) &= S''_{i + 1}(x_{i + 1}) \, . * \f} - * + * * In this variant, the boundary conditions are defined by the first * derivatives * \f{align*}{ * S'(x_0) = f'(x_0) \, , \\ * S'(x_n) = f'(x_n) \, . * \f} - * + * * http://banach.millersville.edu/~bob/math375/CubicSpline/main.pdf - * + * * @param[in] x \f$x_0, \ldots, x_n\f$ * @param[in] y \f$f(x_0), \ldots, f(x_n)\f$ * @param[in] yd0 \f$f'(x_0)\f$ @@ -169,7 +169,7 @@ namespace rl /** * Generates a cubic spline that interpolates a set of data points * with second derivatives at the endpoints set to zero. - * + * * A cubic spline interpolant \f$S\f$ for a function \f$f\f$ with a * set of nodes \f$x_0 < x_1 < \cdots < x_n\f$ is a piecewise cubic polynomial * \f$S_i\f$ on \f$[x_i, x_{i + 1}]\f$ for \f$i = 0, \ldots, n - 1\f$ @@ -179,7 +179,7 @@ namespace rl * S_i'(x) &= b_i + 2 c_i (x - x_i) + 3 d_i (x - x_i)^2 \, , \\ * S_i''(x) &= 2 c_i + 6 d_i (x - x_i) \, . * \f} - * + * * The spline matches the nodes and is continuous in the first and second * derivatives as defined by the properties * \f{align*}{ @@ -188,15 +188,15 @@ namespace rl * S'_i(x_{i + 1}) &= S'_{i + 1}(x_{i + 1}) \, , \\ * S''_i(x_{i + 1}) &= S''_{i + 1}(x_{i + 1}) \, . * \f} - * + * * In this variant, the boundary conditions are defined by the second * derivatives * \f{align*}{ * S''(x_0) = S''(x_n) = 0 \, . * \f} - * + * * http://banach.millersville.edu/~bob/math375/CubicSpline/main.pdf - * + * * @param[in] x \f$x_0, \ldots, x_n\f$ * @param[in] y \f$f(x_0), \ldots, f(x_n)\f$ */ @@ -259,11 +259,11 @@ namespace rl /** * Generates a piecewise spline with parabolic segments around the * given supporting points y and linear segments in between. - * + * * Note that the duration of the returned Spline is longer than the * given x, because there is one parabolic interval more than segments * in x. - * + * * @param[in] parabolicInterval Gives the duration of a parabolic interval, * the following linear interval then has a duration of x(n+1) - x(n) - * parabolicInterval @@ -406,11 +406,11 @@ namespace rl /** * Generates a piecewise spline with quartic polynomial segments around * the given supporting points y and linear segments in between. - * + * * Note that the duration of the returned Spline is longer than the * given x, because there is one quartic polynomial interval more than * segments in x. - * + * * @param[in] quarticInterval Gives the duration of a quartic interval, * the following linear interval then has a duration of x(n+1) - x(n) - * quarticInterval @@ -449,7 +449,7 @@ namespace rl T ydNext = (y[i + 1] - y[i]) / deltaXNext; T yBeforeQuartic = y[i] + (-quarticInterval / 2 * ydPrev); T yBeforeLinear = y[i] + (quarticInterval / 2 * ydNext); - T yAfterLinear = y[i] + ((quarticInterval / 2 + linearInterval) * ydNext); + T yAfterLinear = y[i] + ((quarticInterval / 2 + linearInterval) * ydNext); Polynomial quartic = Polynomial::QuarticFirstSecond(yBeforeQuartic, yBeforeLinear, ydPrev, ydNext, TypeTraits::Zero(dim), quarticInterval); f.push_back(quartic); @@ -553,11 +553,11 @@ namespace rl /** * Generates a piecewise spline with sextic polynomial segments around * the given supporting points y and linear segments in between. - * + * * Note that the duration of the returned Spline is longer than the * given x, because there is one sextic polynomial interval more than * segments in x. - * + * * @param[in] sexticInterval Gives the duration of a sextic interval, * the following linear interval then has a duration of x(n+1) - x(n) - * sexticInterval @@ -596,7 +596,7 @@ namespace rl T ydNext = (y[i + 1] - y[i]) / deltaXNext; T yBeforeSextic = y[i] + (-sexticInterval / 2 * ydPrev); T yBeforeLinear = y[i] + (sexticInterval / 2 * ydNext); - T yAfterLinear = y[i] + ((sexticInterval / 2 + linearInterval) * ydNext); + T yAfterLinear = y[i] + ((sexticInterval / 2 + linearInterval) * ydNext); Polynomial sextic = Polynomial::SexticFirstSecondThird(yBeforeSextic, yBeforeLinear, ydPrev, ydNext, TypeTraits::Zero(dim), TypeTraits::Zero(dim), TypeTraits::Zero(dim), sexticInterval); f.push_back(sextic); @@ -700,7 +700,7 @@ namespace rl /** * Generates a spline of polynomials of degrees 4-1-4 from rest to rest * for one dimension. - * + * * Its acceleration and deceleration segments are parabolic and reach amax. * vmax may or may not be reached; in the latter case, the linear segment * is omitted. @@ -751,7 +751,7 @@ namespace rl /** * Generates a spline of polynomials of degrees 4-1-4 from rest to rest * that is phase-synchronized for multiple degree-of-freedoms. - * + * * Its acceleration and deceleration segments are parabolic and at least * one degree-of-freedon reaches its maximum acceleration amax. * vmax may or may not be reached; in the latter case, the linear segment @@ -831,12 +831,12 @@ namespace rl /** * Generates a spline of polynomials of degrees 6-1-6 from rest to rest * for one dimension. - * + * * Its acceleration and deceleration segments are quartic and reach amax. * vmax may or may not be reached; in the latter case, the linear segment * is omitted. * Compared to QuarticLinearQuarticAtRest, SexticLinearSexticAtRest - * makes sure the jerk is continuous, which results in a smoother and + * makes sure the jerk is continuous, which results in a smoother and * slightly longer trajectory. * The result is the shortest such 6-1-6 spline. */ @@ -885,7 +885,7 @@ namespace rl /** * Generates a spline of polynomials of degrees 6-1-6 from rest to rest * that is phase-synchronized for multiple degree-of-freedoms. - * + * * Its acceleration and deceleration segments are quartic and at least * one degree-of-freedon reaches its maximum acceleration amax. * vmax may or may not be reached; in the latter case, the linear segment @@ -965,10 +965,10 @@ namespace rl /** * Generates a trapezoidal acceleration trajectory from rest to rest * for multiple dimensions that are phase-synchronized. - * - * A trapezoidal acceleration trajectory has up to seven segments of + * + * A trapezoidal acceleration trajectory has up to seven segments of * constant jerk. Its velocity curve is double-S shaped. - * + * * L. Biagiotti, C. Melchiorri (2008) "Trajectory Planning for Automatic * Machines and Robots", pp. 90ff. */ @@ -1174,13 +1174,13 @@ namespace rl } /** - * Returns the array of the maximum function values of each dimension + * Returns the array of the maximum function values of each dimension * within the definition range, not regarding the sign of the function values. - * + * * For polynomials higher than cubics, Eigen::PolynomialSolver is required * and calculations become iterative, without guaranteeing convergence. * A common use case is to verify speed limits with the comparison - * (trajectory.derivate().getAbsoluteMaximum() < maximumSpeed).all() + * (trajectory.derivate().getAbsoluteMaximum() < maximumSpeed).all() */ T getAbsoluteMaximum() const { @@ -1231,12 +1231,12 @@ namespace rl } /** - * Verifies that the spline is smooth and has no jumps + * Verifies that the spline is smooth and has no jumps * at the piecewise function boundaries. - * + * * Mathematically, it checks whether the spline and a certain number * of its derivatives are continuous. - * + * * @param[in] upToDerivative Sets the number of derivatives that are * also checked for continuity. */ @@ -1315,12 +1315,12 @@ namespace rl } } - /** + /** * Stretches the x-axis of a spline by a given factor. - * + * * The returned, scaled spline s' of a given spline s fulfills * s'(x * factor) = s(x), and s'.duration() = factor * s.duration(). - * This is done by recalculating the underlying polynomial coefficients. + * This is done by recalculating the underlying polynomial coefficients. */ Spline scaledX(const Real& factor) const { diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index 890e96e6..a27299ff 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -52,7 +52,7 @@ distance(const Transform& other, /** * Calculate transformation from a linear and angular velocity vector. - * + * * @param[in] useApproximation For rotations a, b, c smaller than a * few degrees, you can use a faster bi-linear approximation. For * rotations larger than 90 degrees, this approximation would be @@ -163,7 +163,7 @@ setDelta(const Matrix& delta) /** * Calculate the linear and angular velocity vector between two transformations. - * + * * @param[in] useApproximation For rotations from t1 to t2 smaller * than a few degrees, you can use a faster bi-linear approximation. * (For a rotation angle < 1e-3, the approximated angular velocity diff --git a/src/rl/math/Unit.h b/src/rl/math/Unit.h index d6d29df7..622bc6d7 100644 --- a/src/rl/math/Unit.h +++ b/src/rl/math/Unit.h @@ -335,7 +335,7 @@ namespace rl * Constant for converting an angular value in * [degree](https://en.wikipedia.org/wiki/Degree_(angle)) to * [radian](https://en.wikipedia.org/wiki/Radian). - * + * * This is equal to a multiplication by π and a division by 180. */ static const Real DEG2RAD = static_cast(M_PI) / static_cast(180); @@ -344,7 +344,7 @@ namespace rl /** * Standard acceleration due to gravity. - * + * * [Standard gravity](https://en.wikipedia.org/wiki/Standard_gravity) is the nominal * [gravitational acceleration](https://en.wikipedia.org/wiki/Gravitational_acceleration) * of an object in a vacuum near the surface of the earth. It is defined as 9.80665 m · s-2 @@ -366,7 +366,7 @@ namespace rl * Constant for converting an angular value in * [radian](https://en.wikipedia.org/wiki/Radian) to * [degree](https://en.wikipedia.org/wiki/Degree_(angle)). - * + * * This is equal to a multiplication by 180 and a division by π. */ static const Real RAD2DEG = static_cast(180) / static_cast(M_PI); diff --git a/src/rl/math/spatial/PlueckerTransform.h b/src/rl/math/spatial/PlueckerTransform.h index 46f104b8..dfe50acf 100644 --- a/src/rl/math/spatial/PlueckerTransform.h +++ b/src/rl/math/spatial/PlueckerTransform.h @@ -36,7 +36,7 @@ namespace rl { /** * Spatial vector algebra. - * + * * Roy Featherstone. Rigid Body Dynamics Algorithms. Springer, New * York, NY, USA, 2008. */ diff --git a/src/rl/mdl/Dynamic.h b/src/rl/mdl/Dynamic.h index 9b1b265e..6bf06981 100644 --- a/src/rl/mdl/Dynamic.h +++ b/src/rl/mdl/Dynamic.h @@ -42,93 +42,93 @@ namespace rl /** * Calculate centrifugal and Coriolis vector. - * + * * @pre setPosition() * @pre setVelocity() * @post getCentrifugalCoriolis() - * + * * @see inverseDynamics() */ void calculateCentrifugalCoriolis(); /** * Calculate centrifugal and Coriolis vector. - * + * * @param[out] V Centrifugal and Coriolis vector \f$\vec{V}(\vec{q}, \dot{\vec{q}})\f$ - * + * * @pre setPosition() * @pre setVelocity() - * + * * @see inverseDynamics() */ void calculateCentrifugalCoriolis(::rl::math::Vector& V); /** * Calculate gravity vector. - * + * * @pre setPosition() * @post getGravity() - * + * * @see inverseDynamics() */ void calculateGravity(); /** * Calculate gravity vector. - * + * * @param[out] G Gravity vector \f$\vec{G}(\vec{q})\f$ - * + * * @pre setPosition() - * + * * @see inverseDynamics() */ void calculateGravity(::rl::math::Vector& G); /** * Calculate joint space mass matrix. - * + * * @pre setPosition() * @post getMassMatrix() - * + * * @see inverseDynamics() */ void calculateMassMatrix(); /** * Calculate joint space mass matrix. - * + * * @param[out] M Joint space mass matrix \f$\matr{M}^{-1}(\vec{q})\f$ - * + * * @pre setPosition() - * + * * @see inverseDynamics() */ void calculateMassMatrix(::rl::math::Matrix& M); /** * Calculate joint space mass matrix inverse. - * + * * @pre setPosition() * @post getMassMatrixInverse() - * + * * @see forwardDynamics() */ void calculateMassMatrixInverse(); /** * Calculate joint space mass matrix inverse. - * + * * @param[out] invM Joint space mass matrix inverse \f$\matr{M}^{-1}(\vec{q})\f$ - * + * * @pre setPosition() - * + * * @see forwardDynamics() */ void calculateMassMatrixInverse(::rl::math::Matrix& invM); /** * Calculate operational space mass matrix inverse. - * + * * @pre setPosition() * @pre calculateJacobian() * @pre calculateMassMatrix() @@ -139,7 +139,7 @@ namespace rl /** * Calculate operational space mass matrix inverse. - * + * * @param[in] J Jacobian matrix \f$\matr{J}(\vec{q})\f$ * @param[in] invM Joint space mass matrix inverse \f$\matr{M}^{-1}(\vec{q})\f$ * @param[out] invMx Operational space mass matrix inverse \f$\matr{M}_{\mathrm{x}}^{-1}(\vec{q})\f$ @@ -148,9 +148,9 @@ namespace rl /** * Forward dynamics via articulated-body algorithm. - * + * * \f[ \ddot{\vec{q}} = \matr{M}^{-1}(\vec{q}) \, \bigl( \vec{\tau} - \vec{C}(\vec{q}, \dot{\vec{q}}) - \vec{V}(\vec{q}) \bigr) \f] - * + * * @pre setPosition() * @pre setVelocity() * @pre setTorque() @@ -160,9 +160,9 @@ namespace rl /** * Access calculated centrifugal and Coriolis vector. - * + * * @return Centrifugal and Coriolis vector \f$\vec{V}(\vec{q}, \dot{\vec{q}})\f$ - * + * * @pre setPosition() * @pre setVelocity() */ @@ -170,9 +170,9 @@ namespace rl /** * Access calculated gravity vector. - * + * * @return Gravity vector \f$\vec{G}(\vec{q})\f$ - * + * * @pre setPosition() * @pre setWorldGravity() */ @@ -180,9 +180,9 @@ namespace rl /** * Access calculated joint space mass matrix inverse. - * + * * @return Joint space mass matrix inverse \f$\matr{M}^{-1}(\vec{q})\f$ - * + * * @pre setPosition() * @pre calculateJacobian() * @pre calculateMassMatrix() @@ -192,18 +192,18 @@ namespace rl /** * Access calculated joint space mass matrix. - * + * * @return Joint space mass matrix \f$\matr{M}(\vec{q})\f$ - * + * * @pre setPosition() */ const ::rl::math::Matrix& getMassMatrix() const; /** * Access calculated operational space mass matrix inverse. - * + * * @return Operational space mass matrix inverse \f$\matr{M}_{\mathrm{x}}^{-1}(\vec{q})\f$ - * + * * @pre setPosition() * @pre calculateJacobian() * @pre calculateMassMatrix() @@ -214,9 +214,9 @@ namespace rl /** * Inverse dynamics via recursive Newton-Euler algorithm. - * + * * \f[ \vec{\tau} = \matr{M}(\vec{q}) \, \ddot{\vec{q}} + \vec{C}(\vec{q}, \dot{\vec{q}}) + \vec{G}(\vec{q}) \f] - * + * * @pre setPosition() * @pre setVelocity() * @pre setAcceleration() @@ -231,55 +231,55 @@ namespace rl protected: /** * Gravity vector - * + * * \f[ \vec{G}(\vec{q}) \f] - * + * * @pre calculateGravity() - * + * * @see getGravity() * */ ::rl::math::Vector G; /** * Joint space mass matrix inverse. - * + * * \f[ \matr{M}^{-1}(\vec{q}) \f] - * + * * @pre calculateMassMatrixInverse() - * + * * @see getMassMatrixInverse() * */ ::rl::math::Matrix invM; /** * Operational space mass matrix inverse. - * + * * \f[ \matr{M}_{\mathrm{x}}^{-1}(\vec{q}) \f] - * + * * @pre calculateOperationalMassMatrixInverse() - * + * * @see getOperationalMassMatrixInverse() * */ ::rl::math::Matrix invMx; /** * Joint space mass matrix. - * + * * \f[ \matr{M}(\vec{q}) \f] - * + * * @pre calculateMassMatrix() - * + * * @see getMassMatrix() * */ ::rl::math::Matrix M; /** * Centrifugal and Coriolis vector. - * + * * \f[ \vec{V}(\vec{q}, \dot{\vec{q}}) \f] - * + * * @pre calculateCentrifugalCoriolis() - * + * * @see getCentrifugalCoriolis() * */ ::rl::math::Vector V; diff --git a/src/rl/mdl/EulerCauchyIntegrator.h b/src/rl/mdl/EulerCauchyIntegrator.h index 85d97d3a..343f081c 100644 --- a/src/rl/mdl/EulerCauchyIntegrator.h +++ b/src/rl/mdl/EulerCauchyIntegrator.h @@ -35,19 +35,19 @@ namespace rl { /** * Integration via Euler-Cauchy. - * + * * \f[ \vec{q}_{i + 1} = \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} \f] * \f[ \dot{\vec{q}}_{i + 1} = \dot{\vec{q}}_{i} + \Delta t \, f(t_{i}, \vec{q}_{i}, \dot{\vec{q}}_{i}) \f] * \f[ \ddot{\vec{q}} = f(t, \vec{q}, \dot{\vec{q}}) \f] * \f[ t_{i + 1} = t_{i} + \Delta t \f] - * + * * @pre Dynamic::setPosition() * @pre Dynamic::setVelocity() * @pre Dynamic::setTorque() * @post Dynamic::getPosition() * @post Dynamic::getVelocity() * @post Dynamic::getAcceleration() - * + * * @see Dynamic::forwardDynamics() */ class RL_MDL_EXPORT EulerCauchyIntegrator : public Integrator diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index c104cfed..3b8edc01 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -39,10 +39,10 @@ namespace rl { /** * Iterative inverse kinematics using Jacobian with random restarts. - * + * * Samuel R. Buss, Introduction to Inverse Kinematics with Jacobian * Transpose, Pseudoinverse and Damped Least Squares Methods, 2009. - * + * * https://www.math.ucsd.edu/~sbuss/ResearchWeb/ikmethods/iksurvey.pdf */ class RL_MDL_EXPORT JacobianInverseKinematics : public IterativeInverseKinematics diff --git a/src/rl/mdl/Kinematic.h b/src/rl/mdl/Kinematic.h index 810a0fe1..6ceb5472 100644 --- a/src/rl/mdl/Kinematic.h +++ b/src/rl/mdl/Kinematic.h @@ -46,37 +46,37 @@ namespace rl /** * Calculate Jacobian matrix. - * + * * @param[in] inWorldFrame Calculate in world or tool frame - * + * * @pre setPosition() * @post getJacobian() - * + * * @see forwardVelocity() */ void calculateJacobian(const bool& inWorldFrame = true); /** * Calculate Jacobian matrix. - * + * * @param[out] J Jacobian matrix \f$\matr{J}(\vec{q})\f$ * @param[in] inWorldFrame Calculate in world or tool frame - * + * * @pre setPosition() - * + * * @see forwardVelocity() */ void calculateJacobian(::rl::math::Matrix& J, const bool& inWorldFrame = true); /** * Calculate Jacobian derivative vector. - * + * * @param[in] inWorldFrame Calculate in world or tool frame - * + * * @pre setPosition() * @pre setVelocity() * @post getJacobianDerivative() - * + * * @see forwardVelocity * @see forwardAcceleration */ @@ -84,13 +84,13 @@ namespace rl /** * Calculate Jacobian derivative vector. - * + * * @param[out] Jdqd Jacobian derivative vector \f$\dot{\matr{J}}(\vec{q}, \dot{\vec{q}}) \, \dot{\vec{q}}\f$ * @param[in] inWorldFrame Calculate in world or tool frame - * + * * @pre setPosition() * @pre setVelocity() - * + * * @see forwardVelocity() * @see forwardAcceleration() */ @@ -98,13 +98,13 @@ namespace rl /** * Calculate Jacobian matrix inverse. - * + * * \f[ \matr{J}^{\dagger}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \f] * \f[ \matr{J}^{\dagger}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \f] - * + * * @param[in] lambda Damping factor \f$\lambda\f$ * @param[in] doSvd Use singular value decomposition or damped least squares - * + * * @pre setPosition() * @pre calculateJacobian() * @post getJacobianInverse() @@ -113,15 +113,15 @@ namespace rl /** * Calculate Jacobian matrix inverse. - * + * * \f[ \matr{J}^{\dagger}(\vec{q}) = \sum_{i = 1}^{r} \frac{ \sigma_{i} }{ \sigma_{i}^{2} + \lambda^{2} } \, \vec{v}_{i} \, \vec{u}_{i}^{\mathrm{T}} \f] * \f[ \matr{J}^{\dagger}(\vec{q}) = \matr{J}^{\mathrm{T}}(\vec{q}) \, \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) + \lambda^{2} \, \matr{1} \bigr)^{-1} \f] - * + * * @param[in] J Jacobian matrix \f$\matr{J}\f$ * @param[in] invJ Jacobian matrix inverse \f$\matr{J}^{\dagger}\f$ * @param[in] lambda Damping factor \f$\lambda\f$ * @param[in] doSvd Use singular value decomposition or damped least squares - * + * * @pre setPosition() * @pre calculateJacobian() */ @@ -129,11 +129,11 @@ namespace rl /** * Calculate manipulability measure. - * + * * \f[ \mu(\vec{q}) = \sqrt{\det \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) \bigr)} \f] - * + * * @return Manipulability measure \f$\mu(\vec{q})\f$ - * + * * @pre setPosition() * @pre calculateJacobian() */ @@ -141,11 +141,11 @@ namespace rl /** * Calculate manipulability measure. - * + * * \f[ \mu(\vec{q}) = \sqrt{\det \bigl( \matr{J}(\vec{q}) \, \matr{J}^{\mathrm{T}}(\vec{q}) \bigr)} \f] - * + * * @param[in] J Jacobian matrix \f$\matr{J}(\vec{q})\f$ - * + * * @return Manipulability measure \f$\mu(\vec{q})\f$ */ ::rl::math::Real calculateManipulabilityMeasure(const ::rl::math::Matrix& J) const; @@ -173,9 +173,9 @@ namespace rl /** * Access calculated Jacobian matrix. - * + * * @return Jacobian matrix \f$\matr{J}(\vec{q})\f$ - * + * * @pre setPosition() * @pre calculateJacobian() */ @@ -183,9 +183,9 @@ namespace rl /** * Access calculated Jacobian derivative vector. - * + * * @return Jacobian derivative vector \f$\dot{\matr{J}}(\vec{q}, \dot{\vec{q}}) \, \dot{\vec{q}}\f$ - * + * * @pre setPosition() * @pre setVelocity() * @pre calculateJacobianDerivative() @@ -194,9 +194,9 @@ namespace rl /** * Access calculated Jacobian matrix inverse. - * + * * @return Jacobian matrix inverse \f$\matr{J}^{\dagger}(\vec{q})\f$ - * + * * @pre setPosition() * @pre calculateJacobian() * @pre calculateJacobianInverse() @@ -205,14 +205,14 @@ namespace rl /** * Check if current configuration is singular. - * + * * @pre calculateJacobian() */ bool isSingular() const; /** * Check if current configuration is singular. - * + * * @param[in] J Jacobian matrix \f$\matr{J}(\vec{q})\f$ */ bool isSingular(const ::rl::math::Matrix& J) const; @@ -222,33 +222,33 @@ namespace rl protected: /** * Jacobian matrix inverse. - * + * * \f[ \matr{J}^{\dagger}(\vec{q}) \f] - * + * * @pre calculateJacobianInverse() - * + * * @see getJacobianInverse() * */ ::rl::math::Matrix invJ; /** * Jacobian matrix. - * + * * \f[ \matr{J}(\vec{q}) \f] - * + * * @pre calculateJacobian() - * + * * @see getJacobian() * */ ::rl::math::Matrix J; /** * Jacobian derivative vector. - * + * * \f[ \dot{\matr{J}}(\vec{q}, \dot{\vec{q}}) \, \dot{\vec{q}} \f] - * + * * @pre calculateJacobianDerivative() - * + * * @see getJacobianDerivative() * */ ::rl::math::Vector Jdqd; diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 2eb2a781..1edd8825 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -43,7 +43,7 @@ namespace rl { /** * Rigid body kinematics and dynamics. - * + * * Roy Featherstone. Rigid Body Dynamics Algorithms. Springer, New * York, NY, USA, 2008. */ diff --git a/src/rl/mdl/RungeKuttaNystromIntegrator.h b/src/rl/mdl/RungeKuttaNystromIntegrator.h index 906c06f9..ecbd1c51 100644 --- a/src/rl/mdl/RungeKuttaNystromIntegrator.h +++ b/src/rl/mdl/RungeKuttaNystromIntegrator.h @@ -35,7 +35,7 @@ namespace rl { /** * Integration via Runge-Kutta-Nyström. - * + * * \f[ \vec{q}_{i + 1} = \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} + \frac{\Delta t}{3} (\vec{k}_{1} + \vec{k}_{2} + \vec{k}_{3}) \f] * \f[ \dot{\vec{q}}_{i + 1} = \dot{\vec{q}}_{i} + \frac{1}{3} (\vec{k}_{1} + 2 \vec{k}_{2} + 2 \vec{k}_{3} + \vec{k}_{4}) \f] * \f[ \ddot{\vec{q}} = f(t, \vec{q}, \dot{\vec{q}}) \f] @@ -44,14 +44,14 @@ namespace rl * \f[ \vec{k}_{2} = \frac{\Delta t}{2} \, f(t_{i} + \frac{\Delta t}{2}, \vec{q}_{i} + \frac{\Delta t}{2} \, \dot{\vec{q}}_{i} + \frac{\Delta t}{4} \, \vec{k}_{1}, \dot{\vec{q}}_{i} + \vec{k}_{1}) \f] * \f[ \vec{k}_{3} = \frac{\Delta t}{2} \, f(t_{i} + \frac{\Delta t}{2}, \vec{q}_{i} + \frac{\Delta t}{2} \, \dot{\vec{q}}_{i} + \frac{\Delta t}{4} \, \vec{k}_{1}, \dot{\vec{q}}_{i} + \vec{k}_{2}) \f] * \f[ \vec{k}_{4} = \frac{\Delta t}{2} \, f(t_{i} + \Delta t, \vec{q}_{i} + \Delta t \, \dot{\vec{q}}_{i} + \Delta t \, \vec{k}_{3}, \dot{\vec{q}}_{i} + 2 \vec{k}_{3}) \f] - * + * * @pre Dynamic::setPosition() * @pre Dynamic::setVelocity() * @pre Dynamic::setTorque() * @post Dynamic::getPosition() * @post Dynamic::getVelocity() * @post Dynamic::getAcceleration() - * + * * @see Dynamic::forwardDynamics() */ class RL_MDL_EXPORT RungeKuttaNystromIntegrator : public Integrator diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 298b1dfe..08e70767 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -27,7 +27,7 @@ #include // TODO #include #include -#include +#include #include #include #include diff --git a/src/rl/plan/AddRrtConCon.h b/src/rl/plan/AddRrtConCon.h index eb7f9440..1d08f89d 100644 --- a/src/rl/plan/AddRrtConCon.h +++ b/src/rl/plan/AddRrtConCon.h @@ -35,12 +35,12 @@ namespace rl { /** * Adaptive Dynamic-Domain RRT. - * + * * Léonard Jaillet, Anna Yershova, Steven M. LaValle, and Thiery * Siméon. Adaptive tuning of the sampling domain for dynamic-domain * RRTs. In Proceedings of the IEEE/RSJ International Conference on Intelligent * Robots and Systems, pages 2851-2856, August 2005. - * + * * http://dx.doi.org/10.1109/IROS.2005.1545607 */ class RL_PLAN_EXPORT AddRrtConCon : public RrtConCon diff --git a/src/rl/plan/BridgeSampler.h b/src/rl/plan/BridgeSampler.h index ef51b45f..f4cc4883 100644 --- a/src/rl/plan/BridgeSampler.h +++ b/src/rl/plan/BridgeSampler.h @@ -35,12 +35,12 @@ namespace rl { /** * Bridge test sampling strategy. - * + * * David Hsu, Tingting Jiang, John Reif, and Zheng Sun. The bridge test * for sampling narrow passages with probabilistic roadmap planners. In * Proceedings of the IEEE International Conference on Robotics and Automation, * pages 4420-4426, September 2003. - * + * * http://dx.doi.org/10.1109/ROBOT.2003.1242285 */ class RL_PLAN_EXPORT BridgeSampler : public GaussianSampler diff --git a/src/rl/plan/Eet.h b/src/rl/plan/Eet.h index 0da240a0..a2c608e5 100644 --- a/src/rl/plan/Eet.h +++ b/src/rl/plan/Eet.h @@ -42,11 +42,11 @@ namespace rl /** * Exploring/Exploiting Trees - * + * * Markus Rickert, Arne Sieverling, and Oliver Brock. Balancing exploration * and exploitation in sampling-based motion planning. IEEE Transactions on * Robotics, 30(6):1305-1317, December 2014. - * + * * http://dx.doi.org/10.1109/TRO.2014.2340191 */ class RL_PLAN_EXPORT Eet : public RrtCon diff --git a/src/rl/plan/GaussianSampler.h b/src/rl/plan/GaussianSampler.h index 98d59147..92f37a4e 100644 --- a/src/rl/plan/GaussianSampler.h +++ b/src/rl/plan/GaussianSampler.h @@ -35,12 +35,12 @@ namespace rl { /** * Gaussian sampling strategy. - * + * * Valérie Boor, Mark H. Overmars, and A. Frank van der Stappen. * The Gaussian sampling strategy for probabilistic roadmap planners. * In Proceedings of the IEEE International Conference on Robotics and * Automation, pages 1018-1023, Detroit, MI, USA, May 1999. - * + * * http://dx.doi.org/10.1109/ROBOT.1999.772447 */ class RL_PLAN_EXPORT GaussianSampler : public UniformSampler diff --git a/src/rl/plan/Planner.h b/src/rl/plan/Planner.h index 63b530d3..246b568c 100644 --- a/src/rl/plan/Planner.h +++ b/src/rl/plan/Planner.h @@ -37,7 +37,7 @@ namespace rl { /** - * Collision-free path planning. + * Collision-free path planning. */ namespace plan { @@ -55,7 +55,7 @@ namespace rl /** * Get solution path. - * + * * @pre solve() */ virtual VectorList getPath() = 0; diff --git a/src/rl/plan/Prm.h b/src/rl/plan/Prm.h index cd4a265b..fb1794db 100644 --- a/src/rl/plan/Prm.h +++ b/src/rl/plan/Prm.h @@ -46,19 +46,19 @@ namespace rl /** * Probabilistic Roadmaps. - * + * * Lydia Kavraki and Jean-Claude Latombe. Randomized preprocessing of * configuration space for path planning: Articulated robots. In Proceedings * of the IEEE/RSJ/GI International Conference on Intelligent Robots and * Systems, pages 1764-1771, Munich, Germany, September 1994. - * + * * http://dx.doi.org/10.1109/IROS.1994.407619 - * + * * Lydia E. Kavraki, Petr Švestka, Jean-Claude Latombe, and Mark H. * Overmars. Probabilistic roadmaps for path planning in high-dimensional * configuration spaces. IEEE Transactions on Robotics and Automation, * 12(4):566-580, August 1996. - * + * * http://dx.doi.org/10.1109/70.508439 */ class RL_PLAN_EXPORT Prm : public Planner @@ -114,7 +114,7 @@ namespace rl ::boost::listS, ::boost::undirectedS, ::boost::listS - >::vertex_descriptor Vertex; + >::vertex_descriptor Vertex; struct VertexBundle { diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index 183b920e..d6da709c 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -82,7 +82,7 @@ namespace rl #else // This works better in our examples. Here we define entropy by using samples where we are unsure, if they are colliding. if (::std::abs(pFree - static_cast<::rl::math::Real>(0.5)) < ::std::abs(pBest - static_cast<::rl::math::Real>(0.5))) - { + { pBest = pFree; bestSample = sample; } @@ -173,7 +173,7 @@ namespace rl ++collisionCount; } - queue.pop(); + queue.pop(); } return 1 - static_cast<::rl::math::Real>(collisionCount) / static_cast<::rl::math::Real>(count); @@ -182,7 +182,7 @@ namespace rl ::std::string PrmUtilityGuided::getName() const { - return "PRM Utility Guided"; + return "PRM Utility Guided"; } ::std::uniform_real_distribution<::rl::math::Real>::result_type diff --git a/src/rl/plan/PrmUtilityGuided.h b/src/rl/plan/PrmUtilityGuided.h index 74f02322..3d272b05 100644 --- a/src/rl/plan/PrmUtilityGuided.h +++ b/src/rl/plan/PrmUtilityGuided.h @@ -40,11 +40,11 @@ namespace rl { /** * Probabilistic Roadmaps with Utility-Guided Sampling. - * + * * Brendan Burns and Oliver Brock. Toward optimal configuration space sampling. * In Proceedings of the Robotics Science and Systems Conference, Cambridge, * MA, USA, June 2005. - * + * * http://www.roboticsproceedings.org/rss01/p15.pdf */ class RL_PLAN_EXPORT PrmUtilityGuided : public Prm diff --git a/src/rl/plan/Rrt.h b/src/rl/plan/Rrt.h index b4ee139d..9fe36479 100644 --- a/src/rl/plan/Rrt.h +++ b/src/rl/plan/Rrt.h @@ -44,11 +44,11 @@ namespace rl /** * Rapidly-Exploring Random Trees. - * + * * Steven M. LaValle. Rapidly-exploring random trees: A new tool for path * planning. Technical Report TR 98-11, Iowa State University, Ames, IA, * USA, October 1998. - * + * * http://msl.cs.uiuc.edu/~lavalle/papers/Lav98c.pdf */ class RL_PLAN_EXPORT Rrt : public Planner @@ -106,7 +106,7 @@ namespace rl ::boost::listS, ::boost::bidirectionalS, ::boost::listS - >::vertex_descriptor Vertex; + >::vertex_descriptor Vertex; struct TreeBundle { diff --git a/src/rl/plan/RrtCon.h b/src/rl/plan/RrtCon.h index 364eb866..0147438b 100644 --- a/src/rl/plan/RrtCon.h +++ b/src/rl/plan/RrtCon.h @@ -35,12 +35,12 @@ namespace rl { /** * RRT-Connect1. - * + * * James J. Kuffner, Jr. and Steven M. LaValle. RRT-connect: An efficient * approach to single-query path planning. In Proceedings of the IEEE * International Conference on Robotics and Automation, pages 995-1001, * April 2000. - * + * * http://dx.doi.org/10.1109/ROBOT.2000.844730 */ class RL_PLAN_EXPORT RrtCon : public RrtGoalBias diff --git a/src/rl/plan/RrtConCon.h b/src/rl/plan/RrtConCon.h index afe94c97..9392afb5 100644 --- a/src/rl/plan/RrtConCon.h +++ b/src/rl/plan/RrtConCon.h @@ -35,12 +35,12 @@ namespace rl { /** * RRT-Connect2. - * + * * James J. Kuffner, Jr. and Steven M. LaValle. RRT-connect: An efficient * approach to single-query path planning. In Proceedings of the IEEE * International Conference on Robotics and Automation, pages 995-1001, * April 2000. - * + * * http://dx.doi.org/10.1109/ROBOT.2000.844730 */ class RL_PLAN_EXPORT RrtConCon : public RrtDual diff --git a/src/rl/plan/WorkspaceSphere.h b/src/rl/plan/WorkspaceSphere.h index e3db388e..d812241d 100644 --- a/src/rl/plan/WorkspaceSphere.h +++ b/src/rl/plan/WorkspaceSphere.h @@ -43,7 +43,7 @@ namespace rl ::boost::listS, ::boost::listS, ::boost::bidirectionalS - >::vertex_descriptor Vertex; + >::vertex_descriptor Vertex; bool operator<(const WorkspaceSphere& rhs) const; diff --git a/src/rl/plan/WorkspaceSphereExplorer.h b/src/rl/plan/WorkspaceSphereExplorer.h index 30de7203..f2410880 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.h +++ b/src/rl/plan/WorkspaceSphereExplorer.h @@ -46,12 +46,12 @@ namespace rl /** * Wavefront expansion. - * + * * Oliver Brock and Lydia E. Kavraki. Decomposition-based motion planning: * A framework for real-time motion planning in high-dimensional configuration * spaces. In Proceedings of the IEEE International Conference on Robotics * and Automation, pages 1469-1474, 2001. - * + * * http://dx.doi.org/10.1109/ROBOT.2001.932817 */ class RL_PLAN_EXPORT WorkspaceSphereExplorer diff --git a/src/rl/sg/bullet/Scene.cpp b/src/rl/sg/bullet/Scene.cpp index 72aa019e..1f67c5dc 100644 --- a/src/rl/sg/bullet/Scene.cpp +++ b/src/rl/sg/bullet/Scene.cpp @@ -235,7 +235,7 @@ namespace rl RayResultCallback resultCallback; - this->world.rayTest(rayFromWorld, rayToWorld, resultCallback); + this->world.rayTest(rayFromWorld, rayToWorld, resultCallback); if (nullptr != resultCallback.collisionShape) { diff --git a/src/rl/sg/bullet/Scene.h b/src/rl/sg/bullet/Scene.h index 91b97c28..552af6bf 100644 --- a/src/rl/sg/bullet/Scene.h +++ b/src/rl/sg/bullet/Scene.h @@ -40,7 +40,7 @@ namespace rl { /** * Bullet Physics Library. - * + * * http://bulletphysics.org/ */ namespace bullet @@ -91,7 +91,7 @@ namespace rl protected: private: - struct ContactResultCallback : public ::btCollisionWorld::ContactResultCallback + struct ContactResultCallback : public ::btCollisionWorld::ContactResultCallback { ContactResultCallback(); diff --git a/src/rl/sg/fcl/Body.cpp b/src/rl/sg/fcl/Body.cpp index 111d93b7..f44b3ed7 100644 --- a/src/rl/sg/fcl/Body.cpp +++ b/src/rl/sg/fcl/Body.cpp @@ -98,7 +98,7 @@ namespace rl void Body::setFrame(const ::rl::math::Transform& frame) - { + { this->frame = frame; for (Iterator i = this->begin(); i != this->end(); ++i) diff --git a/src/rl/sg/fcl/Model.cpp b/src/rl/sg/fcl/Model.cpp index b468e695..fc9365b9 100644 --- a/src/rl/sg/fcl/Model.cpp +++ b/src/rl/sg/fcl/Model.cpp @@ -65,7 +65,7 @@ namespace rl } } - void + void Model::addCollisionObject(::fcl::CollisionObject* collisionObject, Body* body) { this->manager.registerObject(collisionObject); @@ -97,7 +97,7 @@ namespace rl } } - void + void Model::removeCollisionObject(::fcl::CollisionObject* collisionObject) { this->manager.unregisterObject(collisionObject); diff --git a/src/rl/sg/fcl/Scene.cpp b/src/rl/sg/fcl/Scene.cpp index 0d10855e..deb5cc9d 100644 --- a/src/rl/sg/fcl/Scene.cpp +++ b/src/rl/sg/fcl/Scene.cpp @@ -232,7 +232,7 @@ namespace rl point2(i) = distanceData.result.nearest_points[1][i]; } - return distanceData.result.min_distance; + return distanceData.result.min_distance; } ::rl::math::Real @@ -252,7 +252,7 @@ namespace rl point2(i) = distanceData.result.nearest_points[1][i]; } - return distanceData.result.min_distance; + return distanceData.result.min_distance; } ::rl::math::Real diff --git a/src/rl/sg/fcl/Scene.h b/src/rl/sg/fcl/Scene.h index f9039569..30cd3bdb 100644 --- a/src/rl/sg/fcl/Scene.h +++ b/src/rl/sg/fcl/Scene.h @@ -41,7 +41,7 @@ namespace rl { /** * Flexible Collision Library. - * + * * https://github.com/flexible-collision-library/fcl */ namespace fcl diff --git a/src/rl/sg/ode/Scene.cpp b/src/rl/sg/ode/Scene.cpp index f4daa5b3..788ef60a 100644 --- a/src/rl/sg/ode/Scene.cpp +++ b/src/rl/sg/ode/Scene.cpp @@ -240,8 +240,8 @@ namespace rl Scene::rayNearCallback(void* data, ::dGeomID o1, ::dGeomID o2) { if (::dGeomIsSpace(o1) || ::dGeomIsSpace(o2)) - { - ::dSpaceCollide2(o1, o2, data, &Scene::rayNearCallback); + { + ::dSpaceCollide2(o1, o2, data, &Scene::rayNearCallback); if (::dGeomIsSpace(o1)) { diff --git a/src/rl/sg/ode/Scene.h b/src/rl/sg/ode/Scene.h index fd568627..e47771c4 100644 --- a/src/rl/sg/ode/Scene.h +++ b/src/rl/sg/ode/Scene.h @@ -39,7 +39,7 @@ namespace rl { /** * Open Dynamics Engine. - * + * * http://www.ode.org/ */ namespace ode diff --git a/src/rl/sg/pqp/Scene.h b/src/rl/sg/pqp/Scene.h index 6bcf7d9a..06ac4988 100644 --- a/src/rl/sg/pqp/Scene.h +++ b/src/rl/sg/pqp/Scene.h @@ -39,7 +39,7 @@ namespace rl { /** * Proximity Query Package. - * + * * http://gamma.cs.unc.edu/SSV/ */ namespace pqp diff --git a/src/rl/sg/solid/Scene.h b/src/rl/sg/solid/Scene.h index 58a3e864..675e87e4 100644 --- a/src/rl/sg/solid/Scene.h +++ b/src/rl/sg/solid/Scene.h @@ -41,7 +41,7 @@ namespace rl { /** * SOLID. - * + * * http://www.dtecta.com/ */ namespace solid diff --git a/src/rl/xml/Attribute.h b/src/rl/xml/Attribute.h index 7077abdf..fd42dedd 100644 --- a/src/rl/xml/Attribute.h +++ b/src/rl/xml/Attribute.h @@ -83,7 +83,7 @@ namespace rl ::std::string getName() const { - return nullptr != this->attr->name ? reinterpret_cast(this->attr->name) : ::std::string(); + return nullptr != this->attr->name ? reinterpret_cast(this->attr->name) : ::std::string(); } Attribute getNext() const diff --git a/tests/rlCollisionTest/rlCollisionTest.cpp b/tests/rlCollisionTest/rlCollisionTest.cpp index 7d747cd7..40d76cba 100644 --- a/tests/rlCollisionTest/rlCollisionTest.cpp +++ b/tests/rlCollisionTest/rlCollisionTest.cpp @@ -162,7 +162,7 @@ main(int argc, char** argv) for (std::size_t i = 0; i < scenes.size(); ++i) { - std::cout << "Testing SimpleScene::isColliding() in " << sceneNames[i] << ": "; + std::cout << "Testing SimpleScene::isColliding() in " << sceneNames[i] << ": "; std::cout << (collides(scenes[i], kinematics.get()) ? "true" : "false") << std::endl; } diff --git a/tests/rlJacobianKinTest/rlJacobianKinTest.cpp b/tests/rlJacobianKinTest/rlJacobianKinTest.cpp index 8c4f6b1a..b266d9b2 100644 --- a/tests/rlJacobianKinTest/rlJacobianKinTest.cpp +++ b/tests/rlJacobianKinTest/rlJacobianKinTest.cpp @@ -46,12 +46,12 @@ main(int argc, char** argv) std::srand(0); // get reproducible results for (std::size_t n = 0; n < 5; ++n) - { + { rl::math::Vector q(dof); for (std::size_t i = 0; i < dof; ++i) { - rl::math::Real r = static_cast(std::rand()) / static_cast(RAND_MAX); + rl::math::Real r = static_cast(std::rand()) / static_cast(RAND_MAX); q(i) = (r - 0.5) * 360 * rl::math::DEG2RAD; } diff --git a/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp b/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp index 3bad206b..543bcf77 100644 --- a/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp +++ b/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp @@ -49,12 +49,12 @@ main(int argc, char** argv) std::srand(0); // get reproducible results for (std::size_t n = 0; n < 5; ++n) - { + { rl::math::Vector q(dof); for (std::size_t i = 0; i < dof; ++i) { - rl::math::Real r = static_cast(std::rand()) / static_cast(RAND_MAX); + rl::math::Real r = static_cast(std::rand()) / static_cast(RAND_MAX); q(i) = (r - 0.5) * 360 * rl::math::DEG2RAD; } diff --git a/tests/rlSplineTest/rlPolynomialExtremaTest.cpp b/tests/rlSplineTest/rlPolynomialExtremaTest.cpp index c927fb71..ad00040a 100644 --- a/tests/rlSplineTest/rlPolynomialExtremaTest.cpp +++ b/tests/rlSplineTest/rlPolynomialExtremaTest.cpp @@ -34,7 +34,7 @@ main(int argc, char** argv) { rl::math::Polynomial p = rl::math::Polynomial::Quadratic( rl::math::ArrayX::Constant(1, 0), - rl::math::ArrayX::Constant(1, 1), + rl::math::ArrayX::Constant(1, 1), rl::math::ArrayX::Constant(1, 0), 1 ); diff --git a/tests/rlSplineTest/rlSplineTest.cpp b/tests/rlSplineTest/rlSplineTest.cpp index aaa27966..1b457438 100644 --- a/tests/rlSplineTest/rlSplineTest.cpp +++ b/tests/rlSplineTest/rlSplineTest.cpp @@ -33,7 +33,7 @@ main(int argc, char** argv) { /* We mostly test against (Eigen) asserts in the Spline methods, * the tests for continuity are just in addition. - */ + */ { // One-dimensional From 6092050087cbd021eb013c0e44f2305622a4515e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 14 Jun 2020 01:00:13 +0200 Subject: [PATCH 365/546] Minor fixes --- src/rl/sg/fcl/Body.cpp | 20 +++++++------------- src/rl/sg/fcl/Body.h | 2 -- src/rl/sg/fcl/Model.cpp | 3 +-- src/rl/sg/fcl/Scene.cpp | 16 ++++++++++++++++ src/rl/sg/fcl/Scene.h | 16 ++-------------- src/rl/sg/fcl/Shape.cpp | 2 +- 6 files changed, 27 insertions(+), 32 deletions(-) diff --git a/src/rl/sg/fcl/Body.cpp b/src/rl/sg/fcl/Body.cpp index f44b3ed7..9eee4899 100644 --- a/src/rl/sg/fcl/Body.cpp +++ b/src/rl/sg/fcl/Body.cpp @@ -46,11 +46,6 @@ namespace rl Body::~Body() { - for (::std::size_t i = 0; i < this->collisionObjects.size(); ++i) - { - manager.unregisterObject(this->collisionObjects[i]); - } - while (this->shapes.size() > 0) { delete this->shapes[0]; @@ -59,23 +54,22 @@ namespace rl this->getModel()->remove(this); } - ::rl::sg::Shape* - Body::create(SoVRMLShape* shape) - { - Shape* newShape = new Shape(shape, this); - return newShape; - } - void Body::add(::rl::sg::Shape* shape) { Shape* fclShape = static_cast(shape); this->shapes.push_back(fclShape); - fclShape->update(frame); + fclShape->update(this->frame); this->manager.registerObject(fclShape->collisionObject.get()); static_cast(getModel())->addCollisionObject(fclShape->collisionObject.get(), this); } + ::rl::sg::Shape* + Body::create(SoVRMLShape* shape) + { + return new Shape(shape, this); + } + void Body::getFrame(::rl::math::Transform& frame) { diff --git a/src/rl/sg/fcl/Body.h b/src/rl/sg/fcl/Body.h index 21d9c036..ab2237da 100644 --- a/src/rl/sg/fcl/Body.h +++ b/src/rl/sg/fcl/Body.h @@ -57,8 +57,6 @@ namespace rl void setFrame(const ::rl::math::Transform& frame); - ::std::vector<::fcl::CollisionObject*> collisionObjects; - ::fcl::DynamicAABBTreeCollisionManager manager; protected: diff --git a/src/rl/sg/fcl/Model.cpp b/src/rl/sg/fcl/Model.cpp index fc9365b9..26507b42 100644 --- a/src/rl/sg/fcl/Model.cpp +++ b/src/rl/sg/fcl/Model.cpp @@ -75,8 +75,7 @@ namespace rl ::rl::sg::Body* Model::create() { - Body* newBody = new Body(this); - return newBody; + return new Body(this); } void diff --git a/src/rl/sg/fcl/Scene.cpp b/src/rl/sg/fcl/Scene.cpp index deb5cc9d..84293376 100644 --- a/src/rl/sg/fcl/Scene.cpp +++ b/src/rl/sg/fcl/Scene.cpp @@ -347,6 +347,22 @@ namespace rl this->bodyForObj.erase(collisionObject); this->manager.unregisterObject(collisionObject); } + + Scene::CollisionData::CollisionData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj) : + bodyForObj(bodyForObj), + done(false), + request(), + result() + { + } + + Scene::DistanceData::DistanceData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj) : + bodyForObj(bodyForObj), + done(false), + request(true), + result() + { + } } } } diff --git a/src/rl/sg/fcl/Scene.h b/src/rl/sg/fcl/Scene.h index 30cd3bdb..a69a5495 100644 --- a/src/rl/sg/fcl/Scene.h +++ b/src/rl/sg/fcl/Scene.h @@ -92,13 +92,7 @@ namespace rl private: struct CollisionData { - CollisionData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj) : - bodyForObj(bodyForObj), - done(false), - request(), - result() - { - } + CollisionData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj); const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj; @@ -111,13 +105,7 @@ namespace rl struct DistanceData { - DistanceData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj) : - bodyForObj(bodyForObj), - done(false), - request(true), - result() - { - } + DistanceData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj); const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj; diff --git a/src/rl/sg/fcl/Shape.cpp b/src/rl/sg/fcl/Shape.cpp index a9deae51..4ded85d1 100644 --- a/src/rl/sg/fcl/Shape.cpp +++ b/src/rl/sg/fcl/Shape.cpp @@ -190,7 +190,7 @@ namespace rl this->collisionObject = ::std::make_shared<::fcl::CollisionObject>(this->geometry, ::fcl::Transform3f()); this->getBody()->add(this); - setTransform(::rl::math::Transform::Identity()); + this->setTransform(::rl::math::Transform::Identity()); } Shape::~Shape() From f85ea6c605ac9684e6029496b55744e4e92b5b69 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 14 Jun 2020 18:56:22 +0200 Subject: [PATCH 366/546] Update template specialization for type traits --- src/rl/math/TypeTraits.h | 44 ++++++++++++++++++++-------------------- 1 file changed, 22 insertions(+), 22 deletions(-) diff --git a/src/rl/math/TypeTraits.h b/src/rl/math/TypeTraits.h index 72393d4e..2f24ef95 100644 --- a/src/rl/math/TypeTraits.h +++ b/src/rl/math/TypeTraits.h @@ -41,7 +41,7 @@ namespace rl { namespace math { - template + template class TypeTraits { public: @@ -121,43 +121,43 @@ namespace rl }; - template<> - class TypeTraits + template + class TypeTraits::value>::type> { public: - typedef float value_type; + typedef T value_type; - static float Constant(const ::std::size_t& i, const float& value) + static T Constant(const ::std::size_t& i, const T& value) { return value; } - static float Zero(const ::std::size_t& i) + static T Zero(const ::std::size_t& i) { return 0; } - static float abs(const float& t) + static T abs(const float& t) { return ::std::abs(t); } - static bool equal(const float& lhs, const float& rhs, const float& epsilon = ::Eigen::NumTraits::dummy_precision()) + static bool equal(const T& lhs, const T& rhs) { - return ::Eigen::internal::isApprox(lhs, rhs, epsilon); + return lhs == rhs; } - static float max_element(const float& t) + static T max_element(const T& t) { return t; } - static float min_element(const float& t) + static T min_element(const T& t) { return t; } - static ::std::size_t size(const float& t) + static ::std::size_t size(const T& t) { return 1; } @@ -168,43 +168,43 @@ namespace rl }; - template<> - class TypeTraits + template + class TypeTraits::value>::type> { public: - typedef double value_type; + typedef T value_type; - static double Constant(const ::std::size_t& i, const double& value) + static T Constant(const ::std::size_t& i, const T& value) { return value; } - static double Zero(const ::std::size_t& i) + static T Zero(const ::std::size_t& i) { return 0; } - static double abs(const double& t) + static T abs(const float& t) { return ::std::abs(t); } - static bool equal(const double& lhs, const double& rhs, const double& epsilon = ::Eigen::NumTraits::dummy_precision()) + static bool equal(const T& lhs, const T& rhs, const T& epsilon = ::Eigen::NumTraits::dummy_precision()) { return ::Eigen::internal::isApprox(lhs, rhs, epsilon); } - static double max_element(const double& t) + static T max_element(const T& t) { return t; } - static double min_element(const double& t) + static T min_element(const T& t) { return t; } - static ::std::size_t size(const double& t) + static ::std::size_t size(const T& t) { return 1; } From d2af8aa382ee350b62bb45f366b29c08ee3f4dd5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 14 Jun 2020 18:57:54 +0200 Subject: [PATCH 367/546] Minor fix --- src/rl/math/LowPass.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/rl/math/LowPass.h b/src/rl/math/LowPass.h index f874b95e..789dd1b7 100644 --- a/src/rl/math/LowPass.h +++ b/src/rl/math/LowPass.h @@ -42,7 +42,7 @@ namespace rl class LowPass { public: - LowPass(const ::rl::math::Real& alpha, const ::rl::math::Real& dt, const ::rl::math::Real& rc, const T& y = T()) : + LowPass(const Real& alpha, const Real& dt, const Real& rc, const T& y = T()) : alpha(alpha), dt(dt), rc(rc), @@ -50,10 +50,10 @@ namespace rl { } - static LowPass Frequency(const ::rl::math::Real& frequency, const ::rl::math::Real& dt, const T& y = T()) + static LowPass Frequency(const Real& frequency, const Real& dt, const T& y = T()) { - ::rl::math::Real rc = 1 / (2 * M_PI * frequency); - ::rl::math::Real alpha = dt / (rc + dt); + Real rc = 1 / (2 * static_cast(M_PI) * frequency); + Real alpha = dt / (rc + dt); return LowPass(alpha, dt, rc, y); } @@ -69,11 +69,11 @@ namespace rl protected: private: - ::rl::math::Real alpha; + Real alpha; - ::rl::math::Real dt; + Real dt; - ::rl::math::Real rc; + Real rc; T y; }; From ed7e004edeb6de364435b9d7343ba98a4105b5c4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 14 Jun 2020 20:29:59 +0200 Subject: [PATCH 368/546] Add floating point math constants to type traits --- CMakeLists.txt | 1 - src/rl/kin/Puma.cpp | 27 ++++++++++++----------- src/rl/kin/Revolute.cpp | 7 +++--- src/rl/kin/Rhino.cpp | 5 +++-- src/rl/math/CMakeLists.txt | 4 ---- src/rl/math/CircularVector2.h | 3 ++- src/rl/math/LowPass.h | 5 ++--- src/rl/math/MatrixBaseAddons.h | 8 +++++++ src/rl/math/Polynomial.h | 4 ++-- src/rl/math/QuaternionBaseAddons.h | 5 +++++ src/rl/math/TypeTraits.h | 26 ++++++++++++++++++++++ src/rl/math/Unit.h | 7 +++--- src/rl/mdl/Revolute.cpp | 7 +++--- tests/rlMathDeltaTest/rlMathDeltaTest.cpp | 9 ++++---- 14 files changed, 78 insertions(+), 40 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 5e6b5999..d3fd579c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -47,7 +47,6 @@ endif() if(MSVC) add_definitions( -D_ENABLE_EXTENDED_ALIGNED_STORAGE - -D_USE_MATH_DEFINES ) endif() diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index 5e50eb51..45722ef8 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -26,6 +26,7 @@ #include #include +#include #include "Frame.h" #include "Joint.h" @@ -82,12 +83,12 @@ namespace rl && this->joints[4]->a == 0 && this->joints[5]->a == 0 && this->joints[4]->d == 0); - assert(::std::abs(this->joints[0]->alpha - (-static_cast<::rl::math::Real>(M_PI)/2)) < 1e-3 - && ::std::abs(this->joints[1]->alpha ) < 1e-3 - && ::std::abs(this->joints[2]->alpha - (-static_cast<::rl::math::Real>(M_PI)/2)) < 1e-3 - && ::std::abs(this->joints[3]->alpha - ( static_cast<::rl::math::Real>(M_PI)/2)) < 1e-3 - && ::std::abs(this->joints[4]->alpha - ( static_cast<::rl::math::Real>(M_PI)/2)) < 1e-3 - && ::std::abs(this->joints[5]->alpha ) < 1e-3); + assert(::std::abs(this->joints[0]->alpha - (-::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5)) < 1e-3 + && ::std::abs(this->joints[1]->alpha ) < 1e-3 + && ::std::abs(this->joints[2]->alpha - (-::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5)) < 1e-3 + && ::std::abs(this->joints[3]->alpha - ( ::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5)) < 1e-3 + && ::std::abs(this->joints[4]->alpha - ( ::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5)) < 1e-3 + && ::std::abs(this->joints[5]->alpha ) < 1e-3); ::rl::math::Real a1 = this->joints[0]->a; ::rl::math::Real a2 = this->joints[1]->a; @@ -194,10 +195,10 @@ namespace rl ::rl::math::Real theta3plusbeta = ::std::acos(costheta3plusbeta); // elbow - ::rl::math::Real theta3 = K * theta3plusbeta - beta - static_cast<::rl::math::Real>(M_PI); + ::rl::math::Real theta3 = K * theta3plusbeta - beta - ::rl::math::TypeTraits<::rl::math::Real>::pi; - ::rl::math::Real c23 = this->cos(theta2 + theta3 + static_cast<::rl::math::Real>(M_PI)); - ::rl::math::Real s23 = this->sin(theta2 + theta3 + static_cast<::rl::math::Real>(M_PI)); + ::rl::math::Real c23 = this->cos(theta2 + theta3 + ::rl::math::TypeTraits<::rl::math::Real>::pi); + ::rl::math::Real s23 = this->sin(theta2 + theta3 + ::rl::math::TypeTraits<::rl::math::Real>::pi); // forearm @@ -225,7 +226,7 @@ namespace rl c1 * s23 * a(0) + s1 * s23 * a(1) + c23 * a(2) - ) + static_cast<::rl::math::Real>(M_PI); + ) + ::rl::math::TypeTraits<::rl::math::Real>::pi; // flange @@ -274,9 +275,9 @@ namespace rl { myq(i) = q(i) + this->joints[i]->theta + this->joints[i]->offset; myq(i) = ::std::fmod( - myq(i) + static_cast<::rl::math::Real>(M_PI), - 2 * static_cast<::rl::math::Real>(M_PI) - ) - static_cast<::rl::math::Real>(M_PI); + myq(i) + ::rl::math::TypeTraits<::rl::math::Real>::pi, + 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi + ) - ::rl::math::TypeTraits<::rl::math::Real>::pi; } if (myq(4) < 0) diff --git a/src/rl/kin/Revolute.cpp b/src/rl/kin/Revolute.cpp index dbc66963..f7e1faf0 100644 --- a/src/rl/kin/Revolute.cpp +++ b/src/rl/kin/Revolute.cpp @@ -24,6 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include #include #include "Link.h" @@ -79,15 +80,15 @@ namespace rl void Revolute::normalize(::rl::math::Real& q) { - q = ::std::remainder(q, 2 * static_cast<::rl::math::Real>(M_PI)); + q = ::std::remainder(q, 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi); if (q < this->min) { - q += 2 * static_cast<::rl::math::Real>(M_PI); + q += 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi; } else if (q > this->max) { - q -= 2 * static_cast<::rl::math::Real>(M_PI); + q -= 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi; } } diff --git a/src/rl/kin/Rhino.cpp b/src/rl/kin/Rhino.cpp index 51858246..51fb2550 100644 --- a/src/rl/kin/Rhino.cpp +++ b/src/rl/kin/Rhino.cpp @@ -26,6 +26,7 @@ #include #include +#include #include "Frame.h" #include "Joint.h" @@ -138,13 +139,13 @@ namespace rl ::rl::math::Real c2 = cosAlpha * cosBeta - K * sinAlpha * sinBeta; // arm - ::rl::math::Real theta2 = this->atan2(s2, c2) + static_cast<::rl::math::Real>(M_PI_2); + ::rl::math::Real theta2 = this->atan2(s2, c2) + ::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5; ::rl::math::Real c3 = (a2_2 + a3_2 - Q_2) / (2 * a2 * a3); ::rl::math::Real s3 = K * ::std::sqrt(1 - ::std::pow(c3, 2)); // elbow - ::rl::math::Real theta3 = this->atan2(s3, c3) + static_cast<::rl::math::Real>(M_PI); + ::rl::math::Real theta3 = this->atan2(s3, c3) + ::rl::math::TypeTraits<::rl::math::Real>::pi; ::rl::math::Real c23 = this->cos(theta2 + theta3); ::rl::math::Real s23 = this->sin(theta2 + theta3); diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index b83d60d8..5f919c18 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -71,10 +71,6 @@ if(CMAKE_SIZEOF_VOID_P EQUAL 4) target_compile_definitions(math INTERFACE EIGEN_DONT_ALIGN_STATICALLY) endif() -if(MSVC) - target_compile_definitions(math INTERFACE _USE_MATH_DEFINES) -endif() - if(NOT CMAKE_VERSION VERSION_LESS 3.8) target_compile_features(math INTERFACE cxx_std_11) endif() diff --git a/src/rl/math/CircularVector2.h b/src/rl/math/CircularVector2.h index c6edf8e6..e45c50de 100644 --- a/src/rl/math/CircularVector2.h +++ b/src/rl/math/CircularVector2.h @@ -40,6 +40,7 @@ #include "Circular.h" #include "Function.h" #include "Matrix.h" +#include "TypeTraits.h" #include "Vector.h" namespace rl @@ -100,7 +101,7 @@ namespace rl if (f.angle < 0) { - f.angle += 2 * static_cast(M_PI); + f.angle += 2 * TypeTraits::pi; } f.x1 = x1; diff --git a/src/rl/math/LowPass.h b/src/rl/math/LowPass.h index 789dd1b7..1039cca8 100644 --- a/src/rl/math/LowPass.h +++ b/src/rl/math/LowPass.h @@ -27,9 +27,8 @@ #ifndef RL_MATH_LOWPASS_H #define RL_MATH_LOWPASS_H -#include - #include "Real.h" +#include "TypeTraits.h" namespace rl { @@ -52,7 +51,7 @@ namespace rl static LowPass Frequency(const Real& frequency, const Real& dt, const T& y = T()) { - Real rc = 1 / (2 * static_cast(M_PI) * frequency); + Real rc = 1 / (2 * TypeTraits::pi * frequency); Real alpha = dt / (rc + dt); return LowPass(alpha, dt, rc, y); } diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index 169dbb91..5d9cefcf 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -149,7 +149,11 @@ static RandomOnCircle(const Scalar& rand) eigen_assert(rand >= Scalar(0)); eigen_assert(rand <= Scalar(1)); +#ifdef EIGEN_PI + Scalar theta = Scalar(2) * Scalar(EIGEN_PI) * rand; +#else Scalar theta = Scalar(2) * Scalar(M_PI) * rand; +#endif return Matrix( cos(theta), @@ -190,7 +194,11 @@ static RandomOnSphere(const DenseBase& rand) eigen_assert(rand(1) >= Scalar(0)); eigen_assert(rand(1) <= Scalar(1)); +#ifdef EIGEN_PI + Scalar theta = Scalar(2) * Scalar(EIGEN_PI) * rand(0); +#else Scalar theta = Scalar(2) * Scalar(M_PI) * rand(0); +#endif Scalar z = Scalar(2) * rand(1) - Scalar(1); Scalar sqrt_1_z_2 = sqrt(Scalar(1) - pow(z, 2)); diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index f32ef695..7c30473f 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -600,8 +600,8 @@ namespace rl Real tmp2 = ::std::acos((3 * q) / (2 * p) * ::std::sqrt(-3 / p)) / 3; ::std::vector roots(3); roots[0] = tmp1 * ::std::cos(tmp2) - back; - roots[1] = tmp1 * ::std::cos(tmp2 - 2 * M_PI / 3) - back; - roots[2] = tmp1 * ::std::cos(tmp2 - 4 * M_PI / 3) - back; + roots[1] = tmp1 * ::std::cos(tmp2 - 2 * TypeTraits::pi / 3) - back; + roots[2] = tmp1 * ::std::cos(tmp2 - 4 * TypeTraits::pi / 3) - back; return roots; } else diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index 3b2ca28d..a4fb0b85 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -96,8 +96,13 @@ static Quaternion Random(const MatrixBase& rand) Scalar sigma1 = sqrt(Scalar(1) - rand(0)); Scalar sigma2 = sqrt(rand(0)); +#ifdef EIGEN_PI + Scalar theta1 = Scalar(2) * Scalar(EIGEN_PI) * rand(1); + Scalar theta2 = Scalar(2) * Scalar(EIGEN_PI) * rand(2); +#else Scalar theta1 = Scalar(2) * Scalar(M_PI) * rand(1); Scalar theta2 = Scalar(2) * Scalar(M_PI) * rand(2); +#endif return Quaternion( cos(theta2) * sigma2, diff --git a/src/rl/math/TypeTraits.h b/src/rl/math/TypeTraits.h index 2f24ef95..dd9eef55 100644 --- a/src/rl/math/TypeTraits.h +++ b/src/rl/math/TypeTraits.h @@ -209,6 +209,32 @@ namespace rl return 1; } + static constexpr T e = T(2.718281828459045235360287471352662498L); + + static constexpr T log2e = T(1.442695040888963407359924681001892137L); + + static constexpr T log10e = T(0.434294481903251827651128918916605082L); + + static constexpr T pi = T(3.141592653589793238462643383279502884L); + + static constexpr T inv_pi = T(0.318309886183790671537767526745028724L); + + static constexpr T inv_sqrtpi = T(0.564189583547756286948079451560772586L); + + static constexpr T ln2 = T(0.693147180559945309417232121458176568L); + + static constexpr T ln10 = T(2.302585092994045684017991454684364208L); + + static constexpr T sqrt2 = T(1.414213562373095048801688724209698079L); + + static constexpr T sqrt3 = T(1.732050807568877293527446341505872367L); + + static constexpr T inv_sqrt3 = T(0.577350269189625764509148780501957456L); + + static constexpr T egamma = T(0.577215664901532860606512090082402431L); + + static constexpr T phi = T(1.618033988749894848204586834365638118L); + protected: private: diff --git a/src/rl/math/Unit.h b/src/rl/math/Unit.h index 622bc6d7..c255eea5 100644 --- a/src/rl/math/Unit.h +++ b/src/rl/math/Unit.h @@ -27,9 +27,8 @@ #ifndef RL_MATH_UNIT_H #define RL_MATH_UNIT_H -#include - #include "Real.h" +#include "TypeTraits.h" namespace rl { @@ -338,7 +337,7 @@ namespace rl * * This is equal to a multiplication by π and a division by 180. */ - static const Real DEG2RAD = static_cast(M_PI) / static_cast(180); + static const Real DEG2RAD = TypeTraits::pi / static_cast(180); static const Real GIGA2UNIT = static_cast(1.0e+9); @@ -369,7 +368,7 @@ namespace rl * * This is equal to a multiplication by 180 and a division by π. */ - static const Real RAD2DEG = static_cast(180) / static_cast(M_PI); + static const Real RAD2DEG = static_cast(180) / TypeTraits::pi; static const Real UNIT2GIGA = static_cast(1.0e-9); diff --git a/src/rl/mdl/Revolute.cpp b/src/rl/mdl/Revolute.cpp index efeeeb52..bf902e77 100644 --- a/src/rl/mdl/Revolute.cpp +++ b/src/rl/mdl/Revolute.cpp @@ -25,6 +25,7 @@ // #include +#include #include "Revolute.h" @@ -106,15 +107,15 @@ namespace rl void Revolute::normalize(::rl::math::VectorRef q) const { - q(0) = ::std::remainder(q(0), 2 * static_cast<::rl::math::Real>(M_PI)); + q(0) = ::std::remainder(q(0), 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi); if (q(0) < this->min(0)) { - q(0) += 2 * static_cast<::rl::math::Real>(M_PI); + q(0) += 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi; } else if (q(0) > this->max(0)) { - q(0) -= 2 * static_cast<::rl::math::Real>(M_PI); + q(0) -= 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi; } } diff --git a/tests/rlMathDeltaTest/rlMathDeltaTest.cpp b/tests/rlMathDeltaTest/rlMathDeltaTest.cpp index 1dbf82f3..a50e4ba7 100644 --- a/tests/rlMathDeltaTest/rlMathDeltaTest.cpp +++ b/tests/rlMathDeltaTest/rlMathDeltaTest.cpp @@ -30,6 +30,7 @@ #include #include #include +#include #include int @@ -49,16 +50,16 @@ main(int argc, char** argv) rotation = 0.1; break; case 2: - rotation = M_PI / 2; + rotation = rl::math::TypeTraits::pi * 0.5; break; case 3: - rotation = M_PI; + rotation = rl::math::TypeTraits::pi; break; case 4: - rotation = 2 * M_PI; + rotation = 2 * rl::math::TypeTraits::pi; break; default: - rotation = -M_PI / 2; + rotation = -rl::math::TypeTraits::pi * 0.5; break; } From 22a051131c45e3e02e47837e4b71260ea0710f45 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 15 Jun 2020 00:17:28 +0200 Subject: [PATCH 369/546] Add support for FCL 0.6 --- cmake/FindFCL.cmake | 2 +- src/rl/sg/fcl/Body.cpp | 16 ++-- src/rl/sg/fcl/Body.h | 17 +++- src/rl/sg/fcl/Model.cpp | 8 +- src/rl/sg/fcl/Model.h | 20 ++++- src/rl/sg/fcl/Scene.cpp | 142 ++++++++++++++++++++---------- src/rl/sg/fcl/Scene.h | 53 ++++++++--- src/rl/sg/fcl/Shape.cpp | 189 +++++++++++++++++++++++++--------------- src/rl/sg/fcl/Shape.h | 40 +++++++-- 9 files changed, 333 insertions(+), 154 deletions(-) diff --git a/cmake/FindFCL.cmake b/cmake/FindFCL.cmake index f4d1f92d..a8af9e2f 100644 --- a/cmake/FindFCL.cmake +++ b/cmake/FindFCL.cmake @@ -49,7 +49,7 @@ file( find_path( FCL_INCLUDE_DIRS NAMES - fcl/distance.h + fcl/config.h HINTS ${FCL_INCLUDE_HINTS} PATHS diff --git a/src/rl/sg/fcl/Body.cpp b/src/rl/sg/fcl/Body.cpp index 9eee4899..cd7e931c 100644 --- a/src/rl/sg/fcl/Body.cpp +++ b/src/rl/sg/fcl/Body.cpp @@ -57,11 +57,11 @@ namespace rl void Body::add(::rl::sg::Shape* shape) { - Shape* fclShape = static_cast(shape); - this->shapes.push_back(fclShape); - fclShape->update(this->frame); - this->manager.registerObject(fclShape->collisionObject.get()); - static_cast(getModel())->addCollisionObject(fclShape->collisionObject.get(), this); + Shape* fcl = static_cast(shape); + this->shapes.push_back(fcl); + fcl->update(this->frame); + this->manager.registerObject(fcl->collisionObject.get()); + static_cast(getModel())->addCollisionObject(fcl->collisionObject.get(), this); } ::rl::sg::Shape* @@ -83,10 +83,10 @@ namespace rl if (found != this->shapes.end()) { - Shape* fclShape = static_cast(shape); + Shape* fcl = static_cast(shape); this->shapes.erase(found); - this->manager.unregisterObject(fclShape->collisionObject.get()); - static_cast(this->getModel())->removeCollisionObject(fclShape->collisionObject.get()); + this->manager.unregisterObject(fcl->collisionObject.get()); + static_cast(this->getModel())->removeCollisionObject(fcl->collisionObject.get()); } } diff --git a/src/rl/sg/fcl/Body.h b/src/rl/sg/fcl/Body.h index ab2237da..8353e77e 100644 --- a/src/rl/sg/fcl/Body.h +++ b/src/rl/sg/fcl/Body.h @@ -27,8 +27,13 @@ #ifndef RL_SG_FCL_BODY_H #define RL_SG_FCL_BODY_H -#include +#include + +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 #include +#else +#include +#endif #include "../Body.h" @@ -38,6 +43,12 @@ namespace rl { namespace fcl { +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + typedef ::fcl::DynamicAABBTreeCollisionManager DynamicAABBTreeCollisionManager; +#else + typedef ::fcl::DynamicAABBTreeCollisionManager<::rl::math::Real> DynamicAABBTreeCollisionManager; +#endif + class Model; class RL_SG_EXPORT Body : public ::rl::sg::Body @@ -57,7 +68,7 @@ namespace rl void setFrame(const ::rl::math::Transform& frame); - ::fcl::DynamicAABBTreeCollisionManager manager; + DynamicAABBTreeCollisionManager manager; protected: ::rl::math::Transform frame; @@ -69,4 +80,4 @@ namespace rl } } -#endif // RL_SG_BULLET_BODY_H +#endif // RL_SG_FCL_BODY_H diff --git a/src/rl/sg/fcl/Model.cpp b/src/rl/sg/fcl/Model.cpp index 26507b42..ca2f22cb 100644 --- a/src/rl/sg/fcl/Model.cpp +++ b/src/rl/sg/fcl/Model.cpp @@ -56,7 +56,7 @@ namespace rl Model::add(Body* body) { this->bodies.push_back(body); - ::std::vector<::fcl::CollisionObject*> objects; + ::std::vector objects; body->manager.getObjects(objects); if (objects.size() > 0) @@ -66,7 +66,7 @@ namespace rl } void - Model::addCollisionObject(::fcl::CollisionObject* collisionObject, Body* body) + Model::addCollisionObject(CollisionObject* collisionObject, Body* body) { this->manager.registerObject(collisionObject); dynamic_cast(this->getScene())->addCollisionObject(collisionObject, body); @@ -86,7 +86,7 @@ namespace rl if (found != this->bodies.end()) { this->bodies.erase(found); - ::std::vector<::fcl::CollisionObject*> objects; + ::std::vector objects; body->manager.getObjects(objects); for (::std::size_t i = 0; i < objects.size(); ++i) @@ -97,7 +97,7 @@ namespace rl } void - Model::removeCollisionObject(::fcl::CollisionObject* collisionObject) + Model::removeCollisionObject(CollisionObject* collisionObject) { this->manager.unregisterObject(collisionObject); dynamic_cast(this->getScene())->removeCollisionObject(collisionObject); diff --git a/src/rl/sg/fcl/Model.h b/src/rl/sg/fcl/Model.h index 9fd66c3b..2e5c30c6 100644 --- a/src/rl/sg/fcl/Model.h +++ b/src/rl/sg/fcl/Model.h @@ -27,7 +27,13 @@ #ifndef RL_SG_FCL_MODEL_H #define RL_SG_FCL_MODEL_H +#include + +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 #include +#else +#include +#endif #include "../Model.h" @@ -37,6 +43,14 @@ namespace rl { namespace fcl { +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + typedef ::fcl::CollisionObject CollisionObject; + typedef ::fcl::DynamicAABBTreeCollisionManager DynamicAABBTreeCollisionManager; +#else + typedef ::fcl::CollisionObject<::rl::math::Real> CollisionObject; + typedef ::fcl::DynamicAABBTreeCollisionManager<::rl::math::Real> DynamicAABBTreeCollisionManager; +#endif + class Scene; class RL_SG_EXPORT Model : public ::rl::sg::Model @@ -48,15 +62,15 @@ namespace rl void add(Body* body); - void addCollisionObject(::fcl::CollisionObject* collisionObject, Body* body); + void addCollisionObject(CollisionObject* collisionObject, Body* body); ::rl::sg::Body* create(); void remove(Body* body); - void removeCollisionObject(::fcl::CollisionObject* collisionObject); + void removeCollisionObject(CollisionObject* collisionObject); - ::fcl::DynamicAABBTreeCollisionManager manager; + DynamicAABBTreeCollisionManager manager; protected: diff --git a/src/rl/sg/fcl/Scene.cpp b/src/rl/sg/fcl/Scene.cpp index 84293376..4e4d5f29 100644 --- a/src/rl/sg/fcl/Scene.cpp +++ b/src/rl/sg/fcl/Scene.cpp @@ -24,12 +24,18 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include -#include +#include +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 #include #endif +#include +#include +#else +#include +#include +#endif #include "../Exception.h" #include "Body.h" @@ -43,10 +49,24 @@ namespace rl { namespace fcl { +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + typedef ::fcl::Contact Contact; + typedef ::fcl::Sphere Sphere; + typedef ::fcl::Transform3f Transform3; + typedef ::fcl::Vec3f Vector3; +#else + typedef ::fcl::Contact<::rl::math::Real> Contact; + typedef ::fcl::Sphere<::rl::math::Real> Sphere; + typedef ::fcl::Transform3<::rl::math::Real> Transform3; + typedef ::fcl::Translation3<::rl::math::Real> Translation3; + typedef ::fcl::Vector3<::rl::math::Real> Vector3; +#endif + Scene::Scene() : ::rl::sg::Scene(), ::rl::sg::SimpleScene(), - manager() + manager(), + bodyForObj() { this->manager.setup(); } @@ -62,10 +82,9 @@ namespace rl void Scene::add(::rl::sg::Model* model) { - Model* modelFcl = static_cast(model); this->models.push_back(model); - ::std::vector<::fcl::CollisionObject*> objects; - modelFcl->manager.getObjects(objects); + ::std::vector objects; + static_cast(model)->manager.getObjects(objects); if (objects.size() > 0) { @@ -74,7 +93,7 @@ namespace rl } void - Scene::addCollisionObject(::fcl::CollisionObject* collisionObject, Body* body) + Scene::addCollisionObject(CollisionObject* collisionObject, Body* body) { this->bodyForObj[collisionObject] = body; this->manager.registerObject(collisionObject); @@ -91,7 +110,7 @@ namespace rl CollisionData collisionData(this->bodyForObj); body1->manager.collide(&body2->manager, &collisionData, Scene::defaultCollisionFunction); - return collisionData.result.numContacts() > 0; + return collisionData.result.isCollision(); } bool @@ -105,7 +124,7 @@ namespace rl CollisionData collisionData(this->bodyForObj); model1->manager.collide(&model2->manager, &collisionData, Scene::defaultCollisionFunction); - return collisionData.result.numContacts() > 0; + return collisionData.result.isCollision(); } bool @@ -114,8 +133,8 @@ namespace rl Shape* shape1 = static_cast(first); Shape* shape2 = static_cast(second); - ::fcl::CollisionRequest request; - ::fcl::CollisionResult result; + CollisionRequest request; + CollisionResult result; ::fcl::collide(shape1->collisionObject.get(), shape2->collisionObject.get(), request, result); return result.isCollision(); @@ -128,11 +147,11 @@ namespace rl } bool - Scene::defaultCollisionFunction(::fcl::CollisionObject* o1, ::fcl::CollisionObject* o2, void* data) + Scene::defaultCollisionFunction(CollisionObject* o1, CollisionObject* o2, void* data) { CollisionData* collisionData = static_cast(data); - const ::fcl::CollisionRequest& request = collisionData->request; - ::fcl::CollisionResult& result = collisionData->result; + const CollisionRequest& request = collisionData->request; + CollisionResult& result = collisionData->result; if (collisionData->done) { @@ -155,11 +174,11 @@ namespace rl } bool - Scene::defaultDistanceFunction(::fcl::CollisionObject* o1, ::fcl::CollisionObject* o2, void* data, ::fcl::FCL_REAL& dist) + Scene::defaultDistanceFunction(CollisionObject* o1, CollisionObject* o2, void* data, Real& dist) { DistanceData* distanceData = static_cast(data); - const ::fcl::DistanceRequest& request = distanceData->request; - ::fcl::DistanceResult& result = distanceData->result; + const DistanceRequest& request = distanceData->request; + DistanceResult& result = distanceData->result; if (distanceData->done) { @@ -175,8 +194,10 @@ namespace rl ::fcl::distance(o1, o2, request, result); dist = result.min_distance; +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 result.nearest_points[0] = o1->getTransform().transform(result.nearest_points[0]); result.nearest_points[1] = o2->getTransform().transform(result.nearest_points[1]); +#endif if (dist <= 0) { @@ -192,8 +213,8 @@ namespace rl Shape* shape1 = static_cast(first); Shape* shape2 = static_cast(second); - ::fcl::CollisionRequest request(1, true); - ::fcl::CollisionResult result; + CollisionRequest request(1, true); + CollisionResult result; ::fcl::collide(shape1->collisionObject.get(), shape2->collisionObject.get(), request, result); if (0 == result.numContacts()) @@ -201,16 +222,25 @@ namespace rl return 0; } - const ::fcl::Contact& contact = result.getContact(0); + const Contact& contact = result.getContact(0); - ::fcl::Vec3f pos1 = contact.pos; - ::fcl::Vec3f pos2 = contact.pos + contact.normal * contact.penetration_depth; +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + Vector3 pos1 = contact.pos; +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 + Vector3 pos2 = contact.pos + contact.normal * contact.penetration_depth; +#else + Vector3 pos2 = contact.pos - contact.normal * contact.penetration_depth; +#endif for (::std::size_t i = 0; i < 3; ++i) { point1(i) = pos1[i]; point2(i) = pos2[i]; } +#else + point1 = contact.pos - contact.normal * contact.penetration_depth * 0.5; + point2 = contact.pos + contact.normal * contact.penetration_depth * 0.5; +#endif return result.isCollision() ? ::std::abs(contact.penetration_depth) : 0; } @@ -226,13 +256,18 @@ namespace rl DistanceData distanceData(this->bodyForObj); body1->manager.distance(&body2->manager, &distanceData, Scene::defaultDistanceFunction); +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 for (::std::size_t i = 0; i < 3; ++i) { point1(i) = distanceData.result.nearest_points[0][i]; point2(i) = distanceData.result.nearest_points[1][i]; } +#else + point1 = distanceData.result.nearest_points[0]; + point2 = distanceData.result.nearest_points[1]; +#endif - return distanceData.result.min_distance; + return ::std::max(static_cast(0), distanceData.result.min_distance); } ::rl::math::Real @@ -246,13 +281,18 @@ namespace rl DistanceData distanceData(this->bodyForObj); model1->manager.distance(&model2->manager, &distanceData, Scene::defaultDistanceFunction); +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 for (::std::size_t i = 0; i < 3; ++i) { point1(i) = distanceData.result.nearest_points[0][i]; point2(i) = distanceData.result.nearest_points[1][i]; } +#else + point1 = distanceData.result.nearest_points[0]; + point2 = distanceData.result.nearest_points[1]; +#endif - return distanceData.result.min_distance; + return ::std::max(static_cast(0), distanceData.result.min_distance); } ::rl::math::Real @@ -261,51 +301,65 @@ namespace rl Shape* shape1 = static_cast(first); Shape* shape2 = static_cast(second); - ::fcl::DistanceRequest request(true); - ::fcl::DistanceResult result; + DistanceRequest request(true); + DistanceResult result; ::fcl::distance(shape1->collisionObject.get(), shape2->collisionObject.get(), request, result); - ::fcl::Vec3f nearestPoint1 = shape1->collisionObject->getTransform().transform(result.nearest_points[0]); - ::fcl::Vec3f nearestPoint2 = shape2->collisionObject->getTransform().transform(result.nearest_points[1]); +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + Vector3 nearestPoint1 = shape1->collisionObject->getTransform().transform(result.nearest_points[0]); + Vector3 nearestPoint2 = shape2->collisionObject->getTransform().transform(result.nearest_points[1]); for (::std::size_t i = 0; i < 3; ++i) { point1(i) = nearestPoint1[i]; point2(i) = nearestPoint2[i]; } +#else + point1 = result.nearest_points[0]; + point2 = result.nearest_points[1]; +#endif - return result.min_distance; + return ::std::max(static_cast(0), result.min_distance); } ::rl::math::Real Scene::distance(::rl::sg::Shape* shape, const ::rl::math::Vector3& point, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) { #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - ::boost::shared_ptr<::fcl::CollisionGeometry> geometry = ::boost::make_shared<::fcl::Sphere>(0); + ::boost::shared_ptr geometry = ::boost::make_shared(0); #else - ::std::shared_ptr<::fcl::CollisionGeometry> geometry = ::std::make_shared<::fcl::Sphere>(0); + ::std::shared_ptr geometry = ::std::make_shared(0); #endif - ::fcl::Vec3f translation(point(0), point(1), point(2)); +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + Vector3 translation(point(0), point(1), point(2)); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - ::boost::shared_ptr<::fcl::CollisionObject> collisionObject = ::boost::make_shared<::fcl::CollisionObject>(geometry, ::fcl::Transform3f(translation)); + ::boost::shared_ptr collisionObject = ::boost::make_shared(geometry, Transform3(translation)); +#else + ::std::shared_ptr collisionObject = ::std::make_shared(geometry, Transform3(translation)); +#endif #else - ::std::shared_ptr<::fcl::CollisionObject> collisionObject = ::std::make_shared<::fcl::CollisionObject>(geometry, ::fcl::Transform3f(translation)); + ::std::shared_ptr collisionObject = ::std::make_shared(geometry, Transform3(Translation3(point))); #endif - ::fcl::DistanceRequest request; - ::fcl::DistanceResult result; + DistanceRequest request; + DistanceResult result; ::fcl::distance(static_cast(shape)->collisionObject.get(), collisionObject.get(), request, result); - ::fcl::Vec3f nearestPoint1 = static_cast(shape)->collisionObject->getTransform().transform(result.nearest_points[0]); - ::fcl::Vec3f nearestPoint2 = collisionObject->getTransform().transform(result.nearest_points[1]); +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + Vector3 nearestPoint1 = static_cast(shape)->collisionObject->getTransform().transform(result.nearest_points[0]); + Vector3 nearestPoint2 = collisionObject->getTransform().transform(result.nearest_points[1]); for (::std::size_t i = 0; i < 3; ++i) { point1(i) = nearestPoint1[i]; point2(i) = nearestPoint2[i]; } +#else + point1 = result.nearest_points[0]; + point2 = result.nearest_points[1]; +#endif - return result.min_distance; + return ::std::max(static_cast(0), result.min_distance); } bool @@ -314,7 +368,7 @@ namespace rl this->manager.update(); CollisionData collisionData(bodyForObj); this->manager.collide(&collisionData, Scene::defaultCollisionFunction); - return collisionData.result.numContacts() > 0; + return collisionData.result.isCollision(); } bool @@ -331,7 +385,7 @@ namespace rl if (found != this->models.end()) { this->models.erase(found); - ::std::vector<::fcl::CollisionObject*> objects; + ::std::vector objects; static_cast(model)->manager.getObjects(objects); for (::std::size_t i = 0; i < objects.size(); ++i) @@ -342,13 +396,13 @@ namespace rl } void - Scene::removeCollisionObject(::fcl::CollisionObject* collisionObject) + Scene::removeCollisionObject(CollisionObject* collisionObject) { this->bodyForObj.erase(collisionObject); this->manager.unregisterObject(collisionObject); } - Scene::CollisionData::CollisionData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj) : + Scene::CollisionData::CollisionData(const ::std::unordered_map& bodyForObj) : bodyForObj(bodyForObj), done(false), request(), @@ -356,7 +410,7 @@ namespace rl { } - Scene::DistanceData::DistanceData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj) : + Scene::DistanceData::DistanceData(const ::std::unordered_map& bodyForObj) : bodyForObj(bodyForObj), done(false), request(true), diff --git a/src/rl/sg/fcl/Scene.h b/src/rl/sg/fcl/Scene.h index a69a5495..42e448ca 100644 --- a/src/rl/sg/fcl/Scene.h +++ b/src/rl/sg/fcl/Scene.h @@ -28,8 +28,15 @@ #define RL_SG_FCL_SCENE_H #include +#include + +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 #include #include +#else +#include +#include +#endif #include "../DepthScene.h" #include "../DistanceScene.h" @@ -46,6 +53,24 @@ namespace rl */ namespace fcl { +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + typedef ::fcl::CollisionObject CollisionObject; + typedef ::fcl::CollisionRequest CollisionRequest; + typedef ::fcl::CollisionResult CollisionResult; + typedef ::fcl::DistanceRequest DistanceRequest; + typedef ::fcl::DistanceResult DistanceResult; + typedef ::fcl::DynamicAABBTreeCollisionManager DynamicAABBTreeCollisionManager; + typedef ::fcl::FCL_REAL Real; +#else + typedef ::fcl::CollisionObject<::rl::math::Real> CollisionObject; + typedef ::fcl::CollisionRequest<::rl::math::Real> CollisionRequest; + typedef ::fcl::CollisionResult<::rl::math::Real> CollisionResult; + typedef ::fcl::DistanceRequest<::rl::math::Real> DistanceRequest; + typedef ::fcl::DistanceResult<::rl::math::Real> DistanceResult; + typedef ::fcl::DynamicAABBTreeCollisionManager<::rl::math::Real> DynamicAABBTreeCollisionManager; + typedef ::rl::math::Real Real; +#endif + class RL_SG_EXPORT Scene : public ::rl::sg::DepthScene, public ::rl::sg::DistanceScene, public ::rl::sg::SimpleScene { public: @@ -55,7 +80,7 @@ namespace rl void add(::rl::sg::Model* model); - void addCollisionObject(::fcl::CollisionObject* collisionObject, Body* body); + void addCollisionObject(CollisionObject* collisionObject, Body* body); bool areColliding(::rl::sg::Body* first, ::rl::sg::Body* second); @@ -83,44 +108,44 @@ namespace rl void remove(::rl::sg::Model* model); - void removeCollisionObject(::fcl::CollisionObject* collisionObject); + void removeCollisionObject(CollisionObject* collisionObject); - ::fcl::DynamicAABBTreeCollisionManager manager; + DynamicAABBTreeCollisionManager manager; protected: private: struct CollisionData { - CollisionData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj); + CollisionData(const ::std::unordered_map& bodyForObj); - const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj; + const ::std::unordered_map& bodyForObj; bool done; - ::fcl::CollisionRequest request; + CollisionRequest request; - ::fcl::CollisionResult result; + CollisionResult result; }; struct DistanceData { - DistanceData(const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj); + DistanceData(const ::std::unordered_map& bodyForObj); - const ::std::unordered_map<::fcl::CollisionObject*, Body*>& bodyForObj; + const ::std::unordered_map& bodyForObj; bool done; - ::fcl::DistanceRequest request; + DistanceRequest request; - ::fcl::DistanceResult result; + DistanceResult result; }; - static bool defaultCollisionFunction(::fcl::CollisionObject* o1, ::fcl::CollisionObject* o2, void* data); + static bool defaultCollisionFunction(CollisionObject* o1, CollisionObject* o2, void* data); - static bool defaultDistanceFunction(::fcl::CollisionObject* o1, ::fcl::CollisionObject* o2, void* data, ::fcl::FCL_REAL& dist); + static bool defaultDistanceFunction(CollisionObject* o1, CollisionObject* o2, void* data, Real& dist); - ::std::unordered_map<::fcl::CollisionObject*, Body*> bodyForObj; + ::std::unordered_map bodyForObj; }; } } diff --git a/src/rl/sg/fcl/Shape.cpp b/src/rl/sg/fcl/Shape.cpp index 4ded85d1..8d35fbbd 100644 --- a/src/rl/sg/fcl/Shape.cpp +++ b/src/rl/sg/fcl/Shape.cpp @@ -24,8 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include -#include +#include #include #include #include @@ -35,6 +34,12 @@ #include #include +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 +#include +#else +#include +#endif + #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 #include #endif @@ -48,11 +53,39 @@ namespace rl { namespace fcl { +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + typedef ::fcl::Box Box; + typedef ::fcl::Cone Cone; + typedef ::fcl::Convex Convex; + typedef ::fcl::Cylinder Cylinder; + typedef ::fcl::OBBRSS OBBRSS; + typedef ::fcl::Sphere Sphere; + typedef ::fcl::Transform3f Transform3; +#else + typedef ::fcl::Box<::rl::math::Real> Box; + typedef ::fcl::Cone<::rl::math::Real> Cone; + typedef ::fcl::Convex<::rl::math::Real> Convex; + typedef ::fcl::Cylinder<::rl::math::Real> Cylinder; + typedef ::fcl::OBBRSS<::rl::math::Real> OBBRSS; + typedef ::fcl::Sphere<::rl::math::Real> Sphere; + typedef ::fcl::Transform3<::rl::math::Real> Transform3; +#endif + Shape::Shape(SoVRMLShape* shape, ::rl::sg::Body* body) : ::rl::sg::Shape(shape, body), - baseTransform(::rl::math::Transform::Identity()), - currentFrame(::rl::math::Transform::Identity()), - transform(::rl::math::Transform::Identity()) + base(::rl::math::Transform::Identity()), +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + distances(), +#endif + frame(::rl::math::Transform::Identity()), + geometry(), + indices(), +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + normals(), +#endif + polygons(), + transform(::rl::math::Transform::Identity()), + vertices() { SoVRMLGeometry* vrmlGeometry = static_cast(shape->geometry.getValue()); @@ -60,62 +93,62 @@ namespace rl { SoVRMLBox* box = static_cast(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared<::fcl::Box>(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); + this->geometry = ::boost::make_shared(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); #else - this->geometry = ::std::make_shared<::fcl::Box>(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); + this->geometry = ::std::make_shared(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); #endif } else if (vrmlGeometry->isOfType(SoVRMLCone::getClassTypeId())) { SoVRMLCone* cone = static_cast(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared<::fcl::Cone>(cone->bottomRadius.getValue(), cone->height.getValue()); + this->geometry = ::boost::make_shared(cone->bottomRadius.getValue(), cone->height.getValue()); #else - this->geometry = ::std::make_shared<::fcl::Cone>(cone->bottomRadius.getValue(), cone->height.getValue()); + this->geometry = ::std::make_shared(cone->bottomRadius.getValue(), cone->height.getValue()); #endif - this->baseTransform(0, 0) = 1; - this->baseTransform(0, 1) = 0; - this->baseTransform(0, 2) = 0; - this->baseTransform(0, 3) = 0; - this->baseTransform(1, 0) = 0; - this->baseTransform(1, 1) = 0; - this->baseTransform(1, 2) = 1; - this->baseTransform(1, 3) = 0; - this->baseTransform(2, 0) = 0; - this->baseTransform(2, 1) = -1; - this->baseTransform(2, 2) = 0; - this->baseTransform(2, 3) = 0; - this->baseTransform(3, 0) = 0; - this->baseTransform(3, 1) = 0; - this->baseTransform(3, 2) = 0; - this->baseTransform(3, 3) = 1; + this->base(0, 0) = 1; + this->base(0, 1) = 0; + this->base(0, 2) = 0; + this->base(0, 3) = 0; + this->base(1, 0) = 0; + this->base(1, 1) = 0; + this->base(1, 2) = 1; + this->base(1, 3) = 0; + this->base(2, 0) = 0; + this->base(2, 1) = -1; + this->base(2, 2) = 0; + this->base(2, 3) = 0; + this->base(3, 0) = 0; + this->base(3, 1) = 0; + this->base(3, 2) = 0; + this->base(3, 3) = 1; } else if (vrmlGeometry->isOfType(SoVRMLCylinder::getClassTypeId())) { SoVRMLCylinder* cylinder = static_cast(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared<::fcl::Cylinder>(cylinder->radius.getValue(), cylinder->height.getValue()); + this->geometry = ::boost::make_shared(cylinder->radius.getValue(), cylinder->height.getValue()); #else - this->geometry = ::std::make_shared<::fcl::Cylinder>(cylinder->radius.getValue(), cylinder->height.getValue()); + this->geometry = ::std::make_shared(cylinder->radius.getValue(), cylinder->height.getValue()); #endif - this->baseTransform(0, 0) = 1; - this->baseTransform(0, 1) = 0; - this->baseTransform(0, 2) = 0; - this->baseTransform(0, 3) = 0; - this->baseTransform(1, 0) = 0; - this->baseTransform(1, 1) = 0; - this->baseTransform(1, 2) = 1; - this->baseTransform(1, 3) = 0; - this->baseTransform(2, 0) = 0; - this->baseTransform(2, 1) = -1; - this->baseTransform(2, 2) = 0; - this->baseTransform(2, 3) = 0; - this->baseTransform(3, 0) = 0; - this->baseTransform(3, 1) = 0; - this->baseTransform(3, 2) = 0; - this->baseTransform(3, 3) = 1; + this->base(0, 0) = 1; + this->base(0, 1) = 0; + this->base(0, 2) = 0; + this->base(0, 3) = 0; + this->base(1, 0) = 0; + this->base(1, 1) = 0; + this->base(1, 2) = 1; + this->base(1, 3) = 0; + this->base(2, 0) = 0; + this->base(2, 1) = -1; + this->base(2, 2) = 0; + this->base(2, 3) = 0; + this->base(3, 0) = 0; + this->base(3, 1) = 0; + this->base(3, 2) = 0; + this->base(3, 3) = 1; } else if (vrmlGeometry->isOfType(SoVRMLIndexedFaceSet::getClassTypeId())) { @@ -127,40 +160,52 @@ namespace rl if (indexedFaceSet->convex.getValue() && !indexedFaceSet->convex.isDefault()) { - this->normals = ::std::vector<::fcl::Vec3f>(this->indices.size() / 3); - this->distances = ::std::vector<::fcl::FCL_REAL>(this->indices.size() / 3); +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + this->normals = ::std::vector(this->indices.size() / 3); + this->distances = ::std::vector(this->indices.size() / 3); +#endif this->polygons = ::std::vector(this->indices.size() + this->indices.size() / 3); for (::std::size_t i = 0; i < this->indices.size() / 3; ++i) { - ::fcl::Vec3f normal = (this->vertices[this->indices[i * 3 + 1]] - this->vertices[this->indices[i * 3]]).cross(this->vertices[this->indices[i * 3 + 2]] - this->vertices[this->indices[i * 3]]); +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + Vector3 normal = (this->vertices[this->indices[i * 3 + 1]] - this->vertices[this->indices[i * 3]]).cross(this->vertices[this->indices[i * 3 + 2]] - this->vertices[this->indices[i * 3]]); this->normals[i] = normal.normalize(); this->distances[i] = this->vertices[this->indices[i * 3 + 1]].dot(normal); +#endif this->polygons[i * 4] = 3; this->polygons[i * 4 + 1] = this->indices[i * 3]; this->polygons[i * 4 + 2] = this->indices[i * 3 + 1]; this->polygons[i * 4 + 3] = this->indices[i * 3 + 2]; } +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared<::fcl::Convex>( + this->geometry = ::boost::make_shared( #else - this->geometry = ::std::make_shared<::fcl::Convex>( + this->geometry = ::std::make_shared( #endif this->normals.data(), this->distances.data(), this->indices.size() / 3, - this->vertices.empty() ? 0 : &this->vertices.front(), + this->vertices.data(), this->vertices.size(), this->polygons.data() ); +#else + this->geometry = ::std::make_shared( + ::std::shared_ptr>(&this->vertices), + this->indices.size() / 3, + ::std::shared_ptr>(&this->polygons) + ); +#endif } else { #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - ::boost::shared_ptr<::fcl::BVHModel<::fcl::OBBRSS>> mesh = ::boost::make_shared<::fcl::BVHModel<::fcl::OBBRSS>>(); + ::boost::shared_ptr<::fcl::BVHModel> mesh = ::boost::make_shared<::fcl::BVHModel>(); #else - ::std::shared_ptr<::fcl::BVHModel<::fcl::OBBRSS>> mesh = ::std::make_shared<::fcl::BVHModel<::fcl::OBBRSS>>(); + ::std::shared_ptr<::fcl::BVHModel> mesh = ::std::make_shared<::fcl::BVHModel>(); #endif mesh->beginModel(this->indices.size() / 3, this->vertices.size()); @@ -181,13 +226,13 @@ namespace rl { SoVRMLSphere* sphere = static_cast(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - this->geometry = ::boost::make_shared<::fcl::Sphere>(sphere->radius.getValue()); + this->geometry = ::boost::make_shared(sphere->radius.getValue()); #else - this->geometry = ::std::make_shared<::fcl::Sphere>(sphere->radius.getValue()); + this->geometry = ::std::make_shared(sphere->radius.getValue()); #endif } - this->collisionObject = ::std::make_shared<::fcl::CollisionObject>(this->geometry, ::fcl::Transform3f()); + this->collisionObject = ::std::make_shared(this->geometry, Transform3()); this->getBody()->add(this); this->setTransform(::rl::math::Transform::Identity()); @@ -208,7 +253,7 @@ namespace rl Shape::setTransform(const ::rl::math::Transform& transform) { this->transform = transform; - this->update(this->currentFrame); + this->update(this->frame); } void @@ -217,34 +262,42 @@ namespace rl Shape* shape = static_cast(userData); shape->indices.push_back(shape->vertices.size()); - ::fcl::Vec3f fclVertex1(v1->getPoint()[0], v1->getPoint()[1], v1->getPoint()[2]); - shape->vertices.push_back(fclVertex1); + Vector3 vertex1(v1->getPoint()[0], v1->getPoint()[1], v1->getPoint()[2]); + shape->vertices.push_back(vertex1); shape->indices.push_back(shape->vertices.size()); - ::fcl::Vec3f fclVertex2(v2->getPoint()[0], v2->getPoint()[1], v2->getPoint()[2]); - shape->vertices.push_back(fclVertex2); + Vector3 vertex2(v2->getPoint()[0], v2->getPoint()[1], v2->getPoint()[2]); + shape->vertices.push_back(vertex2); shape->indices.push_back(shape->vertices.size()); - ::fcl::Vec3f fclVertex3(v3->getPoint()[0], v3->getPoint()[1], v3->getPoint()[2]); - shape->vertices.push_back(fclVertex3); + Vector3 vertex3(v3->getPoint()[0], v3->getPoint()[1], v3->getPoint()[2]); + shape->vertices.push_back(vertex3); } void Shape::update(const ::rl::math::Transform& frame) { - this->currentFrame = frame; + this->frame = frame; - ::rl::math::Transform fullTransform = this->currentFrame * this->transform * this->baseTransform; + ::rl::math::Transform transform = this->frame * this->transform; - ::fcl::Vec3f translation(fullTransform(0, 3), fullTransform(1, 3), fullTransform(2, 3)); + if (::fcl::GEOM_CONE == this->geometry->getNodeType() || ::fcl::GEOM_CYLINDER == this->geometry->getNodeType()) + { + transform = transform * this->base; + } +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 ::fcl::Matrix3f rotation( - fullTransform(0, 0), fullTransform(0, 1), fullTransform(0, 2), - fullTransform(1, 0), fullTransform(1, 1), fullTransform(1, 2), - fullTransform(2, 0), fullTransform(2, 1), fullTransform(2, 2) + transform(0, 0), transform(0, 1), transform(0, 2), + transform(1, 0), transform(1, 1), transform(1, 2), + transform(2, 0), transform(2, 1), transform(2, 2) ); - + Vector3 translation(transform(0, 3), transform(1, 3), transform(2, 3)); this->collisionObject->setTransform(rotation, translation); +#else + this->collisionObject->setTransform(transform.linear(), transform.translation()); +#endif + this->collisionObject->computeAABB(); } } diff --git a/src/rl/sg/fcl/Shape.h b/src/rl/sg/fcl/Shape.h index 8e10bb16..fb528851 100644 --- a/src/rl/sg/fcl/Shape.h +++ b/src/rl/sg/fcl/Shape.h @@ -28,9 +28,15 @@ #define RL_SG_FCL_SHAPE_H #include -#include +#include #include +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 +#include +#else +#include +#endif + #include "../Shape.h" namespace rl @@ -39,6 +45,18 @@ namespace rl { namespace fcl { +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + typedef ::fcl::CollisionGeometry CollisionGeometry; + typedef ::fcl::CollisionObject CollisionObject; + typedef ::fcl::FCL_REAL Real; + typedef ::fcl::Vec3f Vector3; +#else + typedef ::fcl::CollisionGeometry<::rl::math::Real> CollisionGeometry; + typedef ::fcl::CollisionObject<::rl::math::Real> CollisionObject; + typedef ::rl::math::Real Real; + typedef ::fcl::Vector3<::rl::math::Real> Vector3; +#endif + class RL_SG_EXPORT Shape : public ::rl::sg::Shape { public: @@ -52,34 +70,38 @@ namespace rl void update(const ::rl::math::Transform& frame); - ::std::shared_ptr<::fcl::CollisionObject> collisionObject; + ::std::shared_ptr collisionObject; protected: private: static void triangleCallback(void* userData, SoCallbackAction* action, const SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const SoPrimitiveVertex* v3); - ::rl::math::Transform baseTransform; + ::rl::math::Transform base; - ::rl::math::Transform currentFrame; +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + ::std::vector distances; +#endif - ::std::vector<::fcl::FCL_REAL> distances; + ::rl::math::Transform frame; #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 - ::boost::shared_ptr<::fcl::CollisionGeometry> geometry; + ::boost::shared_ptr geometry; #else - ::std::shared_ptr<::fcl::CollisionGeometry> geometry; + ::std::shared_ptr geometry; #endif ::std::vector indices; - ::std::vector<::fcl::Vec3f> normals; +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + ::std::vector normals; +#endif ::std::vector polygons; ::rl::math::Transform transform; - ::std::vector<::fcl::Vec3f> vertices; + ::std::vector vertices; }; } } From b4a025d1e52a5c9ae446677558d3d3a72c9b4044 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Jun 2020 14:03:49 +0200 Subject: [PATCH 370/546] Match variable name --- src/rl/sg/bullet/Scene.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/rl/sg/bullet/Scene.cpp b/src/rl/sg/bullet/Scene.cpp index 1f67c5dc..a5992e6e 100644 --- a/src/rl/sg/bullet/Scene.cpp +++ b/src/rl/sg/bullet/Scene.cpp @@ -171,7 +171,7 @@ namespace rl Body* body = static_cast(shape->getBody()); - ::btPointCollector gjkOutput; + ::btPointCollector pointCollector; ::btGjkPairDetector::ClosestPointInput input; input.m_transformA = body->object.getWorldTransform() * static_cast(shape)->transform; input.m_transformB.setIdentity(); @@ -181,19 +181,19 @@ namespace rl static_cast<::btScalar>(point.z()) ); - convexConvex.getClosestPoints(input, gjkOutput, 0); + convexConvex.getClosestPoints(input, pointCollector, 0); - point1.x() = gjkOutput.m_pointInWorld.x(); - point1.y() = gjkOutput.m_pointInWorld.y(); - point1.z() = gjkOutput.m_pointInWorld.z(); + point1.x() = pointCollector.m_pointInWorld.x(); + point1.y() = pointCollector.m_pointInWorld.y(); + point1.z() = pointCollector.m_pointInWorld.z(); - ::btVector3 endPt = gjkOutput.m_pointInWorld + gjkOutput.m_normalOnBInWorld * gjkOutput.m_distance; + ::btVector3 endPt = pointCollector.m_pointInWorld + pointCollector.m_normalOnBInWorld * pointCollector.m_distance; point2.x() = endPt.x(); point2.y() = endPt.y(); point2.z() = endPt.z(); - return gjkOutput.m_distance; + return pointCollector.m_distance; } bool From 3b6597e8019e108cdabe88b0d81a5d7fcf9ae7df Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 16 Jun 2020 14:07:37 +0200 Subject: [PATCH 371/546] Return zero for negative distance --- src/rl/sg/bullet/Scene.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/sg/bullet/Scene.cpp b/src/rl/sg/bullet/Scene.cpp index a5992e6e..e09f63b9 100644 --- a/src/rl/sg/bullet/Scene.cpp +++ b/src/rl/sg/bullet/Scene.cpp @@ -151,7 +151,7 @@ namespace rl point2.y() = endPt.y(); point2.z() = endPt.z(); - return pointCollector.m_distance; + return ::std::max(static_cast<::btScalar>(0), pointCollector.m_distance); } ::rl::math::Real @@ -193,7 +193,7 @@ namespace rl point2.y() = endPt.y(); point2.z() = endPt.z(); - return pointCollector.m_distance; + return ::std::max(static_cast<::btScalar>(0), pointCollector.m_distance); } bool From 071a84b8515a4405ca2955d2417644b9090280ec Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 22 Jun 2020 11:47:37 +0200 Subject: [PATCH 372/546] Limit postfixes to MSVC --- demos/rlCoachKin/CMakeLists.txt | 2 +- demos/rlCoachMdl/CMakeLists.txt | 2 +- demos/rlCollisionDemo/CMakeLists.txt | 2 +- demos/rlPlanDemo/CMakeLists.txt | 2 +- demos/rlRotationConverterDemo/CMakeLists.txt | 2 +- demos/rlSimulator/CMakeLists.txt | 2 +- demos/rlViewDemo/CMakeLists.txt | 2 +- extras/wrlview/CMakeLists.txt | 2 +- src/rl/hal/CMakeLists.txt | 2 +- src/rl/kin/CMakeLists.txt | 2 +- src/rl/math/CMakeLists.txt | 2 +- src/rl/mdl/CMakeLists.txt | 2 +- src/rl/plan/CMakeLists.txt | 2 +- src/rl/sg/CMakeLists.txt | 2 +- src/rl/std/CMakeLists.txt | 2 +- src/rl/util/CMakeLists.txt | 2 +- src/rl/xml/CMakeLists.txt | 2 +- 17 files changed, 17 insertions(+), 17 deletions(-) diff --git a/demos/rlCoachKin/CMakeLists.txt b/demos/rlCoachKin/CMakeLists.txt index 82188a53..88842bb8 100644 --- a/demos/rlCoachKin/CMakeLists.txt +++ b/demos/rlCoachKin/CMakeLists.txt @@ -81,7 +81,7 @@ if(QT_FOUND AND SoQt_FOUND) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( rlCoachKin PROPERTIES diff --git a/demos/rlCoachMdl/CMakeLists.txt b/demos/rlCoachMdl/CMakeLists.txt index 0df42656..3c4a258e 100644 --- a/demos/rlCoachMdl/CMakeLists.txt +++ b/demos/rlCoachMdl/CMakeLists.txt @@ -81,7 +81,7 @@ if(QT_FOUND AND SoQt_FOUND) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( rlCoachMdl PROPERTIES diff --git a/demos/rlCollisionDemo/CMakeLists.txt b/demos/rlCollisionDemo/CMakeLists.txt index 7db79883..4425e49c 100644 --- a/demos/rlCollisionDemo/CMakeLists.txt +++ b/demos/rlCollisionDemo/CMakeLists.txt @@ -79,7 +79,7 @@ if(QT_FOUND AND SoQt_FOUND) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( rlCollisionDemo PROPERTIES diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index 522a0b8f..5393562b 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -96,7 +96,7 @@ if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( rlPlanDemo PROPERTIES diff --git a/demos/rlRotationConverterDemo/CMakeLists.txt b/demos/rlRotationConverterDemo/CMakeLists.txt index ca619d38..1da20bd5 100644 --- a/demos/rlRotationConverterDemo/CMakeLists.txt +++ b/demos/rlRotationConverterDemo/CMakeLists.txt @@ -60,7 +60,7 @@ if(QT_FOUND) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( rlRotationConverterDemo PROPERTIES diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index f88c6da5..e7ed9fb3 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -84,7 +84,7 @@ if(QT_FOUND AND SoQt_FOUND) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( rlSimulator PROPERTIES diff --git a/demos/rlViewDemo/CMakeLists.txt b/demos/rlViewDemo/CMakeLists.txt index 128e1760..2a6ab18f 100644 --- a/demos/rlViewDemo/CMakeLists.txt +++ b/demos/rlViewDemo/CMakeLists.txt @@ -50,7 +50,7 @@ if(QT_FOUND AND SoQt_FOUND) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( rlViewDemo PROPERTIES diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index d0169e6c..ccadd0a8 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -89,7 +89,7 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( wrlview PROPERTIES diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 593b2c24..2f7a0cf9 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -246,7 +246,7 @@ if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) ) endif() -if(WIN32) +if(MSVC) if(BUILD_SHARED_LIBS) set_target_properties( hal diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index 30ca6892..9f8736d6 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -75,7 +75,7 @@ if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) ) endif() -if(WIN32) +if(MSVC) if(BUILD_SHARED_LIBS) set_target_properties( kin diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index 5f919c18..a73af920 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -100,7 +100,7 @@ if(CMAKE_VERSION VERSION_LESS 3.0) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( math PROPERTIES diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 66dac2f3..0bc21b17 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -125,7 +125,7 @@ if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) ) endif() -if(WIN32) +if(MSVC) if(BUILD_SHARED_LIBS) set_target_properties( mdl diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index e4e97802..3d19736e 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -136,7 +136,7 @@ if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) ) endif() -if(WIN32) +if(MSVC) if(BUILD_SHARED_LIBS) set_target_properties( plan diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 035a3d9b..3c590b9e 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -278,7 +278,7 @@ if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) ) endif() -if(WIN32) +if(MSVC) if(BUILD_SHARED_LIBS) set_target_properties( sg diff --git a/src/rl/std/CMakeLists.txt b/src/rl/std/CMakeLists.txt index 1a1eba0e..0c97f1a0 100644 --- a/src/rl/std/CMakeLists.txt +++ b/src/rl/std/CMakeLists.txt @@ -35,7 +35,7 @@ if(CMAKE_VERSION VERSION_LESS 3.0) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( std PROPERTIES diff --git a/src/rl/util/CMakeLists.txt b/src/rl/util/CMakeLists.txt index 0e0edd32..68fe056e 100644 --- a/src/rl/util/CMakeLists.txt +++ b/src/rl/util/CMakeLists.txt @@ -97,7 +97,7 @@ if(CMAKE_VERSION VERSION_LESS 3.0) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( util PROPERTIES diff --git a/src/rl/xml/CMakeLists.txt b/src/rl/xml/CMakeLists.txt index 648cb3f3..9367a244 100644 --- a/src/rl/xml/CMakeLists.txt +++ b/src/rl/xml/CMakeLists.txt @@ -85,7 +85,7 @@ if(CMAKE_VERSION VERSION_LESS 3.0) VERSION ${VERSION} ) - if(WIN32) + if(MSVC) set_target_properties( xml PROPERTIES From b0e5144506c8fb26a4192a7576b1bc14f8f4033b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 22 Jun 2020 11:50:34 +0200 Subject: [PATCH 373/546] Use CMakePushCheckState --- cmake/FindODE.cmake | 4 ++++ extras/wrlview/CMakeLists.txt | 7 ++++--- src/rl/sg/CMakeLists.txt | 6 +++--- 3 files changed, 11 insertions(+), 6 deletions(-) diff --git a/cmake/FindODE.cmake b/cmake/FindODE.cmake index 6056ce6c..62304e92 100644 --- a/cmake/FindODE.cmake +++ b/cmake/FindODE.cmake @@ -1,5 +1,6 @@ include(CheckCSourceRuns) include(CheckSymbolExists) +include(CMakePushCheckState) include(FindPackageHandleStandardArgs) include(GNUInstallDirs) include(SelectLibraryConfigurations) @@ -128,6 +129,7 @@ find_library( select_library_configurations(ODE) if(ODE_INCLUDE_DIRS AND ODE_LIBRARIES) + cmake_push_check_state(RESET) set(CMAKE_REQUIRED_INCLUDES ${ODE_INCLUDE_DIRS}) check_symbol_exists(dDOUBLE "ode/precision.h" ODE_HAVE_DOUBLE) @@ -160,6 +162,8 @@ if(ODE_INCLUDE_DIRS AND ODE_LIBRARIES) endif() endif() endif() + + cmake_pop_check_state() endif() mark_as_advanced(ODE_DEFINITIONS) diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index ccadd0a8..18806f8b 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -6,6 +6,8 @@ set(VERSION_PATCH 14) set(VERSION_TWEAK 0) set(VERSION ${VERSION_MAJOR}.${VERSION_MINOR}.${VERSION_PATCH}) +include(CMakePushCheckState) + find_package(SoQt) if(RL_USE_QT5 AND SoQt5_FOUND) @@ -49,6 +51,7 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) ${SoQt_DEFINITIONS} ) + cmake_push_check_state(RESET) set(CMAKE_REQUIRED_DEFINITIONS ${Coin_DEFINITIONS}) set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) set(CMAKE_REQUIRED_LIBRARIES ${Coin_LIBRARIES}) @@ -63,9 +66,7 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) target_compile_definitions(wrlview PRIVATE HAVE_SOSTLFILEKIT_CONVERT) endif() endif() - unset(CMAKE_REQUIRED_DEFINITIONS) - unset(CMAKE_REQUIRED_INCLUDES) - unset(CMAKE_REQUIRED_LIBRARIES) + cmake_pop_check_state() target_include_directories( wrlview diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 3c590b9e..05555352 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -1,5 +1,6 @@ include(CheckCXXSourceCompiles) include(CheckIncludeFileCXX) +include(CMakePushCheckState) find_package(Bullet) find_package(ccd) @@ -207,6 +208,7 @@ if(CCD_FOUND AND (RL_BUILD_SG_FCL OR RL_BUILD_SG_ODE)) endif() if(Coin_FOUND) + cmake_push_check_state(RESET) set(CMAKE_REQUIRED_DEFINITIONS ${Coin_DEFINITIONS}) set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) set(CMAKE_REQUIRED_LIBRARIES ${Coin_LIBRARIES}) @@ -221,9 +223,7 @@ if(Coin_FOUND) target_compile_definitions(sg PRIVATE HAVE_SOSTLFILEKIT_CONVERT) endif() endif() - unset(CMAKE_REQUIRED_DEFINITIONS) - unset(CMAKE_REQUIRED_INCLUDES) - unset(CMAKE_REQUIRED_LIBRARIES) + cmake_pop_check_state() target_compile_definitions(sg PUBLIC ${Coin_DEFINITIONS}) target_include_directories(sg PUBLIC ${Coin_INCLUDE_DIRS}) target_link_libraries(sg ${Coin_LIBRARIES}) From 7f9fbb9fc4fad45742b939236b6ac9d744aa83af Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 22 Jun 2020 17:40:25 +0200 Subject: [PATCH 374/546] Update CMake find modules --- cmake/FindATIDAQ.cmake | 97 ------------------ cmake/FindBullet.cmake | 201 +++++++++++--------------------------- cmake/FindCoin.cmake | 126 +++--------------------- cmake/FindComedi.cmake | 95 ------------------ cmake/FindEigen3.cmake | 71 ++++---------- cmake/FindFCL.cmake | 127 ++++-------------------- cmake/FindIconv.cmake | 162 ++++++++++-------------------- cmake/FindLibLZMA.cmake | 120 ++++------------------- cmake/FindLibXml2.cmake | 109 ++------------------- cmake/FindLibXslt.cmake | 109 ++------------------- cmake/FindNLopt.cmake | 105 +------------------- cmake/FindODE.cmake | 159 +++++++----------------------- cmake/FindPQP.cmake | 102 ------------------- cmake/FindRTAI.cmake | 108 +------------------- cmake/FindSOLID3.cmake | 103 +------------------ cmake/FindSoQt.cmake | 118 ++++------------------ cmake/FindXenomai.cmake | 114 ++------------------- cmake/FindZLIB.cmake | 113 ++------------------- cmake/Findccd.cmake | 101 ------------------- cmake/FindcifX.cmake | 95 ------------------ cmake/Findlibdc1394.cmake | 87 +---------------- src/rl/sg/CMakeLists.txt | 1 + 22 files changed, 263 insertions(+), 2160 deletions(-) diff --git a/cmake/FindATIDAQ.cmake b/cmake/FindATIDAQ.cmake index 1fd699e3..9bc3ef08 100644 --- a/cmake/FindATIDAQ.cmake +++ b/cmake/FindATIDAQ.cmake @@ -1,121 +1,24 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/ATIDAQ*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND ATIDAQ_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - ATIDAQ_INCLUDE_HINTS - $ENV{ATIDAQ_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/ATIDAQ*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND ATIDAQ_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file(GLOB HINTS ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR}) - list(APPEND ATIDAQ_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - ATIDAQ_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include -) - find_path( ATIDAQ_INCLUDE_DIRS NAMES atidaq/ftconfig.h - HINTS - ${ATIDAQ_INCLUDE_HINTS} - HINTS - ${ATIDAQ_INCLUDE_PATHS} ) mark_as_advanced(ATIDAQ_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/ATIDAQ*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND ATIDAQ_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - ATIDAQ_LIBRARY_HINTS - $ENV{ATIDAQ_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/ATIDAQ*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND ATIDAQ_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND ATIDAQ_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - ATIDAQ_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( ATIDAQ_LIBRARY_DEBUG NAMES atidaqd - HINTS - ${ATIDAQ_LIBRARY_HINTS} - PATHS - ${ATIDAQ_LIBRARY_PATHS} ) find_library( ATIDAQ_LIBRARY_RELEASE NAMES atidaq - HINTS - ${ATIDAQ_LIBRARY_HINTS} - PATHS - ${ATIDAQ_LIBRARY_PATHS} ) select_library_configurations(ATIDAQ) diff --git a/cmake/FindBullet.cmake b/cmake/FindBullet.cmake index cdb51f99..c54a2b7e 100644 --- a/cmake/FindBullet.cmake +++ b/cmake/FindBullet.cmake @@ -1,129 +1,28 @@ +include(CheckCXXSourceRuns) +include(CMakePushCheckState) include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Bullet*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND BULLET_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - BULLET_INCLUDE_HINTS - $ENV{Bullet_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Bullet*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND BULLET_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND BULLET_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - BULLET_INCLUDE_PATHS - $ENV{BULLET_ROOT_DIR}/include - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include -) - find_path( BULLET_INCLUDE_DIRS NAMES btBulletCollisionCommon.h - HINTS - ${BULLET_INCLUDE_HINTS} - PATHS - ${BULLET_INCLUDE_PATHS} PATH_SUFFIXES bullet ) mark_as_advanced(BULLET_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/Bullet*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND BULLET_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - BULLET_LIBRARY_HINTS - $ENV{Bullet_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/Bullet*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND BULLET_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND BULLET_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - BULLET_LIBRARY_PATHS - $ENV{BULLET_ROOT_DIR}/lib - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( BULLET_BULLETCOLLISION_LIBRARY_DEBUG NAMES - bulletcollisiond BulletCollisiond BulletCollision_debug BulletCollision_Debug - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + BulletCollision-float64_Debug BulletCollision_Debug ) find_library( BULLET_BULLETCOLLISION_LIBRARY_RELEASE NAMES - bulletcollision BulletCollision BulletCollision_RelWithDebugInfo BulletCollision_MinsizeRel - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + BulletCollision-float64 BulletCollision ) select_library_configurations(BULLET_BULLETCOLLISION) @@ -131,21 +30,13 @@ select_library_configurations(BULLET_BULLETCOLLISION) find_library( BULLET_BULLETDYNAMICS_LIBRARY_DEBUG NAMES - bulletdynamicsd BulletDynamicsd BulletDynamics_debug BulletDynamics_Debug - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + BulletDynamics-float64_Debug BulletDynamics_Debug ) find_library( BULLET_BULLETDYNAMICS_LIBRARY_RELEASE NAMES - bulletdynamics BulletDynamics BulletDynamics_RelWithDebugInfo BulletDynamics_MinsizeRel - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + BulletDynamics-float64 BulletDynamics ) select_library_configurations(BULLET_BULLETDYNAMICS) @@ -153,21 +44,13 @@ select_library_configurations(BULLET_BULLETDYNAMICS) find_library( BULLET_BULLETSOFTBODY_LIBRARY_DEBUG NAMES - bulletsoftbodyd BulletSoftBodyd BulletSoftBody_debug BulletSoftBody_Debug - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + BulletSoftBody-float64_Debug BulletSoftBody_Debug ) find_library( BULLET_BULLETSOFTBODY_LIBRARY_RELEASE NAMES - bulletsoftbody BulletSoftBody BulletSoftBody_RelWithDebugInfo BulletSoftBody_MinsizeRel - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + BulletSoftBody-float64 BulletSoftBody ) select_library_configurations(BULLET_BULLETSOFTBODY) @@ -175,21 +58,13 @@ select_library_configurations(BULLET_BULLETSOFTBODY) find_library( BULLET_CONVEXDECOMPOSITION_LIBRARY_DEBUG NAMES - convexdecompositiond ConvexDecompositiond ConvexDecomposition_debug ConvexDecomposition_Debug - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + ConvexDecomposition-float64_Debug ConvexDecomposition_Debug ) find_library( BULLET_CONVEXDECOMPOSITION_LIBRARY_RELEASE NAMES - convexdecomposition ConvexDecomposition ConvexDecomposition_RelWithDebugInfo ConvexDecomposition_MinsizeRel - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + ConvexDecomposition-float64 ConvexDecomposition ) select_library_configurations(BULLET_CONVEXDECOMPOSITION) @@ -197,21 +72,13 @@ select_library_configurations(BULLET_CONVEXDECOMPOSITION) find_library( BULLET_LINEARMATH_LIBRARY_DEBUG NAMES - bulletmathd LinearMathd LinearMath_debug LinearMath_Debug - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + LinearMath-float64_Debug LinearMath_Debug ) find_library( BULLET_LINEARMATH_LIBRARY_RELEASE NAMES - bulletmath LinearMath LinearMath_RelWithDebugInfo LinearMath_MinsizeRel - HINTS - ${BULLET_LIBRARY_HINTS} - PATHS - ${BULLET_LIBRARY_PATHS} + LinearMath-float64 LinearMath ) select_library_configurations(BULLET_LINEARMATH) @@ -224,10 +91,49 @@ set( ${BULLET_LINEARMATH_LIBRARIES} ) +if(BULLET_INCLUDE_DIRS AND BULLET_LIBRARIES) + cmake_push_check_state(RESET) + set(CMAKE_REQUIRED_DEFINITIONS -DBT_USE_DOUBLE_PRECISION) + set(CMAKE_REQUIRED_INCLUDES ${BULLET_INCLUDE_DIRS}) + set(CMAKE_REQUIRED_LIBRARIES ${BULLET_LIBRARIES}) + check_cxx_source_runs(" + #include + int main() + { + btVector3 boxHalfExtents(1, -2, 3); + btBoxShape box(boxHalfExtents); + btVector3 boxHalfExtentsWithMargin = box.getHalfExtentsWithMargin(); + return !btFuzzyZero(boxHalfExtents.distance(boxHalfExtentsWithMargin)); + } + " _BULLET_DOUBLE_PRECISION) + + if(_BULLET_DOUBLE_PRECISION) + set(BULLET_DEFINITIONS -DBT_USE_DOUBLE_PRECISION) + endif() + + unset(_BULLET_DOUBLE_PRECISION) + cmake_pop_check_state() +endif() + +mark_as_advanced(BULLET_DEFINITIONS) + +if(BULLET_INCLUDE_DIRS AND EXISTS "${BULLET_INCLUDE_DIRS}/LinearMath/btScalar.h") + file(STRINGS "${BULLET_INCLUDE_DIRS}/LinearMath/btScalar.h" _BULLET_VERSION_DEFINE REGEX "#define[\t ]+BT_BULLET_VERSION[\t ]+[0-9]+.*") + string(REGEX REPLACE "#define[\t ]+BT_BULLET_VERSION[\t ]+([0-9])[0-9][0-9].*" "\\1" BULLET_VERSION_MAJOR "${_BULLET_VERSION_DEFINE}") + string(REGEX REPLACE "#define[\t ]+BT_BULLET_VERSION[\t ]+[0-9]([0-9][0-9]).*" "\\1" BULLET_VERSION_MINOR "${_BULLET_VERSION_DEFINE}") + + if(NOT BULLET_VERSION_MAJOR STREQUAL "" AND NOT BULLET_VERSION_MINOR STREQUAL "") + set(BULLET_VERSION "${BULLET_VERSION_MAJOR}.${BULLET_VERSION_MINOR}") + endif() + + unset(_BULLET_VERSION_DEFINE) +endif() + find_package_handle_standard_args( Bullet FOUND_VAR BULLET_FOUND REQUIRED_VARS BULLET_INCLUDE_DIRS BULLET_LIBRARIES + VERSION_VAR BULLET_VERSION ) if((BULLET_BULLETCOLLISION_LIBRARY_RELEASE OR BULLET_BULLETCOLLISION_LIBRARY_DEBUG) AND BULLET_INCLUDE_DIRS) @@ -265,6 +171,7 @@ if(BULLET_BULLETCOLLISION_LIBRARY_FOUND AND NOT TARGET Bullet::BulletCollision) set_target_properties( Bullet::BulletCollision PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" ) endif() @@ -284,6 +191,7 @@ if(BULLET_BULLETDYNAMICS_LIBRARY_FOUND AND NOT TARGET Bullet::BulletDynamics) set_target_properties( Bullet::BulletDynamics PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" ) endif() @@ -303,6 +211,7 @@ if(BULLET_BULLETSOFTBODY_LIBRARY_FOUND AND NOT TARGET Bullet::BulletSoftBody) set_target_properties( Bullet::BulletSoftBody PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" ) endif() @@ -322,6 +231,7 @@ if(BULLET_CONVEXDECOMPOSITION_LIBRARY_FOUND AND NOT TARGET Bullet::ConvexDecompo set_target_properties( Bullet::ConvexDecomposition PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" ) endif() @@ -341,6 +251,7 @@ if(BULLET_LINEARMATH_LIBRARY_FOUND AND NOT TARGET Bullet::LinearMath) set_target_properties( Bullet::LinearMath PROPERTIES + INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" ) endif() diff --git a/cmake/FindCoin.cmake b/cmake/FindCoin.cmake index 6e88f0e6..f2f51f82 100644 --- a/cmake/FindCoin.cmake +++ b/cmake/FindCoin.cmake @@ -1,61 +1,14 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Coin*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Coin_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - Coin_INCLUDE_HINTS - $ENV{Coin_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Coin*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Coin_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Coin_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - Coin_INCLUDE_PATHS - $ENV{COIN3DDIR}/include - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include/Coin* - /usr/include -) - find_path( Coin_INCLUDE_DIR NAMES Inventor/So.h - HINTS - ${Coin_INCLUDE_HINTS} - PATHS - ${Coin_INCLUDE_PATHS} + PATH_SUFFIXES + Coin4 + Coin3 + Coin2 ) mark_as_advanced(Coin_INCLUDE_DIR) @@ -66,12 +19,11 @@ find_path( Coin_FOREIGN_FILES_INCLUDE_DIR NAMES ForeignFiles/SoForeignFileKit.h - HINTS - ${Coin_INCLUDE_HINTS} - PATHS - ${Coin_INCLUDE_PATHS} PATH_SUFFIXES Inventor/annex + Coin4/Inventor/annex + Coin3/Inventor/annex + Coin2/Inventor/annex ) mark_as_advanced(Coin_FOREIGN_FILES_INCLUDE_DIR) @@ -80,69 +32,16 @@ if(Coin_FOREIGN_FILES_INCLUDE_DIR) list(APPEND Coin_INCLUDE_DIRS ${Coin_FOREIGN_FILES_INCLUDE_DIR}) endif() -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/Coin*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Coin_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - Coin_LIBRARY_HINTS - $ENV{Coin_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/Coin*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Coin_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Coin_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - Coin_LIBRARY_PATHS - $ENV{COIN3DDIR}/lib - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( Coin_LIBRARY_DEBUG NAMES - Coind coin2d coin3d Coin4d - HINTS - ${Coin_LIBRARY_HINTS} - PATHS - ${Coin_LIBRARY_PATHS} + Coind Coin4d Coin3d Coin2d ) find_library( Coin_LIBRARY_RELEASE NAMES - Coin coin2 coin3 Coin4 - HINTS - ${Coin_LIBRARY_HINTS} - PATHS - ${Coin_LIBRARY_PATHS} + Coin Coin4 Coin3 Coin2 ) select_library_configurations(Coin) @@ -151,10 +50,17 @@ set(Coin_DEFINITIONS -DCOIN_DLL) mark_as_advanced(Coin_DEFINITIONS) +if(Coin_INCLUDE_DIR AND EXISTS "${Coin_INCLUDE_DIR}/Inventor/C/basic.h") + file(STRINGS "${Coin_INCLUDE_DIR}/Inventor/C/basic.h" _Coin_VERSION_DEFINE REGEX "#define[\t ]+COIN_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "#define[\t ]+COIN_VERSION[\t ]+\"([^\"]*)\".*" "\\1" Coin_VERSION "${_Coin_VERSION_DEFINE}") + unset(_Coin_VERSION_DEFINE) +endif() + find_package_handle_standard_args( Coin FOUND_VAR Coin_FOUND REQUIRED_VARS Coin_INCLUDE_DIRS Coin_LIBRARIES + VERSION_VAR Coin_VERSION ) if(Coin_FOUND AND NOT TARGET Coin::Coin) diff --git a/cmake/FindComedi.cmake b/cmake/FindComedi.cmake index 11c0dcc5..1326e5d0 100644 --- a/cmake/FindComedi.cmake +++ b/cmake/FindComedi.cmake @@ -1,119 +1,24 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Comedi*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Comedi_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - Comedi_INCLUDE_HINTS - $ENV{Comedi_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Comedi*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Comedi_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Comedi_INCLUDE_HINTS ${HINTS}) -endforeach() - find_path( Comedi_INCLUDE_DIRS NAMES comedilib.h - HINTS - ${Comedi_INCLUDE_HINTS} - PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include ) mark_as_advanced(Comedi_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/Comedi*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Comedi_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - Comedi_LIBRARY_HINTS - $ENV{Comedi_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/Comedi*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Comedi_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Comedi_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - Comedi_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( Comedi_LIBRARY_DEBUG NAMES comedid - HINTS - ${Comedi_LIBRARY_HINTS} - PATHS - ${Comedi_LIBRARY_PATHS} ) find_library( Comedi_LIBRARY_RELEASE NAMES comedi - HINTS - ${Comedi_LIBRARY_HINTS} - PATHS - ${Comedi_LIBRARY_PATHS} ) select_library_configurations(Comedi) diff --git a/cmake/FindEigen3.cmake b/cmake/FindEigen3.cmake index f33a828c..738a320c 100644 --- a/cmake/FindEigen3.cmake +++ b/cmake/FindEigen3.cmake @@ -1,73 +1,38 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Eigen*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND EIGEN3_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - EIGEN3_INCLUDE_HINTS - $ENV{Eigen3_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Eigen*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND EIGEN3_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND EIGEN3_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - EIGEN3_INCLUDE_PATHS - $ENV{EIGEN3_ROOT}/include - $ENV{EIGEN3_ROOT} - $ENV{EIGEN3_ROOT_DIR}/include - $ENV{EIGEN3_ROOT_DIR} - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include -) - find_path( EIGEN3_INCLUDE_DIRS NAMES Eigen/Core - HINTS - ${EIGEN3_INCLUDE_HINTS} - PATHS - ${EIGEN3_INCLUDE_PATHS} PATH_SUFFIXES eigen3 ) mark_as_advanced(EIGEN3_INCLUDE_DIRS) +if(EIGEN3_INCLUDE_DIRS AND EXISTS "${EIGEN3_INCLUDE_DIRS}/Eigen/src/Core/util/Macros.h") + file(STRINGS "${EIGEN3_INCLUDE_DIRS}/Eigen/src/Core/util/Macros.h" _EIGEN3_VERSION_WORLD_DEFINE REGEX "#define[\t ]+EIGEN_WORLD_VERSION[\t ]+[0-9]+.*") + string(REGEX REPLACE "#define[\t ]+EIGEN_WORLD_VERSION[\t ]+([0-9]+).*" "\\1" EIGEN3_VERSION_WORLD "${_EIGEN3_VERSION_WORLD_DEFINE}") + file(STRINGS "${EIGEN3_INCLUDE_DIRS}/Eigen/src/Core/util/Macros.h" _EIGEN3_VERSION_MAJOR_DEFINE REGEX "#define[\t ]+EIGEN_MAJOR_VERSION[\t ]+[0-9]+.*") + string(REGEX REPLACE "#define[\t ]+EIGEN_MAJOR_VERSION[\t ]+([0-9]+).*" "\\1" EIGEN3_VERSION_MAJOR "${_EIGEN3_VERSION_MAJOR_DEFINE}") + file(STRINGS "${EIGEN3_INCLUDE_DIRS}/Eigen/src/Core/util/Macros.h" _EIGEN3_VERSION_MINOR_DEFINE REGEX "#define[\t ]+EIGEN_MINOR_VERSION[\t ]+[0-9]+.*") + string(REGEX REPLACE "#define[\t ]+EIGEN_MINOR_VERSION[\t ]+([0-9]+).*" "\\1" EIGEN3_VERSION_MINOR "${_EIGEN3_VERSION_MINOR_DEFINE}") + + if(NOT EIGEN3_VERSION_WORLD STREQUAL "" AND NOT EIGEN3_VERSION_MAJOR STREQUAL "" AND NOT EIGEN3_VERSION_MINOR STREQUAL "") + set(EIGEN3_VERSION "${EIGEN3_VERSION_WORLD}.${EIGEN3_VERSION_MAJOR}.${EIGEN3_VERSION_MINOR}") + endif() + + unset(_EIGEN3_VERSION_WORLD_DEFINE) + unset(_EIGEN3_VERSION_MAJOR_DEFINE) + unset(_EIGEN3_VERSION_MINOR_DEFINE) +endif() + find_package_handle_standard_args( Eigen3 FOUND_VAR EIGEN3_FOUND REQUIRED_VARS EIGEN3_INCLUDE_DIRS + VERSION_VAR EIGEN3_VERSION ) if(EIGEN3_FOUND AND NOT TARGET Eigen3::Eigen) diff --git a/cmake/FindFCL.cmake b/cmake/FindFCL.cmake index a8af9e2f..db208963 100644 --- a/cmake/FindFCL.cmake +++ b/cmake/FindFCL.cmake @@ -1,154 +1,61 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/FCL*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND FCL_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - FCL_INCLUDE_HINTS - $ENV{FCL_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/FCL*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND FCL_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND FCL_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - FCL_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include -) - find_path( FCL_INCLUDE_DIRS NAMES fcl/config.h - HINTS - ${FCL_INCLUDE_HINTS} - PATHS - ${FCL_INCLUDE_PATHS} ) mark_as_advanced(FCL_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/FCL*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND FCL_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - FCL_LIBRARY_HINTS - $ENV{FCL_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/FCL*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND FCL_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND FCL_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - FCL_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( FCL_LIBRARY_DEBUG NAMES fcld - HINTS - ${FCL_LIBRARY_HINTS} - PATHS - ${FCL_LIBRARY_PATHS} ) find_library( FCL_LIBRARY_RELEASE NAMES fcl - HINTS - ${FCL_LIBRARY_HINTS} - PATHS - ${FCL_LIBRARY_PATHS} ) select_library_configurations(FCL) -set(FCL_DEFINITIONS -DBOOST_ALL_NO_LIB -DBOOST_SYSTEM_NO_DEPRECATED) +if(FCL_INCLUDE_DIRS AND EXISTS "${FCL_INCLUDE_DIRS}/fcl/config.h") + file(STRINGS "${FCL_INCLUDE_DIRS}/fcl/config.h" _FCL_VERSION_DEFINE REGEX "#define[\t ]+FCL_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "#define[\t ]+FCL_VERSION[\t ]+\"([^\"]*)\".*" "\\1" FCL_VERSION "${_FCL_VERSION_DEFINE}") + unset(_FCL_VERSION_DEFINE) +endif() -mark_as_advanced(FCL_DEFINITIONS) +if(FCL_VERSION AND FCL_VERSION VERSION_LESS 0.5) + set(FCL_DEFINITIONS -DBOOST_ALL_NO_LIB -DBOOST_SYSTEM_NO_DEPRECATED) + mark_as_advanced(FCL_DEFINITIONS) +endif() find_package_handle_standard_args( FCL FOUND_VAR FCL_FOUND REQUIRED_VARS FCL_INCLUDE_DIRS FCL_LIBRARIES + VERSION_VAR FCL_VERSION ) -if(FCL_FOUND AND NOT TARGET FCL::FCL) - add_library(FCL::FCL UNKNOWN IMPORTED) +if(FCL_FOUND AND NOT TARGET fcl::fcl) + add_library(fcl::fcl UNKNOWN IMPORTED) if(FCL_LIBRARY_RELEASE) - set_property(TARGET FCL::FCL APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(FCL::FCL PROPERTIES IMPORTED_LOCATION_RELEASE "${FCL_LIBRARY_RELEASE}") + set_property(TARGET fcl::fcl APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(fcl::fcl PROPERTIES IMPORTED_LOCATION_RELEASE "${FCL_LIBRARY_RELEASE}") endif() if(FCL_LIBRARY_DEBUG) - set_property(TARGET FCL::FCL APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(FCL::FCL PROPERTIES IMPORTED_LOCATION_DEBUG "${FCL_LIBRARY_DEBUG}") + set_property(TARGET fcl::fcl APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(fcl::fcl PROPERTIES IMPORTED_LOCATION_DEBUG "${FCL_LIBRARY_DEBUG}") endif() set_target_properties( - FCL::FCL PROPERTIES + fcl::fcl PROPERTIES INTERFACE_COMPILE_DEFINITIONS "${FCL_DEFINITIONS}" INTERFACE_INCLUDE_DIRECTORIES "${FCL_INCLUDE_DIRS}" ) diff --git a/cmake/FindIconv.cmake b/cmake/FindIconv.cmake index fcf514be..75d604a8 100644 --- a/cmake/FindIconv.cmake +++ b/cmake/FindIconv.cmake @@ -1,139 +1,75 @@ +include(CheckCSourceRuns) +include(CMakePushCheckState) include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libiconv*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Iconv_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - Iconv_INCLUDE_HINTS - $ENV{Iconv_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libiconv*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Iconv_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Iconv_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - Iconv_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include - $ENV{ProgramW6432}/GnuWin32/include - $ENV{ProgramFiles}/GnuWin32/include - ${CMAKE_OSX_SYSROOT}/usr/include -) - find_path( Iconv_INCLUDE_DIRS NAMES iconv.h - HINTS - ${Iconv_INCLUDE_HINTS} - PATHS - ${Iconv_INCLUDE_PATHS} ) mark_as_advanced(Iconv_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libiconv*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Iconv_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - Iconv_LIBRARY_HINTS - $ENV{Iconv_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libiconv*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Iconv_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Iconv_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - Iconv_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib - $ENV{ProgramW6432}/GnuWin32/lib - $ENV{ProgramFiles}/GnuWin32/lib -) - find_library( Iconv_LIBRARY_DEBUG NAMES - iconvd libiconvd libiconvd_a - HINTS - ${Iconv_LIBRARY_HINTS} - PATHS - ${Iconv_LIBRARY_PATHS} + libiconvd iconvd ) find_library( Iconv_LIBRARY_RELEASE NAMES - iconv libiconv liblibiconv_a - HINTS - ${Iconv_LIBRARY_HINTS} - PATHS - ${Iconv_LIBRARY_PATHS} + libiconv iconv ) select_library_configurations(Iconv) -find_package_handle_standard_args( - Iconv - FOUND_VAR Iconv_FOUND - REQUIRED_VARS Iconv_INCLUDE_DIRS Iconv_LIBRARIES -) +if(Iconv_INCLUDE_DIRS AND NOT Iconv_LIBRARIES) + cmake_push_check_state(RESET) + set(CMAKE_REQUIRED_INCLUDES ${Iconv_INCLUDE_DIRS}) + check_c_source_runs(" + #include + int main() { iconv_t ic = iconv_open(\"to\", \"from\"); return 0; } + " Iconv_IS_BUILT_IN) + cmake_pop_check_state() + + if(Iconv_IS_BUILT_IN) + unset(Iconv_LIBRARIES) + endif() +endif() + +if(Iconv_INCLUDE_DIRS AND EXISTS "${Iconv_INCLUDE_DIRS}/iconv.h") + file(STRINGS "${Iconv_INCLUDE_DIRS}/iconv.h" _Iconv_VERSION_DEFINE REGEX "#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F][0-9A-F][0-9A-F].*") + string(REGEX REPLACE "#define[\t ]+_LIBICONV_VERSION[\t ]+0x([0-9A-F][0-9A-F])[0-9A-F][0-9A-F].*" "\\1" _Iconv_VERSION_MAJOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") + string(REGEX REPLACE "#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F]([0-9A-F][0-9A-F]).*" "\\1" _Iconv_VERSION_MINOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") + + if(NOT _Iconv_VERSION_MAJOR_HEXADECIMAL STREQUAL "" AND NOT _Iconv_VERSION_MINOR_HEXADECIMAL STREQUAL "") + math(EXPR Iconv_VERSION_MAJOR "0x${_Iconv_VERSION_MAJOR_HEXADECIMAL}" OUTPUT_FORMAT DECIMAL) + math(EXPR Iconv_VERSION_MINOR "0x${_Iconv_VERSION_MINOR_HEXADECIMAL}" OUTPUT_FORMAT DECIMAL) + set(Iconv_VERSION "${Iconv_VERSION_MAJOR}.${Iconv_VERSION_MINOR}") + endif() + + unset(_Iconv_VERSION_DEFINE) + unset(_Iconv_VERSION_MAJOR_HEXADECIMAL) + unset(_Iconv_VERSION_MINOR_HEXADECIMAL) +endif() + +if(Iconv_IS_BUILT_IN) + find_package_handle_standard_args( + Iconv + FOUND_VAR Iconv_FOUND + REQUIRED_VARS Iconv_INCLUDE_DIRS + VERSION_VAR Iconv_VERSION + ) +else() + find_package_handle_standard_args( + Iconv + FOUND_VAR Iconv_FOUND + REQUIRED_VARS Iconv_INCLUDE_DIRS Iconv_LIBRARIES + VERSION_VAR Iconv_VERSION + ) +endif() if(Iconv_FOUND AND NOT TARGET Iconv::Iconv) add_library(Iconv::Iconv UNKNOWN IMPORTED) diff --git a/cmake/FindLibLZMA.cmake b/cmake/FindLibLZMA.cmake index 7b209deb..0ce468ea 100644 --- a/cmake/FindLibLZMA.cmake +++ b/cmake/FindLibLZMA.cmake @@ -1,133 +1,49 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/liblzma*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND LIBLZMA_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - LIBLZMA_INCLUDE_HINTS - $ENV{LibLZMA_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/liblzma*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND LIBLZMA_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND LIBLZMA_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - LIBLZMA_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include - ${CMAKE_OSX_SYSROOT}/usr/include -) - find_path( LIBLZMA_INCLUDE_DIRS NAMES lzma.h - HINTS - ${LIBLZMA_INCLUDE_HINTS} - PATHS - ${LIBLZMA_INCLUDE_PATHS} ) mark_as_advanced(LIBLZMA_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/liblzma*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND LIBLZMA_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - LIBLZMA_LIBRARY_HINTS - $ENV{LibLZMA_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/liblzma*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND LIBLZMA_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND LIBLZMA_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - LIBLZMA_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( LIBLZMA_LIBRARY_DEBUG NAMES liblzmad lzmad - HINTS - ${LIBLZMA_LIBRARY_HINTS} - PATHS - ${LIBLZMA_LIBRARY_PATHS} ) find_library( LIBLZMA_LIBRARY_RELEASE NAMES liblzma lzma - HINTS - ${LIBLZMA_LIBRARY_HINTS} - PATHS - ${LIBLZMA_LIBRARY_PATHS} ) select_library_configurations(LIBLZMA) +if(LIBLZMA_INCLUDE_DIRS AND EXISTS "${LIBLZMA_INCLUDE_DIRS}/lzma/version.h") + file(STRINGS "${LIBLZMA_INCLUDE_DIRS}/lzma/version.h" _LZMA_VERSION_MAJOR_DEFINE REGEX "#define[\t ]+LZMA_VERSION_MAJOR[\t ]+[0-9]+.*") + string(REGEX REPLACE "#define[\t ]+LZMA_VERSION_MAJOR[\t ]+([0-9]+).*" "\\1" LZMA_VERSION_MAJOR "${_LZMA_VERSION_MAJOR_DEFINE}") + file(STRINGS "${LIBLZMA_INCLUDE_DIRS}/lzma/version.h" _LZMA_VERSION_MINOR_DEFINE REGEX "#define[\t ]+LZMA_VERSION_MINOR[\t ]+[0-9]+.*") + string(REGEX REPLACE "#define[\t ]+LZMA_VERSION_MINOR[\t ]+([0-9]+).*" "\\1" LZMA_VERSION_MINOR "${_LZMA_VERSION_MINOR_DEFINE}") + file(STRINGS "${LIBLZMA_INCLUDE_DIRS}/lzma/version.h" _LZMA_VERSION_PATCH_DEFINE REGEX "#define[\t ]+LZMA_VERSION_PATCH[\t ]+[0-9]+.*") + string(REGEX REPLACE "#define[\t ]+LZMA_VERSION_PATCH[\t ]+([0-9]+).*" "\\1" LZMA_VERSION_PATCH "${_LZMA_VERSION_PATCH_DEFINE}") + + if(NOT LZMA_VERSION_MAJOR STREQUAL "" AND NOT LZMA_VERSION_MINOR STREQUAL "" AND NOT LZMA_VERSION_PATCH STREQUAL "") + set(LZMA_VERSION "${LZMA_VERSION_MAJOR}.${LZMA_VERSION_MINOR}.${LZMA_VERSION_PATCH}") + endif() + + unset(_LZMA_VERSION_MAJOR_DEFINE) + unset(_LZMA_VERSION_MINOR_DEFINE) + unset(_LZMA_VERSION_PATCH_DEFINE) +endif() + find_package_handle_standard_args( LibLZMA FOUND_VAR LIBLZMA_FOUND REQUIRED_VARS LIBLZMA_INCLUDE_DIRS LIBLZMA_LIBRARIES + VERSION_VAR LZMA_VERSION ) if(LIBLZMA_FOUND AND NOT TARGET LibLZMA::LibLZMA) diff --git a/cmake/FindLibXml2.cmake b/cmake/FindLibXml2.cmake index b73b4704..3a6f714a 100644 --- a/cmake/FindLibXml2.cmake +++ b/cmake/FindLibXml2.cmake @@ -1,135 +1,40 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libxml2*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND LIBXML2_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - LIBXML2_INCLUDE_HINTS - $ENV{LibXml2_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libxml2*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND LIBXML2_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND LIBXML2_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - LIBXML2_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include - ${CMAKE_OSX_SYSROOT}/usr/include -) - find_path( LIBXML2_INCLUDE_DIRS NAMES libxml/parser.h - HINTS - ${LIBXML2_INCLUDE_HINTS} - PATHS - ${LIBXML2_INCLUDE_PATHS} PATH_SUFFIXES libxml2 ) mark_as_advanced(LIBXML2_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libxml2*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND LIBXML2_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - LIBXML2_LIBRARY_HINTS - $ENV{LibXml2_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libxml2*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND LIBXML2_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND LIBXML2_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - LIBXML2_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( LIBXML2_LIBRARY_DEBUG NAMES libxml2d xml2d - HINTS - ${LIBXML2_LIBRARY_HINTS} - PATHS - ${LIBXML2_LIBRARY_PATHS} ) find_library( LIBXML2_LIBRARY_RELEASE NAMES libxml2 xml2 - HINTS - ${LIBXML2_LIBRARY_HINTS} - PATHS - ${LIBXML2_LIBRARY_PATHS} ) select_library_configurations(LIBXML2) +if(LIBXML2_INCLUDE_DIRS AND EXISTS "${LIBXML2_INCLUDE_DIRS}/libxml/xmlversion.h") + file(STRINGS "${LIBXML2_INCLUDE_DIRS}/libxml/xmlversion.h" _LIBXML2_VERSION_DEFINE REGEX "#define[\t ]+LIBXML_DOTTED_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "#define[\t ]+LIBXML_DOTTED_VERSION[\t ]+\"([^\"]*)\".*" "\\1" LIBXML2_VERSION "${_LIBXML2_VERSION_DEFINE}") + unset(_LIBXML2_VERSION_DEFINE) +endif() + find_package_handle_standard_args( LibXml2 FOUND_VAR LibXml2_FOUND REQUIRED_VARS LIBXML2_INCLUDE_DIRS LIBXML2_LIBRARIES + VERSION_VAR LIBXML2_VERSION ) if(LibXml2_FOUND AND NOT TARGET LibXml2::LibXml2) diff --git a/cmake/FindLibXslt.cmake b/cmake/FindLibXslt.cmake index 17e0504e..8bf4ad5c 100644 --- a/cmake/FindLibXslt.cmake +++ b/cmake/FindLibXslt.cmake @@ -1,133 +1,38 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libxslt*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND LIBXSLT_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - LIBXSLT_INCLUDE_HINTS - $ENV{LibXslt_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libxslt*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND LIBXSLT_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND LIBXSLT_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - LIBXSLT_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include - ${CMAKE_OSX_SYSROOT}/usr/include -) - find_path( LIBXSLT_INCLUDE_DIRS NAMES libxslt/xslt.h - HINTS - ${LIBXSLT_INCLUDE_HINTS} - PATHS - ${LIBXSLT_INCLUDE_PATHS} ) mark_as_advanced(LIBXSLT_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libxslt*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND LIBXSLT_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - LIBXSLT_LIBRARY_HINTS - $ENV{LibXslt_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libxslt*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND LIBXSLT_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND LIBXSLT_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - LIBXSLT_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( LIBXSLT_LIBRARY_DEBUG NAMES libxsltd xsltd - HINTS - ${LIBXSLT_LIBRARY_HINTS} - PATHS - ${LIBXSLT_LIBRARY_PATHS} ) find_library( LIBXSLT_LIBRARY_RELEASE NAMES libxslt xslt - HINTS - ${LIBXSLT_LIBRARY_HINTS} - PATHS - ${LIBXSLT_LIBRARY_PATHS} ) select_library_configurations(LIBXSLT) +if(LIBXSLT_INCLUDE_DIRS AND EXISTS "${LIBXSLT_INCLUDE_DIRS}/libxslt/xsltconfig.h") + file(STRINGS "${LIBXSLT_INCLUDE_DIRS}/libxslt/xsltconfig.h" _LIBXSLT_VERSION_DEFINE REGEX "#define[\t ]+LIBXSLT_DOTTED_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "#define[\t ]+LIBXSLT_DOTTED_VERSION[\t ]+\"([^\"]*)\".*" "\\1" LIBXSLT_VERSION "${_LIBXSLT_VERSION_DEFINE}") + unset(_LIBXSLT_VERSION_DEFINE) +endif() + find_package_handle_standard_args( LibXslt FOUND_VAR LIBXSLT_FOUND REQUIRED_VARS LIBXSLT_INCLUDE_DIRS LIBXSLT_LIBRARIES + VERSION_VAR LIBXSLT_VERSION ) if(LIBXSLT_FOUND AND NOT TARGET LibXslt::LibXslt) diff --git a/cmake/FindNLopt.cmake b/cmake/FindNLopt.cmake index a33aed58..79c784be 100644 --- a/cmake/FindNLopt.cmake +++ b/cmake/FindNLopt.cmake @@ -1,124 +1,23 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/NLopt*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND NLOPT_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - NLOPT_INCLUDE_HINTS - $ENV{NLopt_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/NLopt*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND NLOPT_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND NLOPT_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - NLOPT_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include -) - find_path( NLOPT_INCLUDE_DIRS NAMES nlopt.h - HINTS - ${NLOPT_INCLUDE_HINTS} - PATHS - ${NLOPT_INCLUDE_PATHS} ) mark_as_advanced(NLOPT_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/NLopt*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND NLOPT_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - NLOPT_LIBRARY_HINTS - $ENV{NLopt_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/NLopt*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND NLOPT_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND NLOPT_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - NLOPT_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( NLOPT_LIBRARY_DEBUG NAMES - nloptd nlopt_cxxd - HINTS - ${NLOPT_LIBRARY_HINTS} - PATHS - ${NLOPT_LIBRARY_PATHS} + nloptd ) find_library( NLOPT_LIBRARY_RELEASE NAMES - nlopt nlopt_cxx - HINTS - ${NLOPT_LIBRARY_HINTS} - PATHS - ${NLOPT_LIBRARY_PATHS} + nlopt ) select_library_configurations(NLOPT) diff --git a/cmake/FindODE.cmake b/cmake/FindODE.cmake index 62304e92..f9cc82b3 100644 --- a/cmake/FindODE.cmake +++ b/cmake/FindODE.cmake @@ -2,128 +2,26 @@ include(CheckCSourceRuns) include(CheckSymbolExists) include(CMakePushCheckState) include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/ODE*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND ODE_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - ODE_INCLUDE_HINTS - $ENV{ODE_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/ODE*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND ODE_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND ODE_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - ODE_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include -) - find_path( ODE_INCLUDE_DIRS NAMES ode/ode.h - HINTS - ${ODE_INCLUDE_HINTS} - PATHS - ${ODE_INCLUDE_PATHS} ) mark_as_advanced(ODE_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/ODE*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND ODE_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - ODE_LIBRARY_HINTS - $ENV{ODE_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/ODE*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND ODE_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND ODE_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - ODE_LIBRARY_PATHS - $ENV{ODE_LIBRARYDIR} - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( ODE_LIBRARY_DEBUG NAMES ode_doubled ode_singled oded - HINTS - ${ODE_LIBRARY_HINTS} - PATHS - ${ODE_LIBRARY_PATHS} ) find_library( ODE_LIBRARY_RELEASE NAMES ode_double ode_single ode - HINTS - ${ODE_LIBRARY_HINTS} - PATHS - ${ODE_LIBRARY_PATHS} ) select_library_configurations(ODE) @@ -131,47 +29,58 @@ select_library_configurations(ODE) if(ODE_INCLUDE_DIRS AND ODE_LIBRARIES) cmake_push_check_state(RESET) set(CMAKE_REQUIRED_INCLUDES ${ODE_INCLUDE_DIRS}) + check_symbol_exists(dDOUBLE "ode/precision.h" _ODE_HAVE_dDOUBLE) - check_symbol_exists(dDOUBLE "ode/precision.h" ODE_HAVE_DOUBLE) - - if(NOT ODE_HAVE_DOUBLE) - check_symbol_exists(dSINGLE "ode/precision.h" ODE_HAVE_SINGLE) - endif() - - if(NOT ODE_HAVE_DOUBLE AND NOT ODE_HAVE_SINGLE) - set(CMAKE_REQUIRED_DEFINITIONS -DdDOUBLE) - set(CMAKE_REQUIRED_LIBRARIES ${ODE_LIBRARIES}) - - check_c_source_runs(" - #include - int main() { return 1 == dCheckConfiguration(\"ODE_double_precision\") ? 0 : 1; } - " ODE_DOUBLE_PRECISION) + if(NOT _ODE_HAVE_dDOUBLE) + check_symbol_exists(dSINGLE "ode/precision.h" _ODE_HAVE_dSINGLE) - if(ODE_DOUBLE_PRECISION) - set(ODE_DEFINITIONS -DdDOUBLE) - else() - set(CMAKE_REQUIRED_DEFINITIONS -DdSINGLE) - + if(NOT _ODE_HAVE_dSINGLE) + set(CMAKE_REQUIRED_DEFINITIONS -DdDOUBLE) + set(CMAKE_REQUIRED_LIBRARIES ${ODE_LIBRARIES}) check_c_source_runs(" #include - int main() { return 1 == dCheckConfiguration(\"ODE_single_precision\") ? 0 : 1; } - " ODE_SINGLE_PRECISION) + int main() { return 1 == dCheckConfiguration(\"ODE_double_precision\") ? 0 : 1; } + " _ODE_DOUBLE_PRECISION) - if(ODE_SINGLE_PRECISION) - set(ODE_DEFINITIONS -DdSINGLE) + if(_ODE_DOUBLE_PRECISION) + set(ODE_DEFINITIONS -DdDOUBLE) + else() + set(CMAKE_REQUIRED_DEFINITIONS -DdSINGLE) + check_c_source_runs(" + #include + int main() { return 1 == dCheckConfiguration(\"ODE_single_precision\") ? 0 : 1; } + " _ODE_SINGLE_PRECISION) + + if(_ODE_SINGLE_PRECISION) + set(ODE_DEFINITIONS -DdSINGLE) + endif() + + unset(_ODE_SINGLE_PRECISION) endif() + + unset(_ODE_DOUBLE_PRECISION) endif() + + unset(_ODE_HAVE_dSINGLE) endif() + unset(_ODE_HAVE_dDOUBLE) cmake_pop_check_state() endif() mark_as_advanced(ODE_DEFINITIONS) +if(ODE_INCLUDE_DIRS AND EXISTS "${ODE_INCLUDE_DIRS}/ode/version.h") + file(STRINGS "${ODE_INCLUDE_DIRS}/ode/version.h" _ODE_VERSION_DEFINE REGEX "#define[\t ]+dODE_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "#define[\t ]+dODE_VERSION[\t ]+\"([^\"]*)\".*" "\\1" ODE_VERSION "${_ODE_VERSION_DEFINE}") + unset(_ODE_VERSION_DEFINE) +endif() + find_package_handle_standard_args( ODE FOUND_VAR ODE_FOUND REQUIRED_VARS ODE_INCLUDE_DIRS ODE_LIBRARIES + VERSION_VAR ODE_VERSION ) if(ODE_FOUND AND NOT TARGET ODE::ODE) diff --git a/cmake/FindPQP.cmake b/cmake/FindPQP.cmake index 2d884162..2adbc9d8 100644 --- a/cmake/FindPQP.cmake +++ b/cmake/FindPQP.cmake @@ -1,126 +1,24 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/PQP*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND PQP_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - PQP_INCLUDE_HINTS - $ENV{PQP_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/PQP*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND PQP_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND PQP_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - PQP_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include/PQP - /opt/local/include - /usr/include -) - find_path( PQP_INCLUDE_DIRS NAMES PQP.h - HINTS - ${PQP_INCLUDE_HINTS} - PATHS - ${PQP_INCLUDE_PATHS} ) mark_as_advanced(PQP_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/PQP*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND PQP_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - PQP_LIBRARY_HINTS - $ENV{PQP_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/PQP*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND PQP_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND PQP_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - PQP_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( PQP_LIBRARY_DEBUG NAMES PQPd - HINTS - ${PQP_LIBRARY_HINTS} - PATHS - ${PQP_LIBRARY_PATHS} ) find_library( PQP_LIBRARY_RELEASE NAMES PQP - HINTS - ${PQP_LIBRARY_HINTS} - PATHS - ${PQP_LIBRARY_PATHS} ) select_library_configurations(PQP) diff --git a/cmake/FindRTAI.cmake b/cmake/FindRTAI.cmake index 6342e069..2bfde086 100644 --- a/cmake/FindRTAI.cmake +++ b/cmake/FindRTAI.cmake @@ -1,130 +1,32 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/RTAI*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND RTAI_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - RTAI_INCLUDE_HINTS - $ENV{RTAI_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/RTAI*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND RTAI_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND RTAI_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - RTAI_INCLUDE_PATHS - $ENV{RTAI_DIR}/include - $ENV{RTAIDIR}/include - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/realtime/include - /usr/include/rtai - /usr/include -) - find_path( RTAI_INCLUDE_DIRS NAMES rtai_lxrt.h - HINTS - ${RTAI_INCLUDE_HINTS} PATHS - ${RTAI_INCLUDE_PATHS} + /usr/realtime/include + PATH_SUFFIXES + rtai ) mark_as_advanced(RTAI_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/RTAI*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND RTAI_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - RTAI_LIBRARY_HINTS - $ENV{RTAI_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/RTAI*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND RTAI_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND RTAI_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - RTAI_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/realtime/lib - /usr/lib -) - find_library( RTAI_LIBRARY_DEBUG NAMES lxrtd - HINTS - ${RTAI_LIBRARY_HINTS} PATHS - ${RTAI_LIBRARY_PATHS} + /usr/realtime/lib ) find_library( RTAI_LIBRARY_RELEASE NAMES lxrt - HINTS - ${RTAI_LIBRARY_HINTS} PATHS - ${RTAI_LIBRARY_PATHS} + /usr/realtime/lib ) select_library_configurations(RTAI) diff --git a/cmake/FindSOLID3.cmake b/cmake/FindSOLID3.cmake index 08a3c9c4..3f608418 100644 --- a/cmake/FindSOLID3.cmake +++ b/cmake/FindSOLID3.cmake @@ -1,125 +1,24 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/SOLID*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND SOLID3_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - SOLID3_INCLUDE_HINTS - $ENV{SOLID3_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/SOLID*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND SOLID3_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND SOLID3_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - SOLID3_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include -) - find_path( -SOLID3_INCLUDE_DIRS + SOLID3_INCLUDE_DIRS NAMES SOLID/SOLID.h - HINTS - ${SOLID3_INCLUDE_HINTS} - PATHS - ${SOLID3_INCLUDE_PATHS} ) mark_as_advanced(SOLID3_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/SOLID*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND SOLID3_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - SOLID3_LIBRARY_HINTS - $ENV{SOLID3_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/SOLID*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND SOLID3_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND SOLID3_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - SOLID3_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( SOLID3_LIBRARY_DEBUG NAMES solid3d_d solid3_d solidd solidsd - HINTS - ${SOLID3_LIBRARY_HINTS} - PATHS - ${SOLID3_LIBRARY_PATHS} ) find_library( SOLID3_LIBRARY_RELEASE NAMES solid3d solid3 solid solids - HINTS - ${SOLID3_LIBRARY_HINTS} - PATHS - ${SOLID3_LIBRARY_PATHS} ) select_library_configurations(SOLID3) diff --git a/cmake/FindSoQt.cmake b/cmake/FindSoQt.cmake index 69af1329..f5217452 100644 --- a/cmake/FindSoQt.cmake +++ b/cmake/FindSoQt.cmake @@ -1,121 +1,28 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/SoQt*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND SoQt_INCLUDE_HINTS ${HINTS}) -endforeach() - -list(APPEND SoQt_INCLUDE_HINTS $ENV{SoQt_DIR}/${CMAKE_INSTALL_INCLUDEDIR}) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/SoQt*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND SoQt_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND SoQt_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - SoQt_INCLUDE_PATHS - $ENV{COIN3DDIR}/include - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include/Coin* - /usr/include -) - find_path( SoQt_INCLUDE_DIRS NAMES Inventor/Qt/SoQt.h - HINTS - ${SoQt_INCLUDE_HINTS} - PATHS - ${SoQt_INCLUDE_PATHS} + PATH_SUFFIXES + Coin4 + Coin3 + Coin2 ) mark_as_advanced(SoQt_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/SoQt*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND SoQt_LIBRARY_HINTS ${HINTS}) -endforeach() - -list(APPEND SoQt_LIBRARY_HINTS $ENV{SoQt_DIR}/${CMAKE_INSTALL_LIBDIR}) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/SoQt*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND SoQt_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND SoQt_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - SoQt_LIBRARY_PATHS - $ENV{COIN3DDIR}/lib - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( SoQt_LIBRARY_DEBUG NAMES SoQtd SoQt1d - HINTS - ${SoQt_LIBRARY_HINTS} - PATHS - ${SoQt_LIBRARY_PATHS} ) find_library( SoQt_LIBRARY_RELEASE NAMES SoQt SoQt1 - HINTS - HINTS - ${SoQt_LIBRARY_HINTS} - PATHS - ${SoQt_LIBRARY_PATHS} ) select_library_configurations(SoQt) @@ -124,16 +31,25 @@ set(SoQt_DEFINITIONS -DSOQT_DLL) mark_as_advanced(SoQt_DEFINITIONS) -if(EXISTS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h") - file(STRINGS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h" GUI_TOOLKIT_VERSION_DEFINE REGEX "#define GUI_TOOLKIT_VERSION.*[0-9]+.*") - string(REGEX REPLACE ".*([0-9])([0-9])([0-9]).*" "\\1" GUI_TOOLKIT_VERSION_MAJOR "${GUI_TOOLKIT_VERSION_DEFINE}") - set(SoQt${GUI_TOOLKIT_VERSION_MAJOR}_FOUND ON) +if(SoQt_INCLUDE_DIRS AND EXISTS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h") + file(STRINGS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h" _SoQt_VERSION_DEFINE REGEX "#define[\t ]+SOQT_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "#define[\t ]+SOQT_VERSION[\t ]+\"([^\"]*)\".*" "\\1" SoQt_VERSION "${_SoQt_VERSION_DEFINE}") + file(STRINGS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h" _SoQt_GUI_TOOLKIT_VERSION_DEFINE REGEX "#define[\t ]+GUI_TOOLKIT_VERSION[\t ]+\"[0-9][0-9][0-9]\".*") + string(REGEX REPLACE "#define[\t ]+GUI_TOOLKIT_VERSION[\t ]+\"([0-9])[0-9][0-9]\".*" "\\1" SoQt_GUI_TOOLKIT_VERSION_MAJOR "${_SoQt_GUI_TOOLKIT_VERSION_DEFINE}") + + if(NOT SoQt_GUI_TOOLKIT_VERSION_MAJOR STREQUAL "") + set(SoQt${SoQt_GUI_TOOLKIT_VERSION_MAJOR}_FOUND ON) + endif() + + unset(_SoQt_VERSION_DEFINE) + unset(_SoQt_GUI_TOOLKIT_VERSION_DEFINE) endif() find_package_handle_standard_args( SoQt FOUND_VAR SoQt_FOUND REQUIRED_VARS SoQt_INCLUDE_DIRS SoQt_LIBRARIES + VERSION_VAR SoQt_VERSION ) if(SoQt_FOUND AND NOT TARGET SoQt::SoQt) diff --git a/cmake/FindXenomai.cmake b/cmake/FindXenomai.cmake index ea6c8675..fb8f0d4e 100644 --- a/cmake/FindXenomai.cmake +++ b/cmake/FindXenomai.cmake @@ -1,128 +1,32 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Xenomai*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Xenomai_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - Xenomai_INCLUDE_HINTS - $ENV{Xenomai_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/Xenomai*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Xenomai_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND Xenomai_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - Xenomai_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/xenomai/include - /usr/include/xenomai - /usr/include -) - find_path( Xenomai_INCLUDE_DIRS NAMES native/task.h - HINTS - ${Xenomai_INCLUDE_HINTS} PATHS - ${Xenomai_INCLUDE_PATHS} + /usr/xenomai/include + PATH_SUFFIXES + xenomai ) mark_as_advanced(Xenomai_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/Xenomai*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Xenomai_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - Xenomai_LIBRARY_HINTS - $ENV{Xenomai_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/Xenomai*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Xenomai_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND Xenomai_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - Xenomai_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/xenomai/lib - /usr/lib -) - find_library( Xenomai_NATIVE_LIBRARY_DEBUG NAMES natived - HINTS - ${Xenomai_LIBRARY_HINTS} PATHS - ${Xenomai_LIBRARY_PATHS} + /usr/xenomai/lib ) find_library( Xenomai_NATIVE_LIBRARY_RELEASE NAMES native - HINTS - ${Xenomai_LIBRARY_HINTS} PATHS - ${Xenomai_LIBRARY_PATHS} + /usr/xenomai/lib ) select_library_configurations(Xenomai_NATIVE) @@ -131,20 +35,16 @@ find_library( Xenomai_XENOMAI_LIBRARY_DEBUG NAMES xenomaid - HINTS - ${Xenomai_LIBRARY_HINTS} PATHS - ${Xenomai_LIBRARY_PATHS} + /usr/xenomai/lib ) find_library( Xenomai_XENOMAI_LIBRARY_RELEASE NAMES xenomai - HINTS - ${Xenomai_LIBRARY_HINTS} PATHS - ${Xenomai_LIBRARY_PATHS} + /usr/xenomai/lib ) select_library_configurations(Xenomai_XENOMAI) diff --git a/cmake/FindZLIB.cmake b/cmake/FindZLIB.cmake index 24557d14..ec1e0bb5 100644 --- a/cmake/FindZLIB.cmake +++ b/cmake/FindZLIB.cmake @@ -1,138 +1,39 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/zlib*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND ZLIB_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - ZLIB_INCLUDE_HINTS - $ENV{ZLIB_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/zlib*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND ZLIB_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND ZLIB_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - ZLIB_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include - $ENV{ProgramW6432}/GnuWin32/include - $ENV{ProgramFiles}/GnuWin32/include - ${CMAKE_OSX_SYSROOT}/usr/include -) - find_path( ZLIB_INCLUDE_DIRS NAMES zlib.h - HINTS - ${ZLIB_INCLUDE_HINTS} - PATHS - ${ZLIB_INCLUDE_PATHS} ) mark_as_advanced(ZLIB_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/zlib*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND ZLIB_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - ZLIB_LIBRARY_HINTS - $ENV{ZLIB_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/zlib*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND ZLIB_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND ZLIB_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - ZLIB_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib - $ENV{ProgramW6432}/GnuWin32/lib - $ENV{ProgramFiles}/GnuWin32/lib -) - find_library( ZLIB_LIBRARY_DEBUG NAMES zd zlibd zlib_ad zlibstaticd zlibwapid zdlld - HINTS - ${ZLIB_LIBRARY_HINTS} - PATHS - ${ZLIB_LIBRARY_PATHS} ) find_library( ZLIB_LIBRARY_RELEASE NAMES z zlib zlib_a zlibstatic zlibwapi zdll - HINTS - ${ZLIB_LIBRARY_HINTS} - PATHS - ${ZLIB_LIBRARY_PATHS} ) select_library_configurations(ZLIB) +if(ZLIB_INCLUDE_DIRS AND EXISTS "${ZLIB_INCLUDE_DIRS}/zlib.h") + file(STRINGS "${ZLIB_INCLUDE_DIRS}/zlib.h" _ZLIB_VERSION_DEFINE REGEX "#define[\t ]+ZLIB_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "#define[\t ]+ZLIB_VERSION[\t ]+\"([^\"]*)\".*" "\\1" ZLIB_VERSION "${_ZLIB_VERSION_DEFINE}") + unset(_ZLIB_VERSION_DEFINE) +endif() + find_package_handle_standard_args( ZLIB FOUND_VAR ZLIB_FOUND REQUIRED_VARS ZLIB_INCLUDE_DIRS ZLIB_LIBRARIES + VERSION_VAR ZLIB_VERSION ) if(ZLIB_FOUND AND NOT TARGET ZLIB::ZLIB) diff --git a/cmake/Findccd.cmake b/cmake/Findccd.cmake index b5eef4d4..14d29f6c 100644 --- a/cmake/Findccd.cmake +++ b/cmake/Findccd.cmake @@ -1,125 +1,24 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/ccd*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND CCD_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - CCD_INCLUDE_HINTS - $ENV{ccd_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/ccd*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND CCD_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND CCD_INCLUDE_HINTS ${HINTS}) -endforeach() - -file( - GLOB - CCD_INCLUDE_PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include -) - find_path( CCD_INCLUDE_DIRS NAMES ccd/ccd.h - HINTS - ${CCD_INCLUDE_HINTS} - PATHS - ${CCD_INCLUDE_PATHS} ) mark_as_advanced(CCD_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/ccd*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND CCD_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - CCD_LIBRARY_HINTS - $ENV{ccd_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/ccd*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND CCD_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND CCD_LIBRARY_HINTS ${HINTS}) -endforeach() - -file( - GLOB - CCD_LIBRARY_PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib -) - find_library( CCD_LIBRARY_DEBUG NAMES ccdd - HINTS - ${CCD_LIBRARY_HINTS} - PATHS - ${CCD_LIBRARY_PATHS} ) find_library( CCD_LIBRARY_RELEASE NAMES ccd - HINTS - ${CCD_LIBRARY_HINTS} - PATHS - ${CCD_LIBRARY_PATHS} ) select_library_configurations(CCD) diff --git a/cmake/FindcifX.cmake b/cmake/FindcifX.cmake index 3f416423..f22b9e9b 100644 --- a/cmake/FindcifX.cmake +++ b/cmake/FindcifX.cmake @@ -1,53 +1,11 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/cifX*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND cifX_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - cifX_INCLUDE_HINTS - $ENV{cifX_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/cifX*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND cifX_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND cifX_INCLUDE_HINTS ${HINTS}) -endforeach() - find_path( cifX_INCLUDE_DIRS NAMES cifXUser.h - HINTS - ${cifX_INCLUDE_HINTS} PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include "$ENV{ProgramW6432}/cifX Device Driver/SDK/includes" "$ENV{ProgramFiles}/cifX Device Driver/SDK/includes" PATH_SUFFIXES @@ -62,64 +20,11 @@ else() set(cifX_ARCHITECTURE "x86") endif() -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libs - ${PATH}/libs/${cifX_ARCHITECTURE} - ${PATH}/cifX*/${CMAKE_INSTALL_LIBDIR} - ${PATH}/cifX*/libs - ${PATH}/cifX*/libs/${cifX_ARCHITECTURE} - ) - list(APPEND cifX_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - cifX_LIBRARY_HINTS - $ENV{cifX_DIR}/${CMAKE_INSTALL_LIBDIR} - $ENV{cifX_DIR}/libs - $ENV{cifX_DIR}/libs/${cifX_ARCHITECTURE} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libs - ${PATH}/libs/${cifX_ARCHITECTURE} - ${PATH}/cifX*/${CMAKE_INSTALL_LIBDIR} - ${PATH}/cifX*/libs - ${PATH}/cifX*/libs/${cifX_ARCHITECTURE} - ) - list(APPEND cifX_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ${PATH}/../libs - ${PATH}/../libs/${cifX_ARCHITECTURE} - ) - list(APPEND cifX_LIBRARY_HINTS ${HINTS}) -endforeach() - find_library( cifX_LIBRARY_RELEASE NAMES cifx cifx32dll - HINTS - ${cifX_LIBRARY_HINTS} PATHS - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib "$ENV{ProgramW6432}/cifX Device Driver/SDK/libs/${cifX_ARCHITECTURE}" "$ENV{ProgramFiles}/cifX Device Driver/SDK/libs/${cifX_ARCHITECTURE}" ) diff --git a/cmake/Findlibdc1394.cmake b/cmake/Findlibdc1394.cmake index c1c00b4c..345f426c 100644 --- a/cmake/Findlibdc1394.cmake +++ b/cmake/Findlibdc1394.cmake @@ -1,103 +1,18 @@ include(FindPackageHandleStandardArgs) -include(GNUInstallDirs) include(SelectLibraryConfigurations) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libdc1394*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND libdc1394_INCLUDE_HINTS ${HINTS}) -endforeach() - -list( - APPEND - libdc1394_INCLUDE_HINTS - $ENV{libdc1394_DIR}/${CMAKE_INSTALL_INCLUDEDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_INCLUDEDIR} - ${PATH}/libdc1394*/${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND libdc1394_INCLUDE_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_INCLUDEDIR} - ) - list(APPEND libdc1394_INCLUDE_HINTS ${HINTS}) -endforeach() - find_path( libdc1394_INCLUDE_DIRS + NAMES dc1394/dc1394.h - HINTS - ${libdc1394_INCLUDE_HINTS} - PATHS - $ENV{HOME}/include - /usr/local/include - /opt/local/include - /usr/include ) mark_as_advanced(libdc1394_INCLUDE_DIRS) -foreach(PATH ${CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libdc1394*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND libdc1394_LIBRARY_HINTS ${HINTS}) -endforeach() - -list( - APPEND - libdc1394_LIBRARY_HINTS - $ENV{libdc1394_DIR}/${CMAKE_INSTALL_LIBDIR} -) - -foreach(PATH $ENV{CMAKE_PREFIX_PATH}) - file( - GLOB - HINTS - ${PATH}/${CMAKE_INSTALL_LIBDIR} - ${PATH}/libdc1394*/${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND libdc1394_LIBRARY_HINTS ${HINTS}) -endforeach() - -foreach(PATH $ENV{PATH}) - file( - GLOB - HINTS - ${PATH}/../${CMAKE_INSTALL_LIBDIR} - ) - list(APPEND libdc1394_LIBRARY_HINTS ${HINTS}) -endforeach() - find_library( libdc1394_LIBRARY_RELEASE NAMES dc1394 - HINTS - ${libdc1394_LIBRARY_HINTS} - PATHS - $ENV{libdc1394_DIR}/lib - $ENV{HOME}/lib - /usr/local/lib - /opt/local/lib - /usr/lib ) mark_as_advanced(libdc1394_LIBRARY_RELEASE) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 05555352..c2670001 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -197,6 +197,7 @@ target_include_directories( if(RL_BUILD_SG_BULLET) target_compile_definitions(sg INTERFACE RL_SG_BULLET) + target_compile_definitions(sg PUBLIC ${BULLET_DEFINITIONS}) target_include_directories(sg PUBLIC ${BULLET_INCLUDE_DIRS}) target_link_libraries(sg ${BULLET_LIBRARIES}) install(FILES ${BULLET_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/bullet COMPONENT development) From 670a30cbf114cf9d6bf9dd3ff07c348be73eda9a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 22 Jun 2020 22:29:59 +0200 Subject: [PATCH 375/546] Update lexical_cast to float for SoSFFloat --- src/rl/sg/UrdfFactory.cpp | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index a4285793..722e8bef 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -123,12 +123,12 @@ ::std::cout << "\trgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " vrmlMaterial->ref(); vrmlMaterial->diffuseColor.setValue( - ::boost::lexical_cast<::rl::math::Real>(rgba[0]), - ::boost::lexical_cast<::rl::math::Real>(rgba[1]), - ::boost::lexical_cast<::rl::math::Real>(rgba[2]) + ::boost::lexical_cast(rgba[0]), + ::boost::lexical_cast(rgba[1]), + ::boost::lexical_cast(rgba[2]) ); vrmlMaterial->transparency.setValue( - 1 - ::boost::lexical_cast<::rl::math::Real>(rgba[3]) + 1 - ::boost::lexical_cast(rgba[3]) ); name2material[path.eval("string(@name)").getValue<::std::string>()] = vrmlMaterial; @@ -239,12 +239,12 @@ ::std::cout << "\tmaterial rgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2 ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); vrmlMaterial->diffuseColor.setValue( - ::boost::lexical_cast<::rl::math::Real>(rgba[0]), - ::boost::lexical_cast<::rl::math::Real>(rgba[1]), - ::boost::lexical_cast<::rl::math::Real>(rgba[2]) + ::boost::lexical_cast(rgba[0]), + ::boost::lexical_cast(rgba[1]), + ::boost::lexical_cast(rgba[2]) ); vrmlMaterial->transparency.setValue( - 1 - ::boost::lexical_cast<::rl::math::Real>(rgba[3]) + 1 - ::boost::lexical_cast(rgba[3]) ); vrmlAppearance->material = vrmlMaterial; @@ -275,9 +275,9 @@ ::std::cout << "\tmaterial name: " << path.eval("string(material/@name)").getVal ::boost::split(size, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); box->size.setValue( - ::boost::lexical_cast<::rl::math::Real>(size[0]), - ::boost::lexical_cast<::rl::math::Real>(size[1]), - ::boost::lexical_cast<::rl::math::Real>(size[2]) + ::boost::lexical_cast(size[0]), + ::boost::lexical_cast(size[1]), + ::boost::lexical_cast(size[2]) ); } @@ -291,14 +291,14 @@ ::std::cout << "\tbox size: " << box->size.getValue()[0] << " " << box->size.get if (!shapes[k].getProperty("length").empty()) { cylinder->height.setValue( - ::boost::lexical_cast<::rl::math::Real>(shapes[k].getProperty("length")) + ::boost::lexical_cast(shapes[k].getProperty("length")) ); } if (!shapes[k].getProperty("radius").empty()) { cylinder->radius.setValue( - ::boost::lexical_cast<::rl::math::Real>(shapes[k].getProperty("radius")) + ::boost::lexical_cast(shapes[k].getProperty("radius")) ); } @@ -366,7 +366,7 @@ ::std::cout << "\tmesh filename: " << meshFilename << ::std::endl; if (!shapes[k].getProperty("radius").empty()) { sphere->radius.setValue( - ::boost::lexical_cast<::rl::math::Real>(shapes[k].getProperty("radius")) + ::boost::lexical_cast(shapes[k].getProperty("radius")) ); } From 5ac7b594d16a158d1db6ba02432bc9fa266ada24 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 22 Jun 2020 22:30:59 +0200 Subject: [PATCH 376/546] Replace size_t with ptrdiff_t --- demos/rlCoachKin/Socket.cpp | 2 +- demos/rlCoachMdl/Socket.cpp | 2 +- demos/rlFilterDemo/rlLowPassDemo.cpp | 4 ++-- src/rl/hal/UniversalRobotsRtde.cpp | 8 ++++---- src/rl/mdl/Joint.cpp | 10 +++++----- 5 files changed, 13 insertions(+), 13 deletions(-) diff --git a/demos/rlCoachKin/Socket.cpp b/demos/rlCoachKin/Socket.cpp index da2de2c3..324c8dbb 100644 --- a/demos/rlCoachKin/Socket.cpp +++ b/demos/rlCoachKin/Socket.cpp @@ -182,7 +182,7 @@ Socket::readClient() rl::math::Vector q(MainWindow::instance()->kinematicModels[i]->getDof()); MainWindow::instance()->kinematicModels[i]->getPosition(q); - for (std::size_t i = 0; i < q.size(); ++i) + for (std::ptrdiff_t i = 0; i < q.size(); ++i) { textStream << " " << q(i); } diff --git a/demos/rlCoachMdl/Socket.cpp b/demos/rlCoachMdl/Socket.cpp index eda8897d..688925e5 100644 --- a/demos/rlCoachMdl/Socket.cpp +++ b/demos/rlCoachMdl/Socket.cpp @@ -185,7 +185,7 @@ Socket::readClient() { rl::math::Vector q = MainWindow::instance()->kinematicModels[i]->getPosition(); - for (std::size_t i = 0; i < q.size(); ++i) + for (std::ptrdiff_t i = 0; i < q.size(); ++i) { textStream << " " << q(i); } diff --git a/demos/rlFilterDemo/rlLowPassDemo.cpp b/demos/rlFilterDemo/rlLowPassDemo.cpp index 1af03819..db26bf4c 100644 --- a/demos/rlFilterDemo/rlLowPassDemo.cpp +++ b/demos/rlFilterDemo/rlLowPassDemo.cpp @@ -57,7 +57,7 @@ main(int argc, char** argv) rl::math::Vector measurement(3); - for (std::size_t i = 0; i < measurement.size(); ++i) + for (std::ptrdiff_t i = 0; i < measurement.size(); ++i) { stream >> measurement(i); } @@ -66,7 +66,7 @@ main(int argc, char** argv) filtered << time; - for (std::size_t i = 0; i < estimation.size(); ++i) + for (std::ptrdiff_t i = 0; i < estimation.size(); ++i) { filtered << "\t" << estimation(i); } diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 6cd9d1ac..2ba71761 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -396,7 +396,7 @@ namespace rl { ::rl::math::Vector i(this->getDof()); - for (::std::size_t j = 0; j < 6; ++j) + for (::std::ptrdiff_t j = 0; j < 6; ++j) { i(j) = this->output.actualCurrent[j]; } @@ -416,7 +416,7 @@ namespace rl { ::rl::math::Vector q(this->getDof()); - for (::std::size_t i = 0; i < 6; ++i) + for (::std::ptrdiff_t i = 0; i < 6; ++i) { q(i) = this->output.actualQ[i]; } @@ -429,7 +429,7 @@ namespace rl { ::rl::math::Vector temperature(this->getDof()); - for (::std::size_t i = 0; i < 6; ++i) + for (::std::ptrdiff_t i = 0; i < 6; ++i) { temperature(i) = this->output.jointTemperatures[i]; } @@ -442,7 +442,7 @@ namespace rl { ::rl::math::Vector qd(this->getDof()); - for (::std::size_t i = 0; i < 6; ++i) + for (::std::ptrdiff_t i = 0; i < 6; ++i) { qd(i) = this->output.actualQd[i]; } diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index 414adef4..baf2f1ab 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -65,7 +65,7 @@ namespace rl void Joint::clamp(::rl::math::VectorRef q) const { - for (::std::size_t i = 0; i < q.size(); ++i) + for (::std::ptrdiff_t i = 0; i < q.size(); ++i) { if (this->wraparound(i)) { @@ -151,7 +151,7 @@ namespace rl void Joint::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const { - for (::std::size_t i = 0; i < q.size(); ++i) + for (::std::ptrdiff_t i = 0; i < q.size(); ++i) { q(i) = mean(i) + rand(i) * sigma(i); } @@ -162,7 +162,7 @@ namespace rl void Joint::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, ::rl::math::VectorRef q) const { - for (::std::size_t i = 0; i < q.size(); ++i) + for (::std::ptrdiff_t i = 0; i < q.size(); ++i) { q(i) = this->min(i) + rand(i) * (this->max(i) - this->min(i)); } @@ -171,7 +171,7 @@ namespace rl void Joint::generatePositionUniform(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& min, const ::rl::math::ConstVectorRef& max, ::rl::math::VectorRef q) const { - for (::std::size_t i = 0; i < q.size(); ++i) + for (::std::ptrdiff_t i = 0; i < q.size(); ++i) { q(i) = min(i) + rand(i) * (max(i) - min(i)); } @@ -280,7 +280,7 @@ namespace rl bool Joint::isValid(const ::rl::math::ConstVectorRef& q) const { - for (::std::size_t i = 0; i < q.size(); ++i) + for (::std::ptrdiff_t i = 0; i < q.size(); ++i) { if (q(i) < this->min(i) || q(i) > this->max(i)) { From 063b3ee6aa2945f09d92ccdfa98020276caa609c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 23 Jun 2020 18:20:27 +0200 Subject: [PATCH 377/546] Fix XML node deallocation --- src/rl/xml/Node.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/xml/Node.h b/src/rl/xml/Node.h index edfc42c0..422df9dd 100644 --- a/src/rl/xml/Node.h +++ b/src/rl/xml/Node.h @@ -67,9 +67,9 @@ namespace rl ~Node() { - if (nullptr != this->node && nullptr == this->node->doc) + if (nullptr != this->node && nullptr == this->node->doc && nullptr == this->node->parent) { - ::xmlFree(this->node); + ::xmlFreeNode(this->node); } } From 65cfc4294dc1401eba41c768f1d78f446ec7395f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 25 Jun 2020 21:33:59 +0200 Subject: [PATCH 378/546] Add FCL to Ubuntu and macOS --- .github/workflows/ci.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 76bea763..293078ee 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -53,6 +53,7 @@ jobs: cmake coin eigen + fcl ninja nlopt ode @@ -73,6 +74,7 @@ jobs: libcomedi-dev libdc1394-22-dev libeigen3-dev + libfcl-dev libnlopt-dev libode-dev libsimage-dev From 71d4a8dd66715009226d7f8fe9e1f0d70ed1152f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Jun 2020 23:35:42 +0200 Subject: [PATCH 379/546] Add optional FCL dependency OctoMap --- cmake/FindOctoMap.cmake | 84 ++++++++++++++++++++++++++++++++++++++++ src/rl/sg/CMakeLists.txt | 6 +++ 2 files changed, 90 insertions(+) create mode 100644 cmake/FindOctoMap.cmake diff --git a/cmake/FindOctoMap.cmake b/cmake/FindOctoMap.cmake new file mode 100644 index 00000000..322d02fd --- /dev/null +++ b/cmake/FindOctoMap.cmake @@ -0,0 +1,84 @@ +include(FindPackageHandleStandardArgs) +include(SelectLibraryConfigurations) + +find_path( + OCTOMAP_INCLUDE_DIRS + NAMES + octomap/octomap.h +) + +mark_as_advanced(OCTOMAP_INCLUDE_DIRS) + +find_library( + OCTOMAP_OCTOMAP_LIBRARY_DEBUG + NAMES + octomapd +) + +find_library( + OCTOMAP_OCTOMAP_LIBRARY_RELEASE + NAMES + octomap +) + +select_library_configurations(OCTOMAP_OCTOMAP) + +find_library( + OCTOMAP_OCTOMATH_LIBRARY_DEBUG + NAMES + octomathd +) + +find_library( + OCTOMAP_OCTOMATH_LIBRARY_RELEASE + NAMES + octomath +) + +select_library_configurations(OCTOMAP_OCTOMATH) + +set(OCTOMAP_LIBRARIES ${OCTOMAP_OCTOMAP_LIBRARIES} ${OCTOMAP_OCTOMATH_LIBRARIES}) + +find_package_handle_standard_args( + OctoMap + FOUND_VAR OCTOMAP_FOUND + REQUIRED_VARS OCTOMAP_INCLUDE_DIRS OCTOMAP_LIBRARIES +) + +if(OCTOMAP_FOUND AND NOT TARGET octomap::octomap) + add_library(octomap::octomap UNKNOWN IMPORTED) + + if(OCTOMAP_OCTOMAP_LIBRARY_RELEASE) + set_property(TARGET octomap::octomap APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(octomap::octomap PROPERTIES IMPORTED_LOCATION_RELEASE "${OCTOMAP_OCTOMAP_LIBRARY_RELEASE}") + endif() + + if(OCTOMAP_OCTOMAP_LIBRARY_DEBUG) + set_property(TARGET octomap::octomap APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(octomap::octomap PROPERTIES IMPORTED_LOCATION_DEBUG "${OCTOMAP_OCTOMAP_LIBRARY_DEBUG}") + endif() + + set_target_properties( + octomap::octomap PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES "${OCTOMAP_INCLUDE_DIRS}" + ) +endif() + +if(OCTOMAP_FOUND AND NOT TARGET octomap::octomath) + add_library(octomap::octomath UNKNOWN IMPORTED) + + if(OCTOMAP_OCTOMATH_LIBRARY_RELEASE) + set_property(TARGET octomap::octomath APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(octomap::octomath PROPERTIES IMPORTED_LOCATION_RELEASE "${OCTOMAP_OCTOMATH_LIBRARY_RELEASE}") + endif() + + if(OCTOMAP_OCTOMATH_LIBRARY_DEBUG) + set_property(TARGET octomap::octomath APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(octomap::octomath PROPERTIES IMPORTED_LOCATION_DEBUG "${OCTOMAP_OCTOMATH_LIBRARY_DEBUG}") + endif() + + set_target_properties( + octomap::octomath PROPERTIES + INTERFACE_INCLUDE_DIRECTORIES "${OCTOMAP_INCLUDE_DIRS}" + ) +endif() diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index c2670001..a3acafd0 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -6,6 +6,7 @@ find_package(Bullet) find_package(ccd) find_package(Coin REQUIRED) find_package(FCL) +find_package(OctoMap) find_package(ODE) find_package(PQP) find_package(SOLID3) @@ -247,6 +248,11 @@ if(RL_BUILD_SG_ODE) install(FILES ${ODE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/ode COMPONENT development) endif() +if(OCTOMAP_FOUND AND RL_BUILD_SG_FCL) + target_include_directories(sg PUBLIC ${OCTOMAP_INCLUDE_DIRS}) + target_link_libraries(sg ${OCTOMAP_LIBRARIES}) +endif() + if(RL_BUILD_SG_PQP) target_compile_definitions(sg INTERFACE RL_SG_PQP) target_include_directories(sg PUBLIC ${PQP_INCLUDE_DIRS}) From 54649da082771cc581ac1440caffc10cce9a0378 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Jun 2020 23:37:33 +0200 Subject: [PATCH 380/546] Remove SoVRMLShape from Shape constructor --- src/rl/sg/Shape.cpp | 2 +- src/rl/sg/Shape.h | 3 +-- src/rl/sg/bullet/Shape.cpp | 2 +- src/rl/sg/bullet/Shape.h | 1 + src/rl/sg/fcl/Shape.cpp | 2 +- src/rl/sg/fcl/Shape.h | 1 + src/rl/sg/ode/Shape.cpp | 2 +- src/rl/sg/ode/Shape.h | 1 + src/rl/sg/pqp/Shape.cpp | 2 +- src/rl/sg/pqp/Shape.h | 1 + src/rl/sg/so/Shape.cpp | 2 +- src/rl/sg/so/Shape.h | 1 + src/rl/sg/solid/Shape.cpp | 2 +- src/rl/sg/solid/Shape.h | 1 + 14 files changed, 14 insertions(+), 9 deletions(-) diff --git a/src/rl/sg/Shape.cpp b/src/rl/sg/Shape.cpp index 88865165..d563fc24 100644 --- a/src/rl/sg/Shape.cpp +++ b/src/rl/sg/Shape.cpp @@ -31,7 +31,7 @@ namespace rl { namespace sg { - Shape::Shape(::SoVRMLShape* shape, Body* body) : + Shape::Shape(Body* body) : Base(), body(body), name() diff --git a/src/rl/sg/Shape.h b/src/rl/sg/Shape.h index 20de433e..06a88617 100644 --- a/src/rl/sg/Shape.h +++ b/src/rl/sg/Shape.h @@ -28,7 +28,6 @@ #define RL_SG_SHAPE_H #include -#include #include #include "Base.h" @@ -42,7 +41,7 @@ namespace rl class RL_SG_EXPORT Shape : public Base { public: - Shape(::SoVRMLShape* shape, Body* body); + Shape(Body* body); virtual ~Shape(); diff --git a/src/rl/sg/bullet/Shape.cpp b/src/rl/sg/bullet/Shape.cpp index 41e4a5f2..41bcf9d7 100644 --- a/src/rl/sg/bullet/Shape.cpp +++ b/src/rl/sg/bullet/Shape.cpp @@ -47,7 +47,7 @@ namespace rl namespace bullet { Shape::Shape(::SoVRMLShape* shape, Body* body) : - ::rl::sg::Shape(shape, body), + ::rl::sg::Shape(body), shape(), transform(), indices(), diff --git a/src/rl/sg/bullet/Shape.h b/src/rl/sg/bullet/Shape.h index b113ade9..7e9ac0b8 100644 --- a/src/rl/sg/bullet/Shape.h +++ b/src/rl/sg/bullet/Shape.h @@ -30,6 +30,7 @@ #include #include #include +#include #include "../Shape.h" diff --git a/src/rl/sg/fcl/Shape.cpp b/src/rl/sg/fcl/Shape.cpp index 8d35fbbd..100b681f 100644 --- a/src/rl/sg/fcl/Shape.cpp +++ b/src/rl/sg/fcl/Shape.cpp @@ -72,7 +72,7 @@ namespace rl #endif Shape::Shape(SoVRMLShape* shape, ::rl::sg::Body* body) : - ::rl::sg::Shape(shape, body), + ::rl::sg::Shape(body), base(::rl::math::Transform::Identity()), #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 distances(), diff --git a/src/rl/sg/fcl/Shape.h b/src/rl/sg/fcl/Shape.h index fb528851..be306824 100644 --- a/src/rl/sg/fcl/Shape.h +++ b/src/rl/sg/fcl/Shape.h @@ -30,6 +30,7 @@ #include #include #include +#include #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 #include diff --git a/src/rl/sg/ode/Shape.cpp b/src/rl/sg/ode/Shape.cpp index 0b4c7901..43bba495 100644 --- a/src/rl/sg/ode/Shape.cpp +++ b/src/rl/sg/ode/Shape.cpp @@ -46,7 +46,7 @@ namespace rl namespace ode { Shape::Shape(::SoVRMLShape* shape, Body* body) : - ::rl::sg::Shape(shape, body), + ::rl::sg::Shape(body), geom(nullptr), baseTransform(::rl::math::Transform::Identity()), indices(), diff --git a/src/rl/sg/ode/Shape.h b/src/rl/sg/ode/Shape.h index aeae1ade..fd4d9ce0 100644 --- a/src/rl/sg/ode/Shape.h +++ b/src/rl/sg/ode/Shape.h @@ -28,6 +28,7 @@ #define RL_SG_ODE_SHAPE_H #include +#include #include #include "../Shape.h" diff --git a/src/rl/sg/pqp/Shape.cpp b/src/rl/sg/pqp/Shape.cpp index 107971c3..8f7365d5 100644 --- a/src/rl/sg/pqp/Shape.cpp +++ b/src/rl/sg/pqp/Shape.cpp @@ -44,7 +44,7 @@ namespace rl namespace pqp { Shape::Shape(::SoVRMLShape* shape, Body* body) : - ::rl::sg::Shape(shape, body), + ::rl::sg::Shape(body), model(), frame(::rl::math::Transform::Identity()), transform(::rl::math::Transform::Identity()) diff --git a/src/rl/sg/pqp/Shape.h b/src/rl/sg/pqp/Shape.h index 733612ad..6c7e9e82 100644 --- a/src/rl/sg/pqp/Shape.h +++ b/src/rl/sg/pqp/Shape.h @@ -32,6 +32,7 @@ #include #include #include +#include #include "../Shape.h" diff --git a/src/rl/sg/so/Shape.cpp b/src/rl/sg/so/Shape.cpp index c4e0e7dc..6376dc81 100644 --- a/src/rl/sg/so/Shape.cpp +++ b/src/rl/sg/so/Shape.cpp @@ -39,7 +39,7 @@ namespace rl namespace so { Shape::Shape(::SoVRMLShape* shape, Body* body) : - ::rl::sg::Shape(shape, body), + ::rl::sg::Shape(body), root(new ::SoVRMLTransform()), shape(shape) { diff --git a/src/rl/sg/so/Shape.h b/src/rl/sg/so/Shape.h index 6fb06e3a..8c86120a 100644 --- a/src/rl/sg/so/Shape.h +++ b/src/rl/sg/so/Shape.h @@ -27,6 +27,7 @@ #ifndef RL_SG_SO_SHAPE_H #define RL_SG_SO_SHAPE_H +#include #include #include "../Shape.h" diff --git a/src/rl/sg/solid/Shape.cpp b/src/rl/sg/solid/Shape.cpp index df0e4f9d..55783968 100644 --- a/src/rl/sg/solid/Shape.cpp +++ b/src/rl/sg/solid/Shape.cpp @@ -45,7 +45,7 @@ namespace rl namespace solid { Shape::Shape(SoVRMLShape* shape, Body* body) : - ::rl::sg::Shape(shape, body), + ::rl::sg::Shape(body), complex(false), encounters(), object(), diff --git a/src/rl/sg/solid/Shape.h b/src/rl/sg/solid/Shape.h index fc58f810..d6e5b44d 100644 --- a/src/rl/sg/solid/Shape.h +++ b/src/rl/sg/solid/Shape.h @@ -30,6 +30,7 @@ #include #include #include +#include #include #include From db39dc01c326a9d7e454b213e8c11123fb1e4220 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Jun 2020 23:41:53 +0200 Subject: [PATCH 381/546] Update fcl::CollisionObject access --- src/rl/sg/fcl/Body.cpp | 8 ++++---- src/rl/sg/fcl/Scene.cpp | 14 +++++++------- src/rl/sg/fcl/Shape.cpp | 15 +++++++++++---- src/rl/sg/fcl/Shape.h | 6 ++++-- 4 files changed, 26 insertions(+), 17 deletions(-) diff --git a/src/rl/sg/fcl/Body.cpp b/src/rl/sg/fcl/Body.cpp index cd7e931c..6e502404 100644 --- a/src/rl/sg/fcl/Body.cpp +++ b/src/rl/sg/fcl/Body.cpp @@ -60,8 +60,8 @@ namespace rl Shape* fcl = static_cast(shape); this->shapes.push_back(fcl); fcl->update(this->frame); - this->manager.registerObject(fcl->collisionObject.get()); - static_cast(getModel())->addCollisionObject(fcl->collisionObject.get(), this); + this->manager.registerObject(fcl->getCollisionObject()); + static_cast(getModel())->addCollisionObject(fcl->getCollisionObject(), this); } ::rl::sg::Shape* @@ -85,8 +85,8 @@ namespace rl { Shape* fcl = static_cast(shape); this->shapes.erase(found); - this->manager.unregisterObject(fcl->collisionObject.get()); - static_cast(this->getModel())->removeCollisionObject(fcl->collisionObject.get()); + this->manager.unregisterObject(fcl->getCollisionObject()); + static_cast(this->getModel())->removeCollisionObject(fcl->getCollisionObject()); } } diff --git a/src/rl/sg/fcl/Scene.cpp b/src/rl/sg/fcl/Scene.cpp index 4e4d5f29..8c44a95b 100644 --- a/src/rl/sg/fcl/Scene.cpp +++ b/src/rl/sg/fcl/Scene.cpp @@ -135,7 +135,7 @@ namespace rl CollisionRequest request; CollisionResult result; - ::fcl::collide(shape1->collisionObject.get(), shape2->collisionObject.get(), request, result); + ::fcl::collide(shape1->getCollisionObject(), shape2->getCollisionObject(), request, result); return result.isCollision(); } @@ -215,7 +215,7 @@ namespace rl CollisionRequest request(1, true); CollisionResult result; - ::fcl::collide(shape1->collisionObject.get(), shape2->collisionObject.get(), request, result); + ::fcl::collide(shape1->getCollisionObject(), shape2->getCollisionObject(), request, result); if (0 == result.numContacts()) { @@ -303,11 +303,11 @@ namespace rl DistanceRequest request(true); DistanceResult result; - ::fcl::distance(shape1->collisionObject.get(), shape2->collisionObject.get(), request, result); + ::fcl::distance(shape1->getCollisionObject(), shape2->getCollisionObject(), request, result); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 - Vector3 nearestPoint1 = shape1->collisionObject->getTransform().transform(result.nearest_points[0]); - Vector3 nearestPoint2 = shape2->collisionObject->getTransform().transform(result.nearest_points[1]); + Vector3 nearestPoint1 = shape1->getCollisionObject()->getTransform().transform(result.nearest_points[0]); + Vector3 nearestPoint2 = shape2->getCollisionObject()->getTransform().transform(result.nearest_points[1]); for (::std::size_t i = 0; i < 3; ++i) { @@ -343,10 +343,10 @@ namespace rl DistanceRequest request; DistanceResult result; - ::fcl::distance(static_cast(shape)->collisionObject.get(), collisionObject.get(), request, result); + ::fcl::distance(static_cast(shape)->getCollisionObject(), collisionObject.get(), request, result); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 - Vector3 nearestPoint1 = static_cast(shape)->collisionObject->getTransform().transform(result.nearest_points[0]); + Vector3 nearestPoint1 = static_cast(shape)->getCollisionObject()->getTransform().transform(result.nearest_points[0]); Vector3 nearestPoint2 = collisionObject->getTransform().transform(result.nearest_points[1]); for (::std::size_t i = 0; i < 3; ++i) diff --git a/src/rl/sg/fcl/Shape.cpp b/src/rl/sg/fcl/Shape.cpp index 100b681f..61076e88 100644 --- a/src/rl/sg/fcl/Shape.cpp +++ b/src/rl/sg/fcl/Shape.cpp @@ -83,6 +83,7 @@ namespace rl #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 normals(), #endif + object(), polygons(), transform(::rl::math::Transform::Identity()), vertices() @@ -232,7 +233,7 @@ namespace rl #endif } - this->collisionObject = ::std::make_shared(this->geometry, Transform3()); + this->object = ::std::make_shared(this->geometry, Transform3()); this->getBody()->add(this); this->setTransform(::rl::math::Transform::Identity()); @@ -243,6 +244,12 @@ namespace rl static_cast(this->getBody())->remove(this); } + CollisionObject* + Shape::getCollisionObject() const + { + return this->object.get(); + } + void Shape::getTransform(::rl::math::Transform& transform) { @@ -293,12 +300,12 @@ namespace rl transform(2, 0), transform(2, 1), transform(2, 2) ); Vector3 translation(transform(0, 3), transform(1, 3), transform(2, 3)); - this->collisionObject->setTransform(rotation, translation); + this->object->setTransform(rotation, translation); #else - this->collisionObject->setTransform(transform.linear(), transform.translation()); + this->object->setTransform(transform.linear(), transform.translation()); #endif - this->collisionObject->computeAABB(); + this->object->computeAABB(); } } } diff --git a/src/rl/sg/fcl/Shape.h b/src/rl/sg/fcl/Shape.h index be306824..c4a0972d 100644 --- a/src/rl/sg/fcl/Shape.h +++ b/src/rl/sg/fcl/Shape.h @@ -65,14 +65,14 @@ namespace rl virtual ~Shape(); + CollisionObject* getCollisionObject() const; + void getTransform(::rl::math::Transform& transform); void setTransform(const ::rl::math::Transform& transform); void update(const ::rl::math::Transform& frame); - ::std::shared_ptr collisionObject; - protected: private: @@ -98,6 +98,8 @@ namespace rl ::std::vector normals; #endif + ::std::shared_ptr object; + ::std::vector polygons; ::rl::math::Transform transform; From acf0ee62145a3bb077dad10e0f22bfd5203e1cba Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 27 Jun 2020 23:42:44 +0200 Subject: [PATCH 382/546] Add optional constructor for fcl::CollisionGeometry --- src/rl/sg/fcl/Shape.cpp | 27 +++++++++++++++++++++++++++ src/rl/sg/fcl/Shape.h | 6 ++++++ 2 files changed, 33 insertions(+) diff --git a/src/rl/sg/fcl/Shape.cpp b/src/rl/sg/fcl/Shape.cpp index 61076e88..11096e48 100644 --- a/src/rl/sg/fcl/Shape.cpp +++ b/src/rl/sg/fcl/Shape.cpp @@ -239,6 +239,33 @@ namespace rl this->setTransform(::rl::math::Transform::Identity()); } +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 + Shape::Shape(const ::boost::shared_ptr& geometry, ::rl::sg::Body* body) : +#else + Shape::Shape(const ::std::shared_ptr& geometry, ::rl::sg::Body* body) : +#endif + ::rl::sg::Shape(body), + base(::rl::math::Transform::Identity()), +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + distances(), +#endif + frame(::rl::math::Transform::Identity()), + geometry(geometry), + indices(), +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 + normals(), +#endif + object(), + polygons(), + transform(::rl::math::Transform::Identity()), + vertices() + { + this->object = ::std::make_shared(this->geometry, Transform3()); + + this->getBody()->add(this); + this->setTransform(::rl::math::Transform::Identity()); + } + Shape::~Shape() { static_cast(this->getBody())->remove(this); diff --git a/src/rl/sg/fcl/Shape.h b/src/rl/sg/fcl/Shape.h index c4a0972d..b127f8c1 100644 --- a/src/rl/sg/fcl/Shape.h +++ b/src/rl/sg/fcl/Shape.h @@ -63,6 +63,12 @@ namespace rl public: Shape(SoVRMLShape* shape, ::rl::sg::Body* body); +#if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 + Shape(const ::boost::shared_ptr& geometry, ::rl::sg::Body* body); +#else + Shape(const ::std::shared_ptr& geometry, ::rl::sg::Body* body); +#endif + virtual ~Shape(); CollisionObject* getCollisionObject() const; From 502ba03669680f9803bf058a0203623dcabf310b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Jun 2020 18:45:44 +0200 Subject: [PATCH 383/546] Remove extra config file --- CMakeLists.txt | 10 ++-------- 1 file changed, 2 insertions(+), 8 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d3fd579c..fffc4bf5 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -99,11 +99,6 @@ foreach(TARGET ${TARGETS}) list(APPEND RL_LIBRARIES "rl::${TARGET}") endforeach(TARGET) -configure_package_config_file( - rl-config.cmake.in rl-config.cmake - INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${VERSION} -) - export( TARGETS ${TARGETS} NAMESPACE rl:: @@ -111,14 +106,13 @@ export( ) configure_package_config_file( - rl-config.cmake.in rl-config-install.cmake + rl-config.cmake.in rl-config.cmake INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${VERSION} ) install( - FILES ${CMAKE_CURRENT_BINARY_DIR}/rl-config-install.cmake + FILES ${CMAKE_CURRENT_BINARY_DIR}/rl-config.cmake DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${VERSION} - RENAME rl-config.cmake COMPONENT development ) From c60172df40193f92df534984cc877af6b3f09fc6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 15 Jul 2020 16:53:31 +0200 Subject: [PATCH 384/546] Update namespaces --- src/rl/xml/Object.h | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/rl/xml/Object.h b/src/rl/xml/Object.h index 466cd8f3..ca6fbdb4 100644 --- a/src/rl/xml/Object.h +++ b/src/rl/xml/Object.h @@ -77,26 +77,26 @@ namespace rl { switch (this->object->type) { - case XPATH_UNDEFINED: + case ::XPATH_UNDEFINED: throw ::std::bad_typeid(); break; - case XPATH_NODESET: + case ::XPATH_NODESET: return typeid(NodeSet); break; - case XPATH_BOOLEAN: + case ::XPATH_BOOLEAN: return typeid(this->object->boolval); break; - case XPATH_NUMBER: + case ::XPATH_NUMBER: return typeid(this->object->floatval); break; - case XPATH_STRING: + case ::XPATH_STRING: return typeid(this->object->stringval); break; - case XPATH_POINT: - case XPATH_RANGE: - case XPATH_LOCATIONSET: - case XPATH_USERS: - case XPATH_XSLT_TREE: + case ::XPATH_POINT: + case ::XPATH_RANGE: + case ::XPATH_LOCATIONSET: + case ::XPATH_USERS: + case ::XPATH_XSLT_TREE: default: throw ::std::bad_typeid(); break; From d9b49632ec867b86a6df56a3d609dc18564d2b2d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 15 Jul 2020 16:54:13 +0200 Subject: [PATCH 385/546] Check for allocated objects --- src/rl/xml/Object.h | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/src/rl/xml/Object.h b/src/rl/xml/Object.h index ca6fbdb4..b0613447 100644 --- a/src/rl/xml/Object.h +++ b/src/rl/xml/Object.h @@ -31,6 +31,7 @@ #include #include #include +#include #include "Node.h" #include "NodeSet.h" @@ -44,12 +45,23 @@ namespace rl public: explicit Object(::xmlXPathObjectPtr object) : object(object, ::xmlXPathFreeNodeSetList), - nodeSet(object->nodesetval, ::xmlXPathFreeNodeSet) + nodeSet(nullptr != object ? object->nodesetval : nullptr, ::xmlXPathFreeNodeSet) { } ~Object() { + if (nullptr != this->object) + { + if (::XPATH_LOCATIONSET == this->object->type && nullptr != this->object->user) + { + ::xmlXPtrFreeLocationSet(static_cast<::xmlLocationSetPtr>(this->object->user)); + } + else if (::XPATH_STRING == this->object->type && nullptr != this->object->stringval) + { + ::xmlFree(this->object->stringval); + } + } } xmlXPathObjectPtr get() const From f5795b763b2fe17d44d22ab2810137a6c3c9649b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 26 Sep 2018 22:55:32 +0200 Subject: [PATCH 386/546] Improve start/stop synchronization and send actual position/velocity values when idle --- src/rl/hal/UniversalRobotsRtde.cpp | 56 +++++++++++++++++++++++------- 1 file changed, 43 insertions(+), 13 deletions(-) diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 2ba71761..50b44c8b 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -396,7 +396,7 @@ namespace rl { ::rl::math::Vector i(this->getDof()); - for (::std::ptrdiff_t j = 0; j < 6; ++j) + for (::std::ptrdiff_t j = 0; j < i.size(); ++j) { i(j) = this->output.actualCurrent[j]; } @@ -416,7 +416,7 @@ namespace rl { ::rl::math::Vector q(this->getDof()); - for (::std::ptrdiff_t i = 0; i < 6; ++i) + for (::std::ptrdiff_t i = 0; i < q.size(); ++i) { q(i) = this->output.actualQ[i]; } @@ -429,7 +429,7 @@ namespace rl { ::rl::math::Vector temperature(this->getDof()); - for (::std::ptrdiff_t i = 0; i < 6; ++i) + for (::std::ptrdiff_t i = 0; i < temperature.size(); ++i) { temperature(i) = this->output.jointTemperatures[i]; } @@ -442,7 +442,7 @@ namespace rl { ::rl::math::Vector qd(this->getDof()); - for (::std::ptrdiff_t i = 0; i < 6; ++i) + for (::std::ptrdiff_t i = 0; i < qd.size(); ++i) { qd(i) = this->output.actualQd[i]; } @@ -743,6 +743,16 @@ namespace rl this->unserialize(ptr, this->output.outputBitRegisters1); this->unserialize(ptr, this->output.outputIntRegister); this->unserialize(ptr, this->output.outputDoubleRegister); + + this->input.inputDoubleRegister.resize(this->getDof() + this->getDof() + 1); + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + this->input.inputDoubleRegister[i] = this->output.actualQ[i]; + this->input.inputDoubleRegister[this->getDof() + i] = this->output.actualQd[i]; + } + + this->input.inputDoubleRegister[this->getDof() + this->getDof()] = 0; break; case COMMAND_GET_URCONTROL_VERSION: this->unserialize(ptr, this->version.major); @@ -1166,16 +1176,23 @@ namespace rl ::std::stringstream program; program << "def robotics_library():" << '\n'; - program << '\t' << "rtde_set_watchdog(\"input_double_register_0\", 1, \"pause\")" << '\n'; - program << '\t' << "while (read_input_integer_register(0)):" << '\n'; - program << '\t' << '\t' << "q = get_actual_joint_positions()" << '\n'; + program << '\t' << "write_output_integer_register(0, 1)" << '\n'; + program << '\t' << "sync()" << '\n'; + program << '\t' << "write_output_integer_register(0, 0)" << '\n'; + program << '\t' << "sync()" << '\n'; + program << '\t' << "q = get_actual_joint_positions()" << '\n'; + program << '\t' << "qd = get_actual_joint_speeds()" << '\n'; +// program << '\t' << "rtde_set_watchdog(\"input_double_register_0\", 1, \"pause\")" << '\n'; + program << '\t' << "while (1 == read_input_integer_register(0)):" << '\n'; +#if 1 program << '\t' << '\t' << "q[0] = read_input_float_register(0)" << '\n'; program << '\t' << '\t' << "q[1] = read_input_float_register(1)" << '\n'; program << '\t' << '\t' << "q[2] = read_input_float_register(2)" << '\n'; program << '\t' << '\t' << "q[3] = read_input_float_register(3)" << '\n'; program << '\t' << '\t' << "q[4] = read_input_float_register(4)" << '\n'; program << '\t' << '\t' << "q[5] = read_input_float_register(5)" << '\n'; - program << '\t' << '\t' << "qd = [ 0, 0, 0, 0, 0, 0]" << '\n'; + program << '\t' << '\t' << "servoj(q, 0, 0, " << ::std::chrono::duration_cast<::std::chrono::duration>(this->getUpdateRate()).count() << ", 0.03, 2000)" << '\n'; +#else program << '\t' << '\t' << "qd[0] = read_input_float_register(6)" << '\n'; program << '\t' << '\t' << "qd[1] = read_input_float_register(7)" << '\n'; program << '\t' << '\t' << "qd[2] = read_input_float_register(8)" << '\n'; @@ -1183,15 +1200,22 @@ namespace rl program << '\t' << '\t' << "qd[4] = read_input_float_register(10)" << '\n'; program << '\t' << '\t' << "qd[5] = read_input_float_register(11)" << '\n'; program << '\t' << '\t' << "qdd = read_input_float_register(12)" << '\n'; -#if 1 - program << '\t' << '\t' << "servoj(q, 0, 0, " << ::std::chrono::duration_cast<::std::chrono::duration>(this->getUpdateRate()).count() << ", 0.03, 2000)" << '\n'; -#else program << '\t' << '\t' << "speedj(qd, qdd, " << ::std::chrono::duration_cast<::std::chrono::duration>(this->getUpdateRate()).count() << ")" << '\n'; #endif program << '\t' << "end" << '\n'; + program << '\t' << "write_output_integer_register(0, 1)" << '\n'; + program << '\t' << "sync()" << '\n'; + program << '\t' << "write_output_integer_register(0, 0)" << '\n'; + program << '\t' << "sync()" << '\n'; program << "end" << '\n'; this->socket2.send(program.str().c_str(), program.str().size()); + do + { + this->recv(); + } + while (1 != this->output.outputIntRegister[0]); + this->setRunning(true); } @@ -1218,8 +1242,6 @@ namespace rl this->sendBitRegisters(); } - this->recv(); - this->input.configurableDigitalOutput.reset(); this->input.configurableDigitalOutputMask.reset(); this->input.inputBitRegisters0.reset(); @@ -1231,6 +1253,8 @@ namespace rl this->input.standardAnalogOutputMask.reset(); this->input.standardDigitalOutput.reset(); this->input.standardDigitalOutputMask.reset(); + + this->recv(); } void @@ -1240,6 +1264,12 @@ namespace rl this->sendIntegerRegister(); this->input.inputIntRegister.clear(); + do + { + this->recv(); + } + while (1 != this->output.outputIntRegister[0]); + this->send(COMMAND_CONTROL_PACKAGE_PAUSE); this->recv(); From 516d10bbee6c61d174d99c34dc2801609de1a918 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 28 Sep 2018 20:21:32 +0200 Subject: [PATCH 387/546] Minor fix --- src/rl/hal/UniversalRobotsRtde.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 50b44c8b..a4295843 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -1182,7 +1182,7 @@ namespace rl program << '\t' << "sync()" << '\n'; program << '\t' << "q = get_actual_joint_positions()" << '\n'; program << '\t' << "qd = get_actual_joint_speeds()" << '\n'; -// program << '\t' << "rtde_set_watchdog(\"input_double_register_0\", 1, \"pause\")" << '\n'; + program << '\t' << "rtde_set_watchdog(\"input_double_register_0\", 1, \"pause\")" << '\n'; program << '\t' << "while (1 == read_input_integer_register(0)):" << '\n'; #if 1 program << '\t' << '\t' << "q[0] = read_input_float_register(0)" << '\n'; From 49bb679ca1aa1d4565f7269c1b7c5fe52bdd04b8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 4 Oct 2018 19:48:06 +0200 Subject: [PATCH 388/546] Throw exception for safety modes in rl::hal::UniversalRobotsRtde --- src/rl/hal/UniversalRobotsRtde.cpp | 30 ++++++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index a4295843..851bcd67 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -753,6 +753,36 @@ namespace rl } this->input.inputDoubleRegister[this->getDof() + this->getDof()] = 0; + + switch (this->getSafetyMode()) + { + case SAFETY_MODE_NORMAL: + break; + case SAFETY_MODE_REDUCED: + break; + case SAFETY_MODE_PROTECTIVE_STOP: + throw DeviceException("Protective stop"); + break; + case SAFETY_MODE_RECOVERY: + break; + case SAFETY_MODE_SAFEGUARD_STOP: + throw DeviceException("Safeguard stop"); + break; + case SAFETY_MODE_SYSTEM_EMERGENCY_STOP: + throw DeviceException("System emergency stop"); + break; + case SAFETY_MODE_ROBOT_EMERGENCY_STOP: + throw DeviceException("Robot emergency stop"); + break; + case SAFETY_MODE_VIOLATION: + throw DeviceException("Mode violation"); + break; + case SAFETY_MODE_FAULT: + throw DeviceException("Fault"); + break; + default: + break; + } break; case COMMAND_GET_URCONTROL_VERSION: this->unserialize(ptr, this->version.major); From da3aeee98385daea439d98612d486326e414c05a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 4 Oct 2018 19:48:39 +0200 Subject: [PATCH 389/546] Modify start and stop synchronization in rl::hal::UniversalRobotsRtde --- src/rl/hal/UniversalRobotsRtde.cpp | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 851bcd67..7ffde71b 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -1206,10 +1206,6 @@ namespace rl ::std::stringstream program; program << "def robotics_library():" << '\n'; - program << '\t' << "write_output_integer_register(0, 1)" << '\n'; - program << '\t' << "sync()" << '\n'; - program << '\t' << "write_output_integer_register(0, 0)" << '\n'; - program << '\t' << "sync()" << '\n'; program << '\t' << "q = get_actual_joint_positions()" << '\n'; program << '\t' << "qd = get_actual_joint_speeds()" << '\n'; program << '\t' << "rtde_set_watchdog(\"input_double_register_0\", 1, \"pause\")" << '\n'; @@ -1233,10 +1229,6 @@ namespace rl program << '\t' << '\t' << "speedj(qd, qdd, " << ::std::chrono::duration_cast<::std::chrono::duration>(this->getUpdateRate()).count() << ")" << '\n'; #endif program << '\t' << "end" << '\n'; - program << '\t' << "write_output_integer_register(0, 1)" << '\n'; - program << '\t' << "sync()" << '\n'; - program << '\t' << "write_output_integer_register(0, 0)" << '\n'; - program << '\t' << "sync()" << '\n'; program << "end" << '\n'; this->socket2.send(program.str().c_str(), program.str().size()); @@ -1244,7 +1236,7 @@ namespace rl { this->recv(); } - while (1 != this->output.outputIntRegister[0]); + while (ROBOT_MODE_RUNNING != this->getRobotMode() || RUNTIME_STATE_PLAYING != this->getRuntimeState()); this->setRunning(true); } @@ -1298,7 +1290,7 @@ namespace rl { this->recv(); } - while (1 != this->output.outputIntRegister[0]); + while (RUNTIME_STATE_STOPPED != this->getRuntimeState()); this->send(COMMAND_CONTROL_PACKAGE_PAUSE); this->recv(); From 04d6914de1016e95e8154150c73f0c123fc57e24 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 4 Oct 2018 19:49:11 +0200 Subject: [PATCH 390/546] Use target values instead of actual values in rl::hal::UniversalRobotsRtde --- src/rl/hal/UniversalRobotsRtde.cpp | 22 +++++++++++++++++----- src/rl/hal/UniversalRobotsRtde.h | 12 ++++++++++++ 2 files changed, 29 insertions(+), 5 deletions(-) diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 7ffde71b..197c34ea 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -398,7 +398,7 @@ namespace rl for (::std::ptrdiff_t j = 0; j < i.size(); ++j) { - i(j) = this->output.actualCurrent[j]; + i(j) = this->output.targetCurrent[j]; } return i; @@ -418,7 +418,7 @@ namespace rl for (::std::ptrdiff_t i = 0; i < q.size(); ++i) { - q(i) = this->output.actualQ[i]; + q(i) = this->output.targetQ[i]; } return q; @@ -444,7 +444,7 @@ namespace rl for (::std::ptrdiff_t i = 0; i < qd.size(); ++i) { - qd(i) = this->output.actualQd[i]; + qd(i) = this->output.targetQd[i]; } return qd; @@ -498,6 +498,12 @@ namespace rl this->recv(); static const ::std::string outputsArray[] = { + "timestamp", + "target_q", + "target_qd", + "target_qdd", + "target_current", + "target_moment", "actual_q", "actual_qd", "actual_current", @@ -711,6 +717,12 @@ namespace rl break; case COMMAND_DATA_PACKAGE: + this->unserialize(ptr, this->output.timestamp); + this->unserialize(ptr, this->output.targetQ); + this->unserialize(ptr, this->output.targetQd); + this->unserialize(ptr, this->output.targetQdd); + this->unserialize(ptr, this->output.targetCurrent); + this->unserialize(ptr, this->output.targetMoment); this->unserialize(ptr, this->output.actualQ); this->unserialize(ptr, this->output.actualQd); this->unserialize(ptr, this->output.actualCurrent); @@ -748,8 +760,8 @@ namespace rl for (::std::size_t i = 0; i < this->getDof(); ++i) { - this->input.inputDoubleRegister[i] = this->output.actualQ[i]; - this->input.inputDoubleRegister[this->getDof() + i] = this->output.actualQd[i]; + this->input.inputDoubleRegister[i] = this->output.targetQ[i]; + this->input.inputDoubleRegister[this->getDof() + i] = this->output.targetQd[i]; } this->input.inputDoubleRegister[this->getDof() + this->getDof()] = 0; diff --git a/src/rl/hal/UniversalRobotsRtde.h b/src/rl/hal/UniversalRobotsRtde.h index b3fff278..fe45c4c7 100644 --- a/src/rl/hal/UniversalRobotsRtde.h +++ b/src/rl/hal/UniversalRobotsRtde.h @@ -349,10 +349,22 @@ namespace rl double standardAnalogOutput1; + double targetCurrent[6]; + + double targetMoment[6]; + + double targetQ[6]; + + double targetQd[6]; + + double targetQdd[6]; + double targetTcpPose[6]; double targetTcpSpeed[6]; + double timestamp; + double toolAnalogInput0; double toolAnalogInput1; From f3828a0dbac370179cad0b413394b66dde10406a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Jun 2020 22:15:07 +0200 Subject: [PATCH 391/546] Fix namespaces --- src/rl/hal/Ati.cpp | 2 +- src/rl/hal/Dc1394Camera.cpp | 2 +- src/rl/hal/UniversalRobotsRtde.cpp | 4 +- src/rl/kin/Kinematics.cpp | 2 +- src/rl/mdl/JacobianInverseKinematics.cpp | 2 +- src/rl/mdl/XmlFactory.cpp | 6 +- src/rl/sg/UrdfFactory.cpp | 2 +- src/rl/sg/XmlFactory.cpp | 4 +- src/rl/sg/bullet/Scene.cpp | 6 +- src/rl/sg/bullet/Shape.cpp | 2 +- src/rl/sg/fcl/Body.cpp | 2 +- src/rl/sg/fcl/Body.h | 2 +- src/rl/sg/fcl/Shape.cpp | 28 +++---- src/rl/sg/fcl/Shape.h | 4 +- src/rl/sg/ode/Shape.cpp | 6 +- src/rl/sg/pqp/Scene.cpp | 6 +- src/rl/sg/pqp/Shape.cpp | 10 +-- src/rl/sg/pqp/Shape.h | 6 +- src/rl/sg/solid/Body.cpp | 2 +- src/rl/sg/solid/Body.h | 2 +- src/rl/sg/solid/Scene.cpp | 94 +++++++++++------------ src/rl/sg/solid/Scene.h | 4 +- src/rl/sg/solid/Shape.cpp | 98 ++++++++++++------------ src/rl/sg/solid/Shape.h | 18 ++--- 24 files changed, 157 insertions(+), 157 deletions(-) diff --git a/src/rl/hal/Ati.cpp b/src/rl/hal/Ati.cpp index 29c89d81..4dc89385 100644 --- a/src/rl/hal/Ati.cpp +++ b/src/rl/hal/Ati.cpp @@ -187,7 +187,7 @@ namespace rl void Ati::resetBias() { - std::array voltages; + ::std::array voltages; voltages.fill(0.0f); Bias(this->cal, voltages.data()); } diff --git a/src/rl/hal/Dc1394Camera.cpp b/src/rl/hal/Dc1394Camera.cpp index dfb1fba5..fa5246bc 100644 --- a/src/rl/hal/Dc1394Camera.cpp +++ b/src/rl/hal/Dc1394Camera.cpp @@ -479,7 +479,7 @@ namespace rl } return ::std::chrono::duration_cast<::std::chrono::nanoseconds>( - ::std::chrono::duration(1.0 / framerate * rl::math::UNIT2NANO) + ::std::chrono::duration(1.0 / framerate * ::rl::math::UNIT2NANO) ); } diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 197c34ea..af72618f 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -1229,7 +1229,7 @@ namespace rl program << '\t' << '\t' << "q[3] = read_input_float_register(3)" << '\n'; program << '\t' << '\t' << "q[4] = read_input_float_register(4)" << '\n'; program << '\t' << '\t' << "q[5] = read_input_float_register(5)" << '\n'; - program << '\t' << '\t' << "servoj(q, 0, 0, " << ::std::chrono::duration_cast<::std::chrono::duration>(this->getUpdateRate()).count() << ", 0.03, 2000)" << '\n'; + program << '\t' << '\t' << "servoj(q, 0, 0, " << ::std::chrono::duration_cast<::std::chrono::duration<::rl::math::Real>>(this->getUpdateRate()).count() << ", 0.03, 2000)" << '\n'; #else program << '\t' << '\t' << "qd[0] = read_input_float_register(6)" << '\n'; program << '\t' << '\t' << "qd[1] = read_input_float_register(7)" << '\n'; @@ -1238,7 +1238,7 @@ namespace rl program << '\t' << '\t' << "qd[4] = read_input_float_register(10)" << '\n'; program << '\t' << '\t' << "qd[5] = read_input_float_register(11)" << '\n'; program << '\t' << '\t' << "qdd = read_input_float_register(12)" << '\n'; - program << '\t' << '\t' << "speedj(qd, qdd, " << ::std::chrono::duration_cast<::std::chrono::duration>(this->getUpdateRate()).count() << ")" << '\n'; + program << '\t' << '\t' << "speedj(qd, qdd, " << ::std::chrono::duration_cast<::std::chrono::duration<::rl::math::Real>>(this->getUpdateRate()).count() << ")" << '\n'; #endif program << '\t' << "end" << '\n'; program << "end" << '\n'; diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 796e94fe..823cc4db 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -133,7 +133,7 @@ namespace rl { if (document.getRootElement().hasNamespace() && "http://www.w3.org/1999/XSL/Transform" == document.getRootElement().getNamespace().getHref()) { - rl::xml::Stylesheet stylesheet(document); + ::rl::xml::Stylesheet stylesheet(document); document = stylesheet.apply(); } } diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index bb7b99b6..5f57c505 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -44,7 +44,7 @@ namespace rl { } - const math::Real& + const ::rl::math::Real& JacobianInverseKinematics::getDelta() const { return this->delta; diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index 5d8e6d2a..1687926d 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -79,7 +79,7 @@ namespace rl { if (document.getRootElement().hasNamespace() && "http://www.w3.org/1999/XSL/Transform" == document.getRootElement().getNamespace().getHref()) { - rl::xml::Stylesheet stylesheet(document); + ::rl::xml::Stylesheet stylesheet(document); document = stylesheet.apply(); } } @@ -480,7 +480,7 @@ namespace rl for (int l = 0; l < cols.size(); ++l) { - G(k, l) = boost::lexical_cast<::rl::math::Real>(cols[l].getContent().c_str()); + G(k, l) = ::boost::lexical_cast<::rl::math::Real>(cols[l].getContent().c_str()); } } @@ -518,7 +518,7 @@ namespace rl for (int l = 0; l < cols.size(); ++l) { - G(k, l) = boost::lexical_cast<::rl::math::Real>(cols[l].getContent().c_str()); + G(k, l) = ::boost::lexical_cast<::rl::math::Real>(cols[l].getContent().c_str()); } } diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 722e8bef..38ba55e5 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -348,7 +348,7 @@ ::std::cout << "\tmesh filename: " << meshFilename << ::std::endl; if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLIndexedFaceSet::getClassTypeId())) { - SoVRMLIndexedFaceSet* vrmlIndexedFaceSet = static_cast(vrmlShape->geometry.getValue()); + ::SoVRMLIndexedFaceSet* vrmlIndexedFaceSet = static_cast<::SoVRMLIndexedFaceSet*>(vrmlShape->geometry.getValue()); vrmlIndexedFaceSet->convex.setValue(false); } } diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp index 96cce547..dec4771b 100644 --- a/src/rl/sg/XmlFactory.cpp +++ b/src/rl/sg/XmlFactory.cpp @@ -89,7 +89,7 @@ namespace rl throw Exception("rl::sg::XmlFactory::load() - Failed to open file '" + filename + "'"); } - ::SoVRMLGroup* root = SoDB::readAllVRML(&input); + ::SoVRMLGroup* root = ::SoDB::readAllVRML(&input); if (nullptr == root) { @@ -280,7 +280,7 @@ namespace rl } void - XmlFactory::triangleCallback(void* userData, SoCallbackAction* action, const SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const SoPrimitiveVertex* v3) + XmlFactory::triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const ::SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3) { ::std::vector<::rl::math::Vector3>* points = static_cast<::std::vector<::rl::math::Vector3>*>(userData); diff --git a/src/rl/sg/bullet/Scene.cpp b/src/rl/sg/bullet/Scene.cpp index e09f63b9..624a2a8b 100644 --- a/src/rl/sg/bullet/Scene.cpp +++ b/src/rl/sg/bullet/Scene.cpp @@ -77,7 +77,7 @@ namespace rl bool Scene::areColliding(::rl::sg::Shape* first, ::rl::sg::Shape* second) { - throw Exception("::rl::sg::bullet::Scene::areColliding(::rl::sg::Shape* first, ::rl::sg::Shape* second) - not supported"); + throw Exception("rl::sg::bullet::Scene::areColliding(rl::sg::Shape* first, rl::sg::Shape* second) - not supported"); } ::rl::sg::Model* @@ -109,7 +109,7 @@ namespace rl ::rl::math::Real Scene::depth(::rl::sg::Shape* first, ::rl::sg::Shape* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) { - throw Exception("::rl::sg::bullet::Scene::depth(::rl::sg::Shape* first, ::rl::sg::Shape* second, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) - not supported"); + throw Exception("rl::sg::bullet::Scene::depth(rl::sg::Shape* first, rl::sg::Shape* second, rl::math::Vector3& point1, rl::math::Vector3& point2) - not supported"); } ::rl::math::Real @@ -120,7 +120,7 @@ namespace rl if (!shape1->shape->isConvex() || !shape2->shape->isConvex()) { - throw Exception("::rl::sg::bullet::Scene::distance() - distance calculation only supported between convex shapes"); + throw Exception("rl::sg::bullet::Scene::distance() - distance calculation only supported between convex shapes"); } Body* body1 = static_cast(shape1->getBody()); diff --git a/src/rl/sg/bullet/Shape.cpp b/src/rl/sg/bullet/Shape.cpp index 41bcf9d7..b6f91ae4 100644 --- a/src/rl/sg/bullet/Shape.cpp +++ b/src/rl/sg/bullet/Shape.cpp @@ -109,7 +109,7 @@ namespace rl } else { - throw Exception("::rl::sg::bullet::Shape() - geometry not supported"); + throw Exception("rl::sg::bullet::Shape() - geometry not supported"); } this->getBody()->add(this); diff --git a/src/rl/sg/fcl/Body.cpp b/src/rl/sg/fcl/Body.cpp index 6e502404..0f390d2c 100644 --- a/src/rl/sg/fcl/Body.cpp +++ b/src/rl/sg/fcl/Body.cpp @@ -65,7 +65,7 @@ namespace rl } ::rl::sg::Shape* - Body::create(SoVRMLShape* shape) + Body::create(::SoVRMLShape* shape) { return new Shape(shape, this); } diff --git a/src/rl/sg/fcl/Body.h b/src/rl/sg/fcl/Body.h index 8353e77e..7897e23d 100644 --- a/src/rl/sg/fcl/Body.h +++ b/src/rl/sg/fcl/Body.h @@ -60,7 +60,7 @@ namespace rl void add(::rl::sg::Shape* shape); - ::rl::sg::Shape* create(SoVRMLShape* shape); + ::rl::sg::Shape* create(::SoVRMLShape* shape); void getFrame(::rl::math::Transform& frame); diff --git a/src/rl/sg/fcl/Shape.cpp b/src/rl/sg/fcl/Shape.cpp index 11096e48..826957c6 100644 --- a/src/rl/sg/fcl/Shape.cpp +++ b/src/rl/sg/fcl/Shape.cpp @@ -71,7 +71,7 @@ namespace rl typedef ::fcl::Transform3<::rl::math::Real> Transform3; #endif - Shape::Shape(SoVRMLShape* shape, ::rl::sg::Body* body) : + Shape::Shape(::SoVRMLShape* shape, ::rl::sg::Body* body) : ::rl::sg::Shape(body), base(::rl::math::Transform::Identity()), #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 6 @@ -88,20 +88,20 @@ namespace rl transform(::rl::math::Transform::Identity()), vertices() { - SoVRMLGeometry* vrmlGeometry = static_cast(shape->geometry.getValue()); + ::SoVRMLGeometry* vrmlGeometry = static_cast<::SoVRMLGeometry*>(shape->geometry.getValue()); - if (vrmlGeometry->isOfType(SoVRMLBox::getClassTypeId())) + if (vrmlGeometry->isOfType(::SoVRMLBox::getClassTypeId())) { - SoVRMLBox* box = static_cast(vrmlGeometry); + ::SoVRMLBox* box = static_cast<::SoVRMLBox*>(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 this->geometry = ::boost::make_shared(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); #else this->geometry = ::std::make_shared(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); #endif } - else if (vrmlGeometry->isOfType(SoVRMLCone::getClassTypeId())) + else if (vrmlGeometry->isOfType(::SoVRMLCone::getClassTypeId())) { - SoVRMLCone* cone = static_cast(vrmlGeometry); + ::SoVRMLCone* cone = static_cast<::SoVRMLCone*>(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 this->geometry = ::boost::make_shared(cone->bottomRadius.getValue(), cone->height.getValue()); #else @@ -125,9 +125,9 @@ namespace rl this->base(3, 2) = 0; this->base(3, 3) = 1; } - else if (vrmlGeometry->isOfType(SoVRMLCylinder::getClassTypeId())) + else if (vrmlGeometry->isOfType(::SoVRMLCylinder::getClassTypeId())) { - SoVRMLCylinder* cylinder = static_cast(vrmlGeometry); + ::SoVRMLCylinder* cylinder = static_cast<::SoVRMLCylinder*>(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 this->geometry = ::boost::make_shared(cylinder->radius.getValue(), cylinder->height.getValue()); #else @@ -151,11 +151,11 @@ namespace rl this->base(3, 2) = 0; this->base(3, 3) = 1; } - else if (vrmlGeometry->isOfType(SoVRMLIndexedFaceSet::getClassTypeId())) + else if (vrmlGeometry->isOfType(::SoVRMLIndexedFaceSet::getClassTypeId())) { - SoVRMLIndexedFaceSet* indexedFaceSet = static_cast(vrmlGeometry); + ::SoVRMLIndexedFaceSet* indexedFaceSet = static_cast<::SoVRMLIndexedFaceSet*>(vrmlGeometry); - SoCallbackAction callbackAction; + ::SoCallbackAction callbackAction; callbackAction.addTriangleCallback(vrmlGeometry->getTypeId(), Shape::triangleCallback, this); callbackAction.apply(vrmlGeometry); @@ -223,9 +223,9 @@ namespace rl this->geometry = mesh; } } - else if (vrmlGeometry->isOfType(SoVRMLSphere::getClassTypeId())) + else if (vrmlGeometry->isOfType(::SoVRMLSphere::getClassTypeId())) { - SoVRMLSphere* sphere = static_cast(vrmlGeometry); + ::SoVRMLSphere* sphere = static_cast<::SoVRMLSphere*>(vrmlGeometry); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 this->geometry = ::boost::make_shared(sphere->radius.getValue()); #else @@ -291,7 +291,7 @@ namespace rl } void - Shape::triangleCallback(void* userData, SoCallbackAction* action, const SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const SoPrimitiveVertex* v3) + Shape::triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const ::SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3) { Shape* shape = static_cast(userData); diff --git a/src/rl/sg/fcl/Shape.h b/src/rl/sg/fcl/Shape.h index b127f8c1..79eff8fd 100644 --- a/src/rl/sg/fcl/Shape.h +++ b/src/rl/sg/fcl/Shape.h @@ -61,7 +61,7 @@ namespace rl class RL_SG_EXPORT Shape : public ::rl::sg::Shape { public: - Shape(SoVRMLShape* shape, ::rl::sg::Body* body); + Shape(::SoVRMLShape* shape, ::rl::sg::Body* body); #if FCL_MAJOR_VERSION < 1 && FCL_MINOR_VERSION < 5 Shape(const ::boost::shared_ptr& geometry, ::rl::sg::Body* body); @@ -82,7 +82,7 @@ namespace rl protected: private: - static void triangleCallback(void* userData, SoCallbackAction* action, const SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const SoPrimitiveVertex* v3); + static void triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const ::SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3); ::rl::math::Transform base; diff --git a/src/rl/sg/ode/Shape.cpp b/src/rl/sg/ode/Shape.cpp index 43bba495..f028cf0f 100644 --- a/src/rl/sg/ode/Shape.cpp +++ b/src/rl/sg/ode/Shape.cpp @@ -62,7 +62,7 @@ namespace rl } else if (geometry->isOfType(::SoVRMLCone::getClassTypeId())) { - throw Exception("::rl::sg::ode::Shape - SoVRMLCone not supported"); + throw Exception("rl::sg::ode::Shape - SoVRMLCone not supported"); } else if (geometry->isOfType(::SoVRMLCylinder::getClassTypeId())) { @@ -103,7 +103,7 @@ namespace rl } else { - throw Exception("::rl::sg::ode::Shape() - geometry not supported"); + throw Exception("rl::sg::ode::Shape() - geometry not supported"); } if (nullptr != this->geom) @@ -130,7 +130,7 @@ namespace rl } void - Shape::triangleCallback(void* userData, SoCallbackAction* action, const SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const SoPrimitiveVertex* v3) + Shape::triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const ::SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3) { Shape* shape = static_cast(userData); diff --git a/src/rl/sg/pqp/Scene.cpp b/src/rl/sg/pqp/Scene.cpp index 80a661a3..f8f3547e 100644 --- a/src/rl/sg/pqp/Scene.cpp +++ b/src/rl/sg/pqp/Scene.cpp @@ -65,7 +65,7 @@ namespace rl shape2->rotation, shape2->translation, &shape2->model, - PQP_FIRST_CONTACT + ::PQP_FIRST_CONTACT ); return (result.Colliding() == 1 ? true : false); @@ -124,13 +124,13 @@ namespace rl model.AddTri(&p[0], &p[0], &p[0], 0); model.EndModel(); - PQP_REAL rotation[3][3] = { + ::PQP_REAL rotation[3][3] = { {1, 0, 0}, {0, 1, 0}, {0, 0, 1} }; - PQP_REAL translation[3] = {point(0), point(1), point(2)}; + ::PQP_REAL translation[3] = {point(0), point(1), point(2)}; ::PQP_DistanceResult result; diff --git a/src/rl/sg/pqp/Shape.cpp b/src/rl/sg/pqp/Shape.cpp index 8f7365d5..92738d27 100644 --- a/src/rl/sg/pqp/Shape.cpp +++ b/src/rl/sg/pqp/Shape.cpp @@ -53,13 +53,13 @@ namespace rl { for (::std::size_t j = 0; j < 3; ++j) { - this->rotation[i][j] = static_cast(this->frame(i, j)); + this->rotation[i][j] = static_cast<::PQP_REAL>(this->frame(i, j)); } } for (::std::size_t i = 0; i < 3; ++i) { - this->translation[i] = static_cast(this->frame(i, 3)); + this->translation[i] = static_cast<::PQP_REAL>(this->frame(i, 3)); } ::SoVRMLGeometry* geometry = static_cast<::SoVRMLGeometry*>(shape->geometry.getValue()); @@ -108,7 +108,7 @@ namespace rl void Shape::triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const ::SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3) { - PQP_REAL p[3][3] = { + ::PQP_REAL p[3][3] = { {v1->getPoint()[0], v1->getPoint()[1], v1->getPoint()[2]}, {v2->getPoint()[0], v2->getPoint()[1], v2->getPoint()[2]}, {v3->getPoint()[0], v3->getPoint()[1], v3->getPoint()[2]} @@ -130,13 +130,13 @@ namespace rl { for (::std::size_t j = 0; j < 3; ++j) { - this->rotation[i][j] = static_cast(this->frame(i, j)); + this->rotation[i][j] = static_cast<::PQP_REAL>(this->frame(i, j)); } } for (::std::size_t i = 0; i < 3; ++i) { - this->translation[i] = static_cast(this->frame(i, 3)); + this->translation[i] = static_cast<::PQP_REAL>(this->frame(i, 3)); } } } diff --git a/src/rl/sg/pqp/Shape.h b/src/rl/sg/pqp/Shape.h index 6c7e9e82..547fe956 100644 --- a/src/rl/sg/pqp/Shape.h +++ b/src/rl/sg/pqp/Shape.h @@ -61,16 +61,16 @@ namespace rl ::PQP_Model model; - PQP_REAL rotation[3][3]; + ::PQP_REAL rotation[3][3]; - PQP_REAL translation[3]; + ::PQP_REAL translation[3]; protected: private: typedef ::std::pair<::PQP_Model*, ::std::size_t> Model; - static void triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3); + static void triangleCallback(void* userData, ::SoCallbackAction* action, const ::SoPrimitiveVertex* v1, const ::SoPrimitiveVertex* v2, const ::SoPrimitiveVertex* v3); ::rl::math::Transform frame; diff --git a/src/rl/sg/solid/Body.cpp b/src/rl/sg/solid/Body.cpp index 185a01e9..31e1a541 100644 --- a/src/rl/sg/solid/Body.cpp +++ b/src/rl/sg/solid/Body.cpp @@ -52,7 +52,7 @@ namespace rl } ::rl::sg::Shape* - Body::create(SoVRMLShape* shape) + Body::create(::SoVRMLShape* shape) { return new Shape(shape, this); } diff --git a/src/rl/sg/solid/Body.h b/src/rl/sg/solid/Body.h index 46480660..4d8440f7 100644 --- a/src/rl/sg/solid/Body.h +++ b/src/rl/sg/solid/Body.h @@ -46,7 +46,7 @@ namespace rl virtual ~Body(); - ::rl::sg::Shape* create(SoVRMLShape* shape); + ::rl::sg::Shape* create(::SoVRMLShape* shape); void getFrame(::rl::math::Transform& frame); diff --git a/src/rl/sg/solid/Scene.cpp b/src/rl/sg/solid/Scene.cpp index 8c185c82..4dc8c89b 100644 --- a/src/rl/sg/solid/Scene.cpp +++ b/src/rl/sg/solid/Scene.cpp @@ -43,7 +43,7 @@ namespace rl ::rl::sg::DistanceScene(), ::rl::sg::RaycastScene(), ::rl::sg::SimpleScene(), - scene(DT_CreateScene()) + scene(::DT_CreateScene()) { this->broad = BP_CreateScene(this, Scene::beginOverlap, Scene::endOverlap); } @@ -62,7 +62,7 @@ namespace rl if (nullptr != this->scene) { - DT_DestroyScene(this->scene); + ::DT_DestroyScene(this->scene); } } @@ -74,9 +74,9 @@ namespace rl if (shape1->encounters.find(shape2) != shape1->encounters.end() || shape2->encounters.find(shape1) != shape2->encounters.end()) { - DT_Vector3 point; + ::DT_Vector3 point; - return (DT_TRUE == DT_GetCommonPoint( + return (DT_TRUE == ::DT_GetCommonPoint( shape1->complex ? shape1->object : shape2->object, shape1->complex ? shape2->object : shape1->object, point @@ -110,10 +110,10 @@ namespace rl Shape* shape1 = static_cast(first); Shape* shape2 = static_cast(second); - DT_Vector3 vector1; - DT_Vector3 vector2; + ::DT_Vector3 vector1; + ::DT_Vector3 vector2; - DT_Bool intersect = DT_GetPenDepth( + ::DT_Bool intersect = ::DT_GetPenDepth( shape1->complex ? shape1->object : shape2->object, shape1->complex ? shape2->object : shape1->object, shape1->complex ? vector1 : vector2, @@ -137,10 +137,10 @@ namespace rl Shape* shape1 = static_cast(first); Shape* shape2 = static_cast(second); - DT_Vector3 vector1; - DT_Vector3 vector2; + ::DT_Vector3 vector1; + ::DT_Vector3 vector2; - DT_Scalar distance = DT_GetClosestPair( + ::DT_Scalar distance = ::DT_GetClosestPair( shape1->complex ? shape1->object : shape2->object, shape1->complex ? shape2->object : shape1->object, shape1->complex ? vector1 : vector2, @@ -161,19 +161,19 @@ namespace rl ::rl::math::Real Scene::distance(::rl::sg::Shape* shape, const ::rl::math::Vector3& point, ::rl::math::Vector3& point1, ::rl::math::Vector3& point2) { - DT_Vector3 position = { - static_cast(point(0)), - static_cast(point(1)), - static_cast(point(2)) + ::DT_Vector3 position = { + static_cast<::DT_Scalar>(point(0)), + static_cast<::DT_Scalar>(point(1)), + static_cast<::DT_Scalar>(point(2)) }; - DT_ShapeHandle shapeHandle = DT_NewPoint(position); - DT_ObjectHandle objectHandle = DT_CreateObject(nullptr, shapeHandle); + ::DT_ShapeHandle shapeHandle = ::DT_NewPoint(position); + ::DT_ObjectHandle objectHandle = ::DT_CreateObject(nullptr, shapeHandle); - DT_Vector3 vector1; - DT_Vector3 vector2; + ::DT_Vector3 vector1; + ::DT_Vector3 vector2; - DT_Scalar distance = DT_GetClosestPair( + ::DT_Scalar distance = ::DT_GetClosestPair( static_cast(shape)->object, objectHandle, vector1, @@ -188,8 +188,8 @@ namespace rl point2(1) = vector2[1]; point2(2) = vector2[2]; - DT_DestroyObject(objectHandle); - DT_DeleteShape(shapeHandle); + ::DT_DestroyObject(objectHandle); + ::DT_DeleteShape(shapeHandle); return distance; } @@ -207,30 +207,30 @@ namespace rl ::rl::sg::Shape* Scene::raycast(const ::rl::math::Vector3& source, const ::rl::math::Vector3& target, ::rl::math::Real& distance) { - DT_Vector3 vector1; - vector1[0] = static_cast(source(0)); - vector1[1] = static_cast(source(1)); - vector1[2] = static_cast(source(2)); + ::DT_Vector3 vector1; + vector1[0] = static_cast<::DT_Scalar>(source(0)); + vector1[1] = static_cast<::DT_Scalar>(source(1)); + vector1[2] = static_cast<::DT_Scalar>(source(2)); - DT_Vector3 vector2; - vector2[0] = static_cast(target(0)); - vector2[1] = static_cast(target(1)); - vector2[2] = static_cast(target(2)); + ::DT_Vector3 vector2; + vector2[0] = static_cast<::DT_Scalar>(target(0)); + vector2[1] = static_cast<::DT_Scalar>(target(1)); + vector2[2] = static_cast<::DT_Scalar>(target(2)); - DT_Scalar param; - DT_Vector3 normal; + ::DT_Scalar param; + ::DT_Vector3 normal; - void* object = DT_RayCast( + void* object = ::DT_RayCast( this->scene, nullptr, vector1, vector2, - ::std::numeric_limits::max(), + ::std::numeric_limits<::DT_Scalar>::max(), ¶m, normal ); - DT_Vector3 hit; + ::DT_Vector3 hit; hit[0] = vector1[0] + (vector2[0] - vector1[0]) * param; hit[1] = vector1[1] + (vector2[1] - vector1[1]) * param; hit[2] = vector1[2] + (vector2[2] - vector1[2]) * param; @@ -243,29 +243,29 @@ namespace rl bool Scene::raycast(::rl::sg::Shape* shape, const ::rl::math::Vector3& source, const ::rl::math::Vector3& target, ::rl::math::Real& distance) { - DT_Vector3 vector1; - vector1[0] = static_cast(source(0)); - vector1[1] = static_cast(source(1)); - vector1[2] = static_cast(source(2)); + ::DT_Vector3 vector1; + vector1[0] = static_cast<::DT_Scalar>(source(0)); + vector1[1] = static_cast<::DT_Scalar>(source(1)); + vector1[2] = static_cast<::DT_Scalar>(source(2)); - DT_Vector3 vector2; - vector2[0] = static_cast(target(0)); - vector2[1] = static_cast(target(1)); - vector2[2] = static_cast(target(2)); + ::DT_Vector3 vector2; + vector2[0] = static_cast<::DT_Scalar>(target(0)); + vector2[1] = static_cast<::DT_Scalar>(target(1)); + vector2[2] = static_cast<::DT_Scalar>(target(2)); - DT_Scalar param; - DT_Vector3 normal; + ::DT_Scalar param; + ::DT_Vector3 normal; - DT_Bool object = DT_ObjectRayCast( + ::DT_Bool object = ::DT_ObjectRayCast( static_cast(shape)->object, vector1, vector2, - ::std::numeric_limits::max(), + ::std::numeric_limits<::DT_Scalar>::max(), ¶m, normal ); - DT_Vector3 hit; + ::DT_Vector3 hit; hit[0] = vector1[0] + (vector2[0] - vector1[0]) * param; hit[1] = vector1[1] + (vector2[1] - vector1[1]) * param; hit[2] = vector1[2] + (vector2[2] - vector1[2]) * param; diff --git a/src/rl/sg/solid/Scene.h b/src/rl/sg/solid/Scene.h index 675e87e4..51c3a575 100644 --- a/src/rl/sg/solid/Scene.h +++ b/src/rl/sg/solid/Scene.h @@ -77,9 +77,9 @@ namespace rl void setMargin(const ::rl::math::Real& margin); - BP_SceneHandle broad; + ::BP_SceneHandle broad; - DT_SceneHandle scene; + ::DT_SceneHandle scene; protected: diff --git a/src/rl/sg/solid/Shape.cpp b/src/rl/sg/solid/Shape.cpp index 55783968..15aee0a1 100644 --- a/src/rl/sg/solid/Shape.cpp +++ b/src/rl/sg/solid/Shape.cpp @@ -44,7 +44,7 @@ namespace rl { namespace solid { - Shape::Shape(SoVRMLShape* shape, Body* body) : + Shape::Shape(::SoVRMLShape* shape, Body* body) : ::rl::sg::Shape(body), complex(false), encounters(), @@ -56,11 +56,11 @@ namespace rl shape(Shape::create(shape)), transform(::rl::math::Transform::Identity()) { - this->object = DT_CreateObject(this, this->shape); - DT_AddObject(dynamic_cast(this->getBody()->getModel()->getScene())->scene, this->object); + this->object = ::DT_CreateObject(this, this->shape); + ::DT_AddObject(dynamic_cast(this->getBody()->getModel()->getScene())->scene, this->object); - DT_GetBBox(this->object, this->min, this->max); - this->proxy = BP_CreateProxy(dynamic_cast(this->getBody()->getModel()->getScene())->broad, this, this->min, this->max); + ::DT_GetBBox(this->object, this->min, this->max); + this->proxy = ::BP_CreateProxy(dynamic_cast(this->getBody()->getModel()->getScene())->broad, this, this->min, this->max); this->getBody()->add(this); } @@ -76,75 +76,75 @@ namespace rl if (nullptr != this->proxy) { - BP_DestroyProxy(dynamic_cast(this->getBody()->getModel()->getScene())->broad, this->proxy); + ::BP_DestroyProxy(dynamic_cast(this->getBody()->getModel()->getScene())->broad, this->proxy); } if (nullptr != this->object) { - DT_RemoveObject(dynamic_cast(this->getBody()->getModel()->getScene())->scene, this->object); - DT_DestroyObject(this->object); + ::DT_RemoveObject(dynamic_cast(this->getBody()->getModel()->getScene())->scene, this->object); + ::DT_DestroyObject(this->object); } if (nullptr != this->shape) { - DT_DeleteShape(this->shape); + ::DT_DeleteShape(this->shape); } } - DT_ShapeHandle - Shape::create(SoVRMLShape* shape) + ::DT_ShapeHandle + Shape::create(::SoVRMLShape* shape) { - SoVRMLGeometry* geometry = static_cast(shape->geometry.getValue()); + ::SoVRMLGeometry* geometry = static_cast<::SoVRMLGeometry*>(shape->geometry.getValue()); - if (geometry->isOfType(SoVRMLBox::getClassTypeId())) + if (geometry->isOfType(::SoVRMLBox::getClassTypeId())) { - SoVRMLBox* box = static_cast(geometry); - return DT_NewBox(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); + ::SoVRMLBox* box = static_cast<::SoVRMLBox*>(geometry); + return ::DT_NewBox(box->size.getValue()[0], box->size.getValue()[1], box->size.getValue()[2]); } - else if (geometry->isOfType(SoVRMLCone::getClassTypeId())) + else if (geometry->isOfType(::SoVRMLCone::getClassTypeId())) { - SoVRMLCone* cone = static_cast(geometry); - return DT_NewCone(cone->bottomRadius.getValue(), cone->height.getValue()); + ::SoVRMLCone* cone = static_cast<::SoVRMLCone*>(geometry); + return ::DT_NewCone(cone->bottomRadius.getValue(), cone->height.getValue()); } - else if (geometry->isOfType(SoVRMLCylinder::getClassTypeId())) + else if (geometry->isOfType(::SoVRMLCylinder::getClassTypeId())) { - SoVRMLCylinder* cylinder = static_cast(geometry); - return DT_NewCylinder(cylinder->radius.getValue(), cylinder->height.getValue()); + ::SoVRMLCylinder* cylinder = static_cast<::SoVRMLCylinder*>(geometry); + return ::DT_NewCylinder(cylinder->radius.getValue(), cylinder->height.getValue()); } - else if (geometry->isOfType(SoVRMLIndexedFaceSet::getClassTypeId())) + else if (geometry->isOfType(::SoVRMLIndexedFaceSet::getClassTypeId())) { - SoVRMLIndexedFaceSet* indexedFaceSet = static_cast(geometry); + ::SoVRMLIndexedFaceSet* indexedFaceSet = static_cast<::SoVRMLIndexedFaceSet*>(geometry); if (indexedFaceSet->convex.getValue()) { - return Shape::create(static_cast(indexedFaceSet->coord.getValue())->point); + return Shape::create(static_cast<::SoVRMLCoordinate*>(indexedFaceSet->coord.getValue())->point); } else { this->complex = true; - return Shape::create(static_cast(indexedFaceSet->coord.getValue())->point, indexedFaceSet->coordIndex); + return Shape::create(static_cast<::SoVRMLCoordinate*>(indexedFaceSet->coord.getValue())->point, indexedFaceSet->coordIndex); } } - else if (geometry->isOfType(SoVRMLSphere::getClassTypeId())) + else if (geometry->isOfType(::SoVRMLSphere::getClassTypeId())) { - SoVRMLSphere* sphere = static_cast(geometry); - return DT_NewSphere(sphere->radius.getValue()); + ::SoVRMLSphere* sphere = static_cast<::SoVRMLSphere*>(geometry); + return ::DT_NewSphere(sphere->radius.getValue()); } else { - throw Exception("::rl::sg::solid::Shape::create(SoVRMLShape* shape) - geometry not supported"); + throw Exception("rl::sg::solid::Shape::create(SoVRMLShape* shape) - geometry not supported"); } return nullptr; } - DT_ShapeHandle - Shape::create(const SoMFVec3f& point) + ::DT_ShapeHandle + Shape::create(const ::SoMFVec3f& point) { - DT_ShapeHandle shape = DT_NewPolytope(nullptr); + ::DT_ShapeHandle shape = ::DT_NewPolytope(nullptr); - DT_Vector3 vertex; + ::DT_Vector3 vertex; for (int i = 0; i < point.getNum(); ++i) { @@ -152,35 +152,35 @@ namespace rl vertex[1] = point[i][1]; vertex[2] = point[i][2]; - DT_Vertex(vertex); + ::DT_Vertex(vertex); } - DT_EndPolytope(); + ::DT_EndPolytope(); return shape; } - DT_ShapeHandle - Shape::create(const SoMFVec3f& point, const SoMFInt32& coordIndex) + ::DT_ShapeHandle + Shape::create(const ::SoMFVec3f& point, const ::SoMFInt32& coordIndex) { - DT_ShapeHandle shape = DT_NewComplexShape(nullptr); + ::DT_ShapeHandle shape = ::DT_NewComplexShape(nullptr); - DT_Vector3 vertex; + ::DT_Vector3 vertex; if (coordIndex.getNum() > 0) { - DT_Begin(); + ::DT_Begin(); } for (int i = 0; i < coordIndex.getNum(); ++i) { if (SO_END_FACE_INDEX == coordIndex[i]) { - DT_End(); + ::DT_End(); if (i < coordIndex.getNum() - 1) { - DT_Begin(); + ::DT_Begin(); } } else @@ -189,11 +189,11 @@ namespace rl vertex[1] = point[coordIndex[i]][1]; vertex[2] = point[coordIndex[i]][2]; - DT_Vertex(vertex); + ::DT_Vertex(vertex); } } - DT_EndComplexShape(); + ::DT_EndComplexShape(); return shape; } @@ -201,7 +201,7 @@ namespace rl void Shape::getTransform(::rl::math::Transform& transform) { - DT_GetMatrixd(this->object, this->frame.data()); + ::DT_GetMatrixd(this->object, this->frame.data()); this->transform = static_cast(this->getBody())->frame.inverse() * this->frame; transform = this->transform; @@ -210,7 +210,7 @@ namespace rl void Shape::setMargin(const ::rl::math::Real& margin) { - DT_SetMargin(this->object, static_cast(margin)); + ::DT_SetMargin(this->object, static_cast<::DT_Scalar>(margin)); } void @@ -226,9 +226,9 @@ namespace rl { this->frame = static_cast(this->getBody())->frame * this->transform; - DT_SetMatrixd(this->object, this->frame.data()); - DT_GetBBox(this->object, this->min, this->max); - BP_SetBBox(this->proxy, this->min, this->max); + ::DT_SetMatrixd(this->object, this->frame.data()); + ::DT_GetBBox(this->object, this->min, this->max); + ::BP_SetBBox(this->proxy, this->min, this->max); } } } diff --git a/src/rl/sg/solid/Shape.h b/src/rl/sg/solid/Shape.h index d6e5b44d..716895aa 100644 --- a/src/rl/sg/solid/Shape.h +++ b/src/rl/sg/solid/Shape.h @@ -49,7 +49,7 @@ namespace rl public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW - Shape(SoVRMLShape* shape, Body* body); + Shape(::SoVRMLShape* shape, Body* body); virtual ~Shape(); @@ -65,26 +65,26 @@ namespace rl ::std::unordered_set encounters; - DT_ObjectHandle object; + ::DT_ObjectHandle object; - BP_ProxyHandle proxy; + ::BP_ProxyHandle proxy; protected: private: - DT_ShapeHandle create(SoVRMLShape* shape); + ::DT_ShapeHandle create(::SoVRMLShape* shape); - DT_ShapeHandle create(const SoMFVec3f& point); + ::DT_ShapeHandle create(const ::SoMFVec3f& point); - DT_ShapeHandle create(const SoMFVec3f& point, const SoMFInt32& coordIndex); + ::DT_ShapeHandle create(const ::SoMFVec3f& point, const ::SoMFInt32& coordIndex); ::Eigen::Transform<::rl::math::Real, 3, ::Eigen::Affine, ::Eigen::ColMajor> frame; - DT_Vector3 max; + ::DT_Vector3 max; - DT_Vector3 min; + ::DT_Vector3 min; - DT_ShapeHandle shape; + ::DT_ShapeHandle shape; ::rl::math::Transform transform; }; From 9ae4c95281edac9ca42de7a0a5f2bbd47c550bf1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 28 Jun 2020 22:15:28 +0200 Subject: [PATCH 392/546] Add exception for unsupported geometries --- src/rl/sg/fcl/Shape.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/rl/sg/fcl/Shape.cpp b/src/rl/sg/fcl/Shape.cpp index 826957c6..9f5f3a59 100644 --- a/src/rl/sg/fcl/Shape.cpp +++ b/src/rl/sg/fcl/Shape.cpp @@ -44,6 +44,7 @@ #include #endif +#include "../Exception.h" #include "Body.h" #include "Shape.h" @@ -232,6 +233,10 @@ namespace rl this->geometry = ::std::make_shared(sphere->radius.getValue()); #endif } + else + { + throw Exception("rl::sg::fcl::Shape::() - geometry not supported"); + } this->object = ::std::make_shared(this->geometry, Transform3()); From 11f17dd0b3b1640033f83cbf1cd7af7c517c050b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 30 Jun 2020 20:06:17 +0200 Subject: [PATCH 393/546] Update frame and transform getters --- demos/rlCollisionDemo/BodyModel.cpp | 6 ++---- src/rl/sg/Body.cpp | 6 ++++++ src/rl/sg/Body.h | 6 ++++-- src/rl/sg/Shape.cpp | 6 ++++++ src/rl/sg/Shape.h | 4 +++- src/rl/sg/bullet/Body.cpp | 8 ++++++-- src/rl/sg/bullet/Body.h | 4 +++- src/rl/sg/bullet/Shape.cpp | 8 ++++++-- src/rl/sg/bullet/Shape.h | 4 +++- src/rl/sg/fcl/Body.cpp | 6 +++--- src/rl/sg/fcl/Body.h | 4 +++- src/rl/sg/fcl/Shape.cpp | 6 +++--- src/rl/sg/fcl/Shape.h | 4 +++- src/rl/sg/ode/Body.cpp | 8 ++++++-- src/rl/sg/ode/Body.h | 4 +++- src/rl/sg/ode/Shape.cpp | 6 +++--- src/rl/sg/ode/Shape.h | 4 +++- src/rl/sg/pqp/Body.cpp | 6 +++--- src/rl/sg/pqp/Body.h | 4 +++- src/rl/sg/pqp/Shape.cpp | 6 +++--- src/rl/sg/pqp/Shape.h | 4 +++- src/rl/sg/so/Body.cpp | 8 ++++++-- src/rl/sg/so/Body.h | 4 +++- src/rl/sg/so/Shape.cpp | 8 ++++++-- src/rl/sg/so/Shape.h | 4 +++- src/rl/sg/solid/Body.cpp | 6 +++--- src/rl/sg/solid/Body.h | 4 +++- src/rl/sg/solid/Shape.cpp | 11 +++++------ src/rl/sg/solid/Shape.h | 4 +++- 29 files changed, 110 insertions(+), 53 deletions(-) diff --git a/demos/rlCollisionDemo/BodyModel.cpp b/demos/rlCollisionDemo/BodyModel.cpp index 666b3159..61186d12 100644 --- a/demos/rlCollisionDemo/BodyModel.cpp +++ b/demos/rlCollisionDemo/BodyModel.cpp @@ -60,8 +60,7 @@ BodyModel::data(const QModelIndex& index, int role) const return QVariant(); } - rl::math::Transform transform; - this->collision->getFrame(transform); + rl::math::Transform transform = this->collision->getFrame(); rl::math::Transform::TranslationPart position = transform.translation(); rl::math::Vector3 orientation = transform.rotation().eulerAngles(2, 1, 0).reverse(); @@ -190,8 +189,7 @@ BodyModel::setData(const QModelIndex& index, const QVariant& value, int role) if (index.isValid() && Qt::EditRole == role) { - rl::math::Transform transform; - this->collision->getFrame(transform); + rl::math::Transform transform = this->collision->getFrame(); rl::math::Transform::TranslationPart position = transform.translation(); rl::math::Vector3 orientation = transform.linear().eulerAngles(2, 1, 0).reverse(); diff --git a/src/rl/sg/Body.cpp b/src/rl/sg/Body.cpp index 4a608826..6f229425 100644 --- a/src/rl/sg/Body.cpp +++ b/src/rl/sg/Body.cpp @@ -92,6 +92,12 @@ namespace rl } } + void + Body::getFrame(::rl::math::Transform& frame) + { + frame = this->getFrame(); + } + Model* Body::getModel() const { diff --git a/src/rl/sg/Body.h b/src/rl/sg/Body.h index d8ab626c..9491a5bb 100644 --- a/src/rl/sg/Body.h +++ b/src/rl/sg/Body.h @@ -62,6 +62,10 @@ namespace rl void getBoundingBoxPoints(const ::rl::math::Transform& frame, ::std::vector<::rl::math::Vector3>& p) const; + RL_SG_DEPRECATED virtual void getFrame(::rl::math::Transform& frame); + + virtual ::rl::math::Transform getFrame() const = 0; + Model* getModel() const; virtual ::std::string getName() const; @@ -72,8 +76,6 @@ namespace rl Shape* getShape(const ::std::size_t& i) const; - virtual void getFrame(::rl::math::Transform& frame) = 0; - virtual void remove(Shape* shape); virtual void setFrame(const ::rl::math::Transform& frame) = 0; diff --git a/src/rl/sg/Shape.cpp b/src/rl/sg/Shape.cpp index d563fc24..cdc4d87e 100644 --- a/src/rl/sg/Shape.cpp +++ b/src/rl/sg/Shape.cpp @@ -54,6 +54,12 @@ namespace rl return this->name; } + void + Shape::getTransform(::rl::math::Transform& transform) + { + transform = this->getTransform(); + } + void Shape::setName(const ::std::string& name) { diff --git a/src/rl/sg/Shape.h b/src/rl/sg/Shape.h index 06a88617..3465a27a 100644 --- a/src/rl/sg/Shape.h +++ b/src/rl/sg/Shape.h @@ -49,7 +49,9 @@ namespace rl virtual ::std::string getName() const; - virtual void getTransform(::rl::math::Transform& transform) = 0; + RL_SG_DEPRECATED virtual void getTransform(::rl::math::Transform& transform); + + virtual ::rl::math::Transform getTransform() const = 0; virtual void setName(const ::std::string& name); diff --git a/src/rl/sg/bullet/Body.cpp b/src/rl/sg/bullet/Body.cpp index 14609b28..02b0f9ba 100644 --- a/src/rl/sg/bullet/Body.cpp +++ b/src/rl/sg/bullet/Body.cpp @@ -66,9 +66,11 @@ namespace rl return new Shape(shape, this); } - void - Body::getFrame(::rl::math::Transform& frame) + ::rl::math::Transform + Body::getFrame() const { + ::rl::math::Transform frame; + for (int i = 0; i < 3; ++i) { frame(0, i) = this->object.getWorldTransform().getBasis().getRow(i).getX(); @@ -84,6 +86,8 @@ namespace rl frame(3, 1) = 0; frame(3, 2) = 0; frame(3, 3) = 1; + + return frame; } void diff --git a/src/rl/sg/bullet/Body.h b/src/rl/sg/bullet/Body.h index dedcc3b9..99b01418 100644 --- a/src/rl/sg/bullet/Body.h +++ b/src/rl/sg/bullet/Body.h @@ -48,7 +48,9 @@ namespace rl ::rl::sg::Shape* create(::SoVRMLShape* shape); - void getFrame(::rl::math::Transform& frame); + using ::rl::sg::Body::getFrame; + + ::rl::math::Transform getFrame() const; void setFrame(const ::rl::math::Transform& frame); diff --git a/src/rl/sg/bullet/Shape.cpp b/src/rl/sg/bullet/Shape.cpp index b6f91ae4..edeaff74 100644 --- a/src/rl/sg/bullet/Shape.cpp +++ b/src/rl/sg/bullet/Shape.cpp @@ -133,11 +133,13 @@ namespace rl this->getBody()->remove(this); } - void - Shape::getTransform(::rl::math::Transform& transform) + ::rl::math::Transform + Shape::getTransform() const { Body* body = static_cast(this->getBody()); + ::rl::math::Transform transform; + for (int i = 0; i < body->shape.getNumChildShapes(); ++i) { if (this->shape.get() == body->shape.getChildList()[i].m_childShape) @@ -161,6 +163,8 @@ namespace rl break; } } + + return transform; } void diff --git a/src/rl/sg/bullet/Shape.h b/src/rl/sg/bullet/Shape.h index 7e9ac0b8..5b6b7822 100644 --- a/src/rl/sg/bullet/Shape.h +++ b/src/rl/sg/bullet/Shape.h @@ -47,7 +47,9 @@ namespace rl virtual ~Shape(); - void getTransform(::rl::math::Transform& transform); + using ::rl::sg::Shape::getTransform; + + ::rl::math::Transform getTransform() const; void setTransform(const ::rl::math::Transform& transform); diff --git a/src/rl/sg/fcl/Body.cpp b/src/rl/sg/fcl/Body.cpp index 0f390d2c..20598119 100644 --- a/src/rl/sg/fcl/Body.cpp +++ b/src/rl/sg/fcl/Body.cpp @@ -70,10 +70,10 @@ namespace rl return new Shape(shape, this); } - void - Body::getFrame(::rl::math::Transform& frame) + ::rl::math::Transform + Body::getFrame() const { - frame = this->frame; + return this->frame; } void diff --git a/src/rl/sg/fcl/Body.h b/src/rl/sg/fcl/Body.h index 7897e23d..2b08e0b3 100644 --- a/src/rl/sg/fcl/Body.h +++ b/src/rl/sg/fcl/Body.h @@ -62,7 +62,9 @@ namespace rl ::rl::sg::Shape* create(::SoVRMLShape* shape); - void getFrame(::rl::math::Transform& frame); + using ::rl::sg::Body::getFrame; + + ::rl::math::Transform getFrame() const; void remove(::rl::sg::Shape* shape); diff --git a/src/rl/sg/fcl/Shape.cpp b/src/rl/sg/fcl/Shape.cpp index 9f5f3a59..7b486142 100644 --- a/src/rl/sg/fcl/Shape.cpp +++ b/src/rl/sg/fcl/Shape.cpp @@ -282,10 +282,10 @@ namespace rl return this->object.get(); } - void - Shape::getTransform(::rl::math::Transform& transform) + ::rl::math::Transform + Shape::getTransform() const { - transform = this->transform; + return this->transform; } void diff --git a/src/rl/sg/fcl/Shape.h b/src/rl/sg/fcl/Shape.h index 79eff8fd..98f66fe7 100644 --- a/src/rl/sg/fcl/Shape.h +++ b/src/rl/sg/fcl/Shape.h @@ -73,7 +73,9 @@ namespace rl CollisionObject* getCollisionObject() const; - void getTransform(::rl::math::Transform& transform); + using ::rl::sg::Shape::getTransform; + + ::rl::math::Transform getTransform() const; void setTransform(const ::rl::math::Transform& transform); diff --git a/src/rl/sg/ode/Body.cpp b/src/rl/sg/ode/Body.cpp index 825812e7..58c302a2 100644 --- a/src/rl/sg/ode/Body.cpp +++ b/src/rl/sg/ode/Body.cpp @@ -62,9 +62,11 @@ namespace rl return new Shape(shape, this); } - void - Body::getFrame(::rl::math::Transform& frame) + ::rl::math::Transform + Body::getFrame() const { + ::rl::math::Transform frame; + const ::dReal* position = ::dBodyGetPosition(this->body); frame(0, 3) = position[0]; @@ -80,6 +82,8 @@ namespace rl frame(i, j) = rotation[i * 4 + j]; } } + + return frame; } void diff --git a/src/rl/sg/ode/Body.h b/src/rl/sg/ode/Body.h index fd16243d..b91a18ab 100644 --- a/src/rl/sg/ode/Body.h +++ b/src/rl/sg/ode/Body.h @@ -48,7 +48,9 @@ namespace rl ::rl::sg::Shape* create(::SoVRMLShape* shape); - void getFrame(::rl::math::Transform& frame); + using ::rl::sg::Body::getFrame; + + ::rl::math::Transform getFrame() const; void setFrame(const ::rl::math::Transform& frame); diff --git a/src/rl/sg/ode/Shape.cpp b/src/rl/sg/ode/Shape.cpp index f028cf0f..5cce102b 100644 --- a/src/rl/sg/ode/Shape.cpp +++ b/src/rl/sg/ode/Shape.cpp @@ -123,10 +123,10 @@ namespace rl ::dGeomDestroy(this->geom); } - void - Shape::getTransform(::rl::math::Transform& transform) + ::rl::math::Transform + Shape::getTransform() const { - transform = this->transform; + return this->transform; } void diff --git a/src/rl/sg/ode/Shape.h b/src/rl/sg/ode/Shape.h index fd4d9ce0..056dff76 100644 --- a/src/rl/sg/ode/Shape.h +++ b/src/rl/sg/ode/Shape.h @@ -48,7 +48,9 @@ namespace rl virtual ~Shape(); - void getTransform(::rl::math::Transform& transform); + using ::rl::sg::Shape::getTransform; + + ::rl::math::Transform getTransform() const; void setTransform(const ::rl::math::Transform& transform); diff --git a/src/rl/sg/pqp/Body.cpp b/src/rl/sg/pqp/Body.cpp index ebb70515..d0ad71d0 100644 --- a/src/rl/sg/pqp/Body.cpp +++ b/src/rl/sg/pqp/Body.cpp @@ -57,10 +57,10 @@ namespace rl return new Shape(shape, this); } - void - Body::getFrame(::rl::math::Transform& frame) + ::rl::math::Transform + Body::getFrame() const { - frame = this->frame; + return this->frame; } void diff --git a/src/rl/sg/pqp/Body.h b/src/rl/sg/pqp/Body.h index 5b47abce..8106fe11 100644 --- a/src/rl/sg/pqp/Body.h +++ b/src/rl/sg/pqp/Body.h @@ -48,7 +48,9 @@ namespace rl ::rl::sg::Shape* create(::SoVRMLShape* shape); - void getFrame(::rl::math::Transform& frame); + using ::rl::sg::Body::getFrame; + + ::rl::math::Transform getFrame() const; void setFrame(const ::rl::math::Transform& frame); diff --git a/src/rl/sg/pqp/Shape.cpp b/src/rl/sg/pqp/Shape.cpp index 92738d27..0eb15f9c 100644 --- a/src/rl/sg/pqp/Shape.cpp +++ b/src/rl/sg/pqp/Shape.cpp @@ -85,10 +85,10 @@ namespace rl this->getBody()->remove(this); } - void - Shape::getTransform(::rl::math::Transform& transform) + ::rl::math::Transform + Shape::getTransform() const { - transform = this->transform; + return this->transform; } void diff --git a/src/rl/sg/pqp/Shape.h b/src/rl/sg/pqp/Shape.h index 547fe956..34765b20 100644 --- a/src/rl/sg/pqp/Shape.h +++ b/src/rl/sg/pqp/Shape.h @@ -51,7 +51,9 @@ namespace rl virtual ~Shape(); - void getTransform(::rl::math::Transform& transform); + using ::rl::sg::Shape::getTransform; + + ::rl::math::Transform getTransform() const; void setTransform(const ::rl::math::Transform& transform); diff --git a/src/rl/sg/so/Body.cpp b/src/rl/sg/so/Body.cpp index cfdd8a8d..e044ab5d 100644 --- a/src/rl/sg/so/Body.cpp +++ b/src/rl/sg/so/Body.cpp @@ -75,8 +75,8 @@ namespace rl return new Shape(shape, this); } - void - Body::getFrame(::rl::math::Transform& frame) + ::rl::math::Transform + Body::getFrame() const { ::SoSearchAction searchAction; searchAction.setNode(this->root); @@ -87,6 +87,8 @@ namespace rl getMatrixAction.apply(searchAction.getPath()); ::SbMatrix matrix = getMatrixAction.getMatrix(); + ::rl::math::Transform frame; + for (int i = 0; i < 4; ++i) { for (int j = 0; j < 4; ++j) @@ -94,6 +96,8 @@ namespace rl frame(i, j) = matrix[j][i]; } } + + return frame; } ::std::string diff --git a/src/rl/sg/so/Body.h b/src/rl/sg/so/Body.h index 764eeb8f..c1f8ba3d 100644 --- a/src/rl/sg/so/Body.h +++ b/src/rl/sg/so/Body.h @@ -50,7 +50,9 @@ namespace rl ::rl::sg::Shape* create(::SoVRMLShape* shape); - void getFrame(::rl::math::Transform& frame); + using ::rl::sg::Body::getFrame; + + ::rl::math::Transform getFrame() const; ::std::string getName() const; diff --git a/src/rl/sg/so/Shape.cpp b/src/rl/sg/so/Shape.cpp index 6376dc81..3554619f 100644 --- a/src/rl/sg/so/Shape.cpp +++ b/src/rl/sg/so/Shape.cpp @@ -65,8 +65,8 @@ namespace rl return this->root->getName().getString(); } - void - Shape::getTransform(::rl::math::Transform& transform) + ::rl::math::Transform + Shape::getTransform() const { ::SoSearchAction searchAction; searchAction.setNode(this->shape); @@ -77,6 +77,8 @@ namespace rl getMatrixAction.apply(searchAction.getPath()); ::SbMatrix matrix = getMatrixAction.getMatrix(); + ::rl::math::Transform transform; + for (int i = 0; i < 4; ++i) { for (int j = 0; j < 4; ++j) @@ -84,6 +86,8 @@ namespace rl transform(i, j) = matrix[j][i]; } } + + return transform; } void diff --git a/src/rl/sg/so/Shape.h b/src/rl/sg/so/Shape.h index 8c86120a..86130496 100644 --- a/src/rl/sg/so/Shape.h +++ b/src/rl/sg/so/Shape.h @@ -49,7 +49,9 @@ namespace rl ::std::string getName() const; - void getTransform(::rl::math::Transform& transform); + using ::rl::sg::Shape::getTransform; + + ::rl::math::Transform getTransform() const; void setName(const ::std::string& name); diff --git a/src/rl/sg/solid/Body.cpp b/src/rl/sg/solid/Body.cpp index 31e1a541..750b55a9 100644 --- a/src/rl/sg/solid/Body.cpp +++ b/src/rl/sg/solid/Body.cpp @@ -57,10 +57,10 @@ namespace rl return new Shape(shape, this); } - void - Body::getFrame(::rl::math::Transform& frame) + ::rl::math::Transform + Body::getFrame() const { - frame = this->frame; + return this->frame; } void diff --git a/src/rl/sg/solid/Body.h b/src/rl/sg/solid/Body.h index 4d8440f7..04325af3 100644 --- a/src/rl/sg/solid/Body.h +++ b/src/rl/sg/solid/Body.h @@ -48,7 +48,9 @@ namespace rl ::rl::sg::Shape* create(::SoVRMLShape* shape); - void getFrame(::rl::math::Transform& frame); + using ::rl::sg::Body::getFrame; + + ::rl::math::Transform getFrame() const; void setFrame(const ::rl::math::Transform& frame); diff --git a/src/rl/sg/solid/Shape.cpp b/src/rl/sg/solid/Shape.cpp index 15aee0a1..86212284 100644 --- a/src/rl/sg/solid/Shape.cpp +++ b/src/rl/sg/solid/Shape.cpp @@ -198,13 +198,12 @@ namespace rl return shape; } - void - Shape::getTransform(::rl::math::Transform& transform) + ::rl::math::Transform + Shape::getTransform() const { - ::DT_GetMatrixd(this->object, this->frame.data()); - - this->transform = static_cast(this->getBody())->frame.inverse() * this->frame; - transform = this->transform; + ::Eigen::Transform<::rl::math::Real, 3, ::Eigen::Affine, ::Eigen::ColMajor> frame; + ::DT_GetMatrixd(this->object, frame.data()); + return static_cast(this->getBody())->frame.inverse() * frame; } void diff --git a/src/rl/sg/solid/Shape.h b/src/rl/sg/solid/Shape.h index 716895aa..e12c3640 100644 --- a/src/rl/sg/solid/Shape.h +++ b/src/rl/sg/solid/Shape.h @@ -53,7 +53,9 @@ namespace rl virtual ~Shape(); - void getTransform(::rl::math::Transform& transform); + using ::rl::sg::Shape::getTransform; + + ::rl::math::Transform getTransform() const; void setMargin(const ::rl::math::Real& margin); From a28200524bec965c6b57fc2c122460719808d8ec Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 30 Jun 2020 20:29:30 +0200 Subject: [PATCH 394/546] Add transition functions and mark them as deprecated --- src/rl/mdl/Dynamic.cpp | 16 ++++++++++++++++ src/rl/mdl/Dynamic.h | 4 ++++ src/rl/mdl/Kinematic.cpp | 12 ++++++++++++ src/rl/mdl/Kinematic.h | 8 ++++++++ src/rl/sg/Shape.cpp | 7 +++++++ src/rl/sg/Shape.h | 3 +++ 6 files changed, 50 insertions(+) diff --git a/src/rl/mdl/Dynamic.cpp b/src/rl/mdl/Dynamic.cpp index 3bdaee78..8c382c3f 100644 --- a/src/rl/mdl/Dynamic.cpp +++ b/src/rl/mdl/Dynamic.cpp @@ -32,10 +32,12 @@ #include #include +#include "EulerCauchyIntegrator.h" #include "Exception.h" #include "Dynamic.h" #include "Prismatic.h" #include "Revolute.h" +#include "RungeKuttaNystromIntegrator.h" #include "World.h" namespace rl @@ -172,6 +174,13 @@ namespace rl invMx = J * invM * J.transpose(); } + void + Dynamic::eulerCauchy(const ::rl::math::Real& dt) + { + EulerCauchyIntegrator integrator(this); + integrator.integrate(dt); + } + void Dynamic::forwardDynamics() { @@ -244,6 +253,13 @@ namespace rl } } + void + Dynamic::rungeKuttaNystrom(const ::rl::math::Real& dt) + { + RungeKuttaNystromIntegrator integrator(this); + integrator.integrate(dt); + } + void Dynamic::update() { diff --git a/src/rl/mdl/Dynamic.h b/src/rl/mdl/Dynamic.h index 6bf06981..21473949 100644 --- a/src/rl/mdl/Dynamic.h +++ b/src/rl/mdl/Dynamic.h @@ -146,6 +146,8 @@ namespace rl */ void calculateOperationalMassMatrixInverse(const ::rl::math::Matrix& J, const ::rl::math::Matrix& invM, ::rl::math::Matrix& invMx) const; + RL_MDL_DEPRECATED void eulerCauchy(const ::rl::math::Real& dt); + /** * Forward dynamics via articulated-body algorithm. * @@ -226,6 +228,8 @@ namespace rl void inverseForce(); + RL_MDL_DEPRECATED void rungeKuttaNystrom(const ::rl::math::Real& dt); + virtual void update(); protected: diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 051de5bb..8314554f 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -33,6 +33,7 @@ #include #include "Exception.h" +#include "JacobianInverseKinematics.h" #include "Kinematic.h" #include "Prismatic.h" #include "Revolute.h" @@ -53,6 +54,17 @@ namespace rl { } + bool + Kinematic::calculateInversePosition(const ::rl::math::Transform& x, const ::std::size_t& leaf, const ::rl::math::Real& delta, const ::rl::math::Real& epsilon, const ::std::size_t& iterations) + { + JacobianInverseKinematics ik(this); + ik.setDelta(delta); + ik.setEpsilon(epsilon); + ik.setIterations(iterations); + ik.addGoal(x, leaf); + return ik.solve(); + } + void Kinematic::calculateJacobian(const bool& inWorldFrame) { diff --git a/src/rl/mdl/Kinematic.h b/src/rl/mdl/Kinematic.h index 6ceb5472..ed0328b6 100644 --- a/src/rl/mdl/Kinematic.h +++ b/src/rl/mdl/Kinematic.h @@ -44,6 +44,14 @@ namespace rl virtual ~Kinematic(); + RL_MDL_DEPRECATED bool calculateInversePosition( + const ::rl::math::Transform& x, + const ::std::size_t& leaf = 0, + const ::rl::math::Real& delta = ::std::numeric_limits<::rl::math::Real>::infinity(), + const ::rl::math::Real& epsilon = static_cast<::rl::math::Real>(1.0e-6), + const ::std::size_t& iterations = 10000 + ); + /** * Calculate Jacobian matrix. * diff --git a/src/rl/sg/Shape.cpp b/src/rl/sg/Shape.cpp index cdc4d87e..4e550aa7 100644 --- a/src/rl/sg/Shape.cpp +++ b/src/rl/sg/Shape.cpp @@ -38,6 +38,13 @@ namespace rl { } + Shape::Shape(::SoVRMLShape* shape, Body* body) : + Base(), + body(body), + name() + { + } + Shape::~Shape() { } diff --git a/src/rl/sg/Shape.h b/src/rl/sg/Shape.h index 3465a27a..f8f51d5a 100644 --- a/src/rl/sg/Shape.h +++ b/src/rl/sg/Shape.h @@ -28,6 +28,7 @@ #define RL_SG_SHAPE_H #include +#include #include #include "Base.h" @@ -43,6 +44,8 @@ namespace rl public: Shape(Body* body); + RL_SG_DEPRECATED Shape(::SoVRMLShape* shape, Body* body); + virtual ~Shape(); Body* getBody() const; From e140c7bab8d8bf0b5d86946647527af71e47ca9c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 3 Jul 2020 13:37:26 +0200 Subject: [PATCH 395/546] Minor update --- src/rl/sg/XmlFactory.cpp | 16 ++++++++++------ 1 file changed, 10 insertions(+), 6 deletions(-) diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp index dec4771b..1872b42f 100644 --- a/src/rl/sg/XmlFactory.cpp +++ b/src/rl/sg/XmlFactory.cpp @@ -82,6 +82,8 @@ namespace rl for (int i = 0; i < ::std::min(1, scenes.size()); ++i) { + ::rl::xml::Path path(document, scenes[i]); + ::SoInput input; if (!input.openFile(scenes[i].getLocalPath(scenes[i].getProperty("href")).c_str() ,true)) @@ -102,7 +104,7 @@ namespace rl // model - ::rl::xml::NodeSet models = ::rl::xml::Path(document, scenes[i]).eval("model").getValue<::rl::xml::NodeSet>(); + ::rl::xml::NodeSet models = path.eval("model").getValue<::rl::xml::NodeSet>(); for (int j = 0; j < models.size(); ++j) { @@ -127,6 +129,8 @@ namespace rl for (int k = 0; k < bodies.size(); ++k) { + ::rl::xml::Path path(document, bodies[k]); + ::SoSearchAction bodySearchAction; bodySearchAction.setName(bodies[k].getProperty("name").c_str()); bodySearchAction.apply(static_cast<::SoFullPath*>(modelSearchAction.getPath())->getTail()); @@ -199,17 +203,17 @@ namespace rl for (int l = 0; l < shapeSearchAction.getPaths().getLength(); ++l) { - ::SoFullPath* path = static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l]); + ::SoFullPath* fullPath = static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l]); - if (path->getLength() > 1) + if (fullPath->getLength() > 1) { - path = static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l]->copy(1, static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l])->getLength() - 1)); + fullPath = static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l]->copy(1, static_cast<::SoFullPath*>(shapeSearchAction.getPaths()[l])->getLength() - 1)); } - pathList.append(path); + pathList.append(fullPath); ::SoGetMatrixAction shapeGetMatrixAction(viewportRegion); - shapeGetMatrixAction.apply(path); + shapeGetMatrixAction.apply(fullPath); ::SbMatrix shapeMatrix = shapeGetMatrixAction.getMatrix(); if (!scene->isScalingSupported()) From c87911611f8a3bc1289aff13d55bdf698728c368 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 3 Jul 2020 14:38:45 +0200 Subject: [PATCH 396/546] Update analog input and output base classes --- src/rl/hal/AnalogInput.h | 5 +++++ src/rl/hal/AnalogInputReader.h | 1 - src/rl/hal/AnalogInputWriter.h | 1 - src/rl/hal/AnalogOutput.h | 5 +++++ src/rl/hal/AnalogOutputWriter.h | 1 - 5 files changed, 10 insertions(+), 3 deletions(-) diff --git a/src/rl/hal/AnalogInput.h b/src/rl/hal/AnalogInput.h index 6c711ab3..92ff1415 100644 --- a/src/rl/hal/AnalogInput.h +++ b/src/rl/hal/AnalogInput.h @@ -27,6 +27,7 @@ #ifndef RL_HAL_ANALOGINPUT_H #define RL_HAL_ANALOGINPUT_H +#include #include #include "Device.h" @@ -48,6 +49,10 @@ namespace rl virtual ::rl::math::Real getAnalogInputMinimum(const ::std::size_t& i) const = 0; + virtual ::std::vector<::rl::math::Unit> getAnalogInputUnit() const = 0; + + virtual ::rl::math::Unit getAnalogInputUnit(const ::std::size_t& i) const = 0; + protected: private: diff --git a/src/rl/hal/AnalogInputReader.h b/src/rl/hal/AnalogInputReader.h index 1e437f11..d00681ab 100644 --- a/src/rl/hal/AnalogInputReader.h +++ b/src/rl/hal/AnalogInputReader.h @@ -28,7 +28,6 @@ #define RL_HAL_ANALOGINPUTREADER_H #include -#include #include "AnalogInput.h" diff --git a/src/rl/hal/AnalogInputWriter.h b/src/rl/hal/AnalogInputWriter.h index 6e5c5edc..514b8e27 100644 --- a/src/rl/hal/AnalogInputWriter.h +++ b/src/rl/hal/AnalogInputWriter.h @@ -28,7 +28,6 @@ #define RL_HAL_ANALOGINPUTWRITER_H #include -#include #include "AnalogInput.h" diff --git a/src/rl/hal/AnalogOutput.h b/src/rl/hal/AnalogOutput.h index 63a3445a..9c20d693 100644 --- a/src/rl/hal/AnalogOutput.h +++ b/src/rl/hal/AnalogOutput.h @@ -27,6 +27,7 @@ #ifndef RL_HAL_ANALOGOUTPUT_H #define RL_HAL_ANALOGOUTPUT_H +#include #include #include "Device.h" @@ -48,6 +49,10 @@ namespace rl virtual ::rl::math::Real getAnalogOutputMinimum(const ::std::size_t& i) const = 0; + virtual ::std::vector<::rl::math::Unit> getAnalogOutputUnit() const = 0; + + virtual ::rl::math::Unit getAnalogOutputUnit(const ::std::size_t& i) const = 0; + protected: private: diff --git a/src/rl/hal/AnalogOutputWriter.h b/src/rl/hal/AnalogOutputWriter.h index 05267e68..c9be48b8 100644 --- a/src/rl/hal/AnalogOutputWriter.h +++ b/src/rl/hal/AnalogOutputWriter.h @@ -28,7 +28,6 @@ #define RL_HAL_ANALOGOUTPUTWRITER_H #include -#include #include "AnalogOutput.h" From 86ab918f6227474c8ef471451a2898880ebc3805 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 3 Jul 2020 17:03:52 +0200 Subject: [PATCH 397/546] Move constants to class template --- .../rlAxisControllerDemo.cpp | 6 +- demos/rlCoachKin/ConfigurationDelegate.cpp | 5 +- demos/rlCoachKin/ConfigurationModel.cpp | 7 +- demos/rlCoachKin/OperationalModel.cpp | 12 +- demos/rlCoachMdl/ConfigurationDelegate.cpp | 6 +- demos/rlCoachMdl/ConfigurationModel.cpp | 8 +- demos/rlCoachMdl/OperationalModel.cpp | 14 +- demos/rlCollisionDemo/BodyModel.cpp | 12 +- .../rlDenavitHartenbergDemo.cpp | 10 +- demos/rlDynamics2Demo/rlDynamics2Demo.cpp | 4 +- demos/rlEulerAnglesDemo/rlEulerAnglesDemo.cpp | 6 +- .../rlInversePositionDemo.cpp | 6 +- demos/rlJacobianDemo/rlJacobianDemo.cpp | 1 - demos/rlPlanDemo/ConfigurationDelegate.cpp | 5 +- demos/rlPlanDemo/ConfigurationModel.cpp | 6 +- demos/rlPlanDemo/MainWindow.cpp | 90 +++++----- demos/rlPlanDemo/Thread.cpp | 1 - demos/rlPlanDemo/Viewer.cpp | 1 - demos/rlPrmDemo/rlPrmDemo.cpp | 12 +- demos/rlPumaDemo/rlPumaDemo.cpp | 14 +- demos/rlQuaternionDemo/rlQuaternionDemo.cpp | 78 ++++----- .../AngleAxisModel.cpp | 6 +- .../EulerAnglesModel.cpp | 6 +- demos/rlRrtDemo/rlRrtDemo.cpp | 12 +- demos/rlSimulator/ConfigurationDelegate.cpp | 6 +- demos/rlSimulator/ConfigurationModel.cpp | 14 +- demos/rlSimulator/MainWindow.cpp | 3 +- demos/rlSimulator/OperationalModel.cpp | 14 +- src/rl/hal/Dc1394Camera.cpp | 4 +- src/rl/hal/Gnuplot.cpp | 8 +- src/rl/hal/LeuzeRs4.cpp | 8 +- src/rl/hal/RobotiqModelC.cpp | 4 +- src/rl/hal/SchmersalLss300.cpp | 6 +- src/rl/hal/SickLms200.cpp | 14 +- src/rl/hal/SickS300.cpp | 6 +- src/rl/hal/UniversalRobotsRealtime.cpp | 1 - src/rl/hal/UniversalRobotsRtde.cpp | 9 +- src/rl/hal/WeissWsg50.cpp | 40 ++--- src/rl/kin/Kinematics.cpp | 36 ++-- src/rl/kin/Puma.cpp | 28 +-- src/rl/kin/Revolute.cpp | 8 +- src/rl/kin/Rhino.cpp | 6 +- src/rl/math/CMakeLists.txt | 1 + src/rl/math/CircularVector2.h | 4 +- src/rl/math/Constants.h | 159 ++++++++++++++++++ src/rl/math/LowPass.h | 4 +- src/rl/math/Polynomial.h | 5 +- src/rl/math/TypeTraits.h | 26 --- src/rl/math/Unit.h | 60 +++---- src/rl/mdl/Dynamic.cpp | 1 - src/rl/mdl/Kinematic.cpp | 1 - src/rl/mdl/Revolute.cpp | 8 +- src/rl/mdl/UrdfFactory.cpp | 14 +- src/rl/mdl/XmlFactory.cpp | 24 +-- src/rl/plan/Eet.cpp | 1 - src/rl/sg/UrdfFactory.cpp | 4 +- tests/rlCircularTest/rlCircularTest.cpp | 1 - tests/rlCollisionTest/rlCollisionTest.cpp | 7 +- tests/rlEetTest/rlEetTest.cpp | 8 +- tests/rlJacobianKinTest/rlJacobianKinTest.cpp | 4 +- tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp | 4 +- tests/rlMathDeltaTest/rlMathDeltaTest.cpp | 11 +- tests/rlPrmTest/rlPrmTest.cpp | 14 +- 63 files changed, 511 insertions(+), 393 deletions(-) create mode 100644 src/rl/math/Constants.h diff --git a/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp b/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp index bf77cc38..f553d137 100644 --- a/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp +++ b/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp @@ -30,8 +30,8 @@ #include #include #include +#include #include -#include #define COACH //#define GNUPLOT @@ -50,7 +50,7 @@ main(int argc, char** argv) rl::hal::Coach controller(6, std::chrono::microseconds(7110), 0, "localhost"); #endif // COACH #ifdef GNUPLOT - rl::hal::Gnuplot controller(6, std::chrono::microseconds(7110), -10 * rl::math::DEG2RAD, 10 * rl::math::DEG2RAD); + rl::hal::Gnuplot controller(6, std::chrono::microseconds(7110), -10 * rl::math::constants::deg2rad, 10 * rl::math::constants::deg2rad); #endif // GNUPLOT #ifdef MITSUBISHI rl::hal::MitsubishiH7 controller(6, "left", "lefthost"); @@ -67,7 +67,7 @@ main(int argc, char** argv) controller.step(); rl::math::Vector q0 = controller.getJointPosition(); - rl::math::Vector q1 = q0 + rl::math::Vector::Constant(controller.getDof(), 5 * rl::math::DEG2RAD); + rl::math::Vector q1 = q0 + rl::math::Vector::Constant(controller.getDof(), 5 * rl::math::constants::deg2rad); rl::math::Real te = updateRate * 300.0f; diff --git a/demos/rlCoachKin/ConfigurationDelegate.cpp b/demos/rlCoachKin/ConfigurationDelegate.cpp index 2d0101da..e66e7d8a 100644 --- a/demos/rlCoachKin/ConfigurationDelegate.cpp +++ b/demos/rlCoachKin/ConfigurationDelegate.cpp @@ -26,6 +26,7 @@ #include #include +#include #include "ConfigurationDelegate.h" #include "MainWindow.h" @@ -57,8 +58,8 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& if (rl::math::UNIT_RADIAN == qUnits(index.row())) { editor->setDecimals(2); - editor->setMinimum(minimum(index.row()) * rl::math::RAD2DEG); - editor->setMaximum(maximum(index.row()) * rl::math::RAD2DEG); + editor->setMinimum(minimum(index.row()) * rl::math::constants::rad2deg); + editor->setMaximum(maximum(index.row()) * rl::math::constants::rad2deg); editor->setSingleStep(1.0); } else diff --git a/demos/rlCoachKin/ConfigurationModel.cpp b/demos/rlCoachKin/ConfigurationModel.cpp index 7f5441de..bb27ed2e 100644 --- a/demos/rlCoachKin/ConfigurationModel.cpp +++ b/demos/rlCoachKin/ConfigurationModel.cpp @@ -24,6 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include #include #include "ConfigurationModel.h" @@ -72,7 +73,7 @@ ConfigurationModel::data(const QModelIndex& index, int role) const return QString::number(q(index.row()), 'f', 4) + QString(" m"); break; case rl::math::UNIT_RADIAN: - return QString::number(q(index.row()) * rl::math::RAD2DEG, 'f', 2) + QChar(176); + return QString::number(q(index.row()) * rl::math::constants::rad2deg, 'f', 2) + QChar(176); break; default: return q(index.row()); @@ -82,7 +83,7 @@ ConfigurationModel::data(const QModelIndex& index, int role) const case Qt::EditRole: if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - return q(index.row()) * rl::math::RAD2DEG; + return q(index.row()) * rl::math::constants::rad2deg; } else { @@ -156,7 +157,7 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - q(index.row()) = value.value() * rl::math::DEG2RAD; + q(index.row()) = value.value() * rl::math::constants::deg2rad; } else { diff --git a/demos/rlCoachKin/OperationalModel.cpp b/demos/rlCoachKin/OperationalModel.cpp index 847c8490..9cf6d0d6 100644 --- a/demos/rlCoachKin/OperationalModel.cpp +++ b/demos/rlCoachKin/OperationalModel.cpp @@ -24,8 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include #include -#include #include #include "ConfigurationModel.h" @@ -85,7 +85,7 @@ OperationalModel::data(const QModelIndex& index, int role) const case 3: case 4: case 5: - return QString::number(orientation(index.column() - 3) * rl::math::RAD2DEG, 'f', 2) + QChar(176); + return QString::number(orientation(index.column() - 3) * rl::math::constants::rad2deg, 'f', 2) + QChar(176); break; default: break; @@ -102,7 +102,7 @@ OperationalModel::data(const QModelIndex& index, int role) const case 3: case 4: case 5: - return orientation(index.column() - 3) * rl::math::RAD2DEG; + return orientation(index.column() - 3) * rl::math::constants::rad2deg; break; default: break; @@ -207,19 +207,19 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r transform.linear() = ( rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) * rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ).toRotationMatrix(); break; case 4: transform.linear() = ( rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX()) ).toRotationMatrix(); break; case 5: transform.linear() = ( - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) * rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX()) ).toRotationMatrix(); diff --git a/demos/rlCoachMdl/ConfigurationDelegate.cpp b/demos/rlCoachMdl/ConfigurationDelegate.cpp index 65953e8b..561d31e3 100644 --- a/demos/rlCoachMdl/ConfigurationDelegate.cpp +++ b/demos/rlCoachMdl/ConfigurationDelegate.cpp @@ -26,7 +26,7 @@ #include #include -#include +#include #include #include @@ -56,8 +56,8 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& if (rl::math::UNIT_RADIAN == qUnits(index.row())) { editor->setDecimals(2); - editor->setMinimum(minimum(index.row()) * rl::math::RAD2DEG); - editor->setMaximum(maximum(index.row()) * rl::math::RAD2DEG); + editor->setMinimum(minimum(index.row()) * rl::math::constants::rad2deg); + editor->setMaximum(maximum(index.row()) * rl::math::constants::rad2deg); editor->setSingleStep(1.0); } else diff --git a/demos/rlCoachMdl/ConfigurationModel.cpp b/demos/rlCoachMdl/ConfigurationModel.cpp index 41296bd7..9f364a51 100644 --- a/demos/rlCoachMdl/ConfigurationModel.cpp +++ b/demos/rlCoachMdl/ConfigurationModel.cpp @@ -24,7 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include +#include #include #include #include @@ -75,7 +75,7 @@ ConfigurationModel::data(const QModelIndex& index, int role) const return QString::number(q(index.row()), 'f', 4) + QString(" m"); break; case rl::math::UNIT_RADIAN: - return QString::number(q(index.row()) * rl::math::RAD2DEG, 'f', 2) + QChar(176); + return QString::number(q(index.row()) * rl::math::constants::rad2deg, 'f', 2) + QChar(176); break; default: return q(index.row()); @@ -85,7 +85,7 @@ ConfigurationModel::data(const QModelIndex& index, int role) const case Qt::EditRole: if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - return q(index.row()) * rl::math::RAD2DEG; + return q(index.row()) * rl::math::constants::rad2deg; } else { @@ -184,7 +184,7 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - q(index.row()) = value.value() * rl::math::DEG2RAD; + q(index.row()) = value.value() * rl::math::constants::deg2rad; } else { diff --git a/demos/rlCoachMdl/OperationalModel.cpp b/demos/rlCoachMdl/OperationalModel.cpp index a829e81a..f939eaf8 100644 --- a/demos/rlCoachMdl/OperationalModel.cpp +++ b/demos/rlCoachMdl/OperationalModel.cpp @@ -25,8 +25,8 @@ // #include +#include #include -#include #include #include #include @@ -93,7 +93,7 @@ OperationalModel::data(const QModelIndex& index, int role) const case 3: case 4: case 5: - return QString::number(orientation(index.column() - 3) * rl::math::RAD2DEG, 'f', 2) + QChar(176); + return QString::number(orientation(index.column() - 3) * rl::math::constants::rad2deg, 'f', 2) + QChar(176); break; default: break; @@ -110,7 +110,7 @@ OperationalModel::data(const QModelIndex& index, int role) const case 3: case 4: case 5: - return orientation(index.column() - 3) * rl::math::RAD2DEG; + return orientation(index.column() - 3) * rl::math::constants::rad2deg; break; default: break; @@ -217,19 +217,19 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r transform.linear() = ( rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) * rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ).toRotationMatrix(); break; case 4: transform.linear() = ( rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX()) ).toRotationMatrix(); break; case 5: transform.linear() = ( - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) * rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX()) ).toRotationMatrix(); @@ -287,7 +287,7 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r if (solved) { - MainWindow::instance()->statusBar()->showMessage("IK solved in " + QString::number(std::chrono::duration(stop - start).count() * rl::math::UNIT2MILLI) + " ms", 2000); + MainWindow::instance()->statusBar()->showMessage("IK solved in " + QString::number(std::chrono::duration(stop - start).count() * rl::math::constants::unit2milli) + " ms", 2000); kinematic->forwardPosition(); diff --git a/demos/rlCollisionDemo/BodyModel.cpp b/demos/rlCollisionDemo/BodyModel.cpp index 61186d12..f68c6334 100644 --- a/demos/rlCollisionDemo/BodyModel.cpp +++ b/demos/rlCollisionDemo/BodyModel.cpp @@ -24,8 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include #include -#include #include "BodyModel.h" #include "MainWindow.h" @@ -77,7 +77,7 @@ BodyModel::data(const QModelIndex& index, int role) const case 3: case 4: case 5: - return QString::number(orientation(index.row() - 3) * rl::math::RAD2DEG, 'f', 2) + QChar(176); + return QString::number(orientation(index.row() - 3) * rl::math::constants::rad2deg, 'f', 2) + QChar(176); break; default: break; @@ -94,7 +94,7 @@ BodyModel::data(const QModelIndex& index, int role) const case 3: case 4: case 5: - return orientation(index.row() - 3) * rl::math::RAD2DEG; + return orientation(index.row() - 3) * rl::math::constants::rad2deg; break; default: break; @@ -204,19 +204,19 @@ BodyModel::setData(const QModelIndex& index, const QVariant& value, int role) transform.linear() = ( rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) * rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ).toRotationMatrix(); break; case 4: transform.linear() = ( rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX()) ).toRotationMatrix(); break; case 5: transform.linear() = ( - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) * rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX()) ).toRotationMatrix(); diff --git a/demos/rlDenavitHartenbergDemo/rlDenavitHartenbergDemo.cpp b/demos/rlDenavitHartenbergDemo/rlDenavitHartenbergDemo.cpp index 72f248b7..1f875b9d 100644 --- a/demos/rlDenavitHartenbergDemo/rlDenavitHartenbergDemo.cpp +++ b/demos/rlDenavitHartenbergDemo/rlDenavitHartenbergDemo.cpp @@ -25,19 +25,19 @@ // #include +#include #include #include #include -#include #include int main(int argc, char** argv) { rl::math::Real a = 31; - rl::math::Real alpha = 271 * rl::math::DEG2RAD; + rl::math::Real alpha = 271 * rl::math::constants::deg2rad; rl::math::Real d = 101; - rl::math::Real theta = 181 * rl::math::DEG2RAD; + rl::math::Real theta = 181 * rl::math::constants::deg2rad; rl::math::Transform t_d(rl::math::Translation(0, 0, d)); @@ -75,9 +75,9 @@ main(int argc, char** argv) dh.toDenavitHartenbergPaul(d, theta, a, alpha); std::cout << "a = " << a << std::endl; - std::cout << "alpha = " << alpha * rl::math::RAD2DEG << std::endl; + std::cout << "alpha = " << alpha * rl::math::constants::rad2deg << std::endl; std::cout << "d = " << d << std::endl; - std::cout << "theta = " << theta * rl::math::RAD2DEG << std::endl; + std::cout << "theta = " << theta * rl::math::constants::rad2deg << std::endl; return EXIT_SUCCESS; } diff --git a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp index ef67f349..da3a901a 100644 --- a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp +++ b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp @@ -28,7 +28,7 @@ #include #include #include -#include +#include #include #include #include @@ -81,7 +81,7 @@ main(int argc, char** argv) dynamic->forwardPosition(); const rl::math::Transform::ConstTranslationPart& position = dynamic->getOperationalPosition(0).translation(); rl::math::Vector3 orientation = dynamic->getOperationalPosition(0).rotation().eulerAngles(2, 1, 0).reverse(); - std::cout << "x = " << position.x() << " m, y = " << position.y() << " m, z = " << position.z() << " m, a = " << orientation.x() * rl::math::RAD2DEG << " deg, b = " << orientation.y() * rl::math::RAD2DEG << " deg, c = " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; + std::cout << "x = " << position.x() << " m, y = " << position.y() << " m, z = " << position.z() << " m, a = " << orientation.x() * rl::math::constants::rad2deg << " deg, b = " << orientation.y() * rl::math::constants::rad2deg << " deg, c = " << orientation.z() * rl::math::constants::rad2deg << " deg" << std::endl; std::cout << "===============================================================================" << std::endl; diff --git a/demos/rlEulerAnglesDemo/rlEulerAnglesDemo.cpp b/demos/rlEulerAnglesDemo/rlEulerAnglesDemo.cpp index 76d5ec0c..24c1ce21 100644 --- a/demos/rlEulerAnglesDemo/rlEulerAnglesDemo.cpp +++ b/demos/rlEulerAnglesDemo/rlEulerAnglesDemo.cpp @@ -26,9 +26,9 @@ #include #include +#include #include #include -#include #include int @@ -44,7 +44,7 @@ main(int argc, char** argv) for (std::size_t i = 0; i < 3; ++i) { - rl::math::Real angle = boost::lexical_cast(argv[i + 4]) * rl::math::DEG2RAD; + rl::math::Real angle = boost::lexical_cast(argv[i + 4]) * rl::math::constants::deg2rad; rl::math::Vector3 axis( 0 == boost::lexical_cast(argv[i + 1]) ? 1 : 0, @@ -65,7 +65,7 @@ main(int argc, char** argv) std::cout << "angle: " << angleAxis.angle() << " rad - axis: " << angleAxis.axis().transpose() << std::endl; rl::math::Vector3 orientation = rotation.eulerAngles(2, 1, 0).reverse(); - std::cout << "x: " << orientation.x() * rl::math::RAD2DEG << " deg - y: " << orientation.y() * rl::math::RAD2DEG << " deg - z: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; + std::cout << "x: " << orientation.x() * rl::math::constants::rad2deg << " deg - y: " << orientation.y() * rl::math::constants::rad2deg << " deg - z: " << orientation.z() * rl::math::constants::rad2deg << " deg" << std::endl; return EXIT_SUCCESS; } diff --git a/demos/rlInversePositionDemo/rlInversePositionDemo.cpp b/demos/rlInversePositionDemo/rlInversePositionDemo.cpp index d83776ea..375a65db 100644 --- a/demos/rlInversePositionDemo/rlInversePositionDemo.cpp +++ b/demos/rlInversePositionDemo/rlInversePositionDemo.cpp @@ -30,11 +30,11 @@ #include #include #include +#include #include #include #include #include -#include #ifdef RL_MDL_NLOPT #include @@ -79,7 +79,7 @@ main(int argc, char** argv) kinematic->forwardPosition(); rl::math::Vector3 position = kinematic->getOperationalPosition(0).translation(); rl::math::Vector3 orientation = kinematic->getOperationalPosition(0).rotation().eulerAngles(2, 1, 0).reverse(); - std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::RAD2DEG << " deg, b: " << orientation.y() * rl::math::RAD2DEG << " deg, c: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; + std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::constants::rad2deg << " deg, b: " << orientation.y() * rl::math::constants::rad2deg << " deg, c: " << orientation.z() * rl::math::constants::rad2deg << " deg" << std::endl; #ifdef RL_MDL_NLOPT rl::mdl::NloptInverseKinematics ik(kinematic.get()); @@ -103,7 +103,7 @@ main(int argc, char** argv) kinematic->forwardPosition(); position = kinematic->getOperationalPosition(0).translation(); orientation = kinematic->getOperationalPosition(0).rotation().eulerAngles(2, 1, 0).reverse(); - std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::RAD2DEG << " deg, b: " << orientation.y() * rl::math::RAD2DEG << " deg, c: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; + std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::constants::rad2deg << " deg, b: " << orientation.y() * rl::math::constants::rad2deg << " deg, c: " << orientation.z() * rl::math::constants::rad2deg << " deg" << std::endl; std::cout << "q: " << kinematic->getPosition().transpose() << std::endl; diff --git a/demos/rlJacobianDemo/rlJacobianDemo.cpp b/demos/rlJacobianDemo/rlJacobianDemo.cpp index a01844fc..79d407b6 100644 --- a/demos/rlJacobianDemo/rlJacobianDemo.cpp +++ b/demos/rlJacobianDemo/rlJacobianDemo.cpp @@ -28,7 +28,6 @@ #include #include #include -#include #include #include #include diff --git a/demos/rlPlanDemo/ConfigurationDelegate.cpp b/demos/rlPlanDemo/ConfigurationDelegate.cpp index e3989576..abafc145 100644 --- a/demos/rlPlanDemo/ConfigurationDelegate.cpp +++ b/demos/rlPlanDemo/ConfigurationDelegate.cpp @@ -26,6 +26,7 @@ #include #include +#include #include "ConfigurationDelegate.h" #include "MainWindow.h" @@ -52,8 +53,8 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& if (rl::math::UNIT_RADIAN == qUnits(index.row())) { editor->setDecimals(2); - editor->setMinimum(minimum(index.row()) * rl::math::RAD2DEG); - editor->setMaximum(maximum(index.row()) * rl::math::RAD2DEG); + editor->setMinimum(minimum(index.row()) * rl::math::constants::rad2deg); + editor->setMaximum(maximum(index.row()) * rl::math::constants::rad2deg); editor->setSingleStep(1.0); } else diff --git a/demos/rlPlanDemo/ConfigurationModel.cpp b/demos/rlPlanDemo/ConfigurationModel.cpp index f67f0216..a4d16e38 100644 --- a/demos/rlPlanDemo/ConfigurationModel.cpp +++ b/demos/rlPlanDemo/ConfigurationModel.cpp @@ -24,6 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include + #include "ConfigurationModel.h" #include "MainWindow.h" #include "Thread.h" @@ -66,7 +68,7 @@ ConfigurationModel::data(const QModelIndex& index, int role) const if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - return (*MainWindow::instance()->q)(index.row()) * rl::math::RAD2DEG; + return (*MainWindow::instance()->q)(index.row()) * rl::math::constants::rad2deg; } else { @@ -142,7 +144,7 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - (*MainWindow::instance()->q)(index.row()) = value.value() * rl::math::DEG2RAD; + (*MainWindow::instance()->q)(index.row()) = value.value() * rl::math::constants::deg2rad; } else { diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index ab1cdb66..c917c5aa 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -44,8 +44,8 @@ #include #include #include +#include #include -#include #include #include #include @@ -956,13 +956,13 @@ MainWindow::load(const QString& filename) if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/world) > 0").getValue()) { this->mdl->world() = rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/z)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ() ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/y)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitY() ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/x)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitX() ); @@ -981,13 +981,13 @@ MainWindow::load(const QString& filename) if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/world) > 0").getValue()) { this->kin->world() = rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/z)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ() ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/y)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitY() ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/x)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitX() ); @@ -1047,13 +1047,13 @@ MainWindow::load(const QString& filename) if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/world) > 0").getValue()) { this->mdl2->world() = rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/z)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ() ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/y)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitY() ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/x)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitX() ); @@ -1072,13 +1072,13 @@ MainWindow::load(const QString& filename) if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/world) > 0").getValue()) { this->kin2->world() = rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/z)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ() ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/y)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitY() ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/x)").getValue(0) * rl::math::DEG2RAD, + path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, rl::math::Vector3::UnitX() ); @@ -1111,7 +1111,7 @@ MainWindow::load(const QString& filename) if ("deg" == start[i].getProperty("unit")) { - (*this->start)(i) *= rl::math::DEG2RAD; + (*this->start)(i) *= rl::math::constants::deg2rad; } } @@ -1126,7 +1126,7 @@ MainWindow::load(const QString& filename) if ("deg" == goal[i].getProperty("unit")) { - (*this->goal)(i) *= rl::math::DEG2RAD; + (*this->goal)(i) *= rl::math::constants::deg2rad; } } @@ -1141,7 +1141,7 @@ MainWindow::load(const QString& filename) if ("deg" == sigma[i].getProperty("unit")) { - (*this->sigma)(i) *= rl::math::DEG2RAD; + (*this->sigma)(i) *= rl::math::constants::deg2rad; } } } @@ -1215,7 +1215,7 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string((/rl/plan|/rlplan)//recursiveVerifier/delta/@unit)").getValue()) { - this->verifier->delta *= rl::math::DEG2RAD; + this->verifier->delta *= rl::math::constants::deg2rad; } } else if (path.eval("count((/rl/plan|/rlplan)//sequentialVerifier) > 0").getValue()) @@ -1225,7 +1225,7 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string((/rl/plan|/rlplan)//sequentialVerifier/delta/@unit)").getValue()) { - this->verifier->delta *= rl::math::DEG2RAD; + this->verifier->delta *= rl::math::constants::deg2rad; } } @@ -1241,7 +1241,7 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string((/rl/plan|/rlplan)//simpleOptimizer/recursiveVerifier/delta/@unit)").getValue()) { - this->verifier2->delta *= rl::math::DEG2RAD; + this->verifier2->delta *= rl::math::constants::deg2rad; } } else if (path.eval("count((/rl/plan|/rlplan)//advancedOptimizer/recursiveVerifier) > 0").getValue()) @@ -1251,7 +1251,7 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string((/rl/plan|/rlplan)//advancedOptimizer/recursiveVerifier/delta/@unit)").getValue()) { - this->verifier2->delta *= rl::math::DEG2RAD; + this->verifier2->delta *= rl::math::constants::deg2rad; } } @@ -1274,7 +1274,7 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string((/rl/plan|/rlplan)//advancedOptimizer/length/@unit)").getValue()) { - advancedOptimizer->length *= rl::math::DEG2RAD; + advancedOptimizer->length *= rl::math::constants::deg2rad; } advancedOptimizer->ratio = path.eval("number((/rl/plan|/rlplan)//advancedOptimizer/ratio)").getValue(static_cast(0.1)); @@ -1301,28 +1301,28 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(delta/@unit)").getValue()) { - addRrtConCon->delta *= rl::math::DEG2RAD; + addRrtConCon->delta *= rl::math::constants::deg2rad; } addRrtConCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - addRrtConCon->epsilon *= rl::math::DEG2RAD; + addRrtConCon->epsilon *= rl::math::constants::deg2rad; } addRrtConCon->lower = path.eval("number(lower)").getValue(2); if ("deg" == path.eval("string(lower/@unit)").getValue()) { - addRrtConCon->lower *= rl::math::DEG2RAD; + addRrtConCon->lower *= rl::math::constants::deg2rad; } addRrtConCon->radius = path.eval("number(radius)").getValue(20); if ("deg" == path.eval("string(radius/@unit)").getValue()) { - addRrtConCon->radius *= rl::math::DEG2RAD; + addRrtConCon->radius *= rl::math::constants::deg2rad; } addRrtConCon->sampler = this->sampler.get(); @@ -1338,7 +1338,7 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(delta/@unit)").getValue()) { - eet->delta *= rl::math::DEG2RAD; + eet->delta *= rl::math::constants::deg2rad; } eet->distanceWeight = path.eval("number(distanceWeight)").getValue(static_cast(0.1)); @@ -1346,7 +1346,7 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - eet->epsilon *= rl::math::DEG2RAD; + eet->epsilon *= rl::math::constants::deg2rad; } eet->gamma = path.eval("number(gamma)").getValue(static_cast(1) / static_cast(3)); @@ -1515,7 +1515,7 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(radius/@unit)").getValue()) { - prm->radius *= rl::math::DEG2RAD; + prm->radius *= rl::math::constants::deg2rad; } prm->sampler = this->sampler.get(); @@ -1537,7 +1537,7 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(radius/@unit)").getValue()) { - prmUtilityGuided->radius *= rl::math::DEG2RAD; + prmUtilityGuided->radius *= rl::math::constants::deg2rad; } if (path.eval("count(seed) > 0").getValue()) @@ -1562,14 +1562,14 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrt->delta *= rl::math::DEG2RAD; + rrt->delta *= rl::math::constants::deg2rad; } rrt->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrt->epsilon *= rl::math::DEG2RAD; + rrt->epsilon *= rl::math::constants::deg2rad; } rrt->sampler = this->sampler.get(); @@ -1582,14 +1582,14 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtCon->delta *= rl::math::DEG2RAD; + rrtCon->delta *= rl::math::constants::deg2rad; } rrtCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtCon->epsilon *= rl::math::DEG2RAD; + rrtCon->epsilon *= rl::math::constants::deg2rad; } rrtCon->probability = path.eval("number(probability)").getValue(static_cast(0.05)); @@ -1614,14 +1614,14 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtConCon->delta *= rl::math::DEG2RAD; + rrtConCon->delta *= rl::math::constants::deg2rad; } rrtConCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtConCon->epsilon *= rl::math::DEG2RAD; + rrtConCon->epsilon *= rl::math::constants::deg2rad; } rrtConCon->sampler = this->sampler.get(); @@ -1634,14 +1634,14 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtDual->delta *= rl::math::DEG2RAD; + rrtDual->delta *= rl::math::constants::deg2rad; } rrtDual->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtDual->epsilon *= rl::math::DEG2RAD; + rrtDual->epsilon *= rl::math::constants::deg2rad; } rrtDual->sampler = this->sampler.get(); @@ -1654,14 +1654,14 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtExtCon->delta *= rl::math::DEG2RAD; + rrtExtCon->delta *= rl::math::constants::deg2rad; } rrtExtCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtExtCon->epsilon *= rl::math::DEG2RAD; + rrtExtCon->epsilon *= rl::math::constants::deg2rad; } rrtExtCon->sampler = this->sampler.get(); @@ -1674,14 +1674,14 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtExtExt->delta *= rl::math::DEG2RAD; + rrtExtExt->delta *= rl::math::constants::deg2rad; } rrtExtExt->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtExtExt->epsilon *= rl::math::DEG2RAD; + rrtExtExt->epsilon *= rl::math::constants::deg2rad; } rrtExtExt->sampler = this->sampler.get(); @@ -1694,14 +1694,14 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtGoalBias->delta *= rl::math::DEG2RAD; + rrtGoalBias->delta *= rl::math::constants::deg2rad; } rrtGoalBias->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtGoalBias->epsilon *= rl::math::DEG2RAD; + rrtGoalBias->epsilon *= rl::math::constants::deg2rad; } rrtGoalBias->probability = path.eval("number(probability)").getValue(static_cast(0.05)); @@ -1855,14 +1855,14 @@ MainWindow::load(const QString& filename) if ("deg" == path.eval("string((/rl/plan|/rlplan)//viewer/delta/@unit)").getValue()) { - this->viewer->delta *= rl::math::DEG2RAD; + this->viewer->delta *= rl::math::constants::deg2rad; } this->viewer->deltaSwept = path.eval("number((/rl/plan|/rlplan)//viewer/swept)").getValue(this->viewer->delta * 100); if ("deg" == path.eval("string((/rl/plan|/rlplan)//viewer/swept/@unit)").getValue()) { - this->viewer->deltaSwept *= rl::math::DEG2RAD; + this->viewer->deltaSwept *= rl::math::constants::deg2rad; } this->viewer->sceneGroup->addChild(this->scene2->root); diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index 8a2b4eb0..9131dcd4 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -29,7 +29,6 @@ #include #include #include -#include #include #include #include diff --git a/demos/rlPlanDemo/Viewer.cpp b/demos/rlPlanDemo/Viewer.cpp index 434840d1..3d00c762 100644 --- a/demos/rlPlanDemo/Viewer.cpp +++ b/demos/rlPlanDemo/Viewer.cpp @@ -31,7 +31,6 @@ #include #include #include -#include #include #include #include diff --git a/demos/rlPrmDemo/rlPrmDemo.cpp b/demos/rlPrmDemo/rlPrmDemo.cpp index 7acce7a7..6f61cebe 100644 --- a/demos/rlPrmDemo/rlPrmDemo.cpp +++ b/demos/rlPrmDemo/rlPrmDemo.cpp @@ -28,7 +28,7 @@ #include #include #include -#include +#include #include #include #include @@ -113,14 +113,14 @@ main(int argc, char** argv) sampler.model = &model; - verifier.delta = 1 * rl::math::DEG2RAD; + verifier.delta = 1 * rl::math::constants::deg2rad; verifier.model = &model; rl::math::Vector start(kinematic->getDofPosition()); for (std::ptrdiff_t i = 0; i < start.size(); ++i) { - start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::DEG2RAD; + start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::constants::deg2rad; } planner.start = &start; @@ -129,13 +129,13 @@ main(int argc, char** argv) for (std::ptrdiff_t i = 0; i < goal.size(); ++i) { - goal(i) = boost::lexical_cast(argv[start.size() + i + 3]) * rl::math::DEG2RAD; + goal(i) = boost::lexical_cast(argv[start.size() + i + 3]) * rl::math::constants::deg2rad; } planner.goal = &goal; - std::cout << "start: " << start.transpose() * rl::math::RAD2DEG << std::endl;; - std::cout << "goal: " << goal.transpose() * rl::math::RAD2DEG << std::endl;; + std::cout << "start: " << start.transpose() * rl::math::constants::rad2deg << std::endl;; + std::cout << "goal: " << goal.transpose() * rl::math::constants::rad2deg << std::endl;; std::cout << "construct() ... " << std::endl;; std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); diff --git a/demos/rlPumaDemo/rlPumaDemo.cpp b/demos/rlPumaDemo/rlPumaDemo.cpp index 71629ad1..3edeba41 100644 --- a/demos/rlPumaDemo/rlPumaDemo.cpp +++ b/demos/rlPumaDemo/rlPumaDemo.cpp @@ -34,8 +34,8 @@ #include #include #include +#include #include -#include int main(int argc, char** argv) @@ -56,7 +56,7 @@ main(int argc, char** argv) for (std::ptrdiff_t i = 0; i < q.size(); ++i) { - q(i) = boost::lexical_cast(argv[i + 2]) * rl::math::DEG2RAD; + q(i) = boost::lexical_cast(argv[i + 2]) * rl::math::constants::deg2rad; } rl::kin::Puma::Arm arm; @@ -75,7 +75,7 @@ main(int argc, char** argv) << ", Wrist: " << (wrist == rl::kin::Puma::WRIST_FLIP ? "FLIP" : "NONFLIP") << std::endl; - std::cout << "q: " << q.transpose() * rl::math::RAD2DEG << std::endl; + std::cout << "q: " << q.transpose() * rl::math::constants::rad2deg << std::endl; puma->setPosition(q); puma->updateFrames(); @@ -83,10 +83,10 @@ main(int argc, char** argv) rl::math::Vector3 position = puma->forwardPosition().translation(); rl::math::Vector3 orientation = puma->forwardPosition().rotation().eulerAngles(2, 1, 0).reverse(); - std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::RAD2DEG << " deg, b: " << orientation.y() * rl::math::RAD2DEG << " deg, c: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; + std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::constants::rad2deg << " deg, b: " << orientation.y() * rl::math::constants::rad2deg << " deg, c: " << orientation.z() * rl::math::constants::rad2deg << " deg" << std::endl; rl::math::Vector q2(puma->getDof()); - q2.setConstant(1.0 * rl::math::DEG2RAD); + q2.setConstant(1.0 * rl::math::constants::deg2rad); rl::math::Transform x = puma->forwardPosition(); @@ -96,7 +96,7 @@ main(int argc, char** argv) return EXIT_FAILURE; } - std::cout << "q: " << q2.transpose() * rl::math::RAD2DEG << std::endl; + std::cout << "q: " << q2.transpose() * rl::math::constants::rad2deg << std::endl; puma->setPosition(q2); puma->updateFrames(); @@ -104,7 +104,7 @@ main(int argc, char** argv) position = puma->forwardPosition().translation(); orientation = puma->forwardPosition().rotation().eulerAngles(2, 1, 0).reverse(); - std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::RAD2DEG << " deg, b: " << orientation.y() * rl::math::RAD2DEG << " deg, c: " << orientation.z() * rl::math::RAD2DEG << " deg" << std::endl; + std::cout << "x: " << position.x() << " m, y: " << position.y() << " m, z: " << position.z() << " m, a: " << orientation.x() * rl::math::constants::rad2deg << " deg, b: " << orientation.y() * rl::math::constants::rad2deg << " deg, c: " << orientation.z() * rl::math::constants::rad2deg << " deg" << std::endl; } else { diff --git a/demos/rlQuaternionDemo/rlQuaternionDemo.cpp b/demos/rlQuaternionDemo/rlQuaternionDemo.cpp index 96427513..8e092fda 100644 --- a/demos/rlQuaternionDemo/rlQuaternionDemo.cpp +++ b/demos/rlQuaternionDemo/rlQuaternionDemo.cpp @@ -28,12 +28,12 @@ #include #include #include +#include #include #include #include #include #include -#include #include int @@ -41,9 +41,9 @@ main(int argc, char** argv) { { rl::math::Matrix33 r1( - rl::math::AngleAxis(90 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(90 * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(0 * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(0 * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ); std::cout << "r1 = " << std::endl << r1 << std::endl; @@ -54,9 +54,9 @@ main(int argc, char** argv) std::cout << "r1 = " << std::endl << r1 << std::endl; rl::math::Matrix33 r2( - rl::math::AngleAxis(-90 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(-90 * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(0 * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(0 * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ); std::cout << "r2 = " << std::endl << r2 << std::endl; @@ -82,52 +82,52 @@ main(int argc, char** argv) std::cout << "(q1^2)^0.5 = " << q1.pow(2).pow(0.5).coeffs().transpose() << std::endl; rl::math::Vector3 omega( - 45 * rl::math::DEG2RAD, - 90 * rl::math::DEG2RAD, - 135 * rl::math::DEG2RAD + 45 * rl::math::constants::deg2rad, + 90 * rl::math::constants::deg2rad, + 135 * rl::math::constants::deg2rad ); - std::cout << "omega = " << omega.transpose() * rl::math::RAD2DEG << std::endl; + std::cout << "omega = " << omega.transpose() * rl::math::constants::rad2deg << std::endl; rl::math::Quaternion qd = q1.firstDerivative(omega); std::cout << "qd = " << qd.coeffs().transpose() << std::endl; omega = q1.angularVelocity(qd); - std::cout << "omega = " << omega.transpose() * rl::math::RAD2DEG << std::endl; + std::cout << "omega = " << omega.transpose() * rl::math::constants::rad2deg << std::endl; rl::math::Vector3 omegad( - 450 * rl::math::DEG2RAD, - 900 * rl::math::DEG2RAD, - 1350 * rl::math::DEG2RAD + 450 * rl::math::constants::deg2rad, + 900 * rl::math::constants::deg2rad, + 1350 * rl::math::constants::deg2rad ); - std::cout << "omegad = " << omegad.transpose() * rl::math::RAD2DEG << std::endl; + std::cout << "omegad = " << omegad.transpose() * rl::math::constants::rad2deg << std::endl; rl::math::Quaternion qdd = q1.secondDerivative(qd, omega, omegad); std::cout << "qdd = " << qdd.coeffs().transpose() << std::endl; omegad = q1.angularAcceleration(qd, qdd); - std::cout << "omegad = " << omegad.transpose() * rl::math::RAD2DEG << std::endl; + std::cout << "omegad = " << omegad.transpose() * rl::math::constants::rad2deg << std::endl; } { rl::math::Quaternion q0( - rl::math::AngleAxis(90 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(90 * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(0 * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(0 * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ); rl::math::Quaternion q1( - rl::math::AngleAxis(45 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(60 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(45 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(45 * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(60 * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(45 * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ); rl::math::Quaternion q2( - rl::math::AngleAxis(45 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(10 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(30 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(45 * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(10 * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(30 * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ); rl::math::Quaternion q3( - rl::math::AngleAxis(90 * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(10 * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(0 * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(90 * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(10 * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(0 * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ); rl::math::Vector3 p(1, 0, 0); @@ -151,7 +151,7 @@ main(int argc, char** argv) rl::math::Quaternion qd = q0.slerpFirstDerivative(t, q1); rl::math::Vector3 omega = q.angularVelocity(qd); - slerpFirstDerivative << i << "\t" << omega.transpose() * rl::math::RAD2DEG << std::endl; + slerpFirstDerivative << i << "\t" << omega.transpose() * rl::math::constants::rad2deg << std::endl; } for (std::size_t i = 0; i < steps; ++i) @@ -163,7 +163,7 @@ main(int argc, char** argv) rl::math::Quaternion qd = q1.slerpFirstDerivative(t, q2); rl::math::Vector3 omega = q.angularVelocity(qd); - slerpFirstDerivative << steps + i << "\t" << omega.transpose() * rl::math::RAD2DEG << std::endl; + slerpFirstDerivative << steps + i << "\t" << omega.transpose() * rl::math::constants::rad2deg << std::endl; } for (std::size_t i = 0; i < steps; ++i) @@ -175,7 +175,7 @@ main(int argc, char** argv) rl::math::Quaternion qd = q2.slerpFirstDerivative(t, q3); rl::math::Vector3 omega = q.angularVelocity(qd); - slerpFirstDerivative << 2 * steps + i << "\t" << omega.transpose() * rl::math::RAD2DEG << std::endl; + slerpFirstDerivative << 2 * steps + i << "\t" << omega.transpose() * rl::math::constants::rad2deg << std::endl; } slerp.close(); @@ -200,7 +200,7 @@ main(int argc, char** argv) rl::math::Quaternion qd = q0.squadFirstDerivative(t, a, b, q1); rl::math::Vector3 omega = q.angularVelocity(qd); - squadFirstDerivative << i << "\t" << omega.transpose() * rl::math::RAD2DEG << std::endl; + squadFirstDerivative << i << "\t" << omega.transpose() * rl::math::constants::rad2deg << std::endl; } for (std::size_t i = 0; i < steps; ++i) @@ -214,7 +214,7 @@ main(int argc, char** argv) rl::math::Quaternion qd = q1.squadFirstDerivative(t, a, b, q2); rl::math::Vector3 omega = q.angularVelocity(qd); - squadFirstDerivative << steps + i << "\t" << omega.transpose() * rl::math::RAD2DEG << std::endl; + squadFirstDerivative << steps + i << "\t" << omega.transpose() * rl::math::constants::rad2deg << std::endl; } for (std::size_t i = 0; i < steps; ++i) @@ -228,7 +228,7 @@ main(int argc, char** argv) rl::math::Quaternion qd = q2.squadFirstDerivative(t, a, b, q3); rl::math::Vector3 omega = q.angularVelocity(qd); - squadFirstDerivative << 2 * steps + i << "\t" << omega.transpose() * rl::math::RAD2DEG << std::endl; + squadFirstDerivative << 2 * steps + i << "\t" << omega.transpose() * rl::math::constants::rad2deg << std::endl; } squad.close(); @@ -251,9 +251,9 @@ main(int argc, char** argv) x.push_back(360); rl::math::Vector3 yd0; - yd0 << 0, 1 * rl::math::DEG2RAD, 0; + yd0 << 0, 1 * rl::math::constants::deg2rad, 0; rl::math::Vector3 yd1; - yd1 << 0, 1 * rl::math::DEG2RAD, 0; + yd1 << 0, 1 * rl::math::constants::deg2rad, 0; rl::math::Spline f = rl::math::Spline::CubicFirst(x, y, yd0, yd1); @@ -280,11 +280,11 @@ main(int argc, char** argv) rl::math::Quaternion qd = f(t, 1); rl::math::Vector3 omega = q.angularVelocity(qd); - cubicFirstDerivative << t << "\t" << omega.transpose() * rl::math::RAD2DEG << std::endl; + cubicFirstDerivative << t << "\t" << omega.transpose() * rl::math::constants::rad2deg << std::endl; rl::math::Quaternion qdd = f(t, 2); rl::math::Vector3 omegad = q.angularAcceleration(qd, qdd); - cubicSecondDerivative << t << "\t" << omegad.transpose() * rl::math::RAD2DEG << std::endl; + cubicSecondDerivative << t << "\t" << omegad.transpose() * rl::math::constants::rad2deg << std::endl; } cubic.close(); diff --git a/demos/rlRotationConverterDemo/AngleAxisModel.cpp b/demos/rlRotationConverterDemo/AngleAxisModel.cpp index b52d9aa8..a6ce16e4 100644 --- a/demos/rlRotationConverterDemo/AngleAxisModel.cpp +++ b/demos/rlRotationConverterDemo/AngleAxisModel.cpp @@ -25,7 +25,7 @@ // #include -#include +#include #include "AngleAxisModel.h" #include "MainWindow.h" @@ -72,7 +72,7 @@ AngleAxisModel::data(const QModelIndex& index, int role) const return this->angleAxis->axis()(index.column()); break; case 3: - return *this->angleRadians ? this->angleAxis->angle() : this->angleAxis->angle() * rl::math::RAD2DEG; + return *this->angleRadians ? this->angleAxis->angle() : this->angleAxis->angle() * rl::math::constants::rad2deg; break; default: break; @@ -162,7 +162,7 @@ AngleAxisModel::setData(const QModelIndex& index, const QVariant& value, int rol this->angleAxis->axis()(index.column()) = value.value(); break; case 3: - this->angleAxis->angle() = *this->angleRadians ? value.value() : value.value() * rl::math::DEG2RAD; + this->angleAxis->angle() = *this->angleRadians ? value.value() : value.value() * rl::math::constants::deg2rad; break; default: break; diff --git a/demos/rlRotationConverterDemo/EulerAnglesModel.cpp b/demos/rlRotationConverterDemo/EulerAnglesModel.cpp index 4023b268..165100f3 100644 --- a/demos/rlRotationConverterDemo/EulerAnglesModel.cpp +++ b/demos/rlRotationConverterDemo/EulerAnglesModel.cpp @@ -25,7 +25,7 @@ // #include -#include +#include #include "EulerAnglesModel.h" #include "MainWindow.h" @@ -65,7 +65,7 @@ EulerAnglesModel::data(const QModelIndex& index, int role) const { case Qt::DisplayRole: case Qt::EditRole: - return *this->eulerAnglesRadians ? (*this->eulerAngles)(index.column()) : (*this->eulerAngles)(index.column()) * rl::math::RAD2DEG; + return *this->eulerAnglesRadians ? (*this->eulerAngles)(index.column()) : (*this->eulerAngles)(index.column()) * rl::math::constants::rad2deg; break; case Qt::TextAlignmentRole: return QVariant(Qt::AlignRight | Qt::AlignVCenter); @@ -140,7 +140,7 @@ EulerAnglesModel::setData(const QModelIndex& index, const QVariant& value, int r if (index.isValid() && Qt::EditRole == role) { - (*this->eulerAngles)(index.column()) = *this->eulerAnglesRadians ? value.value() : value.value() * rl::math::DEG2RAD; + (*this->eulerAngles)(index.column()) = *this->eulerAnglesRadians ? value.value() : value.value() * rl::math::constants::deg2rad; emit dataChanged(this->createIndex(index.row(), index.column()), this->createIndex(index.row(), index.column())); return true; } diff --git a/demos/rlRrtDemo/rlRrtDemo.cpp b/demos/rlRrtDemo/rlRrtDemo.cpp index 1614e23f..d4f0b125 100644 --- a/demos/rlRrtDemo/rlRrtDemo.cpp +++ b/demos/rlRrtDemo/rlRrtDemo.cpp @@ -28,7 +28,7 @@ #include #include #include -#include +#include #include #include #include @@ -112,13 +112,13 @@ main(int argc, char** argv) sampler.model = &model; - planner.delta = 1 * rl::math::DEG2RAD; + planner.delta = 1 * rl::math::constants::deg2rad; rl::math::Vector start(kinematic->getDofPosition()); for (std::ptrdiff_t i = 0; i < start.size(); ++i) { - start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::DEG2RAD; + start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::constants::deg2rad; } planner.start = &start; @@ -127,13 +127,13 @@ main(int argc, char** argv) for (std::ptrdiff_t i = 0; i < goal.size(); ++i) { - goal(i) = boost::lexical_cast(argv[start.size() + i + 3]) * rl::math::DEG2RAD; + goal(i) = boost::lexical_cast(argv[start.size() + i + 3]) * rl::math::constants::deg2rad; } planner.goal = &goal; - std::cout << "start: " << start.transpose() * rl::math::RAD2DEG << std::endl;; - std::cout << "goal: " << goal.transpose() * rl::math::RAD2DEG << std::endl;; + std::cout << "start: " << start.transpose() * rl::math::constants::rad2deg << std::endl;; + std::cout << "goal: " << goal.transpose() * rl::math::constants::rad2deg << std::endl;; std::cout << "solve() ... " << std::endl;; std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); diff --git a/demos/rlSimulator/ConfigurationDelegate.cpp b/demos/rlSimulator/ConfigurationDelegate.cpp index 017c685c..cb18d4e7 100644 --- a/demos/rlSimulator/ConfigurationDelegate.cpp +++ b/demos/rlSimulator/ConfigurationDelegate.cpp @@ -26,7 +26,7 @@ #include #include -#include +#include #include #include @@ -84,8 +84,8 @@ PositionDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& opti if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - editor->setMinimum(minimum(index.row()) * rl::math::RAD2DEG); - editor->setMaximum(maximum(index.row()) * rl::math::RAD2DEG); + editor->setMinimum(minimum(index.row()) * rl::math::constants::rad2deg); + editor->setMaximum(maximum(index.row()) * rl::math::constants::rad2deg); editor->setSingleStep(1.0); } else diff --git a/demos/rlSimulator/ConfigurationModel.cpp b/demos/rlSimulator/ConfigurationModel.cpp index e031039b..2e6f62b2 100644 --- a/demos/rlSimulator/ConfigurationModel.cpp +++ b/demos/rlSimulator/ConfigurationModel.cpp @@ -24,7 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include +#include #include #include #include @@ -114,7 +114,7 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int if (rl::math::UNIT_RADIAN == qUnits(index.row())) { - q(index.row()) = value.value() * rl::math::DEG2RAD; + q(index.row()) = value.value() * rl::math::constants::deg2rad; } else { @@ -136,7 +136,7 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int if (rl::math::UNIT_RADIAN == qdUnits(index.row())) { - qd(index.row()) = value.value() * rl::math::DEG2RAD; + qd(index.row()) = value.value() * rl::math::constants::deg2rad; } else { @@ -152,7 +152,7 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int if (rl::math::UNIT_RADIAN == qddUnits(index.row())) { - qdd(index.row()) = value.value() * rl::math::DEG2RAD; + qdd(index.row()) = value.value() * rl::math::constants::deg2rad; } else { @@ -286,7 +286,7 @@ PositionModel::data(const QModelIndex& index, int role) const if (rl::math::UNIT_RADIAN == units(index.row())) { - return values(index.row()) * rl::math::RAD2DEG; + return values(index.row()) * rl::math::constants::rad2deg; } else { @@ -327,7 +327,7 @@ VelocityModel::data(const QModelIndex& index, int role) const if (rl::math::UNIT_RADIAN == units(index.row())) { - return values(index.row()) * rl::math::RAD2DEG; + return values(index.row()) * rl::math::constants::rad2deg; } else { @@ -368,7 +368,7 @@ AccelerationModel::data(const QModelIndex& index, int role) const if (rl::math::UNIT_RADIAN == units(index.row())) { - return values(index.row()) * rl::math::RAD2DEG; + return values(index.row()) * rl::math::constants::rad2deg; } else { diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index 39c843d2..f922b02b 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -41,6 +41,7 @@ #include #include #include +#include #include #include #include @@ -82,7 +83,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : simulationDampingValue(static_cast(0.001)), simulationDockWidget(new QDockWidget(this)), simulationGravity(nullptr), - simulationGravityValue(rl::math::GRAVITY), + simulationGravityValue(rl::math::constants::gravity), simulationIsRunning(true), simulationPause(nullptr), simulationReset(nullptr), diff --git a/demos/rlSimulator/OperationalModel.cpp b/demos/rlSimulator/OperationalModel.cpp index b136ddbb..fcf5d9c4 100644 --- a/demos/rlSimulator/OperationalModel.cpp +++ b/demos/rlSimulator/OperationalModel.cpp @@ -23,8 +23,8 @@ // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE // POSSIBILITY OF SUCH DAMAGE. // +#include #include -#include #include #include @@ -93,13 +93,13 @@ OperationalModel::data(const QModelIndex& index, int role) const return position.z(); break; case 3: - return orientation.x() * rl::math::RAD2DEG; + return orientation.x() * rl::math::constants::rad2deg; break; case 4: - return orientation.y() * rl::math::RAD2DEG; + return orientation.y() * rl::math::constants::rad2deg; break; case 5: - return orientation.z() * rl::math::RAD2DEG; + return orientation.z() * rl::math::constants::rad2deg; break; default: break; @@ -212,19 +212,19 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r x.linear() = ( rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) * rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) * - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitX()) + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitX()) ).toRotationMatrix(); break; case 4: x.linear() = ( rl::math::AngleAxis(orientation.z(), rl::math::Vector3::UnitZ()) * - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitY()) * + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitY()) * rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX()) ).toRotationMatrix(); break; case 5: x.linear() = ( - rl::math::AngleAxis(value.value() * rl::math::DEG2RAD, rl::math::Vector3::UnitZ()) * + rl::math::AngleAxis(value.value() * rl::math::constants::deg2rad, rl::math::Vector3::UnitZ()) * rl::math::AngleAxis(orientation.y(), rl::math::Vector3::UnitY()) * rl::math::AngleAxis(orientation.x(), rl::math::Vector3::UnitX()) ).toRotationMatrix(); diff --git a/src/rl/hal/Dc1394Camera.cpp b/src/rl/hal/Dc1394Camera.cpp index fa5246bc..abcc7fe2 100644 --- a/src/rl/hal/Dc1394Camera.cpp +++ b/src/rl/hal/Dc1394Camera.cpp @@ -25,7 +25,7 @@ // #include -#include +#include #include "Dc1394Camera.h" @@ -479,7 +479,7 @@ namespace rl } return ::std::chrono::duration_cast<::std::chrono::nanoseconds>( - ::std::chrono::duration(1.0 / framerate * ::rl::math::UNIT2NANO) + ::std::chrono::duration(1.0 / framerate * ::rl::math::constants::unit2nano) ); } diff --git a/src/rl/hal/Gnuplot.cpp b/src/rl/hal/Gnuplot.cpp index 0c6a8b69..00cc8f3f 100644 --- a/src/rl/hal/Gnuplot.cpp +++ b/src/rl/hal/Gnuplot.cpp @@ -27,7 +27,7 @@ #include #include #include -#include +#include #include "ComException.h" #include "Gnuplot.h" @@ -121,7 +121,7 @@ namespace rl this->ymin = ymin; this->ymax = ymax; - fprintf(this->fp, "set yrange [%f:%f]\n", this->ymin * ::rl::math::RAD2DEG, this->ymax * ::rl::math::RAD2DEG); + fprintf(this->fp, "set yrange [%f:%f]\n", this->ymin * ::rl::math::constants::rad2deg, this->ymax * ::rl::math::constants::rad2deg); } void @@ -157,9 +157,9 @@ namespace rl for (::std::list<::rl::math::Vector>::iterator j = this->history.begin(); j != this->history.end(); ++j) { #ifdef WIN32 - fprintf(this->fp, "%Iu %f\n", t, (*j)(i) * ::rl::math::RAD2DEG); + fprintf(this->fp, "%Iu %f\n", t, (*j)(i) * ::rl::math::constants::rad2deg); #else // WIN32 - fprintf(this->fp, "%zu %f\n", t, (*j)(i) * ::rl::math::RAD2DEG); + fprintf(this->fp, "%zu %f\n", t, (*j)(i) * ::rl::math::constants::rad2deg); #endif // WIN32 ++t; } diff --git a/src/rl/hal/LeuzeRs4.cpp b/src/rl/hal/LeuzeRs4.cpp index b6fbf9e7..6e346463 100644 --- a/src/rl/hal/LeuzeRs4.cpp +++ b/src/rl/hal/LeuzeRs4.cpp @@ -27,7 +27,7 @@ #include #include #include -#include +#include #include "Endian.h" #include "DeviceException.h" @@ -214,7 +214,7 @@ namespace rl { assert(this->isConnected()); - return this->stepSize * static_cast<::rl::math::Real>(0.36) * ::rl::math::DEG2RAD; + return this->stepSize * static_cast<::rl::math::Real>(0.36) * ::rl::math::constants::deg2rad; } ::rl::math::Real @@ -222,7 +222,7 @@ namespace rl { assert(this->isConnected()); - return (-5 + this->startIndex * static_cast<::rl::math::Real>(0.36)) * ::rl::math::DEG2RAD; + return (-5 + this->startIndex * static_cast<::rl::math::Real>(0.36)) * ::rl::math::constants::deg2rad; } ::rl::math::Real @@ -230,7 +230,7 @@ namespace rl { assert(this->isConnected()); - return (185 - (528 - this->stopIndex) * static_cast<::rl::math::Real>(0.36)) * ::rl::math::DEG2RAD; + return (185 - (528 - this->stopIndex) * static_cast<::rl::math::Real>(0.36)) * ::rl::math::constants::deg2rad; } void diff --git a/src/rl/hal/RobotiqModelC.cpp b/src/rl/hal/RobotiqModelC.cpp index 2a15d15d..d6f05272 100644 --- a/src/rl/hal/RobotiqModelC.cpp +++ b/src/rl/hal/RobotiqModelC.cpp @@ -25,7 +25,7 @@ // #include -#include +#include #include "Endian.h" #include "RobotiqModelC.h" @@ -106,7 +106,7 @@ namespace rl ::rl::math::Real RobotiqModelC::getCurrent() const { - return this->in[8] * ::rl::math::MILLI2UNIT; + return this->in[8] * ::rl::math::constants::milli2unit; } RobotiqModelC::FaultStatus diff --git a/src/rl/hal/SchmersalLss300.cpp b/src/rl/hal/SchmersalLss300.cpp index a6cd887e..e47ad17d 100644 --- a/src/rl/hal/SchmersalLss300.cpp +++ b/src/rl/hal/SchmersalLss300.cpp @@ -26,7 +26,7 @@ #include #include -#include +#include #include "DeviceException.h" #include "Endian.h" @@ -177,7 +177,7 @@ namespace rl { assert(this->isConnected()); - return static_cast<::rl::math::Real>(0.36) * ::rl::math::DEG2RAD; + return static_cast<::rl::math::Real>(0.36) * ::rl::math::constants::deg2rad; } ::rl::math::Real @@ -193,7 +193,7 @@ namespace rl { assert(this->isConnected()); - return 180 * ::rl::math::DEG2RAD; + return 180 * ::rl::math::constants::deg2rad; } ::std::string diff --git a/src/rl/hal/SickLms200.cpp b/src/rl/hal/SickLms200.cpp index 5ccd716d..1349d056 100644 --- a/src/rl/hal/SickLms200.cpp +++ b/src/rl/hal/SickLms200.cpp @@ -26,7 +26,7 @@ #include #include -#include +#include #include #include "DeviceException.h" @@ -537,15 +537,15 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (this->variant) { case VARIANT_100_25: - return static_cast<::rl::math::Real>(0.25) * ::rl::math::DEG2RAD; + return static_cast<::rl::math::Real>(0.25) * ::rl::math::constants::deg2rad; break; case VARIANT_100_50: case VARIANT_180_50: - return static_cast<::rl::math::Real>(0.5) * ::rl::math::DEG2RAD; + return static_cast<::rl::math::Real>(0.5) * ::rl::math::constants::deg2rad; break; case VARIANT_100_100: case VARIANT_180_100: - return 1 * ::rl::math::DEG2RAD; + return 1 * ::rl::math::constants::deg2rad; break; default: break; @@ -564,7 +564,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; case VARIANT_100_25: case VARIANT_100_50: case VARIANT_100_100: - return 40 * ::rl::math::DEG2RAD; + return 40 * ::rl::math::constants::deg2rad; break; case VARIANT_180_50: case VARIANT_180_100: @@ -587,11 +587,11 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; case VARIANT_100_25: case VARIANT_100_50: case VARIANT_100_100: - return 140 * ::rl::math::DEG2RAD; + return 140 * ::rl::math::constants::deg2rad; break; case VARIANT_180_50: case VARIANT_180_100: - return 180 * ::rl::math::DEG2RAD; + return 180 * ::rl::math::constants::deg2rad; break; default: break; diff --git a/src/rl/hal/SickS300.cpp b/src/rl/hal/SickS300.cpp index cb0950d4..02afbb0c 100644 --- a/src/rl/hal/SickS300.cpp +++ b/src/rl/hal/SickS300.cpp @@ -26,7 +26,7 @@ #include #include -#include +#include #include #include "DeviceException.h" @@ -197,7 +197,7 @@ ::std::cerr << "Glare (dazzling) detected" << ::std::endl; { assert(this->isConnected()); - return -45 * ::rl::math::DEG2RAD; + return -45 * ::rl::math::constants::deg2rad; } ::rl::math::Real @@ -205,7 +205,7 @@ ::std::cerr << "Glare (dazzling) detected" << ::std::endl; { assert(this->isConnected()); - return 225 * ::rl::math::DEG2RAD; + return 225 * ::rl::math::constants::deg2rad; } ::std::size_t diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index a99576f3..4af02075 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -25,7 +25,6 @@ // #include -#include #include "DeviceException.h" #include "UniversalRobotsRealtime.h" diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index af72618f..19326f5f 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -26,6 +26,7 @@ #include #include +#include #include #include "DeviceException.h" @@ -116,10 +117,10 @@ namespace rl switch (i) { case 0: - return 0 == (this->output.analogIoTypes & 1) ? 20 * ::rl::math::MILLI2UNIT : 10; + return 0 == (this->output.analogIoTypes & 1) ? 20 * ::rl::math::constants::milli2unit : 10; break; case 1: - return 0 == (this->output.analogIoTypes & 2) ? 20 * ::rl::math::MILLI2UNIT : 10; + return 0 == (this->output.analogIoTypes & 2) ? 20 * ::rl::math::constants::milli2unit : 10; break; case 2: return 0 == (this->output.toolAnalogInputTypes & 1) ? 1 : 24; @@ -209,10 +210,10 @@ namespace rl switch (i) { case 0: - return 0 == (this->output.analogIoTypes & 4) ? 20 * ::rl::math::MILLI2UNIT : 10; + return 0 == (this->output.analogIoTypes & 4) ? 20 * ::rl::math::constants::milli2unit : 10; break; case 1: - return 0 == (this->output.analogIoTypes & 8) ? 20 * ::rl::math::MILLI2UNIT : 10; + return 0 == (this->output.analogIoTypes & 8) ? 20 * ::rl::math::constants::milli2unit : 10; break; case 2: return 24; diff --git a/src/rl/hal/WeissWsg50.cpp b/src/rl/hal/WeissWsg50.cpp index 66a507bd..a8575e79 100644 --- a/src/rl/hal/WeissWsg50.cpp +++ b/src/rl/hal/WeissWsg50.cpp @@ -28,7 +28,7 @@ #include #include #include -#include +#include //#define DEBUG_TCP_DATA @@ -214,7 +214,7 @@ namespace rl ::std::memcpy(&this->acceleration, &buf[this->HEADER_SIZE + 2], sizeof(this->acceleration)); - this->acceleration *= static_cast(::rl::math::MILLI2UNIT); + this->acceleration *= ::rl::math::Constants::milli2unit; } void @@ -313,8 +313,8 @@ namespace rl ::std::memcpy(&this->limitMinus, &buf[this->HEADER_SIZE + 2], sizeof(this->limitMinus)); ::std::memcpy(&this->limitPlus, &buf[this->HEADER_SIZE + 2 + 4], sizeof(this->limitPlus)); - this->limitMinus *= static_cast(::rl::math::MILLI2UNIT); - this->limitPlus *= static_cast(::rl::math::MILLI2UNIT); + this->limitMinus *= ::rl::math::Constants::milli2unit; + this->limitPlus *= ::rl::math::Constants::milli2unit; } void @@ -372,11 +372,11 @@ namespace rl ::std::memcpy(&this->forceNominal, &buf[32], sizeof(this->forceNominal)); ::std::memcpy(&this->forceOverdrive, &buf[36], sizeof(this->forceOverdrive)); - this->stroke *= static_cast(::rl::math::MILLI2UNIT); - this->speedMinimum *= static_cast(::rl::math::MILLI2UNIT); - this->speedMaximum *= static_cast(::rl::math::MILLI2UNIT); - this->accelerationMinimum *= static_cast(::rl::math::MILLI2UNIT); - this->accelerationMaximum *= static_cast(::rl::math::MILLI2UNIT); + this->stroke *= ::rl::math::Constants::milli2unit; + this->speedMinimum *= ::rl::math::Constants::milli2unit; + this->speedMaximum *= ::rl::math::Constants::milli2unit; + this->accelerationMinimum *= ::rl::math::Constants::milli2unit; + this->accelerationMaximum *= ::rl::math::Constants::milli2unit; } void @@ -426,8 +426,8 @@ namespace rl assert(width >= 0.0f && width <= 0.11f); assert(speed >= 0.0f && speed <= 0.4f); - float widthMilli = width * static_cast(::rl::math::UNIT2MILLI); - float speedMilli = speed * static_cast(::rl::math::UNIT2MILLI); + float widthMilli = width * ::rl::math::Constants::unit2milli; + float speedMilli = speed * ::rl::math::Constants::unit2milli; ::std::array<::std::uint8_t, 64> buf; @@ -483,8 +483,8 @@ namespace rl assert(width >= 0.0f && width <= 0.11f); assert(speed >= 0.0f && speed <= 0.4f); - float widthMilli = width * static_cast(::rl::math::UNIT2MILLI); - float speedMilli = speed * static_cast(::rl::math::UNIT2MILLI); + float widthMilli = width * ::rl::math::Constants::unit2milli; + float speedMilli = speed * ::rl::math::Constants::unit2milli; ::std::array<::std::uint8_t, 64> buf; @@ -516,8 +516,8 @@ namespace rl assert(width >= 0.0f && width <= 0.11f); assert(speed >= 0.005f && speed <= 0.4f); - float widthMilli = width * static_cast(::rl::math::UNIT2MILLI); - float speedMilli = speed * static_cast(::rl::math::UNIT2MILLI); + float widthMilli = width * ::rl::math::Constants::unit2milli; + float speedMilli = speed * ::rl::math::Constants::unit2milli; ::std::array<::std::uint8_t, 64> buf; @@ -535,7 +535,7 @@ namespace rl assert(this->isConnected()); assert(acceleration >= 0.1f && acceleration <= 5.0f); - float accelerationMilli = acceleration * static_cast(::rl::math::UNIT2MILLI); + float accelerationMilli = acceleration * ::rl::math::Constants::unit2milli; ::std::array<::std::uint8_t, 64> buf; @@ -570,8 +570,8 @@ namespace rl { assert(this->isConnected()); - float limitMinusMilli = limitMinus * static_cast(::rl::math::UNIT2MILLI); - float limitPlusMilli = limitPlus * static_cast(::rl::math::UNIT2MILLI); + float limitMinusMilli = limitMinus * ::rl::math::Constants::unit2milli; + float limitPlusMilli = limitPlus * ::rl::math::Constants::unit2milli; ::std::array<::std::uint8_t, 64> buf; @@ -790,11 +790,11 @@ namespace rl break; case 0x43: ::std::memcpy(&this->openingWidth, &buf[8], sizeof(this->openingWidth)); - this->openingWidth *= static_cast(::rl::math::MILLI2UNIT); + this->openingWidth *= ::rl::math::Constants::milli2unit; break; case 0x44: ::std::memcpy(&this->speed, &buf[8], sizeof(this->speed)); - this->speed *= static_cast(::rl::math::MILLI2UNIT); + this->speed *= ::rl::math::Constants::milli2unit; break; case 0x45: this->force = *reinterpret_cast(&buf[8]); diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 823cc4db..a02aab8a 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -25,8 +25,8 @@ // #include +#include #include -#include #include #include #include @@ -198,13 +198,13 @@ namespace rl f->frame.setIdentity(); f->frame = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitX() ); @@ -231,13 +231,13 @@ namespace rl f->frame.setIdentity(); f->frame = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitX() ); @@ -349,8 +349,8 @@ namespace rl p->theta = path.eval("number(dh/theta)").getValue<::rl::math::Real>(0); p->wraparound = path.eval("count(wraparound) > 0").getValue(); - p->alpha *= ::rl::math::DEG2RAD; - p->theta *= ::rl::math::DEG2RAD; + p->alpha *= ::rl::math::constants::deg2rad; + p->theta *= ::rl::math::constants::deg2rad; kinematics->tree[e].reset(p); } @@ -370,12 +370,12 @@ namespace rl r->theta = path.eval("number(dh/theta)").getValue<::rl::math::Real>(0); r->wraparound = path.eval("count(wraparound) > 0").getValue(); - r->alpha *= ::rl::math::DEG2RAD; - r->max *= ::rl::math::DEG2RAD; - r->min *= ::rl::math::DEG2RAD; - r->offset *= ::rl::math::DEG2RAD; - r->speed *= ::rl::math::DEG2RAD; - r->theta *= ::rl::math::DEG2RAD; + r->alpha *= ::rl::math::constants::deg2rad; + r->max *= ::rl::math::constants::deg2rad; + r->min *= ::rl::math::constants::deg2rad; + r->offset *= ::rl::math::constants::deg2rad; + r->speed *= ::rl::math::constants::deg2rad; + r->theta *= ::rl::math::constants::deg2rad; kinematics->tree[e].reset(r); } @@ -388,13 +388,13 @@ namespace rl t->transform.setIdentity(); t->transform = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitX() ); diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index 45722ef8..1fd17701 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -25,8 +25,8 @@ // #include +#include #include -#include #include "Frame.h" #include "Joint.h" @@ -83,12 +83,12 @@ namespace rl && this->joints[4]->a == 0 && this->joints[5]->a == 0 && this->joints[4]->d == 0); - assert(::std::abs(this->joints[0]->alpha - (-::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5)) < 1e-3 - && ::std::abs(this->joints[1]->alpha ) < 1e-3 - && ::std::abs(this->joints[2]->alpha - (-::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5)) < 1e-3 - && ::std::abs(this->joints[3]->alpha - ( ::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5)) < 1e-3 - && ::std::abs(this->joints[4]->alpha - ( ::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5)) < 1e-3 - && ::std::abs(this->joints[5]->alpha ) < 1e-3); + assert(::std::abs(this->joints[0]->alpha - (-::rl::math::constants::pi * 0.5)) < 1e-3 + && ::std::abs(this->joints[1]->alpha ) < 1e-3 + && ::std::abs(this->joints[2]->alpha - (-::rl::math::constants::pi * 0.5)) < 1e-3 + && ::std::abs(this->joints[3]->alpha - ( ::rl::math::constants::pi * 0.5)) < 1e-3 + && ::std::abs(this->joints[4]->alpha - ( ::rl::math::constants::pi * 0.5)) < 1e-3 + && ::std::abs(this->joints[5]->alpha ) < 1e-3); ::rl::math::Real a1 = this->joints[0]->a; ::rl::math::Real a2 = this->joints[1]->a; @@ -195,10 +195,10 @@ namespace rl ::rl::math::Real theta3plusbeta = ::std::acos(costheta3plusbeta); // elbow - ::rl::math::Real theta3 = K * theta3plusbeta - beta - ::rl::math::TypeTraits<::rl::math::Real>::pi; + ::rl::math::Real theta3 = K * theta3plusbeta - beta - ::rl::math::constants::pi; - ::rl::math::Real c23 = this->cos(theta2 + theta3 + ::rl::math::TypeTraits<::rl::math::Real>::pi); - ::rl::math::Real s23 = this->sin(theta2 + theta3 + ::rl::math::TypeTraits<::rl::math::Real>::pi); + ::rl::math::Real c23 = this->cos(theta2 + theta3 + ::rl::math::constants::pi); + ::rl::math::Real s23 = this->sin(theta2 + theta3 + ::rl::math::constants::pi); // forearm @@ -226,7 +226,7 @@ namespace rl c1 * s23 * a(0) + s1 * s23 * a(1) + c23 * a(2) - ) + ::rl::math::TypeTraits<::rl::math::Real>::pi; + ) + ::rl::math::constants::pi; // flange @@ -275,9 +275,9 @@ namespace rl { myq(i) = q(i) + this->joints[i]->theta + this->joints[i]->offset; myq(i) = ::std::fmod( - myq(i) + ::rl::math::TypeTraits<::rl::math::Real>::pi, - 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi - ) - ::rl::math::TypeTraits<::rl::math::Real>::pi; + myq(i) + ::rl::math::constants::pi, + 2 * ::rl::math::constants::pi + ) - ::rl::math::constants::pi; } if (myq(4) < 0) diff --git a/src/rl/kin/Revolute.cpp b/src/rl/kin/Revolute.cpp index f7e1faf0..0c48c95a 100644 --- a/src/rl/kin/Revolute.cpp +++ b/src/rl/kin/Revolute.cpp @@ -24,7 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include +#include #include #include "Link.h" @@ -80,15 +80,15 @@ namespace rl void Revolute::normalize(::rl::math::Real& q) { - q = ::std::remainder(q, 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi); + q = ::std::remainder(q, 2 * ::rl::math::constants::pi); if (q < this->min) { - q += 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi; + q += 2 * ::rl::math::constants::pi; } else if (q > this->max) { - q -= 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi; + q -= 2 * ::rl::math::constants::pi; } } diff --git a/src/rl/kin/Rhino.cpp b/src/rl/kin/Rhino.cpp index 51fb2550..94025546 100644 --- a/src/rl/kin/Rhino.cpp +++ b/src/rl/kin/Rhino.cpp @@ -25,8 +25,8 @@ // #include +#include #include -#include #include "Frame.h" #include "Joint.h" @@ -139,13 +139,13 @@ namespace rl ::rl::math::Real c2 = cosAlpha * cosBeta - K * sinAlpha * sinBeta; // arm - ::rl::math::Real theta2 = this->atan2(s2, c2) + ::rl::math::TypeTraits<::rl::math::Real>::pi * 0.5; + ::rl::math::Real theta2 = this->atan2(s2, c2) + ::rl::math::constants::pi * 0.5; ::rl::math::Real c3 = (a2_2 + a3_2 - Q_2) / (2 * a2 * a3); ::rl::math::Real s3 = K * ::std::sqrt(1 - ::std::pow(c3, 2)); // elbow - ::rl::math::Real theta3 = this->atan2(s3, c3) + ::rl::math::TypeTraits<::rl::math::Real>::pi; + ::rl::math::Real theta3 = this->atan2(s3, c3) + ::rl::math::constants::pi; ::rl::math::Real c23 = this->cos(theta2 + theta3); ::rl::math::Real s23 = this->sin(theta2 + theta3); diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index a73af920..9aa50216 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -9,6 +9,7 @@ set( Circular.h CircularVector2.h CircularVector3.h + Constants.h Function.h GnatNearestNeighbors.h Kalman.h diff --git a/src/rl/math/CircularVector2.h b/src/rl/math/CircularVector2.h index e45c50de..377c26f9 100644 --- a/src/rl/math/CircularVector2.h +++ b/src/rl/math/CircularVector2.h @@ -38,9 +38,9 @@ #include #include "Circular.h" +#include "Constants.h" #include "Function.h" #include "Matrix.h" -#include "TypeTraits.h" #include "Vector.h" namespace rl @@ -101,7 +101,7 @@ namespace rl if (f.angle < 0) { - f.angle += 2 * TypeTraits::pi; + f.angle += 2 * Constants::pi; } f.x1 = x1; diff --git a/src/rl/math/Constants.h b/src/rl/math/Constants.h new file mode 100644 index 00000000..a5d4fd71 --- /dev/null +++ b/src/rl/math/Constants.h @@ -0,0 +1,159 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MATH_CONSTANTS_H +#define RL_MATH_CONSTANTS_H + +#include + +#include "Real.h" + +namespace rl +{ + namespace math + { + template::value>::type> + class Constants + { + public: + static constexpr T e = static_cast(2.718281828459045235360287471352662498L); + + static constexpr T log2e = static_cast(1.442695040888963407359924681001892137L); + + static constexpr T log10e = static_cast(0.434294481903251827651128918916605082L); + + static constexpr T pi = static_cast(3.141592653589793238462643383279502884L); + + static constexpr T inv_pi = static_cast(0.318309886183790671537767526745028724L); + + static constexpr T inv_sqrtpi = static_cast(0.564189583547756286948079451560772586L); + + static constexpr T ln2 = static_cast(0.693147180559945309417232121458176568L); + + static constexpr T ln10 = static_cast(2.302585092994045684017991454684364208L); + + static constexpr T sqrt2 = static_cast(1.414213562373095048801688724209698079L); + + static constexpr T sqrt3 = static_cast(1.732050807568877293527446341505872367L); + + static constexpr T inv_sqrt3 = static_cast(0.577350269189625764509148780501957456L); + + static constexpr T egamma = static_cast(0.577215664901532860606512090082402431L); + + static constexpr T phi = static_cast(1.618033988749894848204586834365638118L); + + /** + * Standard acceleration due to gravity. + * + * [Standard gravity](https://en.wikipedia.org/wiki/Standard_gravity) is the nominal + * [gravitational acceleration](https://en.wikipedia.org/wiki/Gravitational_acceleration) + * of an object in a vacuum near the surface of the earth. It is defined as 9.80665 m · s-2 + * by [ISO 80000-3](https://en.wikipedia.org/wiki/ISO_80000-3). + */ + static constexpr T gravity = static_cast(9.80665); + + /** + * Constant for converting an angular value in + * [degree](https://en.wikipedia.org/wiki/Degree_(angle)) to + * [radian](https://en.wikipedia.org/wiki/Radian). + * + * This is equal to a multiplication by π and a division by 180. + */ + static constexpr T deg2rad = pi / static_cast(180); + + /** + * Constant for converting an angular value in + * [radian](https://en.wikipedia.org/wiki/Radian) to + * [degree](https://en.wikipedia.org/wiki/Degree_(angle)). + * + * This is equal to a multiplication by 180 and a division by π. + */ + static constexpr T rad2deg = static_cast(180) / pi; + + static constexpr T giga2unit = static_cast(1.0e+9); + + static constexpr T kilo2unit = static_cast(1.0e+3); + + static constexpr T mega2unit = static_cast(1.0e+6); + + static constexpr T micro2unit = static_cast(1.0e-6); + + static constexpr T milli2unit = static_cast(1.0e-3); + + static constexpr T nano2unit = static_cast(1.0e-9); + + static constexpr T unit2giga = static_cast(1.0e-9); + + static constexpr T unit2kilo = static_cast(1.0e-3); + + static constexpr T unit2mega = static_cast(1.0e-6); + + static constexpr T unit2micro = static_cast(1.0e+6); + + static constexpr T unit2milli = static_cast(1.0e+3); + + static constexpr T unit2nano = static_cast(1.0e+9); + + protected: + + private: + + }; + + template constexpr T Constants::e; + template constexpr T Constants::log2e; + template constexpr T Constants::log10e; + template constexpr T Constants::pi; + template constexpr T Constants::inv_pi; + template constexpr T Constants::inv_sqrtpi; + template constexpr T Constants::ln2; + template constexpr T Constants::ln10; + template constexpr T Constants::sqrt2; + template constexpr T Constants::sqrt3; + template constexpr T Constants::inv_sqrt3; + template constexpr T Constants::egamma; + template constexpr T Constants::phi; + template constexpr T Constants::gravity; + template constexpr T Constants::deg2rad; + template constexpr T Constants::rad2deg; + template constexpr T Constants::giga2unit; + template constexpr T Constants::kilo2unit; + template constexpr T Constants::mega2unit; + template constexpr T Constants::micro2unit; + template constexpr T Constants::milli2unit; + template constexpr T Constants::nano2unit; + template constexpr T Constants::unit2giga; + template constexpr T Constants::unit2kilo; + template constexpr T Constants::unit2mega; + template constexpr T Constants::unit2micro; + template constexpr T Constants::unit2milli; + template constexpr T Constants::unit2nano; + + typedef Constants constants; + } +} + +#endif // RL_MATH_CONSTANTS_H diff --git a/src/rl/math/LowPass.h b/src/rl/math/LowPass.h index 1039cca8..b23984fd 100644 --- a/src/rl/math/LowPass.h +++ b/src/rl/math/LowPass.h @@ -27,8 +27,8 @@ #ifndef RL_MATH_LOWPASS_H #define RL_MATH_LOWPASS_H +#include "Constants.h" #include "Real.h" -#include "TypeTraits.h" namespace rl { @@ -51,7 +51,7 @@ namespace rl static LowPass Frequency(const Real& frequency, const Real& dt, const T& y = T()) { - Real rc = 1 / (2 * TypeTraits::pi * frequency); + Real rc = 1 / (2 * Constants::pi * frequency); Real alpha = dt / (rc + dt); return LowPass(alpha, dt, rc, y); } diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index 7c30473f..cf623a3e 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -42,6 +42,7 @@ #include #endif // HAVE_EIGEN_UNSUPPORTED +#include "Constants.h" #include "Function.h" #include "Matrix.h" #include "TypeTraits.h" @@ -600,8 +601,8 @@ namespace rl Real tmp2 = ::std::acos((3 * q) / (2 * p) * ::std::sqrt(-3 / p)) / 3; ::std::vector roots(3); roots[0] = tmp1 * ::std::cos(tmp2) - back; - roots[1] = tmp1 * ::std::cos(tmp2 - 2 * TypeTraits::pi / 3) - back; - roots[2] = tmp1 * ::std::cos(tmp2 - 4 * TypeTraits::pi / 3) - back; + roots[1] = tmp1 * ::std::cos(tmp2 - 2 * Constants::pi / 3) - back; + roots[2] = tmp1 * ::std::cos(tmp2 - 4 * Constants::pi / 3) - back; return roots; } else diff --git a/src/rl/math/TypeTraits.h b/src/rl/math/TypeTraits.h index dd9eef55..2f24ef95 100644 --- a/src/rl/math/TypeTraits.h +++ b/src/rl/math/TypeTraits.h @@ -209,32 +209,6 @@ namespace rl return 1; } - static constexpr T e = T(2.718281828459045235360287471352662498L); - - static constexpr T log2e = T(1.442695040888963407359924681001892137L); - - static constexpr T log10e = T(0.434294481903251827651128918916605082L); - - static constexpr T pi = T(3.141592653589793238462643383279502884L); - - static constexpr T inv_pi = T(0.318309886183790671537767526745028724L); - - static constexpr T inv_sqrtpi = T(0.564189583547756286948079451560772586L); - - static constexpr T ln2 = T(0.693147180559945309417232121458176568L); - - static constexpr T ln10 = T(2.302585092994045684017991454684364208L); - - static constexpr T sqrt2 = T(1.414213562373095048801688724209698079L); - - static constexpr T sqrt3 = T(1.732050807568877293527446341505872367L); - - static constexpr T inv_sqrt3 = T(0.577350269189625764509148780501957456L); - - static constexpr T egamma = T(0.577215664901532860606512090082402431L); - - static constexpr T phi = T(1.618033988749894848204586834365638118L); - protected: private: diff --git a/src/rl/math/Unit.h b/src/rl/math/Unit.h index c255eea5..ec49226d 100644 --- a/src/rl/math/Unit.h +++ b/src/rl/math/Unit.h @@ -27,8 +27,14 @@ #ifndef RL_MATH_UNIT_H #define RL_MATH_UNIT_H +#include "Constants.h" #include "Real.h" -#include "TypeTraits.h" + +#if defined(__GNUC__) || defined(__clang__) +#define RL_MATH_DEPRECATED __attribute__ ((__deprecated__)) +#elif defined(_MSC_VER) +#define RL_MATH_DEPRECATED __declspec(deprecated) +#endif namespace rl { @@ -330,57 +336,35 @@ namespace rl UNIT_NEWTON_METER_SECOND }; - /** - * Constant for converting an angular value in - * [degree](https://en.wikipedia.org/wiki/Degree_(angle)) to - * [radian](https://en.wikipedia.org/wiki/Radian). - * - * This is equal to a multiplication by π and a division by 180. - */ - static const Real DEG2RAD = TypeTraits::pi / static_cast(180); + RL_MATH_DEPRECATED constexpr Real DEG2RAD = constants::deg2rad; - static const Real GIGA2UNIT = static_cast(1.0e+9); + RL_MATH_DEPRECATED constexpr Real GIGA2UNIT = constants::giga2unit; - /** - * Standard acceleration due to gravity. - * - * [Standard gravity](https://en.wikipedia.org/wiki/Standard_gravity) is the nominal - * [gravitational acceleration](https://en.wikipedia.org/wiki/Gravitational_acceleration) - * of an object in a vacuum near the surface of the earth. It is defined as 9.80665 m · s-2 - * by [ISO 80000-3](https://en.wikipedia.org/wiki/ISO_80000-3). - */ - static const Real GRAVITY = static_cast(9.80665); + RL_MATH_DEPRECATED constexpr Real GRAVITY = constants::gravity; - static const Real KILO2UNIT = static_cast(1.0e+3); + RL_MATH_DEPRECATED constexpr Real KILO2UNIT = constants::kilo2unit; - static const Real MEGA2UNIT = static_cast(1.0e+6); + RL_MATH_DEPRECATED constexpr Real MEGA2UNIT = constants::mega2unit; - static const Real MICRO2UNIT = static_cast(1.0e-6); + RL_MATH_DEPRECATED constexpr Real MICRO2UNIT = constants::micro2unit; - static const Real MILLI2UNIT = static_cast(1.0e-3); + RL_MATH_DEPRECATED constexpr Real MILLI2UNIT = constants::milli2unit; - static const Real NANO2UNIT = static_cast(1.0e-9); + RL_MATH_DEPRECATED constexpr Real NANO2UNIT = constants::nano2unit; - /** - * Constant for converting an angular value in - * [radian](https://en.wikipedia.org/wiki/Radian) to - * [degree](https://en.wikipedia.org/wiki/Degree_(angle)). - * - * This is equal to a multiplication by 180 and a division by π. - */ - static const Real RAD2DEG = static_cast(180) / TypeTraits::pi; + RL_MATH_DEPRECATED constexpr Real RAD2DEG = constants::rad2deg; - static const Real UNIT2GIGA = static_cast(1.0e-9); + RL_MATH_DEPRECATED constexpr Real UNIT2GIGA = constants::unit2giga; - static const Real UNIT2KILO = static_cast(1.0e-3); + RL_MATH_DEPRECATED constexpr Real UNIT2KILO = constants::unit2kilo; - static const Real UNIT2MEGA = static_cast(1.0e-6); + RL_MATH_DEPRECATED constexpr Real UNIT2MEGA = constants::unit2mega; - static const Real UNIT2MICRO = static_cast(1.0e+6); + RL_MATH_DEPRECATED constexpr Real UNIT2MICRO = constants::unit2micro; - static const Real UNIT2MILLI = static_cast(1.0e+3); + RL_MATH_DEPRECATED constexpr Real UNIT2MILLI = constants::unit2milli; - static const Real UNIT2NANO = static_cast(1.0e+9); + RL_MATH_DEPRECATED constexpr Real UNIT2NANO = constants::unit2nano; } } diff --git a/src/rl/mdl/Dynamic.cpp b/src/rl/mdl/Dynamic.cpp index 8c382c3f..37b08ec8 100644 --- a/src/rl/mdl/Dynamic.cpp +++ b/src/rl/mdl/Dynamic.cpp @@ -30,7 +30,6 @@ #include #include #include -#include #include "EulerCauchyIntegrator.h" #include "Exception.h" diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 8314554f..88101be1 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -30,7 +30,6 @@ #include #include #include -#include #include "Exception.h" #include "JacobianInverseKinematics.h" diff --git a/src/rl/mdl/Revolute.cpp b/src/rl/mdl/Revolute.cpp index bf902e77..39a15286 100644 --- a/src/rl/mdl/Revolute.cpp +++ b/src/rl/mdl/Revolute.cpp @@ -24,8 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include #include -#include #include "Revolute.h" @@ -107,15 +107,15 @@ namespace rl void Revolute::normalize(::rl::math::VectorRef q) const { - q(0) = ::std::remainder(q(0), 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi); + q(0) = ::std::remainder(q(0), 2 * ::rl::math::constants::pi); if (q(0) < this->min(0)) { - q(0) += 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi; + q(0) += 2 * ::rl::math::constants::pi; } else if (q(0) > this->max(0)) { - q(0) -= 2 * ::rl::math::TypeTraits<::rl::math::Real>::pi; + q(0) -= 2 * ::rl::math::constants::pi; } } diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 08e70767..74b5bb18 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -28,9 +28,9 @@ #include #include #include +#include #include #include -#include #include #include #include @@ -211,7 +211,7 @@ ::std::cout << "\tchild: " << child->getName() << ::std::endl; fixed->x.translation().z() = ::boost::lexical_cast<::rl::math::Real>(xyz[2]); } ::std::cout << "\torigin.translation: " << fixed->x.translation().transpose() << ::std::endl; -::std::cout << "\torigin.rotation: " << fixed->x.linear().eulerAngles(2, 1, 0).reverse().transpose() * ::rl::math::RAD2DEG << ::std::endl; +::std::cout << "\torigin.rotation: " << fixed->x.linear().eulerAngles(2, 1, 0).reverse().transpose() * ::rl::math::constants::rad2deg << ::std::endl; // joint @@ -284,8 +284,8 @@ ::std::cout << "\tname: " << p->getName() << ::std::endl; if ("continuous" == path.eval("string(@type)").getValue<::std::string>()) { - r->max(0) = 180 * ::rl::math::DEG2RAD; - r->min(0) = -180 * ::rl::math::DEG2RAD; + r->max(0) = 180 * ::rl::math::constants::deg2rad; + r->min(0) = -180 * ::rl::math::constants::deg2rad; r->wraparound(0) = true; } else @@ -294,12 +294,12 @@ ::std::cout << "\tname: " << p->getName() << ::std::endl; r->min(0) = path.eval("number(limit/@lower)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); r->wraparound(0) = false; } -::std::cout << "\tmax: " << r->max(0) * ::rl::math::RAD2DEG << ::std::endl; -::std::cout << "\tmin: " << r->min(0) * ::rl::math::RAD2DEG << ::std::endl; +::std::cout << "\tmax: " << r->max(0) * ::rl::math::constants::rad2deg << ::std::endl; +::std::cout << "\tmin: " << r->min(0) * ::rl::math::constants::rad2deg << ::std::endl; r->offset(0) = 0; r->speed(0) = path.eval("number(limit/@velocity)").getValue<::rl::math::Real>(0); -::std::cout << "\tspeed: " << r->speed(0) * ::rl::math::RAD2DEG << ::std::endl; +::std::cout << "\tspeed: " << r->speed(0) * ::rl::math::constants::rad2deg << ::std::endl; if (path.eval("count(axis/@xyz) > 0").getValue()) { diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index 1687926d..c89f4dcb 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -26,9 +26,9 @@ #include #include +#include #include #include -#include #include #include #include @@ -160,13 +160,13 @@ namespace rl model->add(w); w->x.linear() = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitX() ).toRotationMatrix(); @@ -306,13 +306,13 @@ namespace rl model->add(f, a, b); f->x.linear() = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::DEG2RAD, + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitX() ).toRotationMatrix(); @@ -380,10 +380,10 @@ namespace rl r->S(1, 0) = path.eval("number(axis/y)").getValue<::rl::math::Real>(0); r->S(2, 0) = path.eval("number(axis/z)").getValue<::rl::math::Real>(1); - r->max *= ::rl::math::DEG2RAD; - r->min *= ::rl::math::DEG2RAD; - r->offset *= ::rl::math::DEG2RAD; - r->speed *= ::rl::math::DEG2RAD; + r->max *= ::rl::math::constants::deg2rad; + r->min *= ::rl::math::constants::deg2rad; + r->offset *= ::rl::math::constants::deg2rad; + r->speed *= ::rl::math::constants::deg2rad; transform = r; } @@ -442,7 +442,7 @@ namespace rl if ("deg" == home[j].getProperty("unit")) { - q(j) *= ::rl::math::DEG2RAD; + q(j) *= ::rl::math::constants::deg2rad; } } diff --git a/src/rl/plan/Eet.cpp b/src/rl/plan/Eet.cpp index b42436df..7ef07bc4 100644 --- a/src/rl/plan/Eet.cpp +++ b/src/rl/plan/Eet.cpp @@ -27,7 +27,6 @@ #include #include #include -#include #include "DistanceModel.h" #include "Eet.h" diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 38ba55e5..f20de20f 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -43,9 +43,9 @@ #include #include #include +#include #include #include -#include #include #include #include @@ -402,7 +402,7 @@ ::std::cout << "\torigin rpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << : if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLCylinder::getClassTypeId())) { - origin *= ::rl::math::AngleAxis(90 * ::rl::math::DEG2RAD, ::rl::math::Vector3::UnitX()); + origin *= ::rl::math::AngleAxis(90 * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitX()); } if (path.eval("count(origin/@xyz) > 0").getValue()) diff --git a/tests/rlCircularTest/rlCircularTest.cpp b/tests/rlCircularTest/rlCircularTest.cpp index 7804ed44..974cd997 100644 --- a/tests/rlCircularTest/rlCircularTest.cpp +++ b/tests/rlCircularTest/rlCircularTest.cpp @@ -30,7 +30,6 @@ #include #include #include -#include #include template diff --git a/tests/rlCollisionTest/rlCollisionTest.cpp b/tests/rlCollisionTest/rlCollisionTest.cpp index 40d76cba..da46df5b 100644 --- a/tests/rlCollisionTest/rlCollisionTest.cpp +++ b/tests/rlCollisionTest/rlCollisionTest.cpp @@ -30,6 +30,7 @@ #include #include +#include #include #include #include @@ -113,7 +114,7 @@ main(int argc, char** argv) for (std::size_t i = 0; i < kinematics->getDof(); ++i) { - q(i) = boost::lexical_cast(argv[i + 3]) * rl::math::DEG2RAD; + q(i) = boost::lexical_cast(argv[i + 3]) * rl::math::constants::deg2rad; } std::cout << "Set joint angle [rad] " << q.transpose() << std::endl; @@ -167,7 +168,7 @@ main(int argc, char** argv) } std::mt19937 randomGenerator(0); - std::uniform_real_distribution randomDistribution(-180 * rl::math::DEG2RAD, 180 * rl::math::DEG2RAD); + std::uniform_real_distribution randomDistribution(-180 * rl::math::constants::deg2rad, 180 * rl::math::constants::deg2rad); std::size_t j; for (j = 0; j < 10; ++j) @@ -196,7 +197,7 @@ main(int argc, char** argv) if ((results.array() == false).any() && (results.array() == true).any()) { std::cerr << "Error: Counterexample " << j << ": SimpleScene::isColliding() Joint angle [rad] " << q.transpose(); - std::cerr << " [deg] " << q.transpose() * rl::math::RAD2DEG << " "; + std::cerr << " [deg] " << q.transpose() * rl::math::constants::rad2deg << " "; for (std::size_t i = 0; i < scenes.size(); ++i) { std::cerr << " " << sceneNames[i] << "=" << results[i]; diff --git a/tests/rlEetTest/rlEetTest.cpp b/tests/rlEetTest/rlEetTest.cpp index af765b6b..5fff3790 100644 --- a/tests/rlEetTest/rlEetTest.cpp +++ b/tests/rlEetTest/rlEetTest.cpp @@ -28,7 +28,7 @@ #include #include #include -#include +#include #include #include #include @@ -106,7 +106,7 @@ main(int argc, char** argv) if (rl::math::UNIT_RADIAN == qUnits(i)) { - start(i) *= rl::math::DEG2RAD; + start(i) *= rl::math::constants::deg2rad; } } @@ -118,7 +118,7 @@ main(int argc, char** argv) if (rl::math::UNIT_RADIAN == qUnits(i)) { - goal(i) *= rl::math::DEG2RAD; + goal(i) *= rl::math::constants::deg2rad; } } @@ -156,7 +156,7 @@ main(int argc, char** argv) planner.alpha = static_cast(0.01); planner.alternativeDistanceComputation = false; planner.beta = 0; - planner.delta = 1 * rl::math::DEG2RAD; + planner.delta = 1 * rl::math::constants::deg2rad; planner.distanceWeight = static_cast(0.1); planner.epsilon = static_cast(1.0e-9); planner.explorers.push_back(&explorer); diff --git a/tests/rlJacobianKinTest/rlJacobianKinTest.cpp b/tests/rlJacobianKinTest/rlJacobianKinTest.cpp index b266d9b2..36f1d0d7 100644 --- a/tests/rlJacobianKinTest/rlJacobianKinTest.cpp +++ b/tests/rlJacobianKinTest/rlJacobianKinTest.cpp @@ -29,8 +29,8 @@ #include #include #include +#include #include -#include int main(int argc, char** argv) @@ -52,7 +52,7 @@ main(int argc, char** argv) for (std::size_t i = 0; i < dof; ++i) { rl::math::Real r = static_cast(std::rand()) / static_cast(RAND_MAX); - q(i) = (r - 0.5) * 360 * rl::math::DEG2RAD; + q(i) = (r - 0.5) * 360 * rl::math::constants::deg2rad; } kinematics->setPosition(q); diff --git a/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp b/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp index 543bcf77..5ffa9e94 100644 --- a/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp +++ b/tests/rlJacobianMdlTest/rlJacobianMdlTest.cpp @@ -28,8 +28,8 @@ #include #include #include +#include #include -#include #include #include @@ -55,7 +55,7 @@ main(int argc, char** argv) for (std::size_t i = 0; i < dof; ++i) { rl::math::Real r = static_cast(std::rand()) / static_cast(RAND_MAX); - q(i) = (r - 0.5) * 360 * rl::math::DEG2RAD; + q(i) = (r - 0.5) * 360 * rl::math::constants::deg2rad; } kinematics->setPosition(q); diff --git a/tests/rlMathDeltaTest/rlMathDeltaTest.cpp b/tests/rlMathDeltaTest/rlMathDeltaTest.cpp index a50e4ba7..3516be6e 100644 --- a/tests/rlMathDeltaTest/rlMathDeltaTest.cpp +++ b/tests/rlMathDeltaTest/rlMathDeltaTest.cpp @@ -27,10 +27,9 @@ #include #include #include +#include #include #include -#include -#include #include int @@ -50,16 +49,16 @@ main(int argc, char** argv) rotation = 0.1; break; case 2: - rotation = rl::math::TypeTraits::pi * 0.5; + rotation = rl::math::constants::pi * 0.5; break; case 3: - rotation = rl::math::TypeTraits::pi; + rotation = rl::math::constants::pi; break; case 4: - rotation = 2 * rl::math::TypeTraits::pi; + rotation = 2 * rl::math::constants::pi; break; default: - rotation = -rl::math::TypeTraits::pi * 0.5; + rotation = -rl::math::constants::pi * 0.5; break; } diff --git a/tests/rlPrmTest/rlPrmTest.cpp b/tests/rlPrmTest/rlPrmTest.cpp index e40c4c9d..e3c66499 100644 --- a/tests/rlPrmTest/rlPrmTest.cpp +++ b/tests/rlPrmTest/rlPrmTest.cpp @@ -28,7 +28,7 @@ #include #include #include -#include +#include #include #include #include @@ -109,13 +109,13 @@ main(int argc, char** argv) rl::math::Transform world = rl::math::Transform::Identity(); world = rl::math::AngleAxis( - boost::lexical_cast(argv[11]) * ::rl::math::DEG2RAD, + boost::lexical_cast(argv[11]) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( - boost::lexical_cast(argv[10]) * ::rl::math::DEG2RAD, + boost::lexical_cast(argv[10]) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitY() ) * ::rl::math::AngleAxis( - boost::lexical_cast(argv[9]) * ::rl::math::DEG2RAD, + boost::lexical_cast(argv[9]) * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitX() ); @@ -144,14 +144,14 @@ main(int argc, char** argv) sampler.model = &model; - verifier.delta = 1 * rl::math::DEG2RAD; + verifier.delta = 1 * rl::math::constants::deg2rad; verifier.model = &model; rl::math::Vector start(kinematic->getDofPosition()); for (std::ptrdiff_t i = 0; i < start.size(); ++i) { - start(i) = boost::lexical_cast(argv[i + 12]) * rl::math::DEG2RAD; + start(i) = boost::lexical_cast(argv[i + 12]) * rl::math::constants::deg2rad; } planner.start = &start; @@ -160,7 +160,7 @@ main(int argc, char** argv) for (std::ptrdiff_t i = 0; i < goal.size(); ++i) { - goal(i) = boost::lexical_cast(argv[start.size() + i + 12]) * rl::math::DEG2RAD; + goal(i) = boost::lexical_cast(argv[start.size() + i + 12]) * rl::math::constants::deg2rad; } planner.goal = &goal; From daf2eadad424c176f59b0ba837f71519e1a3d8d8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 3 Jul 2020 19:14:05 +0200 Subject: [PATCH 398/546] Use enum class for units --- demos/rlCoachKin/ConfigurationDelegate.cpp | 4 +- demos/rlCoachKin/ConfigurationModel.cpp | 12 +- demos/rlCoachMdl/ConfigurationDelegate.cpp | 4 +- demos/rlCoachMdl/ConfigurationModel.cpp | 12 +- demos/rlPlanDemo/ConfigurationDelegate.cpp | 4 +- demos/rlPlanDemo/ConfigurationModel.cpp | 8 +- demos/rlSimulator/ConfigurationDelegate.cpp | 12 +- demos/rlSimulator/ConfigurationModel.cpp | 24 +- src/rl/hal/AnalogInput.h | 6 +- src/rl/hal/AnalogOutput.h | 6 +- src/rl/hal/UniversalRobotsRtde.cpp | 42 +-- src/rl/hal/UniversalRobotsRtde.h | 12 +- src/rl/kin/Joint.h | 6 +- src/rl/kin/Kinematics.cpp | 4 +- src/rl/kin/Kinematics.h | 6 +- src/rl/kin/Prismatic.cpp | 8 +- src/rl/kin/Prismatic.h | 4 +- src/rl/kin/Revolute.cpp | 8 +- src/rl/kin/Revolute.h | 4 +- src/rl/math/CMakeLists.txt | 1 + src/rl/math/Unit.h | 340 +++----------------- src/rl/math/Units.h | 332 +++++++++++++++++++ src/rl/mdl/Cylindrical.cpp | 20 +- src/rl/mdl/Helical.cpp | 10 +- src/rl/mdl/Joint.cpp | 10 +- src/rl/mdl/Joint.h | 22 +- src/rl/mdl/Model.cpp | 20 +- src/rl/mdl/Model.h | 12 +- src/rl/mdl/Prismatic.cpp | 10 +- src/rl/mdl/Revolute.cpp | 10 +- src/rl/mdl/SixDof.cpp | 62 ++-- src/rl/mdl/Spherical.cpp | 32 +- src/rl/plan/Model.cpp | 4 +- src/rl/plan/Model.h | 2 +- tests/rlEetTest/rlEetTest.cpp | 6 +- 35 files changed, 581 insertions(+), 498 deletions(-) create mode 100644 src/rl/math/Units.h diff --git a/demos/rlCoachKin/ConfigurationDelegate.cpp b/demos/rlCoachKin/ConfigurationDelegate.cpp index e66e7d8a..7573830b 100644 --- a/demos/rlCoachKin/ConfigurationDelegate.cpp +++ b/demos/rlCoachKin/ConfigurationDelegate.cpp @@ -50,12 +50,12 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& MainWindow::instance()->kinematicModels[this->id]->getMaximum(maximum); rl::math::Vector minimum(MainWindow::instance()->kinematicModels[this->id]->getDof()); MainWindow::instance()->kinematicModels[this->id]->getMinimum(minimum); - Eigen::Matrix qUnits(MainWindow::instance()->kinematicModels[this->id]->getDof()); + Eigen::Matrix qUnits(MainWindow::instance()->kinematicModels[this->id]->getDof()); MainWindow::instance()->kinematicModels[this->id]->getPositionUnits(qUnits); Eigen::Matrix wraparounds(MainWindow::instance()->kinematicModels[this->id]->getDof()); MainWindow::instance()->kinematicModels[this->id]->getWraparounds(wraparounds); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { editor->setDecimals(2); editor->setMinimum(minimum(index.row()) * rl::math::constants::rad2deg); diff --git a/demos/rlCoachKin/ConfigurationModel.cpp b/demos/rlCoachKin/ConfigurationModel.cpp index bb27ed2e..93d8e583 100644 --- a/demos/rlCoachKin/ConfigurationModel.cpp +++ b/demos/rlCoachKin/ConfigurationModel.cpp @@ -61,7 +61,7 @@ ConfigurationModel::data(const QModelIndex& index, int role) const rl::math::Vector q(MainWindow::instance()->kinematicModels[this->id]->getDof()); MainWindow::instance()->kinematicModels[this->id]->getPosition(q); - Eigen::Matrix qUnits(MainWindow::instance()->kinematicModels[this->id]->getDof()); + Eigen::Matrix qUnits(MainWindow::instance()->kinematicModels[this->id]->getDof()); MainWindow::instance()->kinematicModels[this->id]->getPositionUnits(qUnits); switch (role) @@ -69,10 +69,10 @@ ConfigurationModel::data(const QModelIndex& index, int role) const case Qt::DisplayRole: switch (qUnits(index.row())) { - case rl::math::UNIT_METER: + case rl::math::Units::meter: return QString::number(q(index.row()), 'f', 4) + QString(" m"); break; - case rl::math::UNIT_RADIAN: + case rl::math::Units::radian: return QString::number(q(index.row()) * rl::math::constants::rad2deg, 'f', 2) + QChar(176); break; default: @@ -81,7 +81,7 @@ ConfigurationModel::data(const QModelIndex& index, int role) const } break; case Qt::EditRole: - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { return q(index.row()) * rl::math::constants::rad2deg; } @@ -152,10 +152,10 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int { rl::math::Vector q(MainWindow::instance()->kinematicModels[this->id]->getDof()); MainWindow::instance()->kinematicModels[this->id]->getPosition(q); - Eigen::Matrix qUnits(MainWindow::instance()->kinematicModels[this->id]->getDof()); + Eigen::Matrix qUnits(MainWindow::instance()->kinematicModels[this->id]->getDof()); MainWindow::instance()->kinematicModels[this->id]->getPositionUnits(qUnits); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { q(index.row()) = value.value() * rl::math::constants::deg2rad; } diff --git a/demos/rlCoachMdl/ConfigurationDelegate.cpp b/demos/rlCoachMdl/ConfigurationDelegate.cpp index 561d31e3..cd4c27d5 100644 --- a/demos/rlCoachMdl/ConfigurationDelegate.cpp +++ b/demos/rlCoachMdl/ConfigurationDelegate.cpp @@ -50,10 +50,10 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& rl::math::Vector maximum = MainWindow::instance()->kinematicModels[this->id]->getMaximum(); rl::math::Vector minimum = MainWindow::instance()->kinematicModels[this->id]->getMinimum(); - Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels[this->id]->getPositionUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels[this->id]->getPositionUnits(); Eigen::Matrix wraparounds = MainWindow::instance()->kinematicModels[this->id]->getWraparounds(); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { editor->setDecimals(2); editor->setMinimum(minimum(index.row()) * rl::math::constants::rad2deg); diff --git a/demos/rlCoachMdl/ConfigurationModel.cpp b/demos/rlCoachMdl/ConfigurationModel.cpp index 9f364a51..1dfc37c8 100644 --- a/demos/rlCoachMdl/ConfigurationModel.cpp +++ b/demos/rlCoachMdl/ConfigurationModel.cpp @@ -64,17 +64,17 @@ ConfigurationModel::data(const QModelIndex& index, int role) const rl::math::Vector q = MainWindow::instance()->kinematicModels[this->id]->getPosition(); rl::math::Vector maximum = MainWindow::instance()->kinematicModels[this->id]->getMaximum(); rl::math::Vector minimum = MainWindow::instance()->kinematicModels[this->id]->getMinimum(); - Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels[this->id]->getPositionUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->kinematicModels[this->id]->getPositionUnits(); switch (role) { case Qt::DisplayRole: switch (qUnits(index.row())) { - case rl::math::UNIT_METER: + case rl::math::Units::meter: return QString::number(q(index.row()), 'f', 4) + QString(" m"); break; - case rl::math::UNIT_RADIAN: + case rl::math::Units::radian: return QString::number(q(index.row()) * rl::math::constants::rad2deg, 'f', 2) + QChar(176); break; default: @@ -83,7 +83,7 @@ ConfigurationModel::data(const QModelIndex& index, int role) const } break; case Qt::EditRole: - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { return q(index.row()) * rl::math::constants::rad2deg; } @@ -180,9 +180,9 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->kinematicModels[this->id].get())) { rl::math::Vector q = kinematic->getPosition(); - Eigen::Matrix qUnits = kinematic->getPositionUnits(); + Eigen::Matrix qUnits = kinematic->getPositionUnits(); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { q(index.row()) = value.value() * rl::math::constants::deg2rad; } diff --git a/demos/rlPlanDemo/ConfigurationDelegate.cpp b/demos/rlPlanDemo/ConfigurationDelegate.cpp index abafc145..a9b4e99e 100644 --- a/demos/rlPlanDemo/ConfigurationDelegate.cpp +++ b/demos/rlPlanDemo/ConfigurationDelegate.cpp @@ -47,10 +47,10 @@ ConfigurationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& rl::math::Vector maximum = MainWindow::instance()->model->getMaximum(); rl::math::Vector minimum = MainWindow::instance()->model->getMinimum(); - Eigen::Matrix qUnits = MainWindow::instance()->model->getPositionUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->model->getPositionUnits(); Eigen::Matrix wraparounds = MainWindow::instance()->model->getWraparounds(); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { editor->setDecimals(2); editor->setMinimum(minimum(index.row()) * rl::math::constants::rad2deg); diff --git a/demos/rlPlanDemo/ConfigurationModel.cpp b/demos/rlPlanDemo/ConfigurationModel.cpp index a4d16e38..864b143d 100644 --- a/demos/rlPlanDemo/ConfigurationModel.cpp +++ b/demos/rlPlanDemo/ConfigurationModel.cpp @@ -64,9 +64,9 @@ ConfigurationModel::data(const QModelIndex& index, int role) const case Qt::DisplayRole: case Qt::EditRole: { - Eigen::Matrix qUnits = MainWindow::instance()->model->getPositionUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->model->getPositionUnits(); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { return (*MainWindow::instance()->q)(index.row()) * rl::math::constants::rad2deg; } @@ -140,9 +140,9 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int if (index.isValid() && Qt::EditRole == role) { - Eigen::Matrix qUnits = MainWindow::instance()->model->getPositionUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->model->getPositionUnits(); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { (*MainWindow::instance()->q)(index.row()) = value.value() * rl::math::constants::deg2rad; } diff --git a/demos/rlSimulator/ConfigurationDelegate.cpp b/demos/rlSimulator/ConfigurationDelegate.cpp index cb18d4e7..2d5c23cc 100644 --- a/demos/rlSimulator/ConfigurationDelegate.cpp +++ b/demos/rlSimulator/ConfigurationDelegate.cpp @@ -80,9 +80,9 @@ PositionDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& opti rl::math::Vector maximum = MainWindow::instance()->dynamicModel->getMaximum(); rl::math::Vector minimum = MainWindow::instance()->dynamicModel->getMinimum(); - Eigen::Matrix qUnits = MainWindow::instance()->dynamicModel->getPositionUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->dynamicModel->getPositionUnits(); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { editor->setMinimum(minimum(index.row()) * rl::math::constants::rad2deg); editor->setMaximum(maximum(index.row()) * rl::math::constants::rad2deg); @@ -105,11 +105,11 @@ VelocityDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& opti { QDoubleSpinBox* editor = new QDoubleSpinBox(parent); - Eigen::Matrix qUnits = MainWindow::instance()->dynamicModel->getVelocityUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->dynamicModel->getVelocityUnits(); editor->setRange(-10000, 10000); //TODO? - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { editor->setSingleStep(1.0); } @@ -128,11 +128,11 @@ AccelerationDelegate::createEditor(QWidget* parent, const QStyleOptionViewItem& { QDoubleSpinBox* editor = new QDoubleSpinBox(parent); - Eigen::Matrix qUnits = MainWindow::instance()->dynamicModel->getVelocityUnits(); + Eigen::Matrix qUnits = MainWindow::instance()->dynamicModel->getVelocityUnits(); editor->setRange(-10000, 10000); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { editor->setSingleStep(10.0); } diff --git a/demos/rlSimulator/ConfigurationModel.cpp b/demos/rlSimulator/ConfigurationModel.cpp index 2e6f62b2..8f81d8ec 100644 --- a/demos/rlSimulator/ConfigurationModel.cpp +++ b/demos/rlSimulator/ConfigurationModel.cpp @@ -110,9 +110,9 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int if (dynamic_cast(this)) { rl::math::Vector q = kinematic->getPosition(); - Eigen::Matrix qUnits = kinematic->getPositionUnits(); + Eigen::Matrix qUnits = kinematic->getPositionUnits(); - if (rl::math::UNIT_RADIAN == qUnits(index.row())) + if (rl::math::Units::radian == qUnits(index.row())) { q(index.row()) = value.value() * rl::math::constants::deg2rad; } @@ -132,9 +132,9 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int else if (dynamic_cast(this)) { rl::math::Vector qd = kinematic->getVelocity(); - Eigen::Matrix qdUnits = kinematic->getVelocityUnits(); + Eigen::Matrix qdUnits = kinematic->getVelocityUnits(); - if (rl::math::UNIT_RADIAN == qdUnits(index.row())) + if (rl::math::Units::radian == qdUnits(index.row())) { qd(index.row()) = value.value() * rl::math::constants::deg2rad; } @@ -148,9 +148,9 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int else if (dynamic_cast(this)) { rl::math::Vector qdd = kinematic->getAcceleration(); - Eigen::Matrix qddUnits = kinematic->getAccelerationUnits(); + Eigen::Matrix qddUnits = kinematic->getAccelerationUnits(); - if (rl::math::UNIT_RADIAN == qddUnits(index.row())) + if (rl::math::Units::radian == qddUnits(index.row())) { qdd(index.row()) = value.value() * rl::math::constants::deg2rad; } @@ -282,9 +282,9 @@ PositionModel::data(const QModelIndex& index, int role) const case Qt::EditRole: { rl::math::Vector values = MainWindow::instance()->dynamicModel->getPosition(); - Eigen::Matrix units = MainWindow::instance()->dynamicModel->getPositionUnits(); + Eigen::Matrix units = MainWindow::instance()->dynamicModel->getPositionUnits(); - if (rl::math::UNIT_RADIAN == units(index.row())) + if (rl::math::Units::radian == units(index.row())) { return values(index.row()) * rl::math::constants::rad2deg; } @@ -323,9 +323,9 @@ VelocityModel::data(const QModelIndex& index, int role) const case Qt::EditRole: { rl::math::Vector values = MainWindow::instance()->dynamicModel->getVelocity(); - Eigen::Matrix units = MainWindow::instance()->dynamicModel->getVelocityUnits(); + Eigen::Matrix units = MainWindow::instance()->dynamicModel->getVelocityUnits(); - if (rl::math::UNIT_RADIAN == units(index.row())) + if (rl::math::Units::radian == units(index.row())) { return values(index.row()) * rl::math::constants::rad2deg; } @@ -364,9 +364,9 @@ AccelerationModel::data(const QModelIndex& index, int role) const case Qt::EditRole: { rl::math::Vector values = MainWindow::instance()->dynamicModel->getAcceleration(); - Eigen::Matrix units = MainWindow::instance()->dynamicModel->getAccelerationUnits(); + Eigen::Matrix units = MainWindow::instance()->dynamicModel->getAccelerationUnits(); - if (rl::math::UNIT_RADIAN == units(index.row())) + if (rl::math::Units::radian == units(index.row())) { return values(index.row()) * rl::math::constants::rad2deg; } diff --git a/src/rl/hal/AnalogInput.h b/src/rl/hal/AnalogInput.h index 92ff1415..1e34a291 100644 --- a/src/rl/hal/AnalogInput.h +++ b/src/rl/hal/AnalogInput.h @@ -28,7 +28,7 @@ #define RL_HAL_ANALOGINPUT_H #include -#include +#include #include "Device.h" @@ -49,9 +49,9 @@ namespace rl virtual ::rl::math::Real getAnalogInputMinimum(const ::std::size_t& i) const = 0; - virtual ::std::vector<::rl::math::Unit> getAnalogInputUnit() const = 0; + virtual ::std::vector<::rl::math::Units> getAnalogInputUnit() const = 0; - virtual ::rl::math::Unit getAnalogInputUnit(const ::std::size_t& i) const = 0; + virtual ::rl::math::Units getAnalogInputUnit(const ::std::size_t& i) const = 0; protected: diff --git a/src/rl/hal/AnalogOutput.h b/src/rl/hal/AnalogOutput.h index 9c20d693..08f19d28 100644 --- a/src/rl/hal/AnalogOutput.h +++ b/src/rl/hal/AnalogOutput.h @@ -28,7 +28,7 @@ #define RL_HAL_ANALOGOUTPUT_H #include -#include +#include #include "Device.h" @@ -49,9 +49,9 @@ namespace rl virtual ::rl::math::Real getAnalogOutputMinimum(const ::std::size_t& i) const = 0; - virtual ::std::vector<::rl::math::Unit> getAnalogOutputUnit() const = 0; + virtual ::std::vector<::rl::math::Units> getAnalogOutputUnit() const = 0; - virtual ::rl::math::Unit getAnalogOutputUnit(const ::std::size_t& i) const = 0; + virtual ::rl::math::Units getAnalogOutputUnit(const ::std::size_t& i) const = 0; protected: diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 19326f5f..a8b31d2a 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -27,7 +27,7 @@ #include #include #include -#include +#include #include "DeviceException.h" #include "UniversalRobotsRtde.h" @@ -140,10 +140,10 @@ namespace rl return 0; } - ::std::vector<::rl::math::Unit> + ::std::vector<::rl::math::Units> UniversalRobotsRtde::getAnalogInputUnit() const { - ::std::vector<::rl::math::Unit> values; + ::std::vector<::rl::math::Units> values; for (::std::size_t i = 0; i < this->getAnalogInputCount(); ++i) { @@ -153,25 +153,25 @@ namespace rl return values; } - ::rl::math::Unit + ::rl::math::Units UniversalRobotsRtde::getAnalogInputUnit(const ::std::size_t& i) const { switch (i) { case 0: - return 0 == (this->output.analogIoTypes & 1) ? ::rl::math::UNIT_AMPERE : ::rl::math::UNIT_VOLT; + return 0 == (this->output.analogIoTypes & 1) ? ::rl::math::Units::ampere : ::rl::math::Units::volt; break; case 1: - return 0 == (this->output.analogIoTypes & 2) ? ::rl::math::UNIT_AMPERE : ::rl::math::UNIT_VOLT; + return 0 == (this->output.analogIoTypes & 2) ? ::rl::math::Units::ampere : ::rl::math::Units::volt; break; case 2: - return 0 == (this->output.toolAnalogInputTypes & 1) ? ::rl::math::UNIT_AMPERE : ::rl::math::UNIT_VOLT; + return 0 == (this->output.toolAnalogInputTypes & 1) ? ::rl::math::Units::ampere : ::rl::math::Units::volt; break; case 3: - return 0 == (this->output.toolAnalogInputTypes & 2) ? ::rl::math::UNIT_AMPERE : ::rl::math::UNIT_VOLT; + return 0 == (this->output.toolAnalogInputTypes & 2) ? ::rl::math::Units::ampere : ::rl::math::Units::volt; break; default: - return ::rl::math::UNIT_NONE; + return ::rl::math::Units::none; break; } } @@ -233,10 +233,10 @@ namespace rl return 0; } - ::std::vector<::rl::math::Unit> + ::std::vector<::rl::math::Units> UniversalRobotsRtde::getAnalogOutputUnit() const { - ::std::vector<::rl::math::Unit> values; + ::std::vector<::rl::math::Units> values; for (::std::size_t i = 0; i < this->getAnalogOutputCount(); ++i) { @@ -246,25 +246,25 @@ namespace rl return values; } - ::rl::math::Unit + ::rl::math::Units UniversalRobotsRtde::getAnalogOutputUnit(const ::std::size_t& i) const { switch (i) { case 0: - return 0 == (this->output.analogIoTypes & 4) ? ::rl::math::UNIT_AMPERE : ::rl::math::UNIT_VOLT; + return 0 == (this->output.analogIoTypes & 4) ? ::rl::math::Units::ampere : ::rl::math::Units::volt; break; case 1: - return 0 == (this->output.analogIoTypes & 8) ? ::rl::math::UNIT_AMPERE : ::rl::math::UNIT_VOLT; + return 0 == (this->output.analogIoTypes & 8) ? ::rl::math::Units::ampere : ::rl::math::Units::volt; break; case 2: - return ::rl::math::UNIT_VOLT; + return ::rl::math::Units::volt; break; case 3: - return ::rl::math::UNIT_AMPERE; + return ::rl::math::Units::ampere; break; default: - return ::rl::math::UNIT_NONE; + return ::rl::math::Units::none; break; } } @@ -1079,7 +1079,7 @@ namespace rl } void - UniversalRobotsRtde::setAnalogOutputUnit(const ::std::vector<::rl::math::Unit>& values) + UniversalRobotsRtde::setAnalogOutputUnit(const ::std::vector<::rl::math::Units>& values) { for (::std::size_t i = 0; i < this->getAnalogOutputCount(); ++i) { @@ -1088,14 +1088,14 @@ namespace rl } void - UniversalRobotsRtde::setAnalogOutputUnit(const ::std::size_t& i, const ::rl::math::Unit& value) + UniversalRobotsRtde::setAnalogOutputUnit(const ::std::size_t& i, const ::rl::math::Units& value) { switch (value) { - case ::rl::math::UNIT_AMPERE: + case ::rl::math::Units::ampere: this->input.standardAnalogOutputType &= ~(1 << i); break; - case ::rl::math::UNIT_VOLT: + case ::rl::math::Units::volt: this->input.standardAnalogOutputType |= 1 << i; break; default: diff --git a/src/rl/hal/UniversalRobotsRtde.h b/src/rl/hal/UniversalRobotsRtde.h index fe45c4c7..978045d7 100644 --- a/src/rl/hal/UniversalRobotsRtde.h +++ b/src/rl/hal/UniversalRobotsRtde.h @@ -169,9 +169,9 @@ namespace rl ::rl::math::Real getAnalogInputMinimum(const ::std::size_t& i) const; - ::std::vector<::rl::math::Unit> getAnalogInputUnit() const; + ::std::vector<::rl::math::Units> getAnalogInputUnit() const; - ::rl::math::Unit getAnalogInputUnit(const ::std::size_t& i) const; + ::rl::math::Units getAnalogInputUnit(const ::std::size_t& i) const; using AnalogOutputReader::getAnalogOutput; @@ -183,9 +183,9 @@ namespace rl ::rl::math::Real getAnalogOutputMinimum(const ::std::size_t& i) const; - ::std::vector<::rl::math::Unit> getAnalogOutputUnit() const; + ::std::vector<::rl::math::Units> getAnalogOutputUnit() const; - ::rl::math::Unit getAnalogOutputUnit(const ::std::size_t& i) const; + ::rl::math::Units getAnalogOutputUnit(const ::std::size_t& i) const; ::rl::math::ForceVector getCartesianForce() const; @@ -235,9 +235,9 @@ namespace rl void setAnalogOutput(const ::std::size_t& i, const ::rl::math::Real& value); - void setAnalogOutputUnit(const ::std::vector<::rl::math::Unit>& values); + void setAnalogOutputUnit(const ::std::vector<::rl::math::Units>& values); - void setAnalogOutputUnit(const ::std::size_t& i, const ::rl::math::Unit& value); + void setAnalogOutputUnit(const ::std::size_t& i, const ::rl::math::Units& value); using DigitalOutputWriter::setDigitalOutput; diff --git a/src/rl/kin/Joint.h b/src/rl/kin/Joint.h index a2d00b10..76ead66c 100644 --- a/src/rl/kin/Joint.h +++ b/src/rl/kin/Joint.h @@ -28,7 +28,7 @@ #define RL_KIN_JOINT_H #include -#include +#include #include "Transform.h" @@ -45,9 +45,9 @@ namespace rl ::rl::math::Real getPosition() const; - virtual ::rl::math::Unit getPositionUnit() const = 0; + virtual ::rl::math::Units getPositionUnit() const = 0; - virtual ::rl::math::Unit getSpeedUnit() const = 0; + virtual ::rl::math::Units getSpeedUnit() const = 0; virtual void jacobian(const ::rl::math::Transform& tcp, ::rl::math::MatrixBlock& j) = 0; diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index a02aab8a..b70634be 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -657,7 +657,7 @@ namespace rl } void - Kinematics::getPositionUnits(::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const + Kinematics::getPositionUnits(::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& units) const { for (::std::size_t i = 0; i < this->joints.size(); ++i) { @@ -675,7 +675,7 @@ namespace rl } void - Kinematics::getSpeedUnits(::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const + Kinematics::getSpeedUnits(::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& units) const { for (::std::size_t i = 0; i < this->joints.size(); ++i) { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 92470018..81e5188f 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -35,7 +35,7 @@ #include #include #include -#include +#include #include namespace rl @@ -188,11 +188,11 @@ namespace rl */ void getPosition(::rl::math::Vector& q) const; - void getPositionUnits(::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const; + void getPositionUnits(::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& units) const; void getSpeed(::rl::math::Vector& speed) const; - void getSpeedUnits(::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& units) const; + void getSpeedUnits(::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& units) const; void getWraparounds(::Eigen::Matrix& wraparounds) const; diff --git a/src/rl/kin/Prismatic.cpp b/src/rl/kin/Prismatic.cpp index 5b5cc31a..96aab1ab 100644 --- a/src/rl/kin/Prismatic.cpp +++ b/src/rl/kin/Prismatic.cpp @@ -40,16 +40,16 @@ namespace rl { } - ::rl::math::Unit + ::rl::math::Units Prismatic::getPositionUnit() const { - return ::rl::math::UNIT_METER; + return ::rl::math::Units::meter; } - ::rl::math::Unit + ::rl::math::Units Prismatic::getSpeedUnit() const { - return ::rl::math::UNIT_METER_PER_SECOND; + return ::rl::math::Units::meterPerSecond; } void diff --git a/src/rl/kin/Prismatic.h b/src/rl/kin/Prismatic.h index 2f2da4bb..0c4518b1 100644 --- a/src/rl/kin/Prismatic.h +++ b/src/rl/kin/Prismatic.h @@ -40,9 +40,9 @@ namespace rl virtual ~Prismatic(); - ::rl::math::Unit getPositionUnit() const; + ::rl::math::Units getPositionUnit() const; - ::rl::math::Unit getSpeedUnit() const; + ::rl::math::Units getSpeedUnit() const; /** * \f[ ^{0}J_{i}(q) = \begin{pmatrix}z_{i - 1}\\0\end{pmatrix} \f] diff --git a/src/rl/kin/Revolute.cpp b/src/rl/kin/Revolute.cpp index 0c48c95a..5982e06a 100644 --- a/src/rl/kin/Revolute.cpp +++ b/src/rl/kin/Revolute.cpp @@ -43,16 +43,16 @@ namespace rl { } - ::rl::math::Unit + ::rl::math::Units Revolute::getPositionUnit() const { - return ::rl::math::UNIT_RADIAN; + return ::rl::math::Units::radian; } - ::rl::math::Unit + ::rl::math::Units Revolute::getSpeedUnit() const { - return ::rl::math::UNIT_RADIAN_PER_SECOND; + return ::rl::math::Units::radianPerSecond; } void diff --git a/src/rl/kin/Revolute.h b/src/rl/kin/Revolute.h index 961fa184..3a5722fa 100644 --- a/src/rl/kin/Revolute.h +++ b/src/rl/kin/Revolute.h @@ -40,9 +40,9 @@ namespace rl virtual ~Revolute(); - ::rl::math::Unit getPositionUnit() const; + ::rl::math::Units getPositionUnit() const; - ::rl::math::Unit getSpeedUnit() const; + ::rl::math::Units getSpeedUnit() const; /** * \f[ {^{0}J_{i}(q)} = \begin{pmatrix}z_{i - 1} \times {^{i - 1}p_{n}}\\z_{i - 1}\end{pmatrix} \f] diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index 9aa50216..d229bf4a 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -35,6 +35,7 @@ set( TrapezoidalVelocity.h TypeTraits.h Unit.h + Units.h Vector.h ) list(APPEND HDRS ${BASE_HDRS}) diff --git a/src/rl/math/Unit.h b/src/rl/math/Unit.h index ec49226d..a6de437d 100644 --- a/src/rl/math/Unit.h +++ b/src/rl/math/Unit.h @@ -29,6 +29,7 @@ #include "Constants.h" #include "Real.h" +#include "Units.h" #if defined(__GNUC__) || defined(__clang__) #define RL_MATH_DEPRECATED __attribute__ ((__deprecated__)) @@ -40,301 +41,50 @@ namespace rl { namespace math { - /** - * Values describing [base units](https://en.wikipedia.org/wiki/SI_base_unit) and - * [derived units](https://en.wikipedia.org/wiki/SI_derived_unit) of the - * [International System of Units](https://en.wikipedia.org/wiki/International_System_of_Units). - */ - enum Unit - { - /** - * Value used for describing dimensionless quantities. - */ - UNIT_NONE, - /** - * The [second](https://en.wikipedia.org/wiki/Second) (symbol **s**) is the - * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) - * of [time](https://en.wikipedia.org/wiki/Time). - */ - UNIT_SECOND, - /** - * The [meter](https://en.wikipedia.org/wiki/Meter) (symbol **m**) is the - * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) - * of [length](https://en.wikipedia.org/wiki/Length). - */ - UNIT_METER, - /** - * The [kilogram](https://en.wikipedia.org/wiki/Kilogram) (symbol **kg**) is the - * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) - * of [mass](https://en.wikipedia.org/wiki/Mass). - */ - UNIT_KILOGRAM, - /** - * The [ampere](https://en.wikipedia.org/wiki/Ampere) (symbol **A**) is the - * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) - * of [electric current](https://en.wikipedia.org/wiki/Electric_current). - */ - UNIT_AMPERE, - /** - * The [kelvin](https://en.wikipedia.org/wiki/Kelvin) (symbol **K**) is the - * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) - * of [thermodynamic temperature](https://en.wikipedia.org/wiki/Thermodynamic_temperature). - */ - UNIT_KELVIN, - /** - * The [mole](https://en.wikipedia.org/wiki/Mole_%28unit%29) (symbol **mol**) is the - * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) - * of [amount of substance](https://en.wikipedia.org/wiki/Amount_of_substance). - */ - UNIT_MOLE, - /** - * The [candela](https://en.wikipedia.org/wiki/Candela) (symbol **cd**) is the - * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) - * of [luminous intensity](https://en.wikipedia.org/wiki/Luminous_intensity). - */ - UNIT_CANDELA, - /** - * The [radian](https://en.wikipedia.org/wiki/Radian) (symbol **rad**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [plane angle](https://en.wikipedia.org/wiki/Angle). - */ - UNIT_RADIAN, - /** - * The [steradian](https://en.wikipedia.org/wiki/Radian) (symbol **sr**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [solid angle](https://en.wikipedia.org/wiki/Solid_angle). - */ - UNIT_STERADIAN, - /** - * The [hertz](https://en.wikipedia.org/wiki/Hertz) (symbol **Hz**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [frequency](https://en.wikipedia.org/wiki/Frequency) - * and is defined as s-1. - */ - UNIT_HERTZ, - /** - * The [newton](https://en.wikipedia.org/wiki/Newton_(unit)) (symbol **N**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [force](https://en.wikipedia.org/wiki/Force) - * and is defined as kg · m · s-2. - */ - UNIT_NEWTON, - /** - * The [pascal](https://en.wikipedia.org/wiki/Pascal_(unit)) (symbol **Pa**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [pressure](https://en.wikipedia.org/wiki/Pressure) - * and is defined as kg · m-1 · s-2. - */ - UNIT_PASCAL, - /** - * The [joule](https://en.wikipedia.org/wiki/Joule) (symbol **J**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [energy](https://en.wikipedia.org/wiki/Energy) - * and is defined as kg · m-2 · s-2. - */ - UNIT_JOULE, - /** - * The [watt](https://en.wikipedia.org/wiki/Watt) (symbol **W**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [power](https://en.wikipedia.org/wiki/Power_(physics)) - * and is defined as kg · m-2 · s-3. - */ - UNIT_WATT, - /** - * The [coulomb](https://en.wikipedia.org/wiki/Coulomb) (symbol **C**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [electric charge](https://en.wikipedia.org/wiki/Electric_charge) - * and is defined as s · A. - */ - UNIT_COULOMB, - /** - * The [volt](https://en.wikipedia.org/wiki/Volt) (symbol **V**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [electric potential](https://en.wikipedia.org/wiki/Electric_potential), - * [electric potential difference](https://en.wikipedia.org/wiki/Electric_potential_difference), and - * [electromotive force](https://en.wikipedia.org/wiki/Electromotive_force) - * and is defined as kg · m2 · s-3 · A-1. - */ - UNIT_VOLT, - /** - * The [farad](https://en.wikipedia.org/wiki/Farad) (symbol **F**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [electrical capacitance](https://en.wikipedia.org/wiki/Capacitance) - * and is defined as kg-1 · m-2 · s4 · A2. - */ - UNIT_FARAD, - /** - * The [ohm](https://en.wikipedia.org/wiki/Ohm) (symbol **Ω**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [electrical resistance](https://en.wikipedia.org/wiki/Electrical_resistance) - * and is defined as kg · m2 · s-3 · A-2. - */ - UNIT_OHM, - /** - * The [siemens](https://en.wikipedia.org/wiki/Siemens_(unit)) (symbol **S**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [electrical conductance](https://en.wikipedia.org/wiki/Electric_conductance) - * and is defined as kg-1 · m-2 · s3 · A2. - */ - UNIT_SIEMENS, - /** - * The [weber](https://en.wikipedia.org/wiki/Weber_(unit)) (symbol **Wb**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [magnetic flux](https://en.wikipedia.org/wiki/Magnetic_flux) - * and is defined as kg · m2 · s-2 · A-1. - */ - UNIT_WEBER, - /** - * The [tesla](https://en.wikipedia.org/wiki/Tesla_(unit)) (symbol **T**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [magnetic flux density](https://en.wikipedia.org/wiki/Magnetic_flux_density) - * and is defined as kg · s-2 · A-1. - */ - UNIT_TESLA, - /** - * The [henry](https://en.wikipedia.org/wiki/Henry_(unit)) (symbol **H**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [electrical inductance](https://en.wikipedia.org/wiki/Inductance) - * and is defined as kg · m2 · s-2 · A-2. - */ - UNIT_HENRY, - /** - * The [degree Celsius](https://en.wikipedia.org/wiki/Degree_Celsius) (symbol **ºC**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * referring to a temperature on the Celsius scale and is defined as temperature - * relative to 273.15 K. - */ - UNIT_CELSIUS, - /** - * The [lumen](https://en.wikipedia.org/wiki/Lumen_(unit)) (symbol **lm**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [luminous flux](https://en.wikipedia.org/wiki/Luminous_flux) - * and is defined as cd · sr. - */ - UNIT_LUMEN, - /** - * The [lux](https://en.wikipedia.org/wiki/Lux) (symbol **lx**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [illuminance](https://en.wikipedia.org/wiki/Illuminance) - * and is defined as m-2 · cd. - */ - UNIT_LUX, - /** - * The [becquerel](https://en.wikipedia.org/wiki/Becquerel) (symbol **Bq**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [radioactivity](https://en.wikipedia.org/wiki/Radioactivity) - * and is defined as s-1. - */ - UNIT_BECQUEREL, - /** - * The [gray](https://en.wikipedia.org/wiki/Gray_(unit)) (symbol **Gy**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [absorbed dose](https://en.wikipedia.org/wiki/Absorbed_dose) - * of [ionising radiation](https://en.wikipedia.org/wiki/Ionizing_radiation) - * and is defined as m2 · s-2. - */ - UNIT_GRAY, - /** - * The [sievert](https://en.wikipedia.org/wiki/Sievert) (symbol **Sv**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [equivalent dose](https://en.wikipedia.org/wiki/Equivalent_dose) - * of [ionising radiation](https://en.wikipedia.org/wiki/Ionizing_radiation) - * and is defined as m2 · s-2. - */ - UNIT_SIEVERT, - /** - * The [katal](https://en.wikipedia.org/wiki/Katal) (symbol **kat**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [catalytic activity](https://en.wikipedia.org/wiki/Catalytic_activity) - * and is defined as mol · s-1. - */ - UNIT_KATAL, - /** - * The [square meter](https://en.wikipedia.org/wiki/Square_metre) (symbol **m2**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [area](https://en.wikipedia.org/wiki/Area) - * and is defined as m2. - */ - UNIT_SQUARE_METER, - /** - * The [cubic meter](https://en.wikipedia.org/wiki/Cubic_metre) (symbol **m3**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [volume](https://en.wikipedia.org/wiki/Volume) - * and is defined as m3. - */ - UNIT_CUBIC_METER, - /** - * The [meter per second](https://en.wikipedia.org/wiki/Metre_per_second) (symbol **m · s-1**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of both [speed](https://en.wikipedia.org/wiki/Speed) and - * [velocity](https://en.wikipedia.org/wiki/Velocity) - * and is defined as m · s-1. - */ - UNIT_METER_PER_SECOND, - /** - * The [meter per second squared](https://en.wikipedia.org/wiki/Metre_per_second_squared) (symbol **m · s-2**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [acceleration](https://en.wikipedia.org/wiki/Acceleration) - * and is defined as m · s-2. - */ - UNIT_METER_PER_SECOND_SQUARED, - /** - * The kilogram per square meter (symbol **kg · m-2**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [surface density](https://en.wikipedia.org/wiki/Surface_density) - * and is defined as kg · m-2. - */ - UNIT_KILOGRAM_PER_SQUARE_METER, - /** - * The [kilogram per cubic meter](https://en.wikipedia.org/wiki/Kilogram_per_cubic_metre) (symbol **kg · m-3**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [density](https://en.wikipedia.org/wiki/Density) - * and is defined as kg · m-3. - */ - UNIT_KILOGRAM_PER_CUBIC_METER, - /** - * The [newton meter](https://en.wikipedia.org/wiki/Newton_metre) (symbol **N · m**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [torque](https://en.wikipedia.org/wiki/Torque) - * and is defined as kg · m2 · s-2. - */ - UNIT_NEWTON_METER, - /** - * The newton per meter (symbol **N · m-1**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [surface tension](https://en.wikipedia.org/wiki/Surface_tension) - * and is defined as kg · s-2. - */ - UNIT_NEWTON_PER_METER, - /** - * The [radian per second](https://en.wikipedia.org/wiki/Radian_per_second) (symbol **rad · s-1**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [angular velocity](https://en.wikipedia.org/wiki/Angular_velocity) - * and is defined as rad · s-1. - */ - UNIT_RADIAN_PER_SECOND, - /** - * The [radian per second squared](https://en.wikipedia.org/wiki/Radian_per_second_squared) (symbol **rad · s-2**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [angular acceleration](https://en.wikipedia.org/wiki/Angular_acceleration) - * and is defined as rad · s-2. - */ - UNIT_RADIAN_PER_SECOND_SQUARED, - /** - * The [newton second](https://en.wikipedia.org/wiki/Newton_second) (symbol **N · s**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [impulse](https://en.wikipedia.org/wiki/Impulse_(physics)) - * and is defined as kg · m · s-1. - */ - UNIT_NEWTON_SECOND, - /** - * The newton meter second (symbol **N · m · s**) is the - * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) - * of [angular momentum](https://en.wikipedia.org/wiki/Angular_momentum) - * and is defined as kg · m2 · s-1. - */ - UNIT_NEWTON_METER_SECOND - }; + RL_MATH_DEPRECATED typedef Units Unit; + + RL_MATH_DEPRECATED constexpr Units UNIT_NONE = Units::none; + RL_MATH_DEPRECATED constexpr Units UNIT_SECOND = Units::second; + RL_MATH_DEPRECATED constexpr Units UNIT_METER = Units::meter; + RL_MATH_DEPRECATED constexpr Units UNIT_KILOGRAM = Units::kilogram; + RL_MATH_DEPRECATED constexpr Units UNIT_AMPERE = Units::ampere; + RL_MATH_DEPRECATED constexpr Units UNIT_KELVIN = Units::kelvin; + RL_MATH_DEPRECATED constexpr Units UNIT_MOLE = Units::mole; + RL_MATH_DEPRECATED constexpr Units UNIT_CANDELA = Units::candela; + RL_MATH_DEPRECATED constexpr Units UNIT_RADIAN = Units::radian; + RL_MATH_DEPRECATED constexpr Units UNIT_STERADIAN = Units::steradian; + RL_MATH_DEPRECATED constexpr Units UNIT_HERTZ = Units::hertz; + RL_MATH_DEPRECATED constexpr Units UNIT_NEWTON1 = Units::newton; + RL_MATH_DEPRECATED constexpr Units UNIT_PASCAL = Units::pascals; + RL_MATH_DEPRECATED constexpr Units UNIT_JOULE = Units::joule; + RL_MATH_DEPRECATED constexpr Units UNIT_WATT = Units::watt; + RL_MATH_DEPRECATED constexpr Units UNIT_COULOMB = Units::coulomb; + RL_MATH_DEPRECATED constexpr Units UNIT_VOLT = Units::volt; + RL_MATH_DEPRECATED constexpr Units UNIT_FARAD = Units::farad; + RL_MATH_DEPRECATED constexpr Units UNIT_OHM = Units::ohm; + RL_MATH_DEPRECATED constexpr Units UNIT_SIEMENS = Units::siemens; + RL_MATH_DEPRECATED constexpr Units UNIT_WEBER = Units::weber; + RL_MATH_DEPRECATED constexpr Units UNIT_TESLA = Units::tesla; + RL_MATH_DEPRECATED constexpr Units UNIT_HENRY = Units::henry; + RL_MATH_DEPRECATED constexpr Units UNIT_CELSIUS = Units::celsius; + RL_MATH_DEPRECATED constexpr Units UNIT_LUMEN = Units::lumen; + RL_MATH_DEPRECATED constexpr Units UNIT_LUX = Units::lux; + RL_MATH_DEPRECATED constexpr Units UNIT_BECQUEREL = Units::becquerel; + RL_MATH_DEPRECATED constexpr Units UNIT_GRAY = Units::gray; + RL_MATH_DEPRECATED constexpr Units UNIT_SIEVERT = Units::sievert; + RL_MATH_DEPRECATED constexpr Units UNIT_KATAL = Units::katal; + RL_MATH_DEPRECATED constexpr Units UNIT_SQUARE_METER = Units::squareMeter; + RL_MATH_DEPRECATED constexpr Units UNIT_CUBIC_METER = Units::cubicMeter; + RL_MATH_DEPRECATED constexpr Units UNIT_METER_PER_SECOND = Units::meterPerSecond; + RL_MATH_DEPRECATED constexpr Units UNIT_METER_PER_SECOND_SQUARED = Units::meterPerSecondSquared; + RL_MATH_DEPRECATED constexpr Units UNIT_KILOGRAM_PER_SQUARE_METER = Units::kilogramPerSquareMeter; + RL_MATH_DEPRECATED constexpr Units UNIT_KILOGRAM_PER_CUBIC_METER = Units::kilogramPerCubicMeter; + RL_MATH_DEPRECATED constexpr Units UNIT_NEWTON_METER = Units::newtonMeter; + RL_MATH_DEPRECATED constexpr Units UNIT_NEWTON_PER_METER = Units::newtonPerMeter; + RL_MATH_DEPRECATED constexpr Units UNIT_RADIAN_PER_SECOND = Units::radianPerSecond; + RL_MATH_DEPRECATED constexpr Units UNIT_RADIAN_PER_SECOND_SQUARED = Units::radianPerSecondSquared; + RL_MATH_DEPRECATED constexpr Units UNIT_NEWTON_SECOND = Units::newtonSecond; + RL_MATH_DEPRECATED constexpr Units UNIT_NEWTON_METER_SECOND = Units::newtonMeterSecond; RL_MATH_DEPRECATED constexpr Real DEG2RAD = constants::deg2rad; diff --git a/src/rl/math/Units.h b/src/rl/math/Units.h new file mode 100644 index 00000000..1fa7d760 --- /dev/null +++ b/src/rl/math/Units.h @@ -0,0 +1,332 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MATH_UNITS_H +#define RL_MATH_UNITS_H + +namespace rl +{ + namespace math + { + /** + * Values describing [base units](https://en.wikipedia.org/wiki/SI_base_unit) and + * [derived units](https://en.wikipedia.org/wiki/SI_derived_unit) of the + * [International System of Units](https://en.wikipedia.org/wiki/International_System_of_Units). + */ + enum class Units + { + /** + * Value used for describing dimensionless quantities. + */ + none, + /** + * The [second](https://en.wikipedia.org/wiki/Second) (symbol **s**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [time](https://en.wikipedia.org/wiki/Time). + */ + second, + /** + * The [meter](https://en.wikipedia.org/wiki/Meter) (symbol **m**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [length](https://en.wikipedia.org/wiki/Length). + */ + meter, + /** + * The [kilogram](https://en.wikipedia.org/wiki/Kilogram) (symbol **kg**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [mass](https://en.wikipedia.org/wiki/Mass). + */ + kilogram, + /** + * The [ampere](https://en.wikipedia.org/wiki/Ampere) (symbol **A**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [electric current](https://en.wikipedia.org/wiki/Electric_current). + */ + ampere, + /** + * The [kelvin](https://en.wikipedia.org/wiki/Kelvin) (symbol **K**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [thermodynamic temperature](https://en.wikipedia.org/wiki/Thermodynamic_temperature). + */ + kelvin, + /** + * The [mole](https://en.wikipedia.org/wiki/Mole_%28unit%29) (symbol **mol**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [amount of substance](https://en.wikipedia.org/wiki/Amount_of_substance). + */ + mole, + /** + * The [candela](https://en.wikipedia.org/wiki/Candela) (symbol **cd**) is the + * [SI base unit](https://en.wikipedia.org/wiki/SI_base_unit) + * of [luminous intensity](https://en.wikipedia.org/wiki/Luminous_intensity). + */ + candela, + /** + * The [radian](https://en.wikipedia.org/wiki/Radian) (symbol **rad**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [plane angle](https://en.wikipedia.org/wiki/Angle). + */ + radian, + /** + * The [steradian](https://en.wikipedia.org/wiki/Radian) (symbol **sr**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [solid angle](https://en.wikipedia.org/wiki/Solid_angle). + */ + steradian, + /** + * The [hertz](https://en.wikipedia.org/wiki/Hertz) (symbol **Hz**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [frequency](https://en.wikipedia.org/wiki/Frequency) + * and is defined as s-1. + */ + hertz, + /** + * The [newton](https://en.wikipedia.org/wiki/Newton_(unit)) (symbol **N**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [force](https://en.wikipedia.org/wiki/Force) + * and is defined as kg · m · s-2. + */ + newton, + /** + * The [pascal](https://en.wikipedia.org/wiki/Pascal_(unit)) (symbol **Pa**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [pressure](https://en.wikipedia.org/wiki/Pressure) + * and is defined as kg · m-1 · s-2. + */ + pascals, + /** + * The [joule](https://en.wikipedia.org/wiki/Joule) (symbol **J**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [energy](https://en.wikipedia.org/wiki/Energy) + * and is defined as kg · m-2 · s-2. + */ + joule, + /** + * The [watt](https://en.wikipedia.org/wiki/Watt) (symbol **W**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [power](https://en.wikipedia.org/wiki/Power_(physics)) + * and is defined as kg · m-2 · s-3. + */ + watt, + /** + * The [coulomb](https://en.wikipedia.org/wiki/Coulomb) (symbol **C**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electric charge](https://en.wikipedia.org/wiki/Electric_charge) + * and is defined as s · A. + */ + coulomb, + /** + * The [volt](https://en.wikipedia.org/wiki/Volt) (symbol **V**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electric potential](https://en.wikipedia.org/wiki/Electric_potential), + * [electric potential difference](https://en.wikipedia.org/wiki/Electric_potential_difference), and + * [electromotive force](https://en.wikipedia.org/wiki/Electromotive_force) + * and is defined as kg · m2 · s-3 · A-1. + */ + volt, + /** + * The [farad](https://en.wikipedia.org/wiki/Farad) (symbol **F**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electrical capacitance](https://en.wikipedia.org/wiki/Capacitance) + * and is defined as kg-1 · m-2 · s4 · A2. + */ + farad, + /** + * The [ohm](https://en.wikipedia.org/wiki/Ohm) (symbol **Ω**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electrical resistance](https://en.wikipedia.org/wiki/Electrical_resistance) + * and is defined as kg · m2 · s-3 · A-2. + */ + ohm, + /** + * The [siemens](https://en.wikipedia.org/wiki/Siemens_(unit)) (symbol **S**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electrical conductance](https://en.wikipedia.org/wiki/Electric_conductance) + * and is defined as kg-1 · m-2 · s3 · A2. + */ + siemens, + /** + * The [weber](https://en.wikipedia.org/wiki/Weber_(unit)) (symbol **Wb**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [magnetic flux](https://en.wikipedia.org/wiki/Magnetic_flux) + * and is defined as kg · m2 · s-2 · A-1. + */ + weber, + /** + * The [tesla](https://en.wikipedia.org/wiki/Tesla_(unit)) (symbol **T**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [magnetic flux density](https://en.wikipedia.org/wiki/Magnetic_flux_density) + * and is defined as kg · s-2 · A-1. + */ + tesla, + /** + * The [henry](https://en.wikipedia.org/wiki/Henry_(unit)) (symbol **H**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [electrical inductance](https://en.wikipedia.org/wiki/Inductance) + * and is defined as kg · m2 · s-2 · A-2. + */ + henry, + /** + * The [degree Celsius](https://en.wikipedia.org/wiki/Degree_Celsius) (symbol **ºC**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * referring to a temperature on the Celsius scale and is defined as temperature + * relative to 273.15 K. + */ + celsius, + /** + * The [lumen](https://en.wikipedia.org/wiki/Lumen_(unit)) (symbol **lm**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [luminous flux](https://en.wikipedia.org/wiki/Luminous_flux) + * and is defined as cd · sr. + */ + lumen, + /** + * The [lux](https://en.wikipedia.org/wiki/Lux) (symbol **lx**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [illuminance](https://en.wikipedia.org/wiki/Illuminance) + * and is defined as m-2 · cd. + */ + lux, + /** + * The [becquerel](https://en.wikipedia.org/wiki/Becquerel) (symbol **Bq**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [radioactivity](https://en.wikipedia.org/wiki/Radioactivity) + * and is defined as s-1. + */ + becquerel, + /** + * The [gray](https://en.wikipedia.org/wiki/Gray_(unit)) (symbol **Gy**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [absorbed dose](https://en.wikipedia.org/wiki/Absorbed_dose) + * of [ionising radiation](https://en.wikipedia.org/wiki/Ionizing_radiation) + * and is defined as m2 · s-2. + */ + gray, + /** + * The [sievert](https://en.wikipedia.org/wiki/Sievert) (symbol **Sv**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [equivalent dose](https://en.wikipedia.org/wiki/Equivalent_dose) + * of [ionising radiation](https://en.wikipedia.org/wiki/Ionizing_radiation) + * and is defined as m2 · s-2. + */ + sievert, + /** + * The [katal](https://en.wikipedia.org/wiki/Katal) (symbol **kat**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [catalytic activity](https://en.wikipedia.org/wiki/Catalytic_activity) + * and is defined as mol · s-1. + */ + katal, + /** + * The [square meter](https://en.wikipedia.org/wiki/Square_metre) (symbol **m2**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [area](https://en.wikipedia.org/wiki/Area) + * and is defined as m2. + */ + squareMeter, + /** + * The [cubic meter](https://en.wikipedia.org/wiki/Cubic_metre) (symbol **m3**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [volume](https://en.wikipedia.org/wiki/Volume) + * and is defined as m3. + */ + cubicMeter, + /** + * The [meter per second](https://en.wikipedia.org/wiki/Metre_per_second) (symbol **m · s-1**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of both [speed](https://en.wikipedia.org/wiki/Speed) and + * [velocity](https://en.wikipedia.org/wiki/Velocity) + * and is defined as m · s-1. + */ + meterPerSecond, + /** + * The [meter per second squared](https://en.wikipedia.org/wiki/Metre_per_second_squared) (symbol **m · s-2**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [acceleration](https://en.wikipedia.org/wiki/Acceleration) + * and is defined as m · s-2. + */ + meterPerSecondSquared, + /** + * The kilogram per square meter (symbol **kg · m-2**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [surface density](https://en.wikipedia.org/wiki/Surface_density) + * and is defined as kg · m-2. + */ + kilogramPerSquareMeter, + /** + * The [kilogram per cubic meter](https://en.wikipedia.org/wiki/Kilogram_per_cubic_metre) (symbol **kg · m-3**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [density](https://en.wikipedia.org/wiki/Density) + * and is defined as kg · m-3. + */ + kilogramPerCubicMeter, + /** + * The [newton meter](https://en.wikipedia.org/wiki/Newton_metre) (symbol **N · m**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [torque](https://en.wikipedia.org/wiki/Torque) + * and is defined as kg · m2 · s-2. + */ + newtonMeter, + /** + * The newton per meter (symbol **N · m-1**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [surface tension](https://en.wikipedia.org/wiki/Surface_tension) + * and is defined as kg · s-2. + */ + newtonPerMeter, + /** + * The [radian per second](https://en.wikipedia.org/wiki/Radian_per_second) (symbol **rad · s-1**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [angular velocity](https://en.wikipedia.org/wiki/Angular_velocity) + * and is defined as rad · s-1. + */ + radianPerSecond, + /** + * The [radian per second squared](https://en.wikipedia.org/wiki/Radian_per_second_squared) (symbol **rad · s-2**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [angular acceleration](https://en.wikipedia.org/wiki/Angular_acceleration) + * and is defined as rad · s-2. + */ + radianPerSecondSquared, + /** + * The [newton second](https://en.wikipedia.org/wiki/Newton_second) (symbol **N · s**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [impulse](https://en.wikipedia.org/wiki/Impulse_(physics)) + * and is defined as kg · m · s-1. + */ + newtonSecond, + /** + * The newton meter second (symbol **N · m · s**) is the + * [SI derived unit](https://en.wikipedia.org/wiki/SI_derived_unit) + * of [angular momentum](https://en.wikipedia.org/wiki/Angular_momentum) + * and is defined as kg · m2 · s-1. + */ + newtonMeterSecond + }; + } +} + +#endif // RL_MATH_UNITS_H diff --git a/src/rl/mdl/Cylindrical.cpp b/src/rl/mdl/Cylindrical.cpp index d9ed682a..7170ad08 100644 --- a/src/rl/mdl/Cylindrical.cpp +++ b/src/rl/mdl/Cylindrical.cpp @@ -35,18 +35,18 @@ namespace rl Cylindrical::Cylindrical() : Joint(2, 2) { - this->qUnits(0) = ::rl::math::UNIT_RADIAN; - this->qUnits(1) = ::rl::math::UNIT_METER; - this->qdUnits(0) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->qdUnits(1) = ::rl::math::UNIT_METER_PER_SECOND; - this->qddUnits(0) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; - this->qddUnits(1) = ::rl::math::UNIT_METER_PER_SECOND_SQUARED; + this->qUnits(0) = ::rl::math::Units::radian; + this->qUnits(1) = ::rl::math::Units::meter; + this->qdUnits(0) = ::rl::math::Units::radianPerSecond; + this->qdUnits(1) = ::rl::math::Units::meterPerSecond; + this->qddUnits(0) = ::rl::math::Units::radianPerSecondSquared; + this->qddUnits(1) = ::rl::math::Units::meterPerSecondSquared; this->S(2, 0) = 1; this->S(5, 1) = 1; - this->speedUnits(0) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->speedUnits(1) = ::rl::math::UNIT_METER_PER_SECOND; - this->tauUnits(0) = ::rl::math::UNIT_NEWTON_METER; - this->tauUnits(1) = ::rl::math::UNIT_NEWTON; + this->speedUnits(0) = ::rl::math::Units::radianPerSecond; + this->speedUnits(1) = ::rl::math::Units::meterPerSecond; + this->tauUnits(0) = ::rl::math::Units::newtonMeter; + this->tauUnits(1) = ::rl::math::Units::newton; } Cylindrical::~Cylindrical() diff --git a/src/rl/mdl/Helical.cpp b/src/rl/mdl/Helical.cpp index 2d659ef0..a43f0b88 100644 --- a/src/rl/mdl/Helical.cpp +++ b/src/rl/mdl/Helical.cpp @@ -36,13 +36,13 @@ namespace rl Joint(1, 1), h(1) { - this->qUnits(0) = ::rl::math::UNIT_NONE; // TODO - this->qdUnits(0) = ::rl::math::UNIT_NONE; // TODO - this->qddUnits(0) = ::rl::math::UNIT_NONE; // TODO + this->qUnits(0) = ::rl::math::Units::none; // TODO + this->qdUnits(0) = ::rl::math::Units::none; // TODO + this->qddUnits(0) = ::rl::math::Units::none; // TODO this->S(2, 0) = 1; this->S(5, 0) = this->h; - this->speedUnits(0) = ::rl::math::UNIT_NONE; // TODO - this->tauUnits(0) = ::rl::math::UNIT_NONE; // TODO + this->speedUnits(0) = ::rl::math::Units::none; // TODO + this->tauUnits(0) = ::rl::math::Units::none; // TODO } Helical::~Helical() diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index baf2f1ab..ebeb709a 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -183,7 +183,7 @@ namespace rl return this->qdd; } - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& Joint::getAccelerationUnits() const { return this->qddUnits; @@ -219,7 +219,7 @@ namespace rl return this->q; } - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& Joint::getPositionUnits() const { return this->qUnits; @@ -231,7 +231,7 @@ namespace rl return this->tau; } - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& Joint::getTorqueUnits() const { return this->tauUnits; @@ -243,7 +243,7 @@ namespace rl return this->speed; } - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& Joint::getSpeedUnits() const { return this->speedUnits; @@ -255,7 +255,7 @@ namespace rl return this->qd; } - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& Joint::getVelocityUnits() const { return this->qdUnits; diff --git a/src/rl/mdl/Joint.h b/src/rl/mdl/Joint.h index a6a42e21..cbcaabf6 100644 --- a/src/rl/mdl/Joint.h +++ b/src/rl/mdl/Joint.h @@ -27,7 +27,7 @@ #ifndef RL_MDL_JOINT_H #define RL_MDL_JOINT_H -#include +#include #include #include "Transform.h" @@ -65,7 +65,7 @@ namespace rl const ::rl::math::Vector& getAcceleration() const; - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getAccelerationUnits() const; + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getAccelerationUnits() const; ::std::size_t getDof() const; @@ -77,19 +77,19 @@ namespace rl const ::rl::math::Vector& getPosition() const; - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getPositionUnits() const; + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getPositionUnits() const; const ::rl::math::Vector& getTorque() const; - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getTorqueUnits() const; + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getTorqueUnits() const; const ::rl::math::Vector& getSpeed() const; - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getSpeedUnits() const; + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getSpeedUnits() const; const ::rl::math::Vector& getVelocity() const; - const ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1>& getVelocityUnits() const; + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getVelocityUnits() const; virtual void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; @@ -125,25 +125,25 @@ namespace rl ::rl::math::Vector q; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> qUnits; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> qUnits; ::rl::math::Vector qd; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> qdUnits; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> qdUnits; ::rl::math::Vector qdd; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> qddUnits; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> qddUnits; ::rl::math::Matrix S; ::rl::math::Vector speed; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> speedUnits; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> speedUnits; ::rl::math::Vector tau; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> tauUnits; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> tauUnits; ::rl::math::Vector u; diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 99472490..a2d17474 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -212,10 +212,10 @@ namespace rl return this->invGammaVelocity * qdd; } - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> Model::getAccelerationUnits() const { - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { @@ -420,10 +420,10 @@ namespace rl return this->invGammaPosition * q; } - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> Model::getPositionUnits() const { - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDofPosition()); + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> units(this->getDofPosition()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) { @@ -446,10 +446,10 @@ namespace rl return speed; } - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> Model::getSpeedUnits() const { - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { @@ -472,10 +472,10 @@ namespace rl return tau; } - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> Model::getTorqueUnits() const { - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { @@ -512,10 +512,10 @@ namespace rl return this->invGammaVelocity * qd; } - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> Model::getVelocityUnits() const { - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDof()); + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> units(this->getDof()); for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 1edd8825..488161a5 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -33,7 +33,7 @@ #include #include #include -#include +#include #include #include "Frame.h" @@ -83,7 +83,7 @@ namespace rl ::rl::math::Vector getAcceleration() const; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getAccelerationUnits() const; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> getAccelerationUnits() const; ::std::size_t getBodies() const; @@ -133,7 +133,7 @@ namespace rl ::rl::math::Vector getPosition() const; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getPositionUnits() const; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> getPositionUnits() const; Transform* getTransform(const ::std::size_t& i) const; @@ -141,15 +141,15 @@ namespace rl ::rl::math::Vector getSpeed() const; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getSpeedUnits() const; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> getSpeedUnits() const; ::rl::math::Vector getTorque() const; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getTorqueUnits() const; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> getTorqueUnits() const; ::rl::math::Vector getVelocity() const; - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getVelocityUnits() const; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> getVelocityUnits() const; World* getWorld() const; diff --git a/src/rl/mdl/Prismatic.cpp b/src/rl/mdl/Prismatic.cpp index 6e0dd461..803ca7f8 100644 --- a/src/rl/mdl/Prismatic.cpp +++ b/src/rl/mdl/Prismatic.cpp @@ -33,12 +33,12 @@ namespace rl Prismatic::Prismatic() : Joint(1, 1) { - this->qUnits(0) = ::rl::math::UNIT_METER; - this->qdUnits(0) = ::rl::math::UNIT_METER_PER_SECOND; - this->qddUnits(0) = ::rl::math::UNIT_METER_PER_SECOND_SQUARED; + this->qUnits(0) = ::rl::math::Units::meter; + this->qdUnits(0) = ::rl::math::Units::meterPerSecond; + this->qddUnits(0) = ::rl::math::Units::meterPerSecondSquared; this->S(5, 0) = 1; - this->speedUnits(0) = ::rl::math::UNIT_METER_PER_SECOND; - this->tauUnits(0) = ::rl::math::UNIT_NEWTON; + this->speedUnits(0) = ::rl::math::Units::meterPerSecond; + this->tauUnits(0) = ::rl::math::Units::newton; } Prismatic::~Prismatic() diff --git a/src/rl/mdl/Revolute.cpp b/src/rl/mdl/Revolute.cpp index 39a15286..ba0a3f04 100644 --- a/src/rl/mdl/Revolute.cpp +++ b/src/rl/mdl/Revolute.cpp @@ -36,12 +36,12 @@ namespace rl Revolute::Revolute() : Joint(1, 1) { - this->qUnits(0) = ::rl::math::UNIT_RADIAN; - this->qdUnits(0) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->qddUnits(0) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; + this->qUnits(0) = ::rl::math::Units::radian; + this->qdUnits(0) = ::rl::math::Units::radianPerSecond; + this->qddUnits(0) = ::rl::math::Units::radianPerSecondSquared; this->S(2, 0) = 1; - this->speedUnits(0) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->tauUnits(0) = ::rl::math::UNIT_NEWTON_METER; + this->speedUnits(0) = ::rl::math::Units::radianPerSecond; + this->tauUnits(0) = ::rl::math::Units::newtonMeter; } Revolute::~Revolute() diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index 5fa9c305..122bb7d8 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -38,41 +38,41 @@ namespace rl { this->max.tail<4>().setConstant(1); // TODO this->min.tail<4>().setConstant(-1); // TODO - this->qUnits(0) = ::rl::math::UNIT_METER; - this->qUnits(1) = ::rl::math::UNIT_METER; - this->qUnits(2) = ::rl::math::UNIT_METER; - this->qUnits(3) = ::rl::math::UNIT_NONE; // TODO - this->qUnits(4) = ::rl::math::UNIT_NONE; // TODO - this->qUnits(5) = ::rl::math::UNIT_NONE; // TODO - this->qUnits(6) = ::rl::math::UNIT_NONE; // TODO - this->qdUnits(0) = ::rl::math::UNIT_METER_PER_SECOND; - this->qdUnits(1) = ::rl::math::UNIT_METER_PER_SECOND; - this->qdUnits(2) = ::rl::math::UNIT_METER_PER_SECOND; - this->qdUnits(3) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->qdUnits(4) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->qdUnits(5) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->qddUnits(0) = ::rl::math::UNIT_METER_PER_SECOND_SQUARED; - this->qddUnits(1) = ::rl::math::UNIT_METER_PER_SECOND_SQUARED; - this->qddUnits(2) = ::rl::math::UNIT_METER_PER_SECOND_SQUARED; - this->qddUnits(3) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; - this->qddUnits(4) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; - this->qddUnits(5) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; + this->qUnits(0) = ::rl::math::Units::meter; + this->qUnits(1) = ::rl::math::Units::meter; + this->qUnits(2) = ::rl::math::Units::meter; + this->qUnits(3) = ::rl::math::Units::none; + this->qUnits(4) = ::rl::math::Units::none; + this->qUnits(5) = ::rl::math::Units::none; + this->qUnits(6) = ::rl::math::Units::none; + this->qdUnits(0) = ::rl::math::Units::meterPerSecond; + this->qdUnits(1) = ::rl::math::Units::meterPerSecond; + this->qdUnits(2) = ::rl::math::Units::meterPerSecond; + this->qdUnits(3) = ::rl::math::Units::radianPerSecond; + this->qdUnits(4) = ::rl::math::Units::radianPerSecond; + this->qdUnits(5) = ::rl::math::Units::radianPerSecond; + this->qddUnits(0) = ::rl::math::Units::meterPerSecondSquared; + this->qddUnits(1) = ::rl::math::Units::meterPerSecondSquared; + this->qddUnits(2) = ::rl::math::Units::meterPerSecondSquared; + this->qddUnits(3) = ::rl::math::Units::radianPerSecondSquared; + this->qddUnits(4) = ::rl::math::Units::radianPerSecondSquared; + this->qddUnits(5) = ::rl::math::Units::radianPerSecondSquared; this->S.topLeftCorner<3, 3>().setZero(); this->S.topRightCorner<3, 3>().setIdentity(); this->S.bottomLeftCorner<3, 3>().setIdentity(); this->S.bottomRightCorner<3, 3>().setZero(); - this->speedUnits(0) = ::rl::math::UNIT_METER_PER_SECOND; - this->speedUnits(1) = ::rl::math::UNIT_METER_PER_SECOND; - this->speedUnits(2) = ::rl::math::UNIT_METER_PER_SECOND; - this->speedUnits(3) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->speedUnits(4) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->speedUnits(5) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->tauUnits(0) = ::rl::math::UNIT_NEWTON; - this->tauUnits(1) = ::rl::math::UNIT_NEWTON; - this->tauUnits(2) = ::rl::math::UNIT_NEWTON; - this->tauUnits(3) = ::rl::math::UNIT_NEWTON_METER; - this->tauUnits(4) = ::rl::math::UNIT_NEWTON_METER; - this->tauUnits(5) = ::rl::math::UNIT_NEWTON_METER; + this->speedUnits(0) = ::rl::math::Units::meterPerSecond; + this->speedUnits(1) = ::rl::math::Units::meterPerSecond; + this->speedUnits(2) = ::rl::math::Units::meterPerSecond; + this->speedUnits(3) = ::rl::math::Units::radianPerSecond; + this->speedUnits(4) = ::rl::math::Units::radianPerSecond; + this->speedUnits(5) = ::rl::math::Units::radianPerSecond; + this->tauUnits(0) = ::rl::math::Units::newton; + this->tauUnits(1) = ::rl::math::Units::newton; + this->tauUnits(2) = ::rl::math::Units::newton; + this->tauUnits(3) = ::rl::math::Units::newtonMeter; + this->tauUnits(4) = ::rl::math::Units::newtonMeter; + this->tauUnits(5) = ::rl::math::Units::newtonMeter; } SixDof::~SixDof() diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 1fa2b06f..04d1bbaf 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -37,25 +37,25 @@ namespace rl { this->max.setConstant(1); // TODO this->min.setConstant(-1); // TODO - this->qUnits(0) = ::rl::math::UNIT_NONE; // TODO - this->qUnits(1) = ::rl::math::UNIT_NONE; // TODO - this->qUnits(2) = ::rl::math::UNIT_NONE; // TODO - this->qUnits(3) = ::rl::math::UNIT_NONE; // TODO - this->qdUnits(0) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->qdUnits(1) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->qdUnits(2) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->qddUnits(0) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; - this->qddUnits(1) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; - this->qddUnits(2) = ::rl::math::UNIT_RADIAN_PER_SECOND_SQUARED; + this->qUnits(0) = ::rl::math::Units::none; + this->qUnits(1) = ::rl::math::Units::none; + this->qUnits(2) = ::rl::math::Units::none; + this->qUnits(3) = ::rl::math::Units::none; + this->qdUnits(0) = ::rl::math::Units::radianPerSecond; + this->qdUnits(1) = ::rl::math::Units::radianPerSecond; + this->qdUnits(2) = ::rl::math::Units::radianPerSecond; + this->qddUnits(0) = ::rl::math::Units::radianPerSecondSquared; + this->qddUnits(1) = ::rl::math::Units::radianPerSecondSquared; + this->qddUnits(2) = ::rl::math::Units::radianPerSecondSquared; this->S(0, 0) = 1; this->S(1, 1) = 1; this->S(2, 2) = 1; - this->speedUnits(0) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->speedUnits(1) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->speedUnits(2) = ::rl::math::UNIT_RADIAN_PER_SECOND; - this->tauUnits(0) = ::rl::math::UNIT_NEWTON_METER; - this->tauUnits(1) = ::rl::math::UNIT_NEWTON_METER; - this->tauUnits(2) = ::rl::math::UNIT_NEWTON_METER; + this->speedUnits(0) = ::rl::math::Units::radianPerSecond; + this->speedUnits(1) = ::rl::math::Units::radianPerSecond; + this->speedUnits(2) = ::rl::math::Units::radianPerSecond; + this->tauUnits(0) = ::rl::math::Units::newtonMeter; + this->tauUnits(1) = ::rl::math::Units::newtonMeter; + this->tauUnits(2) = ::rl::math::Units::newtonMeter; } Spherical::~Spherical() diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index e2221d74..6f7f54c0 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -307,12 +307,12 @@ namespace rl } } - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> Model::getPositionUnits() const { if (nullptr != this->kin) { - ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> units(this->getDofPosition());; + ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> units(this->getDofPosition());; this->kin->getPositionUnits(units); return units; } diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index a4426dc7..932d3f95 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -88,7 +88,7 @@ namespace rl virtual ::std::size_t getOperationalDof() const; - virtual ::Eigen::Matrix<::rl::math::Unit, ::Eigen::Dynamic, 1> getPositionUnits() const; + virtual ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1> getPositionUnits() const; virtual ::Eigen::Matrix getWraparounds() const; diff --git a/tests/rlEetTest/rlEetTest.cpp b/tests/rlEetTest/rlEetTest.cpp index 5fff3790..ae558b3c 100644 --- a/tests/rlEetTest/rlEetTest.cpp +++ b/tests/rlEetTest/rlEetTest.cpp @@ -96,7 +96,7 @@ main(int argc, char** argv) rl::mdl::XmlFactory factory2; std::shared_ptr kinematic = std::dynamic_pointer_cast(factory2.create(argv[3])); - Eigen::Matrix qUnits = kinematic->getPositionUnits(); + Eigen::Matrix qUnits = kinematic->getPositionUnits(); rl::math::Vector start(kinematic->getDofPosition()); @@ -104,7 +104,7 @@ main(int argc, char** argv) { start(i) = boost::lexical_cast(argv[i + 6]); - if (rl::math::UNIT_RADIAN == qUnits(i)) + if (rl::math::Units::radian == qUnits(i)) { start(i) *= rl::math::constants::deg2rad; } @@ -116,7 +116,7 @@ main(int argc, char** argv) { goal(i) = boost::lexical_cast(argv[start.size() + i + 6]); - if (rl::math::UNIT_RADIAN == qUnits(i)) + if (rl::math::Units::radian == qUnits(i)) { goal(i) *= rl::math::constants::deg2rad; } From 6723d6967c5370c99266b6c597977f130a6b5bf9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 7 Jul 2020 17:26:00 +0200 Subject: [PATCH 399/546] Use enum class and constexpr --- demos/rlCameraDemo/rlCameraDemo.cpp | 12 +- demos/rlCoachMdl/OperationalModel.cpp | 6 +- demos/rlGripperDemo/rlGripperDemo.cpp | 8 +- demos/rlGripperDemo/rlRobotiqModelCDemo.cpp | 6 +- demos/rlLaserDemo/rlLaserDemo.cpp | 12 +- demos/rlPlanDemo/MainWindow.cpp | 6 +- demos/rlPumaDemo/rlPumaDemo.cpp | 6 +- demos/rlRangeSensorDemo/rlRangeSensorDemo.cpp | 10 +- extras/wrlview/MainWindow.cpp | 122 +++++----- extras/wrlview/MainWindow.h | 66 ++--- src/rl/hal/Dc1394Camera.cpp | 190 +++++++-------- src/rl/hal/Dc1394Camera.h | 184 +++++++------- src/rl/hal/LeuzeRs4.cpp | 95 ++++---- src/rl/hal/LeuzeRs4.h | 20 +- src/rl/hal/MitsubishiH7.cpp | 62 ++--- src/rl/hal/MitsubishiH7.h | 98 ++++---- src/rl/hal/MitsubishiR3.cpp | 6 +- src/rl/hal/MitsubishiR3.h | 24 +- src/rl/hal/RobotiqModelC.cpp | 36 +-- src/rl/hal/RobotiqModelC.h | 66 ++--- src/rl/hal/SchmersalLss300.cpp | 66 ++--- src/rl/hal/SchmersalLss300.h | 26 +- src/rl/hal/SchunkFpsF5.cpp | 10 +- src/rl/hal/Serial.cpp | 124 +++++----- src/rl/hal/Serial.h | 102 ++++---- src/rl/hal/SickLms200.cpp | 188 +++++++-------- src/rl/hal/SickLms200.h | 58 +++-- src/rl/hal/SickS300.cpp | 10 +- src/rl/hal/SickS300.h | 2 +- src/rl/hal/Socket.cpp | 20 +- src/rl/hal/Socket.h | 14 +- src/rl/hal/UniversalRobotsDashboard.cpp | 44 ++-- src/rl/hal/UniversalRobotsDashboard.h | 48 ++-- src/rl/hal/UniversalRobotsRealtime.cpp | 6 +- src/rl/hal/UniversalRobotsRealtime.h | 120 ++++----- src/rl/hal/UniversalRobotsRtde.cpp | 100 ++++---- src/rl/hal/UniversalRobotsRtde.h | 140 +++++------ src/rl/hal/WeissException.cpp | 62 ++--- src/rl/hal/WeissException.h | 64 ++--- src/rl/hal/WeissKms40.cpp | 4 +- src/rl/hal/WeissKms40.h | 42 ++-- src/rl/hal/WeissWsg50.cpp | 228 +++++++++--------- src/rl/hal/WeissWsg50.h | 68 +++--- src/rl/kin/Puma.cpp | 28 +-- src/rl/kin/Puma.h | 18 +- src/rl/kin/Rhino.cpp | 20 +- src/rl/kin/Rhino.h | 12 +- src/rl/math/CircularVector2.h | 4 +- src/rl/math/CircularVector3.h | 4 +- src/rl/math/Function.h | 6 +- src/rl/math/Polynomial.h | 4 +- src/rl/math/PolynomialQuaternion.h | 4 +- src/rl/math/Spline.h | 4 +- src/rl/math/SplineQuaternion.h | 4 +- src/rl/mdl/JacobianInverseKinematics.cpp | 8 +- src/rl/mdl/JacobianInverseKinematics.h | 8 +- src/rl/plan/WorkspaceSphereExplorer.cpp | 8 +- src/rl/plan/WorkspaceSphereExplorer.h | 8 +- tests/rlEetTest/rlEetTest.cpp | 2 +- .../rlInverseKinematicsMdlTest.cpp | 12 +- 60 files changed, 1371 insertions(+), 1364 deletions(-) diff --git a/demos/rlCameraDemo/rlCameraDemo.cpp b/demos/rlCameraDemo/rlCameraDemo.cpp index 46aed784..d93a742d 100644 --- a/demos/rlCameraDemo/rlCameraDemo.cpp +++ b/demos/rlCameraDemo/rlCameraDemo.cpp @@ -40,13 +40,13 @@ main(int argc, char** argv) dc1394.open(); dc1394.start(); - dc1394.setFramerate(rl::hal::Dc1394Camera::FRAMERATE_7_5); - dc1394.setSpeed(rl::hal::Dc1394Camera::ISO_SPEED_400); - dc1394.setVideoMode(rl::hal::Dc1394Camera::VIDEO_MODE_1024x768_RGB8); + dc1394.setFramerate(rl::hal::Dc1394Camera::Framerate::f7_5); + dc1394.setSpeed(rl::hal::Dc1394Camera::IsoSpeed::i400); + dc1394.setVideoMode(rl::hal::Dc1394Camera::VideoMode::v1024x768_rgb8); - dc1394.setFeatureMode(rl::hal::Dc1394Camera::FEATURE_GAIN, rl::hal::Dc1394Camera::FEATURE_MODE_AUTO); - dc1394.setFeatureMode(rl::hal::Dc1394Camera::FEATURE_SHUTTER, rl::hal::Dc1394Camera::FEATURE_MODE_AUTO); - dc1394.setFeatureMode(rl::hal::Dc1394Camera::FEATURE_WHITE_BALANCE, rl::hal::Dc1394Camera::FEATURE_MODE_AUTO); + dc1394.setFeatureMode(rl::hal::Dc1394Camera::Feature::gain, rl::hal::Dc1394Camera::FeatureMode::automatic); + dc1394.setFeatureMode(rl::hal::Dc1394Camera::Feature::shutter, rl::hal::Dc1394Camera::FeatureMode::automatic); + dc1394.setFeatureMode(rl::hal::Dc1394Camera::Feature::whiteBalance, rl::hal::Dc1394Camera::FeatureMode::automatic); unsigned char image[dc1394.getSize()]; diff --git a/demos/rlCoachMdl/OperationalModel.cpp b/demos/rlCoachMdl/OperationalModel.cpp index f939eaf8..f8154262 100644 --- a/demos/rlCoachMdl/OperationalModel.cpp +++ b/demos/rlCoachMdl/OperationalModel.cpp @@ -251,15 +251,15 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r if ("DLS" == MainWindow::instance()->ikJacobianComboBox->currentText()) { - jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_DLS); + jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::Method::dls); } else if ("SVD" == MainWindow::instance()->ikJacobianComboBox->currentText()) { - jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_SVD); + jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::Method::svd); } else if ("Transpose" == MainWindow::instance()->ikJacobianComboBox->currentText()) { - jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE); + jacobianIk->setMethod(rl::mdl::JacobianInverseKinematics::Method::transpose); } } #ifdef RL_MDL_NLOPT diff --git a/demos/rlGripperDemo/rlGripperDemo.cpp b/demos/rlGripperDemo/rlGripperDemo.cpp index c689c17d..3d1e80d9 100644 --- a/demos/rlGripperDemo/rlGripperDemo.cpp +++ b/demos/rlGripperDemo/rlGripperDemo.cpp @@ -69,11 +69,11 @@ main(int argc, char** argv) std::cout << "force: " << gripper.getForce() << std::endl; std::cout << "speed: " << gripper.getSpeed() << std::endl; - rl::hal::WeissWsg50::SystemState systemState = gripper.getSystemState(); + std::uint32_t systemStateBits = gripper.getSystemStateBits(); - std::cout << "isReferenced: " << (rl::hal::WeissWsg50::SYSTEM_STATE_REFERENCED & systemState) << std::endl; - std::cout << "isMoving: " << (rl::hal::WeissWsg50::SYSTEM_STATE_MOVING & systemState) << std::endl; - std::cout << "isTargetPositionReached: " << (rl::hal::WeissWsg50::SYSTEM_STATE_TARGET_POSITION_REACHED & systemState) << std::endl; + std::cout << "isReferenced: " << (static_cast(rl::hal::WeissWsg50::SystemState::referenced) & systemStateBits) << std::endl; + std::cout << "isMoving: " << (static_cast(rl::hal::WeissWsg50::SystemState::moving) & systemStateBits) << std::endl; + std::cout << "isTargetPositionReached: " << (static_cast(rl::hal::WeissWsg50::SystemState::targetPositionReached) & systemStateBits) << std::endl; if (0 == i % 100) { diff --git a/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp b/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp index 5ba97d8a..e278c9be 100644 --- a/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp +++ b/demos/rlGripperDemo/rlRobotiqModelCDemo.cpp @@ -45,7 +45,7 @@ main(int argc, char** argv) do { gripper.step(); - std::cout << "activationStatus: " << gripper.getActivationStatus() << " - gripperStatus: " << gripper.getGripperStatus() << std::endl; + std::cout << "activationStatus: " << static_cast(gripper.getActivationStatus()) << " - gripperStatus: " << static_cast(gripper.getGripperStatus()) << std::endl; } while (!gripper.isRunning()); @@ -58,7 +58,7 @@ main(int argc, char** argv) gripper.step(); std::cout << "position: " << gripper.getPositionPercentage() << " - current: " << gripper.getCurrent() << std::endl; } - while (rl::hal::RobotiqModelC::OBJECT_STATUS_MOTION == gripper.getObjectStatus()); + while (rl::hal::RobotiqModelC::ObjectStatus::motion == gripper.getObjectStatus()); for (std::size_t i = 0; i < 100; ++i) { @@ -75,7 +75,7 @@ main(int argc, char** argv) gripper.step(); std::cout << "position: " << gripper.getPositionPercentage() << " - current: " << gripper.getCurrent() << std::endl; } - while (rl::hal::RobotiqModelC::OBJECT_STATUS_MOTION == gripper.getObjectStatus()); + while (rl::hal::RobotiqModelC::ObjectStatus::motion == gripper.getObjectStatus()); gripper.stop(); gripper.close(); diff --git a/demos/rlLaserDemo/rlLaserDemo.cpp b/demos/rlLaserDemo/rlLaserDemo.cpp index e701ab37..369af808 100644 --- a/demos/rlLaserDemo/rlLaserDemo.cpp +++ b/demos/rlLaserDemo/rlLaserDemo.cpp @@ -84,27 +84,27 @@ main(int argc, char** argv) #ifdef LEUZE rl::hal::LeuzeRs4 laser( "/dev/ttyUSB0", - rl::hal::LeuzeRs4::BAUDRATE_57600BPS + rl::hal::LeuzeRs4::BaudRate::b57600 ); #endif #ifdef SCHMERSAL rl::hal::SchmersalLss300 laser( "/dev/ttyUSB0", - rl::hal::SchmersalLss300::BAUDRATE_9600BPS, - rl::hal::SchmersalLss300::MONITORING_CONTINUOUS + rl::hal::SchmersalLss300::BaudRate::b9600, + rl::hal::SchmersalLss300::Monitoring::continuous ); #endif #ifdef SICKLMS200 rl::hal::SickLms200 laser( "/dev/ttyUSB0", - rl::hal::SickLms200::BAUDRATE_9600BPS, - rl::hal::SickLms200::MONITORING_CONTINUOUS + rl::hal::SickLms200::BaudRate::b9600, + rl::hal::SickLms200::Monitoring::continuous ); #endif #ifdef SICKS300 rl::hal::SickS300 laser( "/dev/ttyS1", - rl::hal::Serial::BAUDRATE_115200BPS + rl::hal::Serial::BaudRate::b115200 ); #endif diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index c917c5aa..c4e825fd 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -1461,15 +1461,15 @@ MainWindow::load(const QString& filename) if (path.eval("count(distance) > 0").getValue()) { - explorer->greedy = rl::plan::WorkspaceSphereExplorer::GREEDY_DISTANCE; + explorer->greedy = rl::plan::WorkspaceSphereExplorer::Greedy::distance; } else if (path.eval("count(sourceDistance) > 0").getValue()) { - explorer->greedy = rl::plan::WorkspaceSphereExplorer::GREEDY_SOURCE_DISTANCE; + explorer->greedy = rl::plan::WorkspaceSphereExplorer::Greedy::sourceDistance; } else if (path.eval("count(space) > 0").getValue()) { - explorer->greedy = rl::plan::WorkspaceSphereExplorer::GREEDY_SPACE; + explorer->greedy = rl::plan::WorkspaceSphereExplorer::Greedy::space; } if (rl::plan::DistanceModel* model = dynamic_cast(this->model.get())) diff --git a/demos/rlPumaDemo/rlPumaDemo.cpp b/demos/rlPumaDemo/rlPumaDemo.cpp index 3edeba41..25a5c62b 100644 --- a/demos/rlPumaDemo/rlPumaDemo.cpp +++ b/demos/rlPumaDemo/rlPumaDemo.cpp @@ -70,9 +70,9 @@ main(int argc, char** argv) puma->setWrist(wrist); std::cout - << "Arm: " << (arm == rl::kin::Puma::ARM_LEFT ? "LEFT" : "RIGHT") - << ", Elbow: " << (elbow == rl::kin::Puma::ELBOW_ABOVE ? "ABOVE" : "BELOW") - << ", Wrist: " << (wrist == rl::kin::Puma::WRIST_FLIP ? "FLIP" : "NONFLIP") + << "Arm: " << (arm == rl::kin::Puma::Arm::left ? "LEFT" : "RIGHT") + << ", Elbow: " << (elbow == rl::kin::Puma::Elbow::above ? "ABOVE" : "BELOW") + << ", Wrist: " << (wrist == rl::kin::Puma::Wrist::flip ? "FLIP" : "NONFLIP") << std::endl; std::cout << "q: " << q.transpose() * rl::math::constants::rad2deg << std::endl; diff --git a/demos/rlRangeSensorDemo/rlRangeSensorDemo.cpp b/demos/rlRangeSensorDemo/rlRangeSensorDemo.cpp index fc724a39..3f16787f 100644 --- a/demos/rlRangeSensorDemo/rlRangeSensorDemo.cpp +++ b/demos/rlRangeSensorDemo/rlRangeSensorDemo.cpp @@ -61,14 +61,14 @@ main(int argc, char** argv) #ifdef LEUZE rl::hal::LeuzeRs4 sensor( "/dev/ttyUSB0", - rl::hal::LeuzeRs4::BAUDRATE_57600BPS + rl::hal::LeuzeRs4::BaudRate::b57600 ); #endif #ifdef SCHMERSAL rl::hal::SchmersalLss300 sensor( "/dev/ttyUSB0", - rl::hal::SchmersalLss300::BAUDRATE_9600BPS, - rl::hal::SchmersalLss300::MONITORING_CONTINUOUS + rl::hal::SchmersalLss300::BaudRate::b9600, + rl::hal::SchmersalLss300::Monitoring::continuous ); #endif #ifdef SCHUNK @@ -77,8 +77,8 @@ main(int argc, char** argv) #ifdef SICK rl::hal::SickLms200 sensor( "/dev/ttyUSB0", - rl::hal::SickLms200::BAUDRATE_9600BPS, - rl::hal::SickLms200::MONITORING_CONTINUOUS + rl::hal::SickLms200::BaudRate::b9600, + rl::hal::SickLms200::Monitoring::continuous ); #endif diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 8b644f7f..16e79b0f 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -300,52 +300,52 @@ MainWindow::init() QObject::connect(viewActionGroup, SIGNAL(triggered(QAction*)), this, SLOT(selectView(QAction*))); QAction* viewTopAction = new QAction("Top", this); - viewTopAction->setData(VIEW_TOP); + viewTopAction->setData(static_cast(View::top)); viewActionGroup->addAction(viewTopAction); this->viewMenu->addAction(viewTopAction); QAction* viewBottomAction = new QAction("Bottom", this); - viewBottomAction->setData(VIEW_BOTTOM); + viewBottomAction->setData(static_cast(View::bottom)); viewActionGroup->addAction(viewBottomAction); this->viewMenu->addAction(viewBottomAction); QAction* viewFrontAction = new QAction("Front", this); - viewFrontAction->setData(VIEW_FRONT); + viewFrontAction->setData(static_cast(View::front)); viewActionGroup->addAction(viewFrontAction); this->viewMenu->addAction(viewFrontAction); QAction* viewBackAction = new QAction("Back", this); - viewBackAction->setData(VIEW_BACK); + viewBackAction->setData(static_cast(View::back)); viewActionGroup->addAction(viewBackAction); this->viewMenu->addAction(viewBackAction); QAction* viewLeftAction = new QAction("Left", this); - viewLeftAction->setData(VIEW_LEFT); + viewLeftAction->setData(static_cast(View::left)); viewActionGroup->addAction(viewLeftAction); this->viewMenu->addAction(viewLeftAction); QAction* viewRightAction = new QAction("Right", this); - viewRightAction->setData(VIEW_RIGHT); + viewRightAction->setData(static_cast(View::right)); viewActionGroup->addAction(viewRightAction); this->viewMenu->addAction(viewRightAction); QAction* viewTopBackLeftAction = new QAction("Top Back Left", this); - viewTopBackLeftAction->setData(VIEW_TOP_BACK_LEFT); + viewTopBackLeftAction->setData(static_cast(View::topBackLeft)); viewActionGroup->addAction(viewTopBackLeftAction); this->viewMenu->addAction(viewTopBackLeftAction); QAction* viewTopBackRightAction = new QAction("Top Back Right", this); - viewTopBackRightAction->setData(VIEW_TOP_BACK_RIGHT); + viewTopBackRightAction->setData(static_cast(View::topBackRight)); viewActionGroup->addAction(viewTopBackRightAction); this->viewMenu->addAction(viewTopBackRightAction); QAction* viewTopFrontLeftAction = new QAction("Top Front Left", this); - viewTopFrontLeftAction->setData(VIEW_TOP_FRONT_LEFT); + viewTopFrontLeftAction->setData(static_cast(View::topFrontLeft)); viewActionGroup->addAction(viewTopFrontLeftAction); this->viewMenu->addAction(viewTopFrontLeftAction); QAction* viewTopFrontRightAction = new QAction("Top Front Right", this); - viewTopFrontRightAction->setData(VIEW_TOP_FRONT_RIGHT); + viewTopFrontRightAction->setData(static_cast(View::topFrontRight)); viewActionGroup->addAction(viewTopFrontRightAction); this->viewMenu->addAction(viewTopFrontRightAction); @@ -372,19 +372,19 @@ MainWindow::init() QAction* originNoneAction = new QAction("Hide Origin", this); originNoneAction->setCheckable(true); originNoneAction->setChecked(true); - originNoneAction->setData(ORIGIN_NONE); + originNoneAction->setData(static_cast(Origin::none)); originUnitActionGroup->addAction(originNoneAction); this->displayMenu->addAction(originNoneAction); QAction* origin1Action = new QAction("Show Origin (Scale 1)", this); origin1Action->setCheckable(true); - origin1Action->setData(ORIGIN_1); + origin1Action->setData(static_cast(Origin::o1)); originUnitActionGroup->addAction(origin1Action); this->displayMenu->addAction(origin1Action); QAction* origin1000Action = new QAction("Show Origin (Scale 1000)", this); origin1000Action->setCheckable(true); - origin1000Action->setData(ORIGIN_1000); + origin1000Action->setData(static_cast(Origin::o1000)); originUnitActionGroup->addAction(origin1000Action); this->displayMenu->addAction(origin1000Action); @@ -404,14 +404,14 @@ MainWindow::init() QAction* cameraOrthogonalAction = new QAction("Orthogonal Camera", this); cameraOrthogonalAction->setCheckable(true); - cameraOrthogonalAction->setData(CAMERA_ORTHOGONAL); + cameraOrthogonalAction->setData(static_cast(Camera::orthogonal)); cameraActionGroup->addAction(cameraOrthogonalAction); this->displayMenu->addAction(cameraOrthogonalAction); QAction* cameraPerspectiveAction = new QAction("Perspective Camera", this); cameraPerspectiveAction->setCheckable(true); cameraPerspectiveAction->setChecked(true); - cameraPerspectiveAction->setData(CAMERA_PERSPECTIVE); + cameraPerspectiveAction->setData(static_cast(Camera::perspective)); cameraActionGroup->addAction(cameraPerspectiveAction); this->displayMenu->addAction(cameraPerspectiveAction); @@ -423,20 +423,20 @@ MainWindow::init() QAction* backgroundBlackAction = new QAction("Black Background", this); backgroundBlackAction->setCheckable(true); - backgroundBlackAction->setData(BACKGROUND_BLACK); + backgroundBlackAction->setData(static_cast(Background::black)); backgroundActionGroup->addAction(backgroundBlackAction); this->displayMenu->addAction(backgroundBlackAction); QAction* backgroundGradientAction = new QAction("Gradient Background", this); backgroundGradientAction->setCheckable(true); backgroundGradientAction->setChecked(true); - backgroundGradientAction->setData(BACKGROUND_GRADIENT); + backgroundGradientAction->setData(static_cast(Background::gradient)); backgroundActionGroup->addAction(backgroundGradientAction); this->displayMenu->addAction(backgroundGradientAction); QAction* backgroundWhiteAction = new QAction("White Background", this); backgroundWhiteAction->setCheckable(true); - backgroundWhiteAction->setData(BACKGROUND_WHITE); + backgroundWhiteAction->setData(static_cast(Background::white)); backgroundActionGroup->addAction(backgroundWhiteAction); this->displayMenu->addAction(backgroundWhiteAction); @@ -447,52 +447,52 @@ MainWindow::init() QObject::connect(sizeActionGroup, SIGNAL(triggered(QAction*)), this, SLOT(selectSize(QAction*))); QAction* size640x480Action = new QAction("640x480", this); - size640x480Action->setData(SIZE_640x480); + size640x480Action->setData(static_cast(Size::s640x480)); sizeActionGroup->addAction(size640x480Action); this->displayMenu->addAction(size640x480Action); QAction* size800x600Action = new QAction("800x600", this); - size800x600Action->setData(SIZE_800x600); + size800x600Action->setData(static_cast(Size::s800x600)); sizeActionGroup->addAction(size800x600Action); this->displayMenu->addAction(size800x600Action); QAction* size1024x768Action = new QAction("1024x768", this); - size1024x768Action->setData(SIZE_1024x768); + size1024x768Action->setData(static_cast(Size::s1024x768)); sizeActionGroup->addAction(size1024x768Action); this->displayMenu->addAction(size1024x768Action); QAction* size1024x1024Action = new QAction("1024x1024", this); - size1024x1024Action->setData(SIZE_1024x1024); + size1024x1024Action->setData(static_cast(Size::s1024x1024)); sizeActionGroup->addAction(size1024x1024Action); this->displayMenu->addAction(size1024x1024Action); QAction* size1280x720Action = new QAction("1280x720", this); - size1280x720Action->setData(SIZE_1280x720); + size1280x720Action->setData(static_cast(Size::s1280x720)); sizeActionGroup->addAction(size1280x720Action); this->displayMenu->addAction(size1280x720Action); QAction* size1280x960Action = new QAction("1280x960", this); - size1280x960Action->setData(SIZE_1280x960); + size1280x960Action->setData(static_cast(Size::s1280x960)); sizeActionGroup->addAction(size1280x960Action); this->displayMenu->addAction(size1280x960Action); QAction* size1200x1200Action = new QAction("1200x1200", this); - size1200x1200Action->setData(SIZE_1200x1200); + size1200x1200Action->setData(static_cast(Size::s1200x1200)); sizeActionGroup->addAction(size1200x1200Action); this->displayMenu->addAction(size1200x1200Action); QAction* size1600x1200Action = new QAction("1600x1200", this); - size1600x1200Action->setData(SIZE_1600x1200); + size1600x1200Action->setData(static_cast(Size::s1600x1200)); sizeActionGroup->addAction(size1600x1200Action); this->displayMenu->addAction(size1600x1200Action); QAction* size1920x1080Action = new QAction("1920x1080", this); - size1920x1080Action->setData(SIZE_1920x1080); + size1920x1080Action->setData(static_cast(Size::s1920x1080)); sizeActionGroup->addAction(size1920x1080Action); this->displayMenu->addAction(size1920x1080Action); QAction* size2400x2400Action = new QAction("2400x2400", this); - size2400x2400Action->setData(SIZE_2400x2400); + size2400x2400Action->setData(static_cast(Size::s2400x2400)); sizeActionGroup->addAction(size2400x2400Action); this->displayMenu->addAction(size2400x2400Action); } @@ -740,16 +740,16 @@ MainWindow::saveImageWithoutAlpha() void MainWindow::selectBackground(QAction* action) { - switch (action->data().toInt()) + switch (static_cast(action->data().toInt())) { - case BACKGROUND_BLACK: + case Background::black: this->backgroundSwitch->whichChild = SO_SWITCH_NONE; this->viewer->setBackgroundColor(SbColor(0, 0, 0)); break; - case BACKGROUND_GRADIENT: + case Background::gradient: this->backgroundSwitch->whichChild = SO_SWITCH_ALL; break; - case BACKGROUND_WHITE: + case Background::white: this->backgroundSwitch->whichChild = SO_SWITCH_NONE; this->viewer->setBackgroundColor(SbColor(255, 255, 255)); break; @@ -761,12 +761,12 @@ MainWindow::selectBackground(QAction* action) void MainWindow::selectCamera(QAction* action) { - switch (action->data().toInt()) + switch (static_cast(action->data().toInt())) { - case CAMERA_ORTHOGONAL: + case Camera::orthogonal: this->viewer->setCameraType(SoOrthographicCamera::getClassTypeId()); break; - case CAMERA_PERSPECTIVE: + case Camera::perspective: this->viewer->setCameraType(SoPerspectiveCamera::getClassTypeId()); break; default: @@ -780,17 +780,17 @@ MainWindow::selectCamera(QAction* action) void MainWindow::selectOrigin(QAction* action) { - switch (action->data().toInt()) + switch (static_cast(action->data().toInt())) { - case ORIGIN_NONE: + case Origin::none: this->origin1Switch->whichChild = SO_SWITCH_NONE; this->origin1000Switch->whichChild = SO_SWITCH_NONE; break; - case ORIGIN_1: + case Origin::o1: this->origin1000Switch->whichChild = SO_SWITCH_NONE; this->origin1Switch->whichChild = SO_SWITCH_ALL; break; - case ORIGIN_1000: + case Origin::o1000: this->origin1Switch->whichChild = SO_SWITCH_NONE; this->origin1000Switch->whichChild = SO_SWITCH_ALL; break; @@ -802,36 +802,36 @@ MainWindow::selectOrigin(QAction* action) void MainWindow::selectSize(QAction* action) { - switch (action->data().toInt()) + switch (static_cast(action->data().toInt())) { - case SIZE_640x480: + case Size::s640x480: this->widget->setFixedSize(640, 480); break; - case SIZE_800x600: + case Size::s800x600: this->widget->setFixedSize(800, 600); break; - case SIZE_1024x768: + case Size::s1024x768: this->widget->setFixedSize(1024, 768); break; - case SIZE_1024x1024: + case Size::s1024x1024: this->widget->setFixedSize(1024, 1024); break; - case SIZE_1280x720: + case Size::s1280x720: this->widget->setFixedSize(1280, 720); break; - case SIZE_1280x960: + case Size::s1280x960: this->widget->setFixedSize(1280, 960); break; - case SIZE_1200x1200: + case Size::s1200x1200: this->widget->setFixedSize(1200, 1200); break; - case SIZE_1600x1200: + case Size::s1600x1200: this->widget->setFixedSize(1600, 1200); break; - case SIZE_1920x1080: + case Size::s1920x1080: this->widget->setFixedSize(1920, 1080); break; - case SIZE_2400x2400: + case Size::s2400x2400: this->widget->setFixedSize(2400, 2400); break; default: @@ -851,38 +851,38 @@ MainWindow::selectView(QAction* action) SbVec3f position; SbVec3f upvector(0, 0, 1); - switch (action->data().toInt()) + switch (static_cast(action->data().toInt())) { - case VIEW_BACK: + case View::back: position.setValue(0, -1, 0); break; - case VIEW_BOTTOM: + case View::bottom: position.setValue(0, 0, -1); upvector.setValue(0, -1, 0); break; - case VIEW_FRONT: + case View::front: position.setValue(0, 1, 0); break; - case VIEW_LEFT: + case View::left: position.setValue(-1, 0, 0); break; - case VIEW_RIGHT: + case View::right: position.setValue(1, 0, 0); break; - case VIEW_TOP: + case View::top: position.setValue(0, 0, 1); upvector.setValue(0, 1, 0); break; - case VIEW_TOP_BACK_LEFT: + case View::topBackLeft: position.setValue(-1, -1, 1); break; - case VIEW_TOP_BACK_RIGHT: + case View::topBackRight: position.setValue(1, -1, 1); break; - case VIEW_TOP_FRONT_LEFT: + case View::topFrontLeft: position.setValue(-1, 1, 1); break; - case VIEW_TOP_FRONT_RIGHT: + case View::topFrontRight: position.setValue(1, 1, 1); break; default: diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index 0c7e523b..6ebad525 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -57,52 +57,52 @@ class MainWindow : public QMainWindow void dropEvent(QDropEvent* event); private: - enum BACKGROUND + enum class Background { - BACKGROUND_BLACK, - BACKGROUND_GRADIENT, - BACKGROUND_WHITE + black, + gradient, + white }; - enum CAMERA + enum class Camera { - CAMERA_ORTHOGONAL, - CAMERA_PERSPECTIVE + orthogonal, + perspective }; - enum ORIGIN + enum class Origin { - ORIGIN_NONE, - ORIGIN_1, - ORIGIN_1000 + none, + o1, + o1000 }; - enum SIZE + enum class Size { - SIZE_640x480, - SIZE_800x600, - SIZE_1024x768, - SIZE_1024x1024, - SIZE_1280x720, - SIZE_1280x960, - SIZE_1200x1200, - SIZE_1600x1200, - SIZE_1920x1080, - SIZE_2400x2400 + s640x480, + s800x600, + s1024x768, + s1024x1024, + s1280x720, + s1280x960, + s1200x1200, + s1600x1200, + s1920x1080, + s2400x2400 }; - enum VIEW + enum class View { - VIEW_BACK, - VIEW_BOTTOM, - VIEW_FRONT, - VIEW_LEFT, - VIEW_RIGHT, - VIEW_TOP, - VIEW_TOP_BACK_LEFT, - VIEW_TOP_BACK_RIGHT, - VIEW_TOP_FRONT_LEFT, - VIEW_TOP_FRONT_RIGHT + back, + bottom, + front, + left, + right, + top, + topBackLeft, + topBackRight, + topFrontLeft, + topFrontRight }; void init(); diff --git a/src/rl/hal/Dc1394Camera.cpp b/src/rl/hal/Dc1394Camera.cpp index abcc7fe2..8595ef8f 100644 --- a/src/rl/hal/Dc1394Camera.cpp +++ b/src/rl/hal/Dc1394Camera.cpp @@ -39,16 +39,16 @@ namespace rl buffer(8), camera(nullptr), cameras(0), - colorCoding(COLOR_CODING_RAW8), + colorCoding(ColorCoding::raw8), dc1394(::dc1394_new()), frame(), framerate(static_cast(DC1394_FRAMERATE_MIN)), height(DC1394_USE_MAX_AVAIL), left(0), node(node), - speed(ISO_SPEED_400), + speed(IsoSpeed::i400), top(0), - videoMode(VIDEO_MODE_640x480_RGB8), + videoMode(VideoMode::v640x480_rgb8), width(DC1394_USE_MAX_AVAIL) { } @@ -75,66 +75,66 @@ namespace rl { switch (this->videoMode) { - case VIDEO_MODE_640x480_MONO8: - case VIDEO_MODE_800x600_MONO8: - case VIDEO_MODE_1024x768_MONO8: - case VIDEO_MODE_1280x960_MONO8: - case VIDEO_MODE_1600x1200_MONO8: + case VideoMode::v640x480_mono8: + case VideoMode::v800x600_mono8: + case VideoMode::v1024x768_mono8: + case VideoMode::v1280x960_mono8: + case VideoMode::v1600x1200_mono8: return 8; break; - case VIDEO_MODE_640x480_YUV411: + case VideoMode::v640x480_yuv411: return 12; break; - case VIDEO_MODE_640x480_MONO16: - case VIDEO_MODE_800x600_MONO16: - case VIDEO_MODE_1024x768_MONO16: - case VIDEO_MODE_1280x960_MONO16: - case VIDEO_MODE_1600x1200_MONO16: - case VIDEO_MODE_320x240_YUV422: - case VIDEO_MODE_640x480_YUV422: - case VIDEO_MODE_800x600_YUV422: - case VIDEO_MODE_1024x768_YUV422: - case VIDEO_MODE_1280x960_YUV422: - case VIDEO_MODE_1600x1200_YUV422: + case VideoMode::v640x480_mono16: + case VideoMode::v800x600_mono16: + case VideoMode::v1024x768_mono16: + case VideoMode::v1280x960_mono16: + case VideoMode::v1600x1200_mono16: + case VideoMode::v320x240_yuv422: + case VideoMode::v640x480_yuv422: + case VideoMode::v800x600_yuv422: + case VideoMode::v1024x768_yuv422: + case VideoMode::v1280x960_yuv422: + case VideoMode::v1600x1200_yuv422: return 16; break; - case VIDEO_MODE_640x480_RGB8: - case VIDEO_MODE_800x600_RGB8: - case VIDEO_MODE_1024x768_RGB8: - case VIDEO_MODE_1280x960_RGB8: - case VIDEO_MODE_1600x1200_RGB8: - case VIDEO_MODE_160x120_YUV444: + case VideoMode::v640x480_rgb8: + case VideoMode::v800x600_rgb8: + case VideoMode::v1024x768_rgb8: + case VideoMode::v1280x960_rgb8: + case VideoMode::v1600x1200_rgb8: + case VideoMode::v160x120_yuv444: return 24; break; - case VIDEO_MODE_FORMAT7_0: - case VIDEO_MODE_FORMAT7_1: - case VIDEO_MODE_FORMAT7_2: - case VIDEO_MODE_FORMAT7_3: - case VIDEO_MODE_FORMAT7_4: - case VIDEO_MODE_FORMAT7_5: - case VIDEO_MODE_FORMAT7_6: - case VIDEO_MODE_FORMAT7_7: + case VideoMode::format7_0: + case VideoMode::format7_1: + case VideoMode::format7_2: + case VideoMode::format7_3: + case VideoMode::format7_4: + case VideoMode::format7_5: + case VideoMode::format7_6: + case VideoMode::format7_7: switch (this->colorCoding) { - case COLOR_CODING_MONO8: - case COLOR_CODING_RAW8: + case ColorCoding::mono8: + case ColorCoding::raw8: return 8; break; - case COLOR_CODING_YUV411: + case ColorCoding::yuv411: return 12; break; - case COLOR_CODING_MONO16: - case COLOR_CODING_MONO16S: - case COLOR_CODING_RAW16: - case COLOR_CODING_YUV422: + case ColorCoding::mono16: + case ColorCoding::mono16s: + case ColorCoding::raw16: + case ColorCoding::yuv422: return 16; break; - case COLOR_CODING_RGB8: - case COLOR_CODING_YUV444: + case ColorCoding::rgb8: + case ColorCoding::yuv444: return 24; break; - case COLOR_CODING_RGB16: - case COLOR_CODING_RGB16S: + case ColorCoding::rgb16: + case ColorCoding::rgb16s: return 48; break; default: @@ -153,56 +153,56 @@ namespace rl { switch (this->videoMode) { - case VIDEO_MODE_640x480_MONO8: - case VIDEO_MODE_800x600_MONO8: - case VIDEO_MODE_1024x768_MONO8: - case VIDEO_MODE_1280x960_MONO8: - case VIDEO_MODE_1600x1200_MONO8: - case VIDEO_MODE_640x480_RGB8: - case VIDEO_MODE_800x600_RGB8: - case VIDEO_MODE_1024x768_RGB8: - case VIDEO_MODE_1280x960_RGB8: - case VIDEO_MODE_1600x1200_RGB8: - case VIDEO_MODE_640x480_YUV411: - case VIDEO_MODE_320x240_YUV422: - case VIDEO_MODE_640x480_YUV422: - case VIDEO_MODE_800x600_YUV422: - case VIDEO_MODE_1024x768_YUV422: - case VIDEO_MODE_1280x960_YUV422: - case VIDEO_MODE_1600x1200_YUV422: - case VIDEO_MODE_160x120_YUV444: + case VideoMode::v640x480_mono8: + case VideoMode::v800x600_mono8: + case VideoMode::v1024x768_mono8: + case VideoMode::v1280x960_mono8: + case VideoMode::v1600x1200_mono8: + case VideoMode::v640x480_rgb8: + case VideoMode::v800x600_rgb8: + case VideoMode::v1024x768_rgb8: + case VideoMode::v1280x960_rgb8: + case VideoMode::v1600x1200_rgb8: + case VideoMode::v640x480_yuv411: + case VideoMode::v320x240_yuv422: + case VideoMode::v640x480_yuv422: + case VideoMode::v800x600_yuv422: + case VideoMode::v1024x768_yuv422: + case VideoMode::v1280x960_yuv422: + case VideoMode::v1600x1200_yuv422: + case VideoMode::v160x120_yuv444: return 8; break; - case VIDEO_MODE_640x480_MONO16: - case VIDEO_MODE_800x600_MONO16: - case VIDEO_MODE_1024x768_MONO16: - case VIDEO_MODE_1280x960_MONO16: - case VIDEO_MODE_1600x1200_MONO16: + case VideoMode::v640x480_mono16: + case VideoMode::v800x600_mono16: + case VideoMode::v1024x768_mono16: + case VideoMode::v1280x960_mono16: + case VideoMode::v1600x1200_mono16: return 16; break; - case VIDEO_MODE_FORMAT7_0: - case VIDEO_MODE_FORMAT7_1: - case VIDEO_MODE_FORMAT7_2: - case VIDEO_MODE_FORMAT7_3: - case VIDEO_MODE_FORMAT7_4: - case VIDEO_MODE_FORMAT7_5: - case VIDEO_MODE_FORMAT7_6: - case VIDEO_MODE_FORMAT7_7: + case VideoMode::format7_0: + case VideoMode::format7_1: + case VideoMode::format7_2: + case VideoMode::format7_3: + case VideoMode::format7_4: + case VideoMode::format7_5: + case VideoMode::format7_6: + case VideoMode::format7_7: switch (this->colorCoding) { - case COLOR_CODING_MONO8: - case COLOR_CODING_RAW8: - case COLOR_CODING_RGB8: - case COLOR_CODING_YUV411: - case COLOR_CODING_YUV422: - case COLOR_CODING_YUV444: + case ColorCoding::mono8: + case ColorCoding::raw8: + case ColorCoding::rgb8: + case ColorCoding::yuv411: + case ColorCoding::yuv422: + case ColorCoding::yuv444: return 8; break; - case COLOR_CODING_MONO16: - case COLOR_CODING_MONO16S: - case COLOR_CODING_RAW16: - case COLOR_CODING_RGB16: - case COLOR_CODING_RGB16S: + case ColorCoding::mono16: + case ColorCoding::mono16s: + case ColorCoding::raw16: + case ColorCoding::rgb16: + case ColorCoding::rgb16s: return 16; break; default: @@ -449,28 +449,28 @@ namespace rl switch (this->framerate) { - case FRAMERATE_1_875: + case Framerate::f1_875: framerate = 1.875; break; - case FRAMERATE_3_75: + case Framerate::f3_75: framerate = 3.75; break; - case FRAMERATE_7_5: + case Framerate::f7_5: framerate = 7.5; break; - case FRAMERATE_15: + case Framerate::f15: framerate = 15.0; break; - case FRAMERATE_30: + case Framerate::f30: framerate = 30.0; break; - case FRAMERATE_60: + case Framerate::f60: framerate = 60.0; break; - case FRAMERATE_120: + case Framerate::f120: framerate = 120.0; break; - case FRAMERATE_240: + case Framerate::f240: framerate = 240.0; break; default: diff --git a/src/rl/hal/Dc1394Camera.h b/src/rl/hal/Dc1394Camera.h index 0f05ff76..f3f47da7 100644 --- a/src/rl/hal/Dc1394Camera.h +++ b/src/rl/hal/Dc1394Camera.h @@ -44,116 +44,116 @@ namespace rl class RL_HAL_EXPORT Dc1394Camera : public Camera, public CyclicDevice { public: - enum ColorCoding + enum class ColorCoding { - COLOR_CODING_MONO8 = ::DC1394_COLOR_CODING_MONO8, - COLOR_CODING_YUV411, - COLOR_CODING_YUV422, - COLOR_CODING_YUV444, - COLOR_CODING_RGB8, - COLOR_CODING_MONO16, - COLOR_CODING_RGB16, - COLOR_CODING_MONO16S, - COLOR_CODING_RGB16S, - COLOR_CODING_RAW8, - COLOR_CODING_RAW16 + mono8 = ::DC1394_COLOR_CODING_MONO8, + yuv411, + yuv422, + yuv444, + rgb8, + mono16, + rgb16, + mono16s, + rgb16s, + raw8, + raw16 }; - enum Feature + enum class Feature { - FEATURE_BRIGHTNESS = ::DC1394_FEATURE_BRIGHTNESS, - FEATURE_EXPOSURE, - FEATURE_SHARPNESS, - FEATURE_WHITE_BALANCE, - FEATURE_HUE, - FEATURE_SATURATION, - FEATURE_GAMMA, - FEATURE_SHUTTER, - FEATURE_GAIN, - FEATURE_IRIS, - FEATURE_FOCUS, - FEATURE_TEMPERATURE, - FEATURE_TRIGGER, - FEATURE_TRIGGER_DELAY, - FEATURE_WHITE_SHADING, - FEATURE_FRAME_RATE, - FEATURE_ZOOM, - FEATURE_PAN, - FEATURE_TILT, - FEATURE_OPTICAL_FILTER, - FEATURE_CAPTURE_SIZE, - FEATURE_CAPTURE_QUALITY + brightness = ::DC1394_FEATURE_BRIGHTNESS, + exposure, + sharpness, + whiteBalance, + hue, + saturation, + gamma, + shutter, + gain, + iris, + focus, + temperature, + trigger, + triggerDelay, + whiteShading, + frameRate, + zoom, + pan, + tilt, + opticalFilter, + captureSize, + captureQuality }; - enum FeatureMode + enum class FeatureMode { - FEATURE_MODE_MANUAL = ::DC1394_FEATURE_MODE_MANUAL, - FEATURE_MODE_AUTO, - FEATURE_MODE_ONE_PUSH_AUTO + manual = ::DC1394_FEATURE_MODE_MANUAL, + automatic, + onePushAuto }; - enum Framerate + enum class Framerate { - FRAMERATE_1_875 = ::DC1394_FRAMERATE_1_875, - FRAMERATE_3_75, - FRAMERATE_7_5, - FRAMERATE_15, - FRAMERATE_30, - FRAMERATE_60, - FRAMERATE_120, - FRAMERATE_240 + f1_875 = ::DC1394_FRAMERATE_1_875, + f3_75, + f7_5, + f15, + f30, + f60, + f120, + f240 }; - enum IsoSpeed + enum class IsoSpeed { - ISO_SPEED_100 = ::DC1394_ISO_SPEED_100, - ISO_SPEED_200, - ISO_SPEED_400, - ISO_SPEED_800, - ISO_SPEED_1600, - ISO_SPEED_3200 + i100 = ::DC1394_ISO_SPEED_100, + i200, + i400, + i800, + i1600, + i3200 }; - enum OperationMode + enum class OperationMode { - OPERATION_MODE_LEGACY = ::DC1394_OPERATION_MODE_LEGACY, - OPERATION_MODE_1394B + legacy = ::DC1394_OPERATION_MODE_LEGACY, + o1394b }; - enum VideoMode + enum class VideoMode { - VIDEO_MODE_160x120_YUV444 = ::DC1394_VIDEO_MODE_160x120_YUV444, - VIDEO_MODE_320x240_YUV422, - VIDEO_MODE_640x480_YUV411, - VIDEO_MODE_640x480_YUV422, - VIDEO_MODE_640x480_RGB8, - VIDEO_MODE_640x480_MONO8, - VIDEO_MODE_640x480_MONO16, - VIDEO_MODE_800x600_YUV422, - VIDEO_MODE_800x600_RGB8, - VIDEO_MODE_800x600_MONO8, - VIDEO_MODE_1024x768_YUV422, - VIDEO_MODE_1024x768_RGB8, - VIDEO_MODE_1024x768_MONO8, - VIDEO_MODE_800x600_MONO16, - VIDEO_MODE_1024x768_MONO16, - VIDEO_MODE_1280x960_YUV422, - VIDEO_MODE_1280x960_RGB8, - VIDEO_MODE_1280x960_MONO8, - VIDEO_MODE_1600x1200_YUV422, - VIDEO_MODE_1600x1200_RGB8, - VIDEO_MODE_1600x1200_MONO8, - VIDEO_MODE_1280x960_MONO16, - VIDEO_MODE_1600x1200_MONO16, - VIDEO_MODE_EXIF, - VIDEO_MODE_FORMAT7_0, - VIDEO_MODE_FORMAT7_1, - VIDEO_MODE_FORMAT7_2, - VIDEO_MODE_FORMAT7_3, - VIDEO_MODE_FORMAT7_4, - VIDEO_MODE_FORMAT7_5, - VIDEO_MODE_FORMAT7_6, - VIDEO_MODE_FORMAT7_7 + v160x120_yuv444 = ::DC1394_VIDEO_MODE_160x120_YUV444, + v320x240_yuv422, + v640x480_yuv411, + v640x480_yuv422, + v640x480_rgb8, + v640x480_mono8, + v640x480_mono16, + v800x600_yuv422, + v800x600_rgb8, + v800x600_mono8, + v1024x768_yuv422, + v1024x768_rgb8, + v1024x768_mono8, + v800x600_mono16, + v1024x768_mono16, + v1280x960_yuv422, + v1280x960_rgb8, + v1280x960_mono8, + v1600x1200_yuv422, + v1600x1200_rgb8, + v1600x1200_mono8, + v1280x960_mono16, + v1600x1200_mono16, + exif, + format7_0, + format7_1, + format7_2, + format7_3, + format7_4, + format7_5, + format7_6, + format7_7 }; class Exception : public DeviceException @@ -292,7 +292,7 @@ namespace rl unsigned int node; - unsigned int speed; + IsoSpeed speed; unsigned int top; diff --git a/src/rl/hal/LeuzeRs4.cpp b/src/rl/hal/LeuzeRs4.cpp index 6e346463..cbac4107 100644 --- a/src/rl/hal/LeuzeRs4.cpp +++ b/src/rl/hal/LeuzeRs4.cpp @@ -44,7 +44,7 @@ namespace rl ) : CyclicDevice(::std::chrono::nanoseconds::zero()), Lidar(), - baudRate(BAUDRATE_57600BPS), + baudRate(BaudRate::b57600), data(), desired(baudRate), far1(false), @@ -55,11 +55,11 @@ namespace rl password(password), serial( filename, - Serial::BAUDRATE_57600BPS, - Serial::DATABITS_8BITS, - Serial::FLOWCONTROL_OFF, - Serial::PARITY_NOPARITY, - Serial::STOPBITS_1BIT + Serial::BaudRate::b57600, + Serial::DataBits::d8, + Serial::FlowControl::off, + Serial::Parity::none, + Serial::StopBits::s1 ), startIndex(0xFFFF), stepSize(0xFFFF), @@ -78,14 +78,9 @@ namespace rl { assert(this->isConnected()); -// if (MONITORING_SINGLE != this->monitoring) +// if (BaudRate::b57600 != this->baudRate) // { -// this->setMonitoring(MONITORING_SINGLE); -// } -// -// if (BAUDRATE_57600BPS != this->baudRate) -// { -// this->setBaudRate(BAUDRATE_57600BPS); +// this->setBaudRate(BaudRate::b57600); // } this->serial.close(); @@ -249,14 +244,14 @@ namespace rl buf[5] = 0x42; Serial::BaudRate baudRates[6] = { -// Serial::BAUDRATE_625000BPS, -// Serial::BAUDRATE_345600BPS, - Serial::BAUDRATE_115200BPS, - Serial::BAUDRATE_57600BPS, - Serial::BAUDRATE_38400BPS, - Serial::BAUDRATE_19200BPS, - Serial::BAUDRATE_9600BPS, - Serial::BAUDRATE_4800BPS +// Serial::BaudRate::b625000, +// Serial::BaudRate::b345600, + Serial::BaudRate::b115200, + Serial::BaudRate::b57600, + Serial::BaudRate::b38400, + Serial::BaudRate::b19200, + Serial::BaudRate::b9600, + Serial::BaudRate::b4800 }; for (::std::size_t i = 0; i < 6; ++i) @@ -308,17 +303,17 @@ namespace rl { #ifndef WIN32 case 0x01: - this->baudRate = BAUDRATE_500000BPS; + this->baudRate = BaudRate::b500000; break; #endif // WIN32 case 0x19: - this->baudRate = BAUDRATE_38400BPS; + this->baudRate = BaudRate::b38400; break; case 0x33: - this->baudRate = BAUDRATE_19200BPS; + this->baudRate = BaudRate::b19200; break; case 0x67: - this->baudRate = BAUDRATE_9600BPS; + this->baudRate = BaudRate::b9600; break; default: break; @@ -333,7 +328,7 @@ namespace rl if (0x25 != buf[12]) { - this->setMonitoring(MONITORING_SINGLE); + this->setMonitoring(Monitoring::single); } #endif } @@ -555,42 +550,42 @@ namespace rl switch (baudRate) { - case BAUDRATE_4800BPS: + case BaudRate::b4800: ::std::cout << "setting to 4,800 baud" << ::std::endl; this->set(0x00, ptr, len); this->set(0x00, ptr, len); break; - case BAUDRATE_9600BPS: + case BaudRate::b9600: ::std::cout << "setting to 9,600 baud" << ::std::endl; this->set(0x00, ptr, len); this->set(0x01, ptr, len); break; - case BAUDRATE_19200BPS: + case BaudRate::b19200: ::std::cout << "setting to 19,200 baud" << ::std::endl; this->set(0x00, ptr, len); this->set(0x02, ptr, len); break; - case BAUDRATE_38400BPS: + case BaudRate::b38400: ::std::cout << "setting to 38,400 baud" << ::std::endl; this->set(0x00, ptr, len); this->set(0x03, ptr, len); break; - case BAUDRATE_57600BPS: + case BaudRate::b57600: ::std::cout << "setting to 57,600 baud" << ::std::endl; this->set(0x00, ptr, len); this->set(0x04, ptr, len); break; - case BAUDRATE_115200BPS: + case BaudRate::b115200: ::std::cout << "setting to 115,200 baud" << ::std::endl; this->set(0x00, ptr, len); this->set(0x05, ptr, len); break; -// case BAUDRATE_345600BPS: +// case BaudRate::b345600: //::std::cout << "setting to 345,600 baud" << ::std::endl; // this->set(0x00, ptr, len); // this->set(0x06, ptr, len); // break; -// case BAUDRATE_625000BPS: +// case BaudRate::b625000: //::std::cout << "setting to 625,000 baud" << ::std::endl; // this->set(0x00, ptr, len); // this->set(0xFF, ptr, len); @@ -610,29 +605,29 @@ ::std::cout << "setting to 115,200 baud" << ::std::endl; switch (baudRate) { - case BAUDRATE_4800BPS: - this->serial.setBaudRate(Serial::BAUDRATE_4800BPS); + case BaudRate::b4800: + this->serial.setBaudRate(Serial::BaudRate::b4800); break; - case BAUDRATE_9600BPS: - this->serial.setBaudRate(Serial::BAUDRATE_9600BPS); + case BaudRate::b9600: + this->serial.setBaudRate(Serial::BaudRate::b9600); break; - case BAUDRATE_19200BPS: - this->serial.setBaudRate(Serial::BAUDRATE_19200BPS); + case BaudRate::b19200: + this->serial.setBaudRate(Serial::BaudRate::b19200); break; - case BAUDRATE_38400BPS: - this->serial.setBaudRate(Serial::BAUDRATE_38400BPS); + case BaudRate::b38400: + this->serial.setBaudRate(Serial::BaudRate::b38400); break; - case BAUDRATE_57600BPS: - this->serial.setBaudRate(Serial::BAUDRATE_57600BPS); + case BaudRate::b57600: + this->serial.setBaudRate(Serial::BaudRate::b57600); break; - case BAUDRATE_115200BPS: - this->serial.setBaudRate(Serial::BAUDRATE_115200BPS); + case BaudRate::b115200: + this->serial.setBaudRate(Serial::BaudRate::b115200); break; -// case BAUDRATE_345600BPS: -// this->serial.setBaudRate(Serial::BAUDRATE_345600BPS); +// case BaudRate::b345600: +// this->serial.setBaudRate(Serial::BaudRate::b345600); // break; -// case BAUDRATE_625000BPS: -// this->serial.setBaudRate(Serial::BAUDRATE_625000BPS); +// case BaudRate::b625000: +// this->serial.setBaudRate(Serial::BaudRate::b625000); // break; default: break; diff --git a/src/rl/hal/LeuzeRs4.h b/src/rl/hal/LeuzeRs4.h index d786728a..21f0595d 100644 --- a/src/rl/hal/LeuzeRs4.h +++ b/src/rl/hal/LeuzeRs4.h @@ -45,24 +45,24 @@ namespace rl class RL_HAL_EXPORT LeuzeRs4 : public CyclicDevice, public Lidar { public: - enum BaudRate + enum class BaudRate { /** 4,800 bps. */ - BAUDRATE_4800BPS, + b4800, /** 9,600 bps. */ - BAUDRATE_9600BPS, + b9600, /** 19,200 bps. */ - BAUDRATE_19200BPS, + b19200, /** 38,400 bps. */ - BAUDRATE_38400BPS, + b38400, /** 57,600 bps. */ - BAUDRATE_57600BPS, + b57600, /** 115,200 bps. */ - BAUDRATE_115200BPS, + b115200, /** 345,600 bps. */ - BAUDRATE_345600BPS, + b345600, /** 625,000 bps. */ - BAUDRATE_625000BPS + b625000 }; /** @@ -70,7 +70,7 @@ namespace rl */ LeuzeRs4( const ::std::string& device = "/dev/ttyS0", - const BaudRate& baudRate = BAUDRATE_57600BPS, + const BaudRate& baudRate = BaudRate::b57600, const ::std::string& password = "ROD4LE" ); diff --git a/src/rl/hal/MitsubishiH7.cpp b/src/rl/hal/MitsubishiH7.cpp index d95aaf90..016001f9 100644 --- a/src/rl/hal/MitsubishiH7.cpp +++ b/src/rl/hal/MitsubishiH7.cpp @@ -253,8 +253,8 @@ namespace rl this->out.dat.pos.w.y = static_cast(x.translation().y() * 1000); this->out.dat.pos.w.z = static_cast(x.translation().z() * 1000); - this->out.command = MXT_COMMAND_MOVE; - this->out.sendType = MXT_TYPE_POSE; + this->out.command = static_cast<::std::uint16_t>(MxtCommand::move); + this->out.sendType = static_cast<::std::uint16_t>(MxtType::pose); } void @@ -267,8 +267,8 @@ namespace rl MitsubishiH7::setInput(const ::std::uint16_t& bitTop) { this->out.bitTop = bitTop; - this->out.recvIoType = MXT_IO_IN; - this->out.sendIoType = MXT_IO_NULL; + this->out.recvIoType = static_cast<::std::uint16_t>(MxtIo::in); + this->out.sendIoType = static_cast<::std::uint16_t>(MxtIo::null); } void @@ -307,8 +307,8 @@ namespace rl break; } - this->out.command = MXT_COMMAND_MOVE; - this->out.sendType = MXT_TYPE_JOINT; + this->out.command = static_cast<::std::uint16_t>(MxtCommand::move); + this->out.sendType = static_cast<::std::uint16_t>(MxtType::joint); } void @@ -353,8 +353,8 @@ namespace rl break; } - this->out.command = MXT_COMMAND_MOVE; - this->out.sendType = MXT_TYPE_PULSE; + this->out.command = static_cast<::std::uint16_t>(MxtCommand::move); + this->out.sendType = static_cast<::std::uint16_t>(MxtType::pulse); } void @@ -363,8 +363,8 @@ namespace rl this->out.bitMask = bitMask; this->out.bitTop = bitTop; this->out.ioData = ioData; - this->out.recvIoType = MXT_IO_NULL; - this->out.sendIoType = MXT_IO_OUT; + this->out.recvIoType = static_cast<::std::uint16_t>(MxtIo::null); + this->out.sendIoType = static_cast<::std::uint16_t>(MxtIo::out); } void @@ -382,7 +382,7 @@ namespace rl ::std::stringstream program; program << "10 OPEN \"ENET:" << address.getNameInfo(true) << "\" AS #1" << "\v"; - program << "20 MXT 1," << this->mode << "," << this->filter << "\v"; + program << "20 MXT 1," << static_cast(this->mode) << "," << this->filter << "\v"; program << "30 HLT" << "\v"; program << "40 END"; @@ -417,10 +417,10 @@ namespace rl void MitsubishiH7::step() { - this->out.recvType = MXT_TYPE_JOINT; - this->out.recvType1 = MXT_TYPE_POSE; - this->out.recvType2 = MXT_TYPE_PULSE; - this->out.recvType3 = MXT_TYPE_CURRENT_FEEDBACK; + this->out.recvType = static_cast<::std::uint16_t>(MxtType::joint); + this->out.recvType1 = static_cast<::std::uint16_t>(MxtType::pose); + this->out.recvType2 = static_cast<::std::uint16_t>(MxtType::pulse); + this->out.recvType3 = static_cast<::std::uint16_t>(MxtType::currentFeedback); this->socket.send(&this->out, sizeof(Command)); @@ -439,15 +439,15 @@ namespace rl this->out.bitMask = 0; this->out.bitTop = 0; - this->out.command = MXT_COMMAND_NULL; + this->out.command = static_cast<::std::uint16_t>(MxtCommand::null); this->out.ioData = 0; - this->out.recvIoType = MXT_IO_NULL; - this->out.recvType = MXT_TYPE_NULL; - this->out.recvType1 = MXT_TYPE_NULL; - this->out.recvType2 = MXT_TYPE_NULL; - this->out.recvType3 = MXT_TYPE_NULL; - this->out.sendIoType = MXT_IO_NULL; - this->out.sendType = MXT_TYPE_NULL; + this->out.recvIoType = static_cast<::std::uint16_t>(MxtIo::null); + this->out.recvType = static_cast<::std::uint16_t>( MxtType::null); + this->out.recvType1 = static_cast<::std::uint16_t>(MxtType::null); + this->out.recvType2 = static_cast<::std::uint16_t>(MxtType::null); + this->out.recvType3 = static_cast<::std::uint16_t>(MxtType::null); + this->out.sendIoType = static_cast<::std::uint16_t>(MxtIo::null); + this->out.sendType = static_cast<::std::uint16_t>(MxtType::null); } void @@ -455,15 +455,15 @@ namespace rl { this->out.bitMask = 0; this->out.bitTop = 0; - this->out.command = MXT_COMMAND_END; + this->out.command = static_cast<::std::uint16_t>(MxtCommand::end); this->out.ioData = 0; - this->out.recvType = MXT_TYPE_NULL; - this->out.recvType1 = MXT_TYPE_NULL; - this->out.recvType2 = MXT_TYPE_NULL; - this->out.recvType3 = MXT_TYPE_NULL; - this->out.recvIoType = MXT_IO_NULL; - this->out.sendType = MXT_TYPE_NULL; - this->out.sendIoType = MXT_IO_NULL; + this->out.recvType = static_cast<::std::uint16_t>(MxtType::null); + this->out.recvType1 = static_cast<::std::uint16_t>(MxtType::null); + this->out.recvType2 = static_cast<::std::uint16_t>(MxtType::null); + this->out.recvType3 = static_cast<::std::uint16_t>(MxtType::null); + this->out.recvIoType = static_cast<::std::uint16_t>(MxtIo::null); + this->out.sendType = static_cast<::std::uint16_t>(MxtType::null); + this->out.sendIoType = static_cast<::std::uint16_t>(MxtIo::null); this->socket.send(&this->out, sizeof(Command)); diff --git a/src/rl/hal/MitsubishiH7.h b/src/rl/hal/MitsubishiH7.h index b1abd4b6..ad56b31d 100644 --- a/src/rl/hal/MitsubishiH7.h +++ b/src/rl/hal/MitsubishiH7.h @@ -55,11 +55,11 @@ namespace rl public JointPositionSensor { public: - enum Mode + enum class Mode { - MODE_JOINT = 1, - MODE_POSE = 0, - MODE_PULSE = 2 + joint = 1, + pose = 0, + pulse = 2 }; MitsubishiH7( @@ -68,7 +68,7 @@ namespace rl const ::std::string& addressClient, const unsigned short int& portTcp = 10001, const unsigned short int& portUdp = 10000, - const Mode& mode = MODE_JOINT, + const Mode& mode = Mode::joint, const ::std::uint16_t& haltIoData = 0x00AA, const ::std::uint16_t& releaseIoData = 0x00A6, const ::std::uint16_t& shutIoData = 0x000A9 @@ -127,6 +127,55 @@ namespace rl void stopProgram(); protected: + enum class MxtCommand + { + /** Real-time external command invalid. */ + null = 0, + /** Real-time external command valid. */ + move = 1, + /** Real-time external command end. */ + end = 255 + }; + + enum class MxtIo + { + + /** No data. */ + null = 0, + /** Output signal. */ + out = 1, + /** Input signal. */ + in = 2 + }; + + enum class MxtType + { + /** No data. */ + null = 0, + /** XYZ data. */ + pose = 1, + /** Joint data. */ + joint = 2, + /** Motor pulse data. */ + pulse = 3, + /** XYZ data (position after filter process). */ + poseFilter = 4, + /** Joint data (position after filter process). */ + jointFilter = 5, + /** Motor pulse data (position after filter process). */ + pulseFilter = 6, + /** XYZ data (encoder feedback value). */ + poseFeedback = 7, + /** Joint data (encoder feedback value). */ + jointFeedback = 8, + /** Motor pulse data (encoder feedback value). */ + pulseFeedback = 9, + /** Current command [\%]. */ + currentCommand = 10, + /** Current feedback [\%]. */ + currentFeedback = 11 + }; + struct World { /** X axis coordinate value [mm]. */ @@ -253,45 +302,6 @@ namespace rl Data dat3; }; - /** Real-time external command invalid. */ - const static ::std::uint16_t MXT_COMMAND_NULL = 0; - /** Real-time external command valid. */ - const static ::std::uint16_t MXT_COMMAND_MOVE = 1; - /** Real-time external command end. */ - const static ::std::uint16_t MXT_COMMAND_END = 255; - - /** No data. */ - const static ::std::uint16_t MXT_IO_NULL = 0; - /** Output signal. */ - const static ::std::uint16_t MXT_IO_OUT = 1; - /** Input signal. */ - const static ::std::uint16_t MXT_IO_IN = 2; - - /** No data. */ - const static ::std::uint16_t MXT_TYPE_NULL = 0; - /** XYZ data. */ - const static ::std::uint16_t MXT_TYPE_POSE = 1; - /** Joint data. */ - const static ::std::uint16_t MXT_TYPE_JOINT = 2; - /** Motor pulse data. */ - const static ::std::uint16_t MXT_TYPE_PULSE = 3; - /** XYZ data (position after filter process). */ - const static ::std::uint16_t MXT_TYPE_POSE_FILTER = 4; - /** Joint data (position after filter process). */ - const static ::std::uint16_t MXT_TYPE_JOINT_FILTER = 5; - /** Motor pulse data (position after filter process). */ - const static ::std::uint16_t MXT_TYPE_PULSE_FILTER = 6; - /** XYZ data (encoder feedback value). */ - const static ::std::uint16_t MXT_TYPE_POSE_FEEDBACK = 7; - /** Joint data (encoder feedback value). */ - const static ::std::uint16_t MXT_TYPE_JOINT_FEEDBACK = 8; - /** Motor pulse data (encoder feedback value). */ - const static ::std::uint16_t MXT_TYPE_PULSE_FEEDBACK = 9; - /** Current command [\%]. */ - const static ::std::uint16_t MXT_TYPE_CURRENT_COMMAND = 10; - /** Current feedback [\%]. */ - const static ::std::uint16_t MXT_TYPE_CURRENT_FEEDBACK = 11; - private: /** Client ip address or hostname. */ ::std::string addressClient; diff --git a/src/rl/hal/MitsubishiR3.cpp b/src/rl/hal/MitsubishiR3.cpp index b30b33dd..282468d7 100644 --- a/src/rl/hal/MitsubishiR3.cpp +++ b/src/rl/hal/MitsubishiR3.cpp @@ -372,15 +372,15 @@ namespace rl if ("START" == tokens[16]) { - state.taskCond = TASKCOND_START; + state.taskCond = TaskCond::start; } else if ("ALWAYS" == tokens[16]) { - state.taskCond = TASKCOND_ALWAYS; + state.taskCond = TaskCond::always; } else if ("ERROR" == tokens[16]) { - state.taskCond = TASKCOND_ERROR; + state.taskCond = TaskCond::error; } state.taskPri = ::std::stoi(tokens[17]); diff --git a/src/rl/hal/MitsubishiR3.h b/src/rl/hal/MitsubishiR3.h index fec6bcb9..3d33efb5 100644 --- a/src/rl/hal/MitsubishiR3.h +++ b/src/rl/hal/MitsubishiR3.h @@ -45,32 +45,32 @@ namespace rl class RL_HAL_EXPORT MitsubishiR3 : public Com { public: - enum HandSts + enum class HandSts { - HANDSTS_NOTUSED = -1, + notused = -1, /** Hand open. */ - HANDSTS_OPEN = 1, + open = 1, /** Hand closed. */ - HANDSTS_CLOSED = 2 + closed = 2 }; - enum HandType + enum class HandType { - HANDTYPE_NOTUSED = -1, + notUsed = -1, /** Single-solenoid. */ - HANDTYPE_SINGLE = 0, + singleSolenoid = 0, /** Double-solenoid. */ - HANDTYPE_DOUBLE = 1 + doubleSolenoid = 1 }; - enum TaskCond + enum class TaskCond { /** START. */ - TASKCOND_START, + start, /** ALWAYS. */ - TASKCOND_ALWAYS, + always, /** ERROR. */ - TASKCOND_ERROR + error }; struct EditSts diff --git a/src/rl/hal/RobotiqModelC.cpp b/src/rl/hal/RobotiqModelC.cpp index d6f05272..e53729d5 100644 --- a/src/rl/hal/RobotiqModelC.cpp +++ b/src/rl/hal/RobotiqModelC.cpp @@ -41,11 +41,11 @@ namespace rl out(), serial( filename, - Serial::BAUDRATE_115200BPS, - Serial::DATABITS_8BITS, - Serial::FLOWCONTROL_OFF, - Serial::PARITY_NOPARITY, - Serial::STOPBITS_1BIT + Serial::BaudRate::b115200, + Serial::DataBits::d8, + Serial::FlowControl::off, + Serial::Parity::none, + Serial::StopBits::s1 ) { this->in.fill(0x00); @@ -229,7 +229,7 @@ namespace rl { this->step(); - if (ACTIVATION_STATUS_READY != this->getActivationStatus() || GRIPPER_STATUS_READY != this->getGripperStatus()) + if (ActivationStatus::ready != this->getActivationStatus() || GripperStatus::ready != this->getGripperStatus()) { this->out[1] = 0x10; // function code @@ -306,12 +306,12 @@ namespace rl this->send(this->out.data(), 1 + 1 + 2 + 2 + 2); this->recv(this->in.data(), 1 + 1 + 1 + 6 + 2); - if (this->getFaultStatus() >= 0x0A) + if (static_cast(this->getFaultStatus()) >= 0x0A) { throw Exception(this->getFaultStatus()); } - if (ACTIVATION_STATUS_READY == this->getActivationStatus() && GRIPPER_STATUS_READY == this->getGripperStatus()) + if (ActivationStatus::ready == this->getActivationStatus() && GripperStatus::ready == this->getGripperStatus()) { this->setRunning(true); } @@ -348,34 +348,34 @@ namespace rl { switch (this->faultStatus) { - case FAULT_STATUS_NONE: + case FaultStatus::none: return "No fault."; break; - case FAULT_STATUS_NOTICE_ACTIVATION_NEEDED: + case FaultStatus::noticeActivationNeeded: return "The activation bit must be set prior to action"; break; - case FAULT_STATUS_WARNING_TEMPERATURE: + case FaultStatus::warningTemperature: return "Maximum operating temperature exceeded, wait for cool-down"; break; - case FAULT_STATUS_WARNING_COMM_NOT_READY: + case FaultStatus::warningCommNotReady: return "The communication chip is not ready (may be booting)."; break; - case FAULT_STATUS_WARNING_VOLTAGE: + case FaultStatus::warningVoltage: return "Under minimum operating voltage."; break; - case FAULT_STATUS_WARNING_AUTOMATIC_RELEASE: + case FaultStatus::warningAutomaticRelease: return "Automatic release in progress."; break; - case FAULT_STATUS_ERROR_INTERNAL: + case FaultStatus::errorInternal: return "Internal fault."; break; - case FAULT_STATUS_ERROR_ACTIVATION_FAULT: + case FaultStatus::errorActivationFault: return "Activation fault, verify that no interference or other error occurred."; break; - case FAULT_STATUS_ERROR_MODE_FAULT: + case FaultStatus::errorModeFault: return "Overcurrent triggered."; break; - case FAULT_STATUS_ERROR_AUTOMATIC_RELEASE_COMPLETE: + case FaultStatus::errorAutomaticReleaseComplete: return "Automatic release completed."; break; default: diff --git a/src/rl/hal/RobotiqModelC.h b/src/rl/hal/RobotiqModelC.h index af3773e0..07d7b93a 100644 --- a/src/rl/hal/RobotiqModelC.h +++ b/src/rl/hal/RobotiqModelC.h @@ -42,52 +42,52 @@ namespace rl class RL_HAL_EXPORT RobotiqModelC : public CyclicDevice, public Gripper { public: - enum ActionStatus + enum class ActionStatus { - ACTION_STATUS_STOPPED = 0x00, - ACTION_STATUS_GOING = 0x01 + stopped = 0x00, + going = 0x01 }; - enum ActivationStatus + enum class ActivationStatus { - ACTIVATION_STATUS_RESET = 0x00, - ACTIVATION_STATUS_READY = 0x01 + reset = 0x00, + ready = 0x01 }; - enum FaultStatus + enum class FaultStatus { - FAULT_STATUS_NONE = 0x00, - FAULT_STATUS_UNKNOWN_1 = 0x01, - FAULT_STATUS_UNKNOWN_2 = 0x02, - FAULT_STATUS_UNKNOWN_3 = 0x03, - FAULT_STATUS_UNKNOWN_4 = 0x04, - FAULT_STATUS_NOTICE_ACTIVATION_DELAYED = 0x05, - FAULT_STATUS_NOTICE_MODE_DELAYED = 0x06, - FAULT_STATUS_NOTICE_ACTIVATION_NEEDED = 0x07, - FAULT_STATUS_WARNING_TEMPERATURE = 0x08, - FAULT_STATUS_WARNING_COMM_NOT_READY = 0x09, - FAULT_STATUS_WARNING_VOLTAGE = 0x0A, - FAULT_STATUS_WARNING_AUTOMATIC_RELEASE = 0x0B, - FAULT_STATUS_ERROR_INTERNAL = 0x0C, - FAULT_STATUS_ERROR_ACTIVATION_FAULT = 0x0D, - FAULT_STATUS_ERROR_MODE_FAULT = 0x0E, - FAULT_STATUS_ERROR_AUTOMATIC_RELEASE_COMPLETE = 0x0F + none = 0x00, + unknown1 = 0x01, + unknown2 = 0x02, + unknown3 = 0x03, + unknown4 = 0x04, + noticeActivationDelayed = 0x05, + noticeModeDelayed = 0x06, + noticeActivationNeeded = 0x07, + warningTemperature = 0x08, + warningCommNotReady = 0x09, + warningVoltage = 0x0a, + warningAutomaticRelease = 0x0b, + errorInternal = 0x0c, + errorActivationFault = 0x0d, + errorModeFault = 0x0e, + errorAutomaticReleaseComplete = 0x0f }; - enum GripperStatus + enum class GripperStatus { - GRIPPER_STATUS_RESET = 0x00, - GRIPPER_STATUS_ACTIVATING = 0x01, - GRIPPER_STATUS_UNUSED = 0x02, - GRIPPER_STATUS_READY = 0x03 + reset = 0x00, + activating = 0x01, + unused = 0x02, + ready = 0x03 }; - enum ObjectStatus + enum class ObjectStatus { - OBJECT_STATUS_MOTION = 0x00, - OBJECT_STATUS_CONTACT_OPEN = 0x01, - OBJECT_STATUS_CONTACT_CLOSE = 0x02, - OBJECT_STATUS_MOTION_COMPLETE = 0x03 + motion = 0x00, + contactOpen = 0x01, + contactClose = 0x02, + motionComplete = 0x03 }; class Exception : public DeviceException diff --git a/src/rl/hal/SchmersalLss300.cpp b/src/rl/hal/SchmersalLss300.cpp index e47ad17d..18bff07a 100644 --- a/src/rl/hal/SchmersalLss300.cpp +++ b/src/rl/hal/SchmersalLss300.cpp @@ -45,18 +45,18 @@ namespace rl ) : CyclicDevice(::std::chrono::nanoseconds::zero()), Lidar(), - baudRate(BAUDRATE_9600BPS), + baudRate(BaudRate::b9600), data(), desired(baudRate), monitoring(monitoring), password(password), serial( filename, - Serial::BAUDRATE_9600BPS, - Serial::DATABITS_8BITS, - Serial::FLOWCONTROL_OFF, - Serial::PARITY_NOPARITY, - Serial::STOPBITS_1BIT + Serial::BaudRate::b9600, + Serial::DataBits::d8, + Serial::FlowControl::off, + Serial::Parity::none, + Serial::StopBits::s1 ) { assert(8 == password.length()); @@ -71,14 +71,14 @@ namespace rl { assert(this->isConnected()); - if (MONITORING_SINGLE != this->monitoring) + if (Monitoring::single != this->monitoring) { - this->setMonitoring(MONITORING_SINGLE); + this->setMonitoring(Monitoring::single); } - if (BAUDRATE_9600BPS != this->baudRate) + if (BaudRate::b9600 != this->baudRate) { - this->setBaudRate(BAUDRATE_9600BPS); + this->setBaudRate(BaudRate::b9600); } this->serial.close(); @@ -243,10 +243,10 @@ namespace rl buf[5] = 0x00; Serial::BaudRate baudRates[4] = { - Serial::BAUDRATE_57600BPS, - Serial::BAUDRATE_38400BPS, - Serial::BAUDRATE_19200BPS, - Serial::BAUDRATE_9600BPS + Serial::BaudRate::b57600, + Serial::BaudRate::b38400, + Serial::BaudRate::b19200, + Serial::BaudRate::b9600 }; for (::std::size_t i = 0; i < 4; ++i) @@ -296,7 +296,7 @@ namespace rl if (0x25 != buf[5]) { - this->setMonitoring(MONITORING_SINGLE); + this->setMonitoring(Monitoring::single); } } @@ -422,16 +422,16 @@ namespace rl switch (baudRate) { - case BAUDRATE_9600BPS: + case BaudRate::b9600: buf[5] = 0x00; break; - case BAUDRATE_19200BPS: + case BaudRate::b19200: buf[5] = 0x01; break; - case BAUDRATE_38400BPS: + case BaudRate::b38400: buf[5] = 0x02; break; - case BAUDRATE_57600BPS: + case BaudRate::b57600: buf[5] = 0x03; break; default: @@ -453,17 +453,17 @@ namespace rl switch (baudRate) { - case BAUDRATE_9600BPS: - this->serial.setBaudRate(Serial::BAUDRATE_9600BPS); + case BaudRate::b9600: + this->serial.setBaudRate(Serial::BaudRate::b9600); break; - case BAUDRATE_19200BPS: - this->serial.setBaudRate(Serial::BAUDRATE_19200BPS); + case BaudRate::b19200: + this->serial.setBaudRate(Serial::BaudRate::b19200); break; - case BAUDRATE_38400BPS: - this->serial.setBaudRate(Serial::BAUDRATE_38400BPS); + case BaudRate::b38400: + this->serial.setBaudRate(Serial::BaudRate::b38400); break; - case BAUDRATE_57600BPS: - this->serial.setBaudRate(Serial::BAUDRATE_57600BPS); + case BaudRate::b57600: + this->serial.setBaudRate(Serial::BaudRate::b57600); break; default: break; @@ -485,10 +485,10 @@ namespace rl switch (monitoring) { - case MONITORING_CONTINUOUS: + case Monitoring::continuous: buf[5] = 0x24; break; - case MONITORING_SINGLE: + case Monitoring::single: buf[5] = 0x25; break; default: @@ -529,7 +529,7 @@ namespace rl { assert(this->isConnected()); - if (MONITORING_SINGLE != this->monitoring) + if (Monitoring::single != this->monitoring) { this->setMonitoring(this->monitoring); } @@ -540,7 +540,7 @@ namespace rl { assert(this->isConnected()); - if (MONITORING_SINGLE == this->monitoring) + if (Monitoring::single == this->monitoring) { this->data[4] = 0x30; this->data[5] = 0x01; @@ -560,9 +560,9 @@ namespace rl { assert(this->isConnected()); - if (MONITORING_SINGLE != this->monitoring) + if (Monitoring::single != this->monitoring) { - this->setMonitoring(MONITORING_SINGLE); + this->setMonitoring(Monitoring::single); } } diff --git a/src/rl/hal/SchmersalLss300.h b/src/rl/hal/SchmersalLss300.h index b9809434..aeff25d0 100644 --- a/src/rl/hal/SchmersalLss300.h +++ b/src/rl/hal/SchmersalLss300.h @@ -45,30 +45,30 @@ namespace rl class RL_HAL_EXPORT SchmersalLss300 : public CyclicDevice, public Lidar { public: - enum BaudRate + enum class BaudRate { /** 9,600 bps. */ - BAUDRATE_9600BPS, + b9600, /** 19,200 bps. */ - BAUDRATE_19200BPS, + b19200, /** 38,400 bps. */ - BAUDRATE_38400BPS, + b38400, /** 57,600 bps. */ - BAUDRATE_57600BPS + b57600 #if 0 /** 125,000 bps. */ - BAUDRATE_125000BPS, + b125000, /** 208,333 bps. */ - BAUDRATE_208333BPS, + b208333, /** 312,500 bps. */ - BAUDRATE_312500BPS + b312500 #endif }; - enum Monitoring + enum class Monitoring { - MONITORING_CONTINUOUS, - MONITORING_SINGLE + continuous, + single }; /** @@ -76,8 +76,8 @@ namespace rl */ SchmersalLss300( const ::std::string& device = "/dev/ttyS0", - const BaudRate& baudRate = BAUDRATE_9600BPS, - const Monitoring& monitoring = MONITORING_SINGLE, + const BaudRate& baudRate = BaudRate::b9600, + const Monitoring& monitoring = Monitoring::single, const ::std::string& password = "PASS_LSS" ); diff --git a/src/rl/hal/SchunkFpsF5.cpp b/src/rl/hal/SchunkFpsF5.cpp index 786b4210..2a4ea3ee 100644 --- a/src/rl/hal/SchunkFpsF5.cpp +++ b/src/rl/hal/SchunkFpsF5.cpp @@ -49,11 +49,11 @@ namespace rl record(false), serial( filename, - Serial::BAUDRATE_9600BPS, - Serial::DATABITS_8BITS, - Serial::FLOWCONTROL_OFF, - Serial::PARITY_NOPARITY, - Serial::STOPBITS_1BIT + Serial::BaudRate::b9600, + Serial::DataBits::d8, + Serial::FlowControl::off, + Serial::Parity::none, + Serial::StopBits::s1 ), temperature(0), update(false), diff --git a/src/rl/hal/Serial.cpp b/src/rl/hal/Serial.cpp index 701e73a5..b6c46851 100644 --- a/src/rl/hal/Serial.cpp +++ b/src/rl/hal/Serial.cpp @@ -477,46 +477,46 @@ namespace rl #ifdef WIN32 switch (baudRate) { - case BAUDRATE_110BPS: + case BaudRate::b110: this->impl->current.BaudRate = CBR_110; break; - case BAUDRATE_300BPS: + case BaudRate::b300: this->impl->current.BaudRate = CBR_300; break; - case BAUDRATE_600BPS: + case BaudRate::b600: this->impl->current.BaudRate = CBR_600; break; - case BAUDRATE_1200BPS: + case BaudRate::b1200: this->impl->current.BaudRate = CBR_1200; break; - case BAUDRATE_2400BPS: + case BaudRate::b2400: this->impl->current.BaudRate = CBR_2400; break; - case BAUDRATE_4800BPS: + case BaudRate::b4800: this->impl->current.BaudRate = CBR_4800; break; - case BAUDRATE_9600BPS: + case BaudRate::b9600: this->impl->current.BaudRate = CBR_9600; break; - case BAUDRATE_14400BPS: + case BaudRate::b14400: this->impl->current.BaudRate = CBR_14400; break; - case BAUDRATE_19200BPS: + case BaudRate::b19200: this->impl->current.BaudRate = CBR_19200; break; - case BAUDRATE_38400BPS: + case BaudRate::b38400: this->impl->current.BaudRate = CBR_38400; break; - case BAUDRATE_57600BPS: + case BaudRate::b57600: this->impl->current.BaudRate = CBR_57600; break; - case BAUDRATE_115200BPS: + case BaudRate::b115200: this->impl->current.BaudRate = CBR_115200; break; - case BAUDRATE_128000BPS: + case BaudRate::b128000: this->impl->current.BaudRate = CBR_128000; break; - case BAUDRATE_256000BPS: + case BaudRate::b256000: this->impl->current.BaudRate = CBR_256000; break; default: @@ -527,79 +527,79 @@ namespace rl switch (baudRate) { - case BAUDRATE_110BPS: + case BaudRate::b110: speed = B110; break; - case BAUDRATE_300BPS: + case BaudRate::b300: speed = B300; break; - case BAUDRATE_600BPS: + case BaudRate::b600: speed = B600; break; - case BAUDRATE_1200BPS: + case BaudRate::b1200: speed = B1200; break; - case BAUDRATE_2400BPS: + case BaudRate::b2400: speed = B2400; break; - case BAUDRATE_4800BPS: + case BaudRate::b4800: speed = B4800; break; - case BAUDRATE_9600BPS: + case BaudRate::b9600: speed = B9600; break; - case BAUDRATE_19200BPS: + case BaudRate::b19200: speed = B19200; break; - case BAUDRATE_38400BPS: + case BaudRate::b38400: speed = B38400; break; - case BAUDRATE_57600BPS: + case BaudRate::b57600: speed = B57600; break; - case BAUDRATE_115200BPS: + case BaudRate::b115200: speed = B115200; break; #ifndef __QNX__ - case BAUDRATE_230400BPS: + case BaudRate::b230400: speed = B230400; break; #ifndef __APPLE__ - case BAUDRATE_460800BPS: + case BaudRate::b460800: speed = B460800; break; - case BAUDRATE_500000BPS: + case BaudRate::b500000: speed = B500000; break; - case BAUDRATE_576000BPS: + case BaudRate::b576000: speed = B576000; break; - case BAUDRATE_921600BPS: + case BaudRate::b921600: speed = B921600; break; - case BAUDRATE_1000000BPS: + case BaudRate::b1000000: speed = B1000000; break; - case BAUDRATE_1152000BPS: + case BaudRate::b1152000: speed = B1152000; break; - case BAUDRATE_1500000BPS: + case BaudRate::b1500000: speed = B1500000; break; - case BAUDRATE_2000000BPS: + case BaudRate::b2000000: speed = B2000000; break; - case BAUDRATE_2500000BPS: + case BaudRate::b2500000: speed = B2500000; break; - case BAUDRATE_3000000BPS: + case BaudRate::b3000000: speed = B3000000; break; #ifndef __CYGWIN__ - case BAUDRATE_3500000BPS: + case BaudRate::b3500000: speed = B3500000; break; - case BAUDRATE_4000000BPS: + case BaudRate::b4000000: speed = B4000000; break; #endif // __CYGWIN__ @@ -629,16 +629,16 @@ namespace rl #ifdef WIN32 switch (dataBits) { - case DATABITS_5BITS: + case DataBits::d5: this->impl->current.ByteSize = 5; break; - case DATABITS_6BITS: + case DataBits::d6: this->impl->current.ByteSize = 6; break; - case DATABITS_7BITS: + case DataBits::d7: this->impl->current.ByteSize = 7; break; - case DATABITS_8BITS: + case DataBits::d8: this->impl->current.ByteSize = 8; break; default: @@ -647,22 +647,22 @@ namespace rl #else // WIN32 switch (dataBits) { - case DATABITS_5BITS: + case DataBits::d5: this->impl->current.c_cflag &= ~(CS6 | CS7 | CS8); this->impl->current.c_cflag |= CS5; this->impl->current.c_iflag |= ISTRIP; break; - case DATABITS_6BITS: + case DataBits::d6: this->impl->current.c_cflag &= ~(CS5 | CS7 | CS8); this->impl->current.c_cflag |= CS6; this->impl->current.c_iflag |= ISTRIP; break; - case DATABITS_7BITS: + case DataBits::d7: this->impl->current.c_cflag &= ~(CS5 | CS6 | CS8); this->impl->current.c_cflag |= CS7; this->impl->current.c_iflag |= ISTRIP; break; - case DATABITS_8BITS: + case DataBits::d8: this->impl->current.c_cflag &= ~(CS5 | CS6 | CS7); this->impl->current.c_cflag |= CS8; this->impl->current.c_iflag &= ~ISTRIP; @@ -687,7 +687,7 @@ namespace rl #ifdef WIN32 switch (flowControl) { - case FLOWCONTROL_OFF: + case FlowControl::off: this->impl->current.fOutxCtsFlow = false; this->impl->current.fOutxDsrFlow = false; this->impl->current.fDtrControl = DTR_CONTROL_DISABLE; @@ -697,7 +697,7 @@ namespace rl this->impl->current.XoffChar = 0x00; this->impl->current.XonChar = 0x00; break; - case FLOWCONTROL_RTSCTS: + case FlowControl::rtscts: this->impl->current.fOutxCtsFlow = true; this->impl->current.fOutxDsrFlow = true; this->impl->current.fDtrControl = DTR_CONTROL_HANDSHAKE; @@ -707,7 +707,7 @@ namespace rl this->impl->current.XoffChar = 0x00; this->impl->current.XonChar = 0x00; break; - case FLOWCONTROL_XONXOFF: + case FlowControl::xonxoff: this->impl->current.fOutxCtsFlow = false; this->impl->current.fOutxDsrFlow = false; this->impl->current.fDtrControl = DTR_CONTROL_DISABLE; @@ -723,19 +723,19 @@ namespace rl #else // WIN32 switch (flowControl) { - case FLOWCONTROL_OFF: + case FlowControl::off: this->impl->current.c_cflag &= ~CRTSCTS; this->impl->current.c_iflag &= ~(IXANY | IXOFF | IXON); this->impl->current.c_cc[VSTART] = 0x00; this->impl->current.c_cc[VSTOP] = 0x00; break; - case FLOWCONTROL_RTSCTS: + case FlowControl::rtscts: this->impl->current.c_cflag |= CRTSCTS; this->impl->current.c_iflag &= ~(IXANY | IXOFF | IXON); this->impl->current.c_cc[VSTART] = 0x00; this->impl->current.c_cc[VSTOP] = 0x00; break; - case FLOWCONTROL_XONXOFF: + case FlowControl::xonxoff: this->impl->current.c_cflag &= ~CRTSCTS; this->impl->current.c_iflag |= IXANY | IXOFF | IXON; this->impl->current.c_cc[VSTART] = 0x11; @@ -755,13 +755,13 @@ namespace rl #ifdef WIN32 switch (parity) { - case PARITY_EVENPARITY: + case Parity::even: this->impl->current.Parity = EVENPARITY; break; - case PARITY_NOPARITY: + case Parity::none: this->impl->current.Parity = NOPARITY; break; - case PARITY_ODDPARITY: + case Parity::odd: this->impl->current.Parity = ODDPARITY; break; default: @@ -770,18 +770,18 @@ namespace rl #else // WIN32 switch (parity) { - case PARITY_EVENPARITY: + case Parity::even: this->impl->current.c_cflag &= ~PARODD; this->impl->current.c_cflag |= PARENB; this->impl->current.c_iflag &= ~IGNPAR; this->impl->current.c_iflag |= INPCK; break; - case PARITY_NOPARITY: + case Parity::none: this->impl->current.c_cflag &= ~(PARENB | PARODD); this->impl->current.c_iflag &= ~INPCK; this->impl->current.c_iflag |= IGNPAR; break; - case PARITY_ODDPARITY: + case Parity::odd: this->impl->current.c_cflag |= PARENB | PARODD; this->impl->current.c_iflag &= ~IGNPAR; this->impl->current.c_iflag |= INPCK; @@ -800,10 +800,10 @@ namespace rl #ifdef WIN32 switch (stopBits) { - case STOPBITS_1BIT: + case StopBits::s1: this->impl->current.StopBits = ONESTOPBIT; break; - case STOPBITS_2BITS: + case StopBits::s2: this->impl->current.StopBits = TWOSTOPBITS; break; default: @@ -812,10 +812,10 @@ namespace rl #else // WIN32 switch (stopBits) { - case STOPBITS_1BIT: + case StopBits::s1: this->impl->current.c_cflag &= ~CSTOPB; break; - case STOPBITS_2BITS: + case StopBits::s2: this->impl->current.c_cflag |= CSTOPB; break; default: diff --git a/src/rl/hal/Serial.h b/src/rl/hal/Serial.h index 7ff258d0..58844fea 100644 --- a/src/rl/hal/Serial.h +++ b/src/rl/hal/Serial.h @@ -41,126 +41,126 @@ namespace rl class RL_HAL_EXPORT Serial : public Com { public: - enum BaudRate + enum class BaudRate { /** 110 bps. */ - BAUDRATE_110BPS, + b110, /** 300 bps. */ - BAUDRATE_300BPS, + b300, /** 600 bps. */ - BAUDRATE_600BPS, + b600, /** 1,200 bps. */ - BAUDRATE_1200BPS, + b1200, /** 2,400 bps. */ - BAUDRATE_2400BPS, + b2400, /** 4,800 bps. */ - BAUDRATE_4800BPS, + b4800, /** 9,600 bps. */ - BAUDRATE_9600BPS, + b9600, #ifdef WIN32 /** 14,400 bps. */ - BAUDRATE_14400BPS, + b14400, #endif // WIN32 /** 19,200 bps. */ - BAUDRATE_19200BPS, + b19200, /** 38,400 bps. */ - BAUDRATE_38400BPS, + b38400, /** 57,600 bps. */ - BAUDRATE_57600BPS, + b57600, /** 115,200 bps. */ #ifdef __QNX__ - BAUDRATE_115200BPS + b115200 #else // __QNX__ - BAUDRATE_115200BPS, + b115200, #endif // __QNX__ #ifdef WIN32 /** 128,000 bps. */ - BAUDRATE_128000BPS, + b128000, /** 256,000 bps. */ - BAUDRATE_256000BPS + b256000 #else // WIN32 #ifndef __QNX__ /** 230,400 bps. */ - BAUDRATE_230400BPS, + b230400, /** 460,800 bps. */ - BAUDRATE_460800BPS, + b460800, /** 500,000 bps. */ - BAUDRATE_500000BPS, + b500000, /** 576,000 bps. */ - BAUDRATE_576000BPS, + b576000, /** 921,600 bps. */ - BAUDRATE_921600BPS, + b921600, /** 1,000,000 bps. */ - BAUDRATE_1000000BPS, + b1000000, /** 1,152000 bps. */ - BAUDRATE_1152000BPS, + b1152000, /** 1,500,000 bps. */ - BAUDRATE_1500000BPS, + b1500000, /** 2,000,000 bps. */ - BAUDRATE_2000000BPS, + b2000000, /** 2,500,000 bps. */ - BAUDRATE_2500000BPS, + b2500000, /** 3,000,000 bps. */ #ifdef __CYGWIN__ - BAUDRATE_3000000BPS + b3000000 #else // __CYGWIN__ - BAUDRATE_3000000BPS, + b3000000, /** 3,500,000 bps. */ - BAUDRATE_3500000BPS, + b3500000, /** 4,000,000 bps. */ - BAUDRATE_4000000BPS + b4000000 #endif // __CYGWIN__ #endif // __QNX__ #endif // WIN32 }; - enum DataBits + enum class DataBits { /** 5 data bits. */ - DATABITS_5BITS, + d5, /** 6 data bits. */ - DATABITS_6BITS, + d6, /** 7 data bits. */ - DATABITS_7BITS, + d7, /** 8 data bits. */ - DATABITS_8BITS + d8 }; - enum FlowControl + enum class FlowControl { /** No flow control. */ - FLOWCONTROL_OFF, + off, /** Hardware flow control (RTS/CTS). */ - FLOWCONTROL_RTSCTS, + rtscts, /** Software flow control (XON/XOFF). */ - FLOWCONTROL_XONXOFF + xonxoff }; - enum Parity + enum class Parity { /** Even parity. */ - PARITY_EVENPARITY, + even, /** No parity. */ - PARITY_NOPARITY, + none, /** Odd parity. */ - PARITY_ODDPARITY + odd }; - enum StopBits + enum class StopBits { /** 1 stop bit. */ - STOPBITS_1BIT, + s1, /** 2 stop bits. */ - STOPBITS_2BITS + s2 }; Serial( const ::std::string& filename, - const BaudRate& baudRate = BAUDRATE_9600BPS, - const DataBits& dataBits = DATABITS_8BITS, - const FlowControl& flowControl = FLOWCONTROL_OFF, - const Parity& parity = PARITY_NOPARITY, - const StopBits& stopBits = STOPBITS_1BIT + const BaudRate& baudRate = BaudRate::b9600, + const DataBits& dataBits = DataBits::d8, + const FlowControl& flowControl = FlowControl::off, + const Parity& parity = Parity::none, + const StopBits& stopBits = StopBits::s1 ); Serial( diff --git a/src/rl/hal/SickLms200.cpp b/src/rl/hal/SickLms200.cpp index 1349d056..fd3528fb 100644 --- a/src/rl/hal/SickLms200.cpp +++ b/src/rl/hal/SickLms200.cpp @@ -48,7 +48,7 @@ namespace rl ) : CyclicDevice(::std::chrono::nanoseconds::zero()), Lidar(), - baudRate(BAUDRATE_9600BPS), + baudRate(BaudRate::b9600), configuration(0x00), data(), desired(baudRate), @@ -57,11 +57,11 @@ namespace rl password(password), serial( filename, - Serial::BAUDRATE_9600BPS, - Serial::DATABITS_8BITS, - Serial::FLOWCONTROL_OFF, - Serial::PARITY_NOPARITY, - Serial::STOPBITS_1BIT + Serial::BaudRate::b9600, + Serial::DataBits::d8, + Serial::FlowControl::off, + Serial::Parity::none, + Serial::StopBits::s1 ), variant(variant) { @@ -77,24 +77,24 @@ namespace rl { assert(this->isConnected()); - if (MEASURING_8M != this->measuring) + if (Measuring::m8 != this->measuring) { - this->setMeasuring(MEASURING_8M); + this->setMeasuring(Measuring::m8); } - if (VARIANT_180_50 != this->variant) + if (Variant::v180_50 != this->variant) { - this->setVariant(VARIANT_180_50); + this->setVariant(Variant::v180_50); } - if (MONITORING_SINGLE != this->monitoring) + if (Monitoring::single != this->monitoring) { - this->setMonitoring(MONITORING_SINGLE); + this->setMonitoring(Monitoring::single); } - if (BAUDRATE_9600BPS != this->baudRate) + if (BaudRate::b9600 != this->baudRate) { - this->setBaudRate(BAUDRATE_9600BPS); + this->setBaudRate(BaudRate::b9600); } this->serial.close(); @@ -449,19 +449,19 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (this->variant) { - case VARIANT_100_25: + case Variant::v100_25: return 401; break; - case VARIANT_100_50: + case Variant::v100_50: return 201; break; - case VARIANT_100_100: + case Variant::v100_100: return 101; break; - case VARIANT_180_50: + case Variant::v180_50: return 361; break; - case VARIANT_180_100: + case Variant::v180_100: return 181; break; default: @@ -479,23 +479,23 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (this->measuring) { - case MEASURING_8M: - return 8.182f; + case Measuring::m8: + return static_cast<::rl::math::Real>(8.182); break; - case MEASURING_16M: - return 16.374f; + case Measuring::m16: + return static_cast<::rl::math::Real>(16.374); break; - case MEASURING_32M: - return 32.758f; + case Measuring::m32: + return static_cast<::rl::math::Real>(32.758); break; - case MEASURING_80M: - return 81.82f; + case Measuring::m80: + return static_cast<::rl::math::Real>(81.82); break; - case MEASURING_160M: - return 163.74f; + case Measuring::m160: + return static_cast<::rl::math::Real>(163.74); break; - case MEASURING_320M: - return 327.58f; + case Measuring::m320: + return static_cast<::rl::math::Real>(327.58); break; default: break; @@ -536,15 +536,15 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (this->variant) { - case VARIANT_100_25: + case Variant::v100_25: return static_cast<::rl::math::Real>(0.25) * ::rl::math::constants::deg2rad; break; - case VARIANT_100_50: - case VARIANT_180_50: + case Variant::v100_50: + case Variant::v180_50: return static_cast<::rl::math::Real>(0.5) * ::rl::math::constants::deg2rad; break; - case VARIANT_100_100: - case VARIANT_180_100: + case Variant::v100_100: + case Variant::v180_100: return 1 * ::rl::math::constants::deg2rad; break; default: @@ -561,13 +561,13 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (this->variant) { - case VARIANT_100_25: - case VARIANT_100_50: - case VARIANT_100_100: + case Variant::v100_25: + case Variant::v100_50: + case Variant::v100_100: return 40 * ::rl::math::constants::deg2rad; break; - case VARIANT_180_50: - case VARIANT_180_100: + case Variant::v180_50: + case Variant::v180_100: return 0; break; default: @@ -584,13 +584,13 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (this->variant) { - case VARIANT_100_25: - case VARIANT_100_50: - case VARIANT_100_100: + case Variant::v100_25: + case Variant::v100_50: + case Variant::v100_100: return 140 * ::rl::math::constants::deg2rad; break; - case VARIANT_180_50: - case VARIANT_180_100: + case Variant::v180_50: + case Variant::v180_100: return 180 * ::rl::math::constants::deg2rad; break; default: @@ -646,11 +646,11 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; Serial::BaudRate baudRates[3] = { #else // defined(WIN32) || defined(__QNX__) Serial::BaudRate baudRates[4] = { - Serial::BAUDRATE_500000BPS, + Serial::BaudRate::b500000, #endif // defined(WIN32) || defined(__QNX__) - Serial::BAUDRATE_38400BPS, - Serial::BAUDRATE_19200BPS, - Serial::BAUDRATE_9600BPS + Serial::BaudRate::b38400, + Serial::BaudRate::b19200, + Serial::BaudRate::b9600 }; #if defined(WIN32) || defined(__QNX__) @@ -710,17 +710,17 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { #if !(defined(WIN32) || defined(__QNX__)) case 0x01: - this->baudRate = BAUDRATE_500000BPS; + this->baudRate = BaudRate::b500000; break; #endif // !(defined(WIN32) || defined(__QNX__)) case 0x19: - this->baudRate = BAUDRATE_38400BPS; + this->baudRate = BaudRate::b38400; break; case 0x33: - this->baudRate = BAUDRATE_19200BPS; + this->baudRate = BaudRate::b19200; break; case 0x67: - this->baudRate = BAUDRATE_9600BPS; + this->baudRate = BaudRate::b9600; break; default: break; @@ -735,7 +735,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; if (0x25 != buf[12]) { - this->setMonitoring(MONITORING_SINGLE); + this->setMonitoring(Monitoring::single); } // measuring @@ -752,16 +752,16 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (resolution) { case 25: - variant = VARIANT_100_25; + variant = Variant::v100_25; break; case 50: switch (angle) { case 100: - variant = VARIANT_100_50; + variant = Variant::v100_50; break; case 180: - variant = VARIANT_180_50; + variant = Variant::v180_50; break; default: throw DeviceException("unknown variant"); @@ -772,10 +772,10 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (angle) { case 100: - variant = VARIANT_100_100; + variant = Variant::v100_100; break; case 180: - variant = VARIANT_180_100; + variant = Variant::v180_100; break; default: throw DeviceException("unknown variant"); @@ -952,17 +952,17 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (baudRate) { - case BAUDRATE_9600BPS: + case BaudRate::b9600: buf[5] = 0x42; break; - case BAUDRATE_19200BPS: + case BaudRate::b19200: buf[5] = 0x41; break; - case BAUDRATE_38400BPS: + case BaudRate::b38400: buf[5] = 0x40; break; #if !(defined(WIN32) || defined(__QNX__)) - case BAUDRATE_500000BPS: + case BaudRate::b500000: buf[5] = 0x48; break; #endif // !(defined(WIN32) || defined(__QNX__)) @@ -992,18 +992,18 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (baudRate) { - case BAUDRATE_9600BPS: - this->serial.setBaudRate(Serial::BAUDRATE_9600BPS); + case BaudRate::b9600: + this->serial.setBaudRate(Serial::BaudRate::b9600); break; - case BAUDRATE_19200BPS: - this->serial.setBaudRate(Serial::BAUDRATE_19200BPS); + case BaudRate::b19200: + this->serial.setBaudRate(Serial::BaudRate::b19200); break; - case BAUDRATE_38400BPS: - this->serial.setBaudRate(Serial::BAUDRATE_38400BPS); + case BaudRate::b38400: + this->serial.setBaudRate(Serial::BaudRate::b38400); break; #if !(defined(WIN32) || defined(__QNX__)) - case BAUDRATE_500000BPS: - this->serial.setBaudRate(Serial::BAUDRATE_500000BPS); + case BaudRate::b500000: + this->serial.setBaudRate(Serial::BaudRate::b500000); break; #endif // !(defined(WIN32) || defined(__QNX__)) default: @@ -1065,27 +1065,27 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (measuring) { - case MEASURING_8M: + case Measuring::m8: buf[10] = 0x00; buf[11] = 0x01; break; - case MEASURING_16M: + case Measuring::m16: buf[10] = 0x04; buf[11] = 0x01; break; - case MEASURING_32M: + case Measuring::m32: buf[10] = 0x06; buf[11] = 0x01; break; - case MEASURING_80M: + case Measuring::m80: buf[10] = 0x00; buf[11] = 0x00; break; - case MEASURING_160M: + case Measuring::m160: buf[10] = 0x04; buf[11] = 0x00; break; - case MEASURING_320M: + case Measuring::m320: buf[10] = 0x06; buf[11] = 0x00; break; @@ -1124,10 +1124,10 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (monitoring) { - case MONITORING_CONTINUOUS: + case Monitoring::continuous: buf[5] = 0x24; break; - case MONITORING_SINGLE: + case Monitoring::single: buf[5] = 0x25; break; default: @@ -1168,31 +1168,31 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (variant) { - case VARIANT_100_25: + case Variant::v100_25: buf[5] = 0x64; buf[6] = 0x0; buf[7] = 0x19; buf[8] = 0x0; break; - case VARIANT_100_50: + case Variant::v100_50: buf[5] = 0x64; buf[6] = 0x0; buf[7] = 0x32; buf[8] = 0x0; break; - case VARIANT_100_100: + case Variant::v100_100: buf[5] = 0x64; buf[6] = 0x0; buf[7] = 0x64; buf[8] = 0x0; break; - case VARIANT_180_50: + case Variant::v180_50: buf[5] = 0xB4; buf[6] = 0x0; buf[7] = 0x32; buf[8] = 0x0; break; - case VARIANT_180_100: + case Variant::v180_100: buf[5] = 0xB4; buf[6] = 0x0; buf[7] = 0x64; @@ -1223,7 +1223,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { assert(this->isConnected()); - if (MONITORING_SINGLE != this->monitoring) + if (Monitoring::single != this->monitoring) { this->setMonitoring(this->monitoring); } @@ -1234,7 +1234,7 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { assert(this->isConnected()); - if (MONITORING_SINGLE == this->monitoring) + if (Monitoring::single == this->monitoring) { this->data[4] = 0x30; this->data[5] = 0x01; @@ -1248,19 +1248,19 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; switch (this->variant) { - case VARIANT_100_25: + case Variant::v100_25: this->recv(this->data.data(), 1 + 1 + 2 + 1 + 1 + 1 + 802 + 1 + 2, 0xB0); break; - case VARIANT_100_50: + case Variant::v100_50: this->recv(this->data.data(), 1 + 1 + 2 + 1 + 1 + 1 + 402 + 1 + 2, 0xB0); break; - case VARIANT_100_100: + case Variant::v100_100: this->recv(this->data.data(), 1 + 1 + 2 + 1 + 1 + 1 + 202 + 1 + 2, 0xB0); break; - case VARIANT_180_50: + case Variant::v180_50: this->recv(this->data.data(), 1 + 1 + 2 + 1 + 1 + 1 + 722 + 1 + 2, 0xB0); break; - case VARIANT_180_100: + case Variant::v180_100: this->recv(this->data.data(), 1 + 1 + 2 + 1 + 1 + 1 + 362 + 1 + 2, 0xB0); break; default: @@ -1273,9 +1273,9 @@ ::std::cerr << "Measured value > Maximum value" << ::std::endl; { assert(this->isConnected()); - if (MONITORING_SINGLE != this->monitoring) + if (Monitoring::single != this->monitoring) { - this->setMonitoring(MONITORING_SINGLE); + this->setMonitoring(Monitoring::single); } } diff --git a/src/rl/hal/SickLms200.h b/src/rl/hal/SickLms200.h index f639bae6..1a824f69 100644 --- a/src/rl/hal/SickLms200.h +++ b/src/rl/hal/SickLms200.h @@ -45,50 +45,56 @@ namespace rl class RL_HAL_EXPORT SickLms200 : public CyclicDevice, public Lidar { public: - enum BaudRate + enum class BaudRate { /** 9,600 bps. */ - BAUDRATE_9600BPS, + b9600, /** 19,200 bps. */ - BAUDRATE_19200BPS, + b19200, /** 38,400 bps. */ #if defined(WIN32) || defined(__QNX__) - BAUDRATE_38400BPS + b38400 #else // defined(WIN32) || defined(__QNX__) - BAUDRATE_38400BPS, + b38400, /** 500,000 bps. */ - BAUDRATE_500000BPS + b500000 #endif // defined(WIN32) || defined(__QNX__) }; - enum Measuring + enum class Measuring { - MEASURING_8M, - MEASURING_16M, - MEASURING_32M, - MEASURING_80M, - MEASURING_160M, - MEASURING_320M + /** 8 meter. */ + m8, + /** 16 meter. */ + m16, + /** 32 meter. */ + m32, + /** 80 meter. */ + m80, + /** 160 meter. */ + m160, + /** 320 meter. */ + m320 }; - enum Monitoring + enum class Monitoring { - MONITORING_CONTINUOUS, - MONITORING_SINGLE + continuous, + single }; - enum Variant + enum class Variant { /** Angle = 100 degrees, resolution = 0.25 degrees. */ - VARIANT_100_25, + v100_25, /** Angle = 100 degrees, resolution = 0.5 degrees. */ - VARIANT_100_50, + v100_50, /** Angle = 100 degrees, resolution = 1 degree. */ - VARIANT_100_100, + v100_100, /** Angle = 180 degrees, resolution = 0.5 degrees. */ - VARIANT_180_50, + v180_50, /** Angle = 180 degrees, resolution = 1 degree. */ - VARIANT_180_100 + v180_100 }; /** @@ -96,10 +102,10 @@ namespace rl */ SickLms200( const ::std::string& device = "/dev/ttyS0", - const BaudRate& baudRate = BAUDRATE_9600BPS, - const Monitoring& monitoring = MONITORING_SINGLE, - const Variant& variant = VARIANT_180_50, - const Measuring& measuring = MEASURING_8M, + const BaudRate& baudRate = BaudRate::b9600, + const Monitoring& monitoring = Monitoring::single, + const Variant& variant = Variant::v180_50, + const Measuring& measuring = Measuring::m8, const ::std::string& password = "SICK_LMS" ); diff --git a/src/rl/hal/SickS300.cpp b/src/rl/hal/SickS300.cpp index 02afbb0c..676dcd93 100644 --- a/src/rl/hal/SickS300.cpp +++ b/src/rl/hal/SickS300.cpp @@ -33,7 +33,7 @@ #include "Endian.h" #include "SickS300.h" -static const ::std::uint16_t crcTable[256] = { +static constexpr ::std::uint16_t crcTable[256] = { 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50a5, 0x60c6, 0x70e7, 0x8108, 0x9129, 0xa14a, 0xb16b, 0xc18c, 0xd1ad, 0xe1ce, 0xf1ef, 0x1231, 0x0210, 0x3273, 0x2252, 0x52b5, 0x4294, 0x72f7, 0x62d6, @@ -82,10 +82,10 @@ namespace rl serial( filename, baudRate, - Serial::DATABITS_8BITS, - Serial::FLOWCONTROL_OFF, - Serial::PARITY_NOPARITY, - Serial::STOPBITS_1BIT + Serial::DataBits::d8, + Serial::FlowControl::off, + Serial::Parity::none, + Serial::StopBits::s1 ) { } diff --git a/src/rl/hal/SickS300.h b/src/rl/hal/SickS300.h index c0e5bb55..2eef54d1 100644 --- a/src/rl/hal/SickS300.h +++ b/src/rl/hal/SickS300.h @@ -47,7 +47,7 @@ namespace rl public: SickS300( const ::std::string& device = "/dev/ttyS0", - const Serial::BaudRate& baudRate = Serial::BAUDRATE_9600BPS + const Serial::BaudRate& baudRate = Serial::BaudRate::b9600 ); virtual ~SickS300(); diff --git a/src/rl/hal/Socket.cpp b/src/rl/hal/Socket.cpp index 4d0508e3..3f4e6936 100644 --- a/src/rl/hal/Socket.cpp +++ b/src/rl/hal/Socket.cpp @@ -245,11 +245,11 @@ namespace rl switch (option) { - case OPTION_KEEPALIVE: + case Option::keepalive: level = SOL_SOCKET; optname = SO_KEEPALIVE; break; - case OPTION_MULTICAST_LOOP: + case Option::multicastLoop: if (AF_INET6 == this->address.get()->addr.ss_family) { level = IPPROTO_IPV6; @@ -261,7 +261,7 @@ namespace rl optname = IP_MULTICAST_LOOP; } break; - case OPTION_MULTICAST_TTL: + case Option::multicastTtl: if (AF_INET6 == this->address.get()->addr.ss_family) { level = IPPROTO_IPV6; @@ -273,12 +273,12 @@ namespace rl optname = IP_MULTICAST_TTL; } break; - case OPTION_NODELAY: + case Option::nodelay: level = IPPROTO_TCP; optname = TCP_NODELAY; break; #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) - case OPTION_QUICKACK: + case Option::quickack: level = IPPROTO_TCP; optname = TCP_QUICKACK; break; @@ -531,11 +531,11 @@ namespace rl switch (option) { - case OPTION_KEEPALIVE: + case Option::keepalive: level = SOL_SOCKET; optname = SO_KEEPALIVE; break; - case OPTION_MULTICAST_LOOP: + case Option::multicastLoop: if (AF_INET6 == this->address.get()->addr.ss_family) { level = IPPROTO_IPV6; @@ -547,7 +547,7 @@ namespace rl optname = IP_MULTICAST_LOOP; } break; - case OPTION_MULTICAST_TTL: + case Option::multicastTtl: if (AF_INET6 == this->address.get()->addr.ss_family) { level = IPPROTO_IPV6; @@ -559,12 +559,12 @@ namespace rl optname = IP_MULTICAST_TTL; } break; - case OPTION_NODELAY: + case Option::nodelay: level = IPPROTO_TCP; optname = TCP_NODELAY; break; #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) - case OPTION_QUICKACK: + case Option::quickack: level = IPPROTO_TCP; optname = TCP_QUICKACK; break; diff --git a/src/rl/hal/Socket.h b/src/rl/hal/Socket.h index d069c1f0..15a2c0c3 100644 --- a/src/rl/hal/Socket.h +++ b/src/rl/hal/Socket.h @@ -83,16 +83,16 @@ namespace rl ::std::unique_ptr impl; }; - enum Option + enum class Option { - OPTION_KEEPALIVE, - OPTION_MULTICAST_LOOP, - OPTION_MULTICAST_TTL, + keepalive, + multicastLoop, + multicastTtl, #if defined(__APPLE__) || defined(__QNX__) || defined(WIN32) || defined(__CYGWIN__) - OPTION_NODELAY + nodelay #else // __APPLE__ || __QNX__ || WIN32 || __CYGWIN__ - OPTION_NODELAY, - OPTION_QUICKACK + nodelay, + quickack #endif // __APPLE__ || __QNX__ || WIN32 || __CYGWIN__ }; diff --git a/src/rl/hal/UniversalRobotsDashboard.cpp b/src/rl/hal/UniversalRobotsDashboard.cpp index e154f968..67b38a4c 100644 --- a/src/rl/hal/UniversalRobotsDashboard.cpp +++ b/src/rl/hal/UniversalRobotsDashboard.cpp @@ -361,15 +361,15 @@ namespace rl if ("STOPPED" == reply.substr(0, 7)) { - return ::std::make_pair(PROGRAM_STATE_STOPPED, reply.substr(8, reply.size() - 9)); + return ::std::make_pair(ProgramState::stopped, reply.substr(8, reply.size() - 9)); } else if ("PLAYING" == reply.substr(0, 7)) { - return ::std::make_pair(PROGRAM_STATE_PLAYING, reply.substr(8, reply.size() - 9)); + return ::std::make_pair(ProgramState::playing, reply.substr(8, reply.size() - 9)); } else if ("PAUSED" == reply.substr(0, 6)) { - return ::std::make_pair(PROGRAM_STATE_PAUSED, reply.substr(7, reply.size() - 8)); + return ::std::make_pair(ProgramState::paused, reply.substr(7, reply.size() - 8)); } else { @@ -388,39 +388,39 @@ namespace rl if ("Robotmode: NO_CONTROLLER\n" == reply) { - return ROBOT_MODE_NO_CONTROLLER; + return RobotMode::noController; } else if ("Robotmode: DISCONNECTED\n" == reply) { - return ROBOT_MODE_DISCONNECTED; + return RobotMode::disconnected; } else if ("Robotmode: CONFIRM_SAFETY\n" == reply) { - return ROBOT_MODE_CONFIRM_SAFETY; + return RobotMode::confirmSafety; } else if ("Robotmode: BOOTING\n" == reply) { - return ROBOT_MODE_BOOTING; + return RobotMode::booting; } else if ("Robotmode: POWER_OFF\n" == reply) { - return ROBOT_MODE_POWER_OFF; + return RobotMode::powerOff; } else if ("Robotmode: POWER_ON\n" == reply) { - return ROBOT_MODE_POWER_ON; + return RobotMode::powerOn; } else if ("Robotmode: IDLE\n" == reply) { - return ROBOT_MODE_IDLE; + return RobotMode::idle; } else if ("Robotmode: BACKDRIVE\n" == reply) { - return ROBOT_MODE_BACKDRIVE; + return RobotMode::backdrive; } else if ("Robotmode: RUNNING\n" == reply) { - return ROBOT_MODE_RUNNING; + return RobotMode::running; } else { @@ -462,39 +462,39 @@ namespace rl if ("Safetymode: NORMAL\n" == reply) { - return SAFETY_MODE_NORMAL; + return SafetyMode::normal; } else if ("Safetymode: REDUCED\n" == reply) { - return SAFETY_MODE_REDUCED; + return SafetyMode::reduced; } else if ("Safetymode: PROTECTIVE_STOP\n" == reply) { - return SAFETY_MODE_PROTECTIVE_STOP; + return SafetyMode::protectiveStop; } else if ("Safetymode: RECOVERY\n" == reply) { - return SAFETY_MODE_RECOVERY; + return SafetyMode::recovery; } else if ("Safetymode: SAFEGUARD_STOP\n" == reply) { - return SAFETY_MODE_SAFEGUARD_STOP; + return SafetyMode::safeguardStop; } else if ("Safetymode: SYSTEM_EMERGENCY_STOP\n" == reply) { - return SAFETY_MODE_SYSTEM_EMERGENCY_STOP; + return SafetyMode::systemEmergencyStop; } else if ("Safetymode: ROBOT_EMERGENCY_STOP\n" == reply) { - return SAFETY_MODE_ROBOT_EMERGENCY_STOP; + return SafetyMode::robotEmergencyStop; } else if ("Safetymode: VIOLATION\n" == reply) { - return SAFETY_MODE_VIOLATION; + return SafetyMode::violation; } else if ("Safetymode: FAULT\n" == reply) { - return SAFETY_MODE_FAULT; + return SafetyMode::fault; } else { @@ -587,7 +587,7 @@ namespace rl { this->socket.open(); this->socket.connect(); - this->socket.setOption(::rl::hal::Socket::OPTION_NODELAY, 1); + this->socket.setOption(Socket::Option::nodelay, 1); this->setConnected(true); ::std::array<::std::uint8_t, 4096> buffer; diff --git a/src/rl/hal/UniversalRobotsDashboard.h b/src/rl/hal/UniversalRobotsDashboard.h index 48457c7e..fe3e9871 100644 --- a/src/rl/hal/UniversalRobotsDashboard.h +++ b/src/rl/hal/UniversalRobotsDashboard.h @@ -43,37 +43,37 @@ namespace rl class RL_HAL_EXPORT UniversalRobotsDashboard : public Com { public: - enum ProgramState + enum class ProgramState { - PROGRAM_STATE_STOPPED, - PROGRAM_STATE_PLAYING, - PROGRAM_STATE_PAUSED + stopped, + playing, + paused }; - enum RobotMode + enum class RobotMode { - ROBOT_MODE_NO_CONTROLLER, - ROBOT_MODE_DISCONNECTED, - ROBOT_MODE_CONFIRM_SAFETY, - ROBOT_MODE_BOOTING, - ROBOT_MODE_POWER_OFF, - ROBOT_MODE_POWER_ON, - ROBOT_MODE_IDLE, - ROBOT_MODE_BACKDRIVE, - ROBOT_MODE_RUNNING + noController, + disconnected, + confirmSafety, + booting, + powerOff, + powerOn, + idle, + backdrive, + running }; - enum SafetyMode + enum class SafetyMode { - SAFETY_MODE_NORMAL, - SAFETY_MODE_REDUCED, - SAFETY_MODE_PROTECTIVE_STOP, - SAFETY_MODE_RECOVERY, - SAFETY_MODE_SAFEGUARD_STOP, - SAFETY_MODE_SYSTEM_EMERGENCY_STOP, - SAFETY_MODE_ROBOT_EMERGENCY_STOP, - SAFETY_MODE_VIOLATION, - SAFETY_MODE_FAULT + normal, + reduced, + protectiveStop, + recovery, + safeguardStop, + systemEmergencyStop, + robotEmergencyStop, + violation, + fault }; UniversalRobotsDashboard(const ::std::string& address); diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index 4af02075..ce66ec3b 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -238,7 +238,7 @@ namespace rl { this->socket.open(); this->socket.connect(); - this->socket.setOption(::rl::hal::Socket::OPTION_NODELAY, 1); + this->socket.setOption(Socket::Option::nodelay, 1); this->setConnected(true); } @@ -255,7 +255,7 @@ namespace rl this->socket.recv(buffer.data(), sizeof(this->in.messageSize)); #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) - this->socket.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); + this->socket.setOption(Socket::Option::quickack, 1); #endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ ::std::uint8_t* ptr = buffer.data(); @@ -272,7 +272,7 @@ namespace rl case 1116: this->socket.recv(ptr, this->in.messageSize - sizeof(this->in.messageSize)); #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) - this->socket.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); + this->socket.setOption(Socket::Option::quickack, 1); #endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ this->in.unserialize(ptr); break; diff --git a/src/rl/hal/UniversalRobotsRealtime.h b/src/rl/hal/UniversalRobotsRealtime.h index e844e802..18ca60a3 100644 --- a/src/rl/hal/UniversalRobotsRealtime.h +++ b/src/rl/hal/UniversalRobotsRealtime.h @@ -63,79 +63,79 @@ namespace rl public JointVelocitySensor { public: - enum JointMode + enum class JointMode { - JOINT_MODE_RESET = 235, - JOINT_MODE_SHUTTING_DOWN = 236, - JOINT_MODE_PART_D_CALIBRATION = 237, - JOINT_MODE_BACKDRIVE = 238, - JOINT_MODE_POWER_OFF = 239, - JOINT_MODE_NOT_RESPONDING = 245, - JOINT_MODE_MOTOR_INITIALISATION = 246, - JOINT_MODE_BOOTING = 247, - JOINT_MODE_PART_D_CALIBRATION_ERROR = 248, - JOINT_MODE_BOOTLOADER = 249, - JOINT_MODE_CALIBRATION = 250, - JOINT_MODE_VIOLATION = 251, - JOINT_MODE_FAULT = 252, - JOINT_MODE_RUNNING = 253, - JOINT_MODE_IDLE = 255 + reset = 235, + shuttingDown = 236, + partDCalibration = 237, + backdrive = 238, + powerOff = 239, + notResponding = 245, + motorInitialisation = 246, + booting = 247, + partDCalibrationError = 248, + bootloader = 249, + calibration = 250, + violation = 251, + fault = 252, + running = 253, + idle = 255 }; - enum ProgramState + enum class ProgramState { - PROGRAM_STATE_STOPPING = 0, - PROGRAM_STATE_STOPPED = 1, - PROGRAM_STATE_PLAYING = 2, - PROGRAM_STATE_PAUSING = 3, - PROGRAM_STATE_PAUSED = 4, - PROGRAM_STATE_RESUMING = 5 + stopping = 0, + stopped = 1, + playing = 2, + pausing = 3, + paused = 4, + resuming = 5 }; - enum RobotMode + enum class RobotMode { - ROBOT_MODE_NO_CONTROLLER = -1, - ROBOT_MODE_DISCONNECTED = 0, - ROBOT_MODE_CONFIRM_SAFETY = 1, - ROBOT_MODE_BOOTING = 2, - ROBOT_MODE_POWER_OFF = 3, - ROBOT_MODE_POWER_ON = 4, - ROBOT_MODE_IDLE = 5, - ROBOT_MODE_BACKDRIVE = 6, - ROBOT_MODE_RUNNING = 7, - ROBOT_MODE_UPDATING_FIRMWARE = 8 + noController = -1, + disconnected = 0, + confirmSafety = 1, + booting = 2, + powerOff = 3, + powerOn = 4, + idle = 5, + backdrive = 6, + running = 7, + updatingFirmware = 8 }; - enum SafetyMode + enum class SafetyMode { - SAFETY_MODE_NORMAL = 1, - SAFETY_MODE_REDUCED = 2, - SAFETY_MODE_PROTECTIVE_STOP = 3, - SAFETY_MODE_RECOVERY = 4, - SAFETY_MODE_SAFEGUARD_STOP = 5, - SAFETY_MODE_SYSTEM_EMERGENCY_STOP = 6, - SAFETY_MODE_ROBOT_EMERGENCY_STOP = 7, - SAFETY_MODE_VIOLATION = 8, - SAFETY_MODE_FAULT = 9, - SAFETY_MODE_VALIDATE_JOINT_ID = 10, - SAFETY_MODE_UNDEFINED_SAFETY_MODE = 11 + normal = 1, + reduced = 2, + protectiveStop = 3, + recovery = 4, + safeguardStop = 5, + systemEmergencyStop = 6, + robotEmergencyStop = 7, + violation = 8, + fault = 9, + validateJointId = 10, + undefinedSafetyMode = 11 }; - enum SafetyStatus + enum class SafetyStatus { - SAFETY_STATUS_NORMAL = 1, - SAFETY_STATUS_REDUCED = 2, - SAFETY_STATUS_PROTECTIVE_STOP = 3, - SAFETY_STATUS_RECOVERY = 4, - SAFETY_STATUS_SAFEGUARD_STOP = 5, - SAFETY_STATUS_SYSTEM_EMERGENCY_STOP = 6, - SAFETY_STATUS_ROBOT_EMERGENCY_STOP = 7, - SAFETY_STATUS_VIOLATION = 8, - SAFETY_STATUS_FAULT = 9, - SAFETY_STATUS_VALIDATE_JOINT_ID = 10, - SAFETY_STATUS_UNDEFINED_SAFETY_MODE = 11, - SAFETY_STATUS_AUTOMATIC_MODE_SAFEGUARD_STOP = 12, - SAFETY_STATUS_SYSTEM_THREE_POSITION_ENABLING_STOP = 13 + normal = 1, + reduced = 2, + protectiveStop = 3, + recovery = 4, + safeguardStop = 5, + systemEmergencyStop = 6, + robotEmergencyStop = 7, + violation = 8, + fault = 9, + validateJointId = 10, + undefinedSafetyMode = 11, + automaticModeSafeguardStop = 12, + systemThreePositionEnablingStop = 13 }; UniversalRobotsRealtime(const ::std::string& address); diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index a8b31d2a..3d88569f 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -486,19 +486,19 @@ namespace rl { this->socket2.open(); this->socket2.connect(); - this->socket2.setOption(::rl::hal::Socket::OPTION_NODELAY, 1); + this->socket2.setOption(Socket::Option::nodelay, 1); this->socket4.open(); this->socket4.connect(); - this->socket4.setOption(::rl::hal::Socket::OPTION_NODELAY, 1); + this->socket4.setOption(Socket::Option::nodelay, 1); this->setConnected(true); - this->send(COMMAND_REQUEST_PROTOCOL_VERSION, 1); + this->send(Command::requestProtocolVersion, 1); this->recv(); - this->send(COMMAND_GET_URCONTROL_VERSION); + this->send(Command::getUrcontrolVersion); this->recv(); - static const ::std::string outputsArray[] = { + static constexpr const char* outputsArray[] = { "timestamp", "target_q", "target_qd", @@ -585,17 +585,17 @@ namespace rl "output_double_register_23" }; static const ::std::vector<::std::string> outputs(::std::begin(outputsArray), ::std::end(outputsArray)); - this->send(COMMAND_CONTROL_PACKAGE_SETUP_OUTPUTS, outputs); + this->send(Command::controlPackageSetupOutputs, outputs); this->recv(); - static const ::std::string inputs1Array[] = { + static constexpr const char* inputs1Array[] = { "input_int_register_0" }; static const ::std::vector<::std::string> inputs1(::std::begin(inputs1Array), ::std::end(inputs1Array)); - this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs1); + this->send(Command::controlPackageSetupInputs, inputs1); this->recv(); - static const ::std::string inputs2Array[] = { + static constexpr const char* inputs2Array[] = { "input_double_register_0", "input_double_register_1", "input_double_register_2", @@ -611,35 +611,35 @@ namespace rl "input_double_register_12" }; static const ::std::vector<::std::string> inputs2(::std::begin(inputs2Array), ::std::end(inputs2Array)); - this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs2); + this->send(Command::controlPackageSetupInputs, inputs2); this->recv(); - static const ::std::string inputs3Array[] = { + static constexpr const char* inputs3Array[] = { "standard_digital_output_mask", "configurable_digital_output_mask", "standard_digital_output", "configurable_digital_output" }; static const ::std::vector<::std::string> inputs3(::std::begin(inputs3Array), ::std::end(inputs3Array)); - this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs3); + this->send(Command::controlPackageSetupInputs, inputs3); this->recv(); - static const ::std::string inputs4Array[] = { + static constexpr const char* inputs4Array[] = { "standard_analog_output_mask", "standard_analog_output_type", "standard_analog_output_0", "standard_analog_output_1" }; static const ::std::vector<::std::string> inputs4(::std::begin(inputs4Array), ::std::end(inputs4Array)); - this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs4); + this->send(Command::controlPackageSetupInputs, inputs4); this->recv(); - static const ::std::string inputs5Array[] = { + static constexpr const char* inputs5Array[] = { "input_bit_registers0_to_31", "input_bit_registers32_to_63" }; static const ::std::vector<::std::string> inputs5(::std::begin(inputs5Array), ::std::end(inputs5Array)); - this->send(COMMAND_CONTROL_PACKAGE_SETUP_INPUTS, inputs5); + this->send(Command::controlPackageSetupInputs, inputs5); this->recv(); } @@ -649,7 +649,7 @@ namespace rl ::std::array<::std::uint8_t, 4096> buffer; ::std::size_t size = this->socket4.recv(buffer.data(), buffer.size()); #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) - this->socket4.setOption(::rl::hal::Socket::OPTION_QUICKACK, 1); + this->socket4.setOption(Socket::Option::quickack, 1); #endif // !__APPLE__ && !__QNX__ && !WIN32 && !__CYGWIN__ // ::std::cout << "size: " << size << ::std::endl; @@ -665,9 +665,9 @@ namespace rl this->unserialize(ptr, packageType); // ::std::cout << "packageType: " << packageType << ::std::endl; - switch (packageType) + switch (static_cast(packageType)) { - case COMMAND_CONTROL_PACKAGE_PAUSE: + case Command::controlPackagePause: ::std::uint8_t pauseAccepted; this->unserialize(ptr, pauseAccepted); // ::std::cout << "accepted: " << static_cast(pauseAccepted & 0x01) << ::std::endl; @@ -678,7 +678,7 @@ namespace rl } break; - case COMMAND_CONTROL_PACKAGE_SETUP_INPUTS: + case Command::controlPackageSetupInputs: { ::std::uint8_t recipeId; this->unserialize(ptr, recipeId); @@ -694,7 +694,7 @@ namespace rl ptr += packageSize - 4; } break; - case COMMAND_CONTROL_PACKAGE_SETUP_OUTPUTS: + case Command::controlPackageSetupOutputs: { ::std::string variableTypes(reinterpret_cast(ptr), packageSize - 3); // ::std::cout << "variableTypes: " << variableTypes << ::std::endl; @@ -706,7 +706,7 @@ namespace rl } } break; - case COMMAND_CONTROL_PACKAGE_START: + case Command::controlPackageStart: ::std::uint8_t startAccepted; this->unserialize(ptr, startAccepted); // ::std::cout << "accepted: " << static_cast(startAccepted & 0x01) << ::std::endl; @@ -717,7 +717,7 @@ namespace rl } break; - case COMMAND_DATA_PACKAGE: + case Command::dataPackage: this->unserialize(ptr, this->output.timestamp); this->unserialize(ptr, this->output.targetQ); this->unserialize(ptr, this->output.targetQd); @@ -769,35 +769,35 @@ namespace rl switch (this->getSafetyMode()) { - case SAFETY_MODE_NORMAL: + case SafetyMode::normal: break; - case SAFETY_MODE_REDUCED: + case SafetyMode::reduced: break; - case SAFETY_MODE_PROTECTIVE_STOP: + case SafetyMode::protectiveStop: throw DeviceException("Protective stop"); break; - case SAFETY_MODE_RECOVERY: + case SafetyMode::recovery: break; - case SAFETY_MODE_SAFEGUARD_STOP: + case SafetyMode::safeguardStop: throw DeviceException("Safeguard stop"); break; - case SAFETY_MODE_SYSTEM_EMERGENCY_STOP: + case SafetyMode::systemEmergencyStop: throw DeviceException("System emergency stop"); break; - case SAFETY_MODE_ROBOT_EMERGENCY_STOP: + case SafetyMode::robotEmergencyStop: throw DeviceException("Robot emergency stop"); break; - case SAFETY_MODE_VIOLATION: + case SafetyMode::violation: throw DeviceException("Mode violation"); break; - case SAFETY_MODE_FAULT: + case SafetyMode::fault: throw DeviceException("Fault"); break; default: break; } break; - case COMMAND_GET_URCONTROL_VERSION: + case Command::getUrcontrolVersion: this->unserialize(ptr, this->version.major); // ::std::cout << "major: " << this->version.major << ::std::endl; this->unserialize(ptr, this->version.minor); @@ -807,7 +807,7 @@ namespace rl this->unserialize(ptr, this->version.build); // ::std::cout << "build: " << this->version.build << ::std::endl; break; - case COMMAND_REQUEST_PROTOCOL_VERSION: + case Command::requestProtocolVersion: ::std::uint8_t protocolAccepted; this->unserialize(ptr, protocolAccepted); // ::std::cout << "accepted: " << static_cast(protocolAccepted & 0x01) << ::std::endl; @@ -818,7 +818,7 @@ namespace rl } break; - case COMMAND_TEXT_MESSAGE: + case Command::textMessage: { ::std::uint8_t level; this->unserialize(ptr, level); @@ -859,7 +859,7 @@ namespace rl } void - UniversalRobotsRtde::send(const ::std::uint8_t& command) + UniversalRobotsRtde::send(const Command& command) { ::std::vector<::std::uint8_t> buffer; @@ -867,13 +867,13 @@ namespace rl buffer.push_back(0); buffer.push_back(0); - buffer.push_back(command); + buffer.push_back(static_cast<::std::uint8_t>(command)); this->send(buffer.data(), buffer.size()); } void - UniversalRobotsRtde::send(const ::std::uint8_t& command, const ::std::vector<::std::string>& strings) + UniversalRobotsRtde::send(const Command& command, const ::std::vector<::std::string>& strings) { ::std::vector<::std::uint8_t> buffer; @@ -881,7 +881,7 @@ namespace rl buffer.push_back(0); buffer.push_back(0); - buffer.push_back(command); + buffer.push_back(static_cast<::std::uint8_t>(command)); for (::std::size_t i = 0; i < strings.size(); ++i) { @@ -905,7 +905,7 @@ namespace rl } void - UniversalRobotsRtde::send(const ::std::uint8_t& command, const ::std::uint16_t& word) + UniversalRobotsRtde::send(const Command& command, const ::std::uint16_t& word) { ::std::vector<::std::uint8_t> buffer; @@ -913,7 +913,7 @@ namespace rl buffer.push_back(0); buffer.push_back(0); - buffer.push_back(command); + buffer.push_back(static_cast<::std::uint8_t>(command)); buffer.push_back(Endian::hostHighByte(word)); buffer.push_back(Endian::hostLowByte(word)); @@ -929,7 +929,7 @@ namespace rl buffer.push_back(0); buffer.push_back(0); - buffer.push_back(COMMAND_DATA_PACKAGE); + buffer.push_back(static_cast<::std::uint8_t>(Command::dataPackage)); buffer.push_back(4); buffer.resize(buffer.size() + 2 + 2 * sizeof(double)); @@ -953,7 +953,7 @@ namespace rl buffer.push_back(0); buffer.push_back(0); - buffer.push_back(COMMAND_DATA_PACKAGE); + buffer.push_back(static_cast<::std::uint8_t>(Command::dataPackage)); buffer.push_back(5); ::std::uint8_t* ptr = &buffer[4]; @@ -982,7 +982,7 @@ namespace rl buffer.push_back(0); buffer.push_back(0); - buffer.push_back(COMMAND_DATA_PACKAGE); + buffer.push_back(static_cast<::std::uint8_t>(Command::dataPackage)); buffer.push_back(3); buffer.resize(buffer.size() + 4); @@ -1006,7 +1006,7 @@ namespace rl buffer.push_back(0); buffer.push_back(0); - buffer.push_back(COMMAND_DATA_PACKAGE); + buffer.push_back(static_cast<::std::uint8_t>(Command::dataPackage)); buffer.push_back(2); buffer.resize(buffer.size() + this->input.inputDoubleRegister.size() * sizeof(double)); @@ -1030,7 +1030,7 @@ namespace rl buffer.push_back(0); buffer.push_back(0); - buffer.push_back(COMMAND_DATA_PACKAGE); + buffer.push_back(static_cast<::std::uint8_t>(Command::dataPackage)); buffer.push_back(1); buffer.resize(buffer.size() + this->input.inputIntRegister.size() * sizeof(::std::int32_t)); @@ -1210,7 +1210,7 @@ namespace rl void UniversalRobotsRtde::start() { - this->send(COMMAND_CONTROL_PACKAGE_START); + this->send(Command::controlPackageStart); this->recv(); this->input.inputIntRegister.push_back(1); @@ -1249,7 +1249,7 @@ namespace rl { this->recv(); } - while (ROBOT_MODE_RUNNING != this->getRobotMode() || RUNTIME_STATE_PLAYING != this->getRuntimeState()); + while (RobotMode::running != this->getRobotMode() || RuntimeState::playing != this->getRuntimeState()); this->setRunning(true); } @@ -1303,9 +1303,9 @@ namespace rl { this->recv(); } - while (RUNTIME_STATE_STOPPED != this->getRuntimeState()); + while (RuntimeState::stopped != this->getRuntimeState()); - this->send(COMMAND_CONTROL_PACKAGE_PAUSE); + this->send(Command::controlPackagePause); this->recv(); this->setRunning(false); diff --git a/src/rl/hal/UniversalRobotsRtde.h b/src/rl/hal/UniversalRobotsRtde.h index 978045d7..0e5c9448 100644 --- a/src/rl/hal/UniversalRobotsRtde.h +++ b/src/rl/hal/UniversalRobotsRtde.h @@ -75,80 +75,80 @@ namespace rl public JointVelocitySensor { public: - enum JointMode + enum class JointMode { - JOINT_MODE_SHUTTING_DOWN = 236, - JOINT_MODE_PART_D_CALIBRATION = 237, - JOINT_MODE_BACKDRIVE = 238, - JOINT_MODE_POWER_OFF = 239, - JOINT_MODE_NOT_RESPONDING = 245, - JOINT_MODE_MOTOR_INITIALISATION = 246, - JOINT_MODE_BOOTING = 247, - JOINT_MODE_PART_D_CALIBRATION_ERROR = 248, - JOINT_MODE_BOOTLOADER = 249, - JOINT_MODE_CALIBRATION = 250, - JOINT_MODE_FAULT = 252, - JOINT_MODE_RUNNING = 253, - JOINT_MODE_IDLE_MODE = 255 + shuttingDown = 236, + partDCalibration = 237, + backdrive = 238, + powerOff = 239, + notResponding = 245, + motorInitialisation = 246, + booting = 247, + partDCalibrationError = 248, + bootloader = 249, + calibration = 250, + fault = 252, + running = 253, + idleMode = 255 }; - enum RobotMode + enum class RobotMode { - ROBOT_MODE_DISCONNECTED = 0, - ROBOT_MODE_CONFIRM_SAFETY = 1, - ROBOT_MODE_BOOTING = 2, - ROBOT_MODE_POWER_OFF = 3, - ROBOT_MODE_POWER_ON = 4, - ROBOT_MODE_IDLE = 5, - ROBOT_MODE_BACKDRIVE = 6, - ROBOT_MODE_RUNNING = 7, - ROBOT_MODE_UPDATING_FIRMWARE = 8 + disconnected = 0, + confirmSafety = 1, + booting = 2, + powerOff = 3, + powerOn = 4, + idle = 5, + backdrive = 6, + running = 7, + updatingFirmware = 8 }; - enum RobotStatus + enum class RobotStatus { - ROBOT_STATUS_POWER_ON = 1, - ROBOT_STATUS_PROGRAM_RUNNING = 2, - ROBOT_STATUS_TEACH_BUTTON_PRESSED = 4, - ROBOT_STATUS_POWER_BUTTON_PRESSED = 8 + powerOn = 1, + programRunning = 2, + teachButtonPressed = 4, + powerButtonPressed = 8 }; - enum RuntimeState + enum class RuntimeState { - RUNTIME_STATE_STOPPING = 0, - RUNTIME_STATE_STOPPED = 1, - RUNTIME_STATE_PLAYING = 2, - RUNTIME_STATE_PAUSING = 3, - RUNTIME_STATE_PAUSED = 4, - RUNTIME_STATE_RESUMING = 5 + stopping = 0, + stopped = 1, + playing = 2, + pausing = 3, + paused = 4, + resuming = 5 }; - enum SafetyMode + enum class SafetyMode { - SAFETY_MODE_NORMAL = 1, - SAFETY_MODE_REDUCED = 2, - SAFETY_MODE_PROTECTIVE_STOP = 3, - SAFETY_MODE_RECOVERY = 4, - SAFETY_MODE_SAFEGUARD_STOP = 5, - SAFETY_MODE_SYSTEM_EMERGENCY_STOP = 6, - SAFETY_MODE_ROBOT_EMERGENCY_STOP = 7, - SAFETY_MODE_VIOLATION = 8, - SAFETY_MODE_FAULT = 9 + normal = 1, + reduced = 2, + protectiveStop = 3, + recovery = 4, + safeguardStop = 5, + systemEmergencyStop = 6, + robotEmergencyStop = 7, + violation = 8, + fault = 9 }; - enum SafetyStatus + enum class SafetyStatus { - SAFETY_STATUS_NORMAL_MODE = 1, - SAFETY_STATUS_REDUCED_MODE = 2, - SAFETY_STATUS_PROTECTIVE_STOPPED = 4, - SAFETY_STATUS_RECOVERY_MODE = 8, - SAFETY_STATUS_SAFEGUARD_STOPPED = 16, - SAFETY_STATUS_SYSTEM_EMERGENCY_STOPPED = 32, - SAFETY_STATUS_ROBOT_EMERGENCY_STOPPED = 64, - SAFETY_STATUS_EMERGENCY_STOPPED = 128, - SAFETY_STATUS_VIOLATION = 256, - SAFETY_STATUS_FAULT = 512, - SAFETY_STATUS_STOPPED_DUE_TO_SAFETY = 1024 + normalMode = 1, + reducedMode = 2, + protectiveStopped = 4, + recoveryMode = 8, + safeguardStopped = 16, + systemEmergencyStopped = 32, + robotEmergencyStopped = 64, + emergencyStopped = 128, + violation = 256, + fault = 512, + stoppedDueToSafety = 1024 }; UniversalRobotsRtde(const ::std::string& address, const ::std::chrono::nanoseconds& updateRate = ::std::chrono::milliseconds(8)); @@ -258,16 +258,16 @@ namespace rl protected: private: - enum Command + enum class Command : ::std::uint8_t { - COMMAND_CONTROL_PACKAGE_PAUSE = 80, - COMMAND_CONTROL_PACKAGE_SETUP_INPUTS = 73, - COMMAND_CONTROL_PACKAGE_SETUP_OUTPUTS = 79, - COMMAND_CONTROL_PACKAGE_START = 83, - COMMAND_DATA_PACKAGE = 85, - COMMAND_GET_URCONTROL_VERSION = 118, - COMMAND_REQUEST_PROTOCOL_VERSION = 86, - COMMAND_TEXT_MESSAGE = 77 + controlPackagePause = 80, + controlPackageSetupInputs = 73, + controlPackageSetupOutputs = 79, + controlPackageStart = 83, + dataPackage = 85, + getUrcontrolVersion = 118, + requestProtocolVersion = 86, + textMessage = 77 }; struct Input @@ -391,11 +391,11 @@ namespace rl void send(::std::uint8_t* buffer, const ::std::size_t& size); - void send(const ::std::uint8_t& command); + void send(const Command& command); - void send(const ::std::uint8_t& command, const ::std::vector<::std::string>& strings); + void send(const Command& command, const ::std::vector<::std::string>& strings); - void send(const ::std::uint8_t& command, const ::std::uint16_t& word); + void send(const Command& command, const ::std::uint16_t& word); void sendAnalogOutputs(); diff --git a/src/rl/hal/WeissException.cpp b/src/rl/hal/WeissException.cpp index 655d631b..74f8369e 100644 --- a/src/rl/hal/WeissException.cpp +++ b/src/rl/hal/WeissException.cpp @@ -51,97 +51,97 @@ namespace rl { switch (this->code) { - case CODE_SUCCESS: + case Code::success: return "No error."; break; - case CODE_NOT_AVAILABLE: + case Code::notAvailable: return "Device, service or data is not available."; break; - case CODE_NO_SENSOR: + case Code::noSensor: return "No sensor connected."; break; - case CODE_NOT_INITIALIZED: + case Code::notInitialized: return "The device is not initialized."; break; - case CODE_ALREADY_RUNNING: + case Code::alreadyRunning: return "Service is already running."; break; - case CODE_FEATURE_NOT_SUPPORTED: + case Code::featureNotSupported: return "The asked feature is not supported."; break; - case CODE_INCONSISTENT_DATA: + case Code::inconsistentData: return "One or more dependent parameters mismatch."; break; - case CODE_TIMEOUT: + case Code::timeout: return "Timeout error."; break; - case CODE_READ_ERROR: + case Code::readError: return "Error while reading from a device."; break; - case CODE_WRITE_ERROR: + case Code::writeError: return "Error while writing to a device."; break; - case CODE_INSUFFICIENT_RESOURCES: + case Code::insufficientResources: return "No memory available."; break; - case CODE_CHECKSUM_ERROR: + case Code::checksumError: return "Checksum error."; break; - case CODE_NO_PARAM_EXPECTED: + case Code::noParamExpected: return "No parameters expected."; break; - case CODE_NOT_ENOUGH_PARAMS: + case Code::notEnoughParams: return "Not enough parameters."; break; - case CODE_COMMAND_UNKNOWN: + case Code::commandUnknown: return "Unknown command."; break; - case CODE_COMMAND_FORMAT_ERROR: + case Code::commandFormatError: return "Command format error."; break; - case CODE_ACCESS_DENIED: + case Code::accessDenied: return "Access denied."; break; - case CODE_ALREADY_OPEN: + case Code::alreadyOpen: return "The interface is already open."; break; - case CODE_COMMAND_FAILED: + case Code::commandFailed: return "Command failed."; break; - case CODE_COMMAND_ABORTED: + case Code::commandAborted: return "Command aborted."; break; - case CODE_INVALID_HANDLE: + case Code::invalidHandle: return "invalid handle."; break; - case CODE_NOT_FOUND: + case Code::notFound: return "device not found."; break; - case CODE_NOT_OPEN: + case Code::notOpen: return "device not open."; break; - case CODE_IO_ERROR: + case Code::ioError: return "I/O error."; break; - case CODE_INVALID_PARAMETER: + case Code::invalidParameter: return "invalid parameter."; break; - case CODE_INDEX_OUT_OF_BOUNDS: + case Code::indexOutOfBounds: return "index out of bounds."; break; - case CODE_COMMAND_PENDING: + case Code::commandPending: return "Command was received correctly, but the execution needs more time. If the command was completely processed, another status message is returned indicating the command's result."; break; - case CODE_OVERRUN: + case Code::overrun: return "Data overrun."; break; - case CODE_RANGE_ERROR: + case Code::rangeError: return "Range error."; break; - case CODE_AXIS_BLOCKED: + case Code::axisBlocked: return "Axis is blocked."; break; - case CODE_FILE_EXISTS: + case Code::fileExists: return "File already exists."; break; default: diff --git a/src/rl/hal/WeissException.h b/src/rl/hal/WeissException.h index 23ab6e7e..d7951695 100644 --- a/src/rl/hal/WeissException.h +++ b/src/rl/hal/WeissException.h @@ -36,39 +36,39 @@ namespace rl class RL_HAL_EXPORT WeissException : public DeviceException { public: - enum Code + enum class Code { - CODE_SUCCESS = 0, - CODE_NOT_AVAILABLE = 1, - CODE_NO_SENSOR = 2, - CODE_NOT_INITIALIZED = 3, - CODE_ALREADY_RUNNING = 4, - CODE_FEATURE_NOT_SUPPORTED = 5, - CODE_INCONSISTENT_DATA = 6, - CODE_TIMEOUT = 7, - CODE_READ_ERROR = 8, - CODE_WRITE_ERROR = 9, - CODE_INSUFFICIENT_RESOURCES = 10, - CODE_CHECKSUM_ERROR = 11, - CODE_NO_PARAM_EXPECTED = 12, - CODE_NOT_ENOUGH_PARAMS = 13, - CODE_COMMAND_UNKNOWN = 14, - CODE_COMMAND_FORMAT_ERROR = 15, - CODE_ACCESS_DENIED = 16, - CODE_ALREADY_OPEN = 17, - CODE_COMMAND_FAILED = 18, - CODE_COMMAND_ABORTED = 19, - CODE_INVALID_HANDLE = 20, - CODE_NOT_FOUND = 21, - CODE_NOT_OPEN = 22, - CODE_IO_ERROR = 23, - CODE_INVALID_PARAMETER = 24, - CODE_INDEX_OUT_OF_BOUNDS = 25, - CODE_COMMAND_PENDING = 26, - CODE_OVERRUN = 27, - CODE_RANGE_ERROR = 28, - CODE_AXIS_BLOCKED = 29, - CODE_FILE_EXISTS = 30 + success = 0, + notAvailable = 1, + noSensor = 2, + notInitialized = 3, + alreadyRunning = 4, + featureNotSupported = 5, + inconsistentData = 6, + timeout = 7, + readError = 8, + writeError = 9, + insufficientResources = 10, + checksumError = 11, + noParamExpected = 12, + notEnoughParams = 13, + commandUnknown = 14, + commandFormatError = 15, + accessDenied = 16, + alreadyOpen = 17, + commandFailed = 18, + commandAborted = 19, + invalidHandle = 20, + notFound = 21, + notOpen = 22, + ioError = 23, + invalidParameter = 24, + indexOutOfBounds = 25, + commandPending = 26, + overrun = 27, + rangeError = 28, + axisBlocked = 29, + fileExists = 30 }; WeissException(const Code& code); diff --git a/src/rl/hal/WeissKms40.cpp b/src/rl/hal/WeissKms40.cpp index a6646e04..f92473ea 100644 --- a/src/rl/hal/WeissKms40.cpp +++ b/src/rl/hal/WeissKms40.cpp @@ -188,7 +188,7 @@ namespace rl return ::std::stoi(reply.substr(3)); } - WeissKms40::SystemState + int WeissKms40::doGetSystemFlags() { ::std::string command = "FLAGS()\n"; @@ -196,7 +196,7 @@ namespace rl ::std::string reply = this->recv("FLAGS="); - return static_cast(::std::stoi(reply.substr(6))); + return ::std::stoi(reply.substr(6)); } ::std::string diff --git a/src/rl/hal/WeissKms40.h b/src/rl/hal/WeissKms40.h index 823e28f3..3b8e92f7 100644 --- a/src/rl/hal/WeissKms40.h +++ b/src/rl/hal/WeissKms40.h @@ -50,27 +50,27 @@ namespace rl class RL_HAL_EXPORT WeissKms40 : public CyclicDevice, public SixAxisForceTorqueSensor { public: - enum SystemState + enum class SystemState { - SYSTEM_STATE_SCRIPT_FAILURE = 1073741824, - SYSTEM_STATE_CMD_FAILURE = 536870912, - SYSTEM_STATE_POWER_FAULT = 268435456, - SYSTEM_STATE_TEMP_FAULT = 134217728, - SYSTEM_STATE_CALIBRATION_FAULT = 67108864, - SYSTEM_STATE_OVERRUN_MZ = 33554432, - SYSTEM_STATE_OVERRUN_MY = 16777216, - SYSTEM_STATE_OVERRUN_MX = 8388608, - SYSTEM_STATE_OVERRUN_FZ = 4194304, - SYSTEM_STATE_OVERRUN_FY = 2097152, - SYSTEM_STATE_OVERRUN_FX = 1048576, - SYSTEM_STATE_TEMP_WARNING = 2048, - SYSTEM_STATE_CALIBRATION_EXPIRED = 1024, - SYSTEM_STATE_SCRIPT_RUNNING = 32, - SYSTEM_STATE_DAQ_RUNNING = 16, - SYSTEM_STATE_FILTER_ENABLED = 8, - SYSTEM_STATE_TARA = 4, - SYSTEM_STATE_STABLE = 2, - SYSTEM_STATE_CALIBRATION_VALID = 1 + calibrationValid = 1, + stable = 2, + tara = 4, + filterEnabled = 8, + daqRunning = 16, + scriptRunning = 32, + calibrationExpired = 1024, + tempWarning = 2048, + overrunFx = 1048576, + overrunFy = 2097152, + overrunFz = 4194304, + overrunMx = 8388608, + overrunMy = 16777216, + overrunMz = 33554432, + calibrationFault = 67108864, + tempFault = 134217728, + powerFault = 268435456, + cmdFailure = 536870912, + scriptFailure = 1073741824 }; /** @@ -108,7 +108,7 @@ namespace rl ::std::size_t doGetSerialNumber(); - SystemState doGetSystemFlags(); + int doGetSystemFlags(); ::std::string doGetSystemType(); diff --git a/src/rl/hal/WeissWsg50.cpp b/src/rl/hal/WeissWsg50.cpp index a8575e79..e2818775 100644 --- a/src/rl/hal/WeissWsg50.cpp +++ b/src/rl/hal/WeissWsg50.cpp @@ -40,7 +40,7 @@ #include "WeissException.h" #include "WeissWsg50.h" -static const ::std::uint16_t CRC_TABLE_CCITT16[256] = { +static constexpr ::std::uint16_t crcTableCcitt16[256] = { 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF, 0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6, @@ -96,7 +96,7 @@ namespace rl forceMinimum(0), forceNominal(0), forceOverdrive(0), - graspingState(GRASPING_STATE_IDLE), + graspingState(static_cast<::std::uint8_t>(GraspingState::idle)), limitMinus(0), limitPlus(0), openingWidth(0), @@ -106,7 +106,7 @@ namespace rl speedMaximum(0), speedMinimum(0), stroke(0), - systemState(SYSTEM_STATE_REFERENCED) + systemState(static_cast<::std::uint32_t>(SystemState::referenced)) { } @@ -136,7 +136,7 @@ namespace rl for (::std::size_t i = 0; i < len; ++i) { ::std::uint8_t index = checksum ^ buf[i]; - checksum = CRC_TABLE_CCITT16[index] ^ (checksum >> 8); + checksum = crcTableCcitt16[index] ^ (checksum >> 8); } return checksum; @@ -150,12 +150,12 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x24; - buf[this->HEADER_SIZE] = 0x61; - buf[this->HEADER_SIZE + 1] = 0x63; - buf[this->HEADER_SIZE + 2] = 0x6B; + buf[this->headerSize] = 0x61; + buf[this->headerSize + 1] = 0x63; + buf[this->headerSize + 2] = 0x6B; - this->send(buf.data(), this->HEADER_SIZE + 3 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x24); + this->send(buf.data(), this->headerSize + 3 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x24); } void @@ -167,8 +167,8 @@ namespace rl buf[3] = 0x36; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x36); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x36); this->limitMinus = 0; this->limitPlus = 0; @@ -183,8 +183,8 @@ namespace rl buf[3] = 0x07; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x07); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x07); } void @@ -196,8 +196,8 @@ namespace rl buf[3] = 0x23; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x23); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x23); } void @@ -209,10 +209,10 @@ namespace rl buf[3] = 0x31; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 4 + 2, 0x31); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 4 + 2, 0x31); - ::std::memcpy(&this->acceleration, &buf[this->HEADER_SIZE + 2], sizeof(this->acceleration)); + ::std::memcpy(&this->acceleration, &buf[this->headerSize + 2], sizeof(this->acceleration)); this->acceleration *= ::rl::math::Constants::milli2unit; } @@ -225,12 +225,12 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x45; - buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doAutomaticUpdate << 1); - buf[this->HEADER_SIZE + 1] = Endian::hostLowByte(period); - buf[this->HEADER_SIZE + 2] = Endian::hostHighByte(period); + buf[this->headerSize] = 0x00 | (doAutomaticUpdate << 0) | (doAutomaticUpdate << 1); + buf[this->headerSize + 1] = Endian::hostLowByte(period); + buf[this->headerSize + 2] = Endian::hostHighByte(period); - this->send(buf.data(), this->HEADER_SIZE + 3 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 4 + 2, 0x45); + this->send(buf.data(), this->headerSize + 3 + 2); + this->recv(buf.data(), this->headerSize + 2 + 4 + 2, 0x45); } void @@ -242,10 +242,10 @@ namespace rl buf[3] = 0x33; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 4 + 2, 0x33); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 4 + 2, 0x33); - ::std::memcpy(&this->forceLimit, &buf[this->HEADER_SIZE + 2], sizeof(this->forceLimit)); + ::std::memcpy(&this->forceLimit, &buf[this->headerSize + 2], sizeof(this->forceLimit)); } void @@ -256,12 +256,12 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x41; - buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); - buf[this->HEADER_SIZE + 1] = Endian::hostLowByte(period); - buf[this->HEADER_SIZE + 2] = Endian::hostHighByte(period); + buf[this->headerSize] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); + buf[this->headerSize + 1] = Endian::hostLowByte(period); + buf[this->headerSize + 2] = Endian::hostHighByte(period); - this->send(buf.data(), this->HEADER_SIZE + 3 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 1 + 2, 0x41); + this->send(buf.data(), this->headerSize + 3 + 2); + this->recv(buf.data(), this->headerSize + 2 + 1 + 2, 0x41); } void @@ -272,10 +272,10 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x42; - buf[this->HEADER_SIZE] = 0x00 | doReset; + buf[this->headerSize] = 0x00 | doReset; - this->send(buf.data(), this->HEADER_SIZE + 1 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 8 + 2, 0x42); + this->send(buf.data(), this->headerSize + 1 + 2); + this->recv(buf.data(), this->headerSize + 2 + 8 + 2, 0x42); numberGraspsTotal = Endian::hostDoubleWord(Endian::hostWord(buf[11], buf[10]), Endian::hostWord(buf[9], buf[8])); numberGraspsNoPart = Endian::hostWord(buf[13], buf[12]); @@ -290,12 +290,12 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x43; - buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); - buf[this->HEADER_SIZE + 1] = Endian::hostLowByte(period); - buf[this->HEADER_SIZE + 2] = Endian::hostHighByte(period); + buf[this->headerSize] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); + buf[this->headerSize + 1] = Endian::hostLowByte(period); + buf[this->headerSize + 2] = Endian::hostHighByte(period); - this->send(buf.data(), this->HEADER_SIZE + 3 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 4 + 2, 0x43); + this->send(buf.data(), this->headerSize + 3 + 2); + this->recv(buf.data(), this->headerSize + 2 + 4 + 2, 0x43); } void @@ -307,11 +307,11 @@ namespace rl buf[3] = 0x35; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 8 + 2, 0x35); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 8 + 2, 0x35); - ::std::memcpy(&this->limitMinus, &buf[this->HEADER_SIZE + 2], sizeof(this->limitMinus)); - ::std::memcpy(&this->limitPlus, &buf[this->HEADER_SIZE + 2 + 4], sizeof(this->limitPlus)); + ::std::memcpy(&this->limitMinus, &buf[this->headerSize + 2], sizeof(this->limitMinus)); + ::std::memcpy(&this->limitPlus, &buf[this->headerSize + 2 + 4], sizeof(this->limitPlus)); this->limitMinus *= ::rl::math::Constants::milli2unit; this->limitPlus *= ::rl::math::Constants::milli2unit; @@ -325,12 +325,12 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x44; - buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); - buf[this->HEADER_SIZE + 1] = Endian::hostLowByte(period); - buf[this->HEADER_SIZE + 2] = Endian::hostHighByte(period); + buf[this->headerSize] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); + buf[this->headerSize + 1] = Endian::hostLowByte(period); + buf[this->headerSize + 2] = Endian::hostHighByte(period); - this->send(buf.data(), this->HEADER_SIZE + 3 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 4 + 2, 0x44); + this->send(buf.data(), this->headerSize + 3 + 2); + this->recv(buf.data(), this->headerSize + 2 + 4 + 2, 0x44); } void @@ -342,8 +342,8 @@ namespace rl buf[3] = 0x50; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 8 + 2, 0x50); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 8 + 2, 0x50); isWsg50 = (1 == buf[8]) ? true : false; hardwareRevision = buf[9]; @@ -360,8 +360,8 @@ namespace rl buf[3] = 0x53; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 32 + 2, 0x53); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 32 + 2, 0x53); ::std::memcpy(&this->stroke, &buf[8], sizeof(this->stroke)); ::std::memcpy(&this->speedMinimum, &buf[12], sizeof(this->speedMinimum)); @@ -387,18 +387,16 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x40; - buf[this->HEADER_SIZE] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); - buf[this->HEADER_SIZE + 1] = Endian::hostLowByte(period); - buf[this->HEADER_SIZE + 2] = Endian::hostHighByte(period); - - this->send(buf.data(), this->HEADER_SIZE + 3 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 4 + 2, 0x40); - - this->systemState = static_cast( - Endian::hostDoubleWord( - Endian::hostWord(buf[this->HEADER_SIZE + 5], buf[this->HEADER_SIZE + 4]), - Endian::hostWord(buf[this->HEADER_SIZE + 3], buf[this->HEADER_SIZE + 2]) - ) + buf[this->headerSize] = 0x00 | (doAutomaticUpdate << 0) | (doUpdateOnChange << 1); + buf[this->headerSize + 1] = Endian::hostLowByte(period); + buf[this->headerSize + 2] = Endian::hostHighByte(period); + + this->send(buf.data(), this->headerSize + 3 + 2); + this->recv(buf.data(), this->headerSize + 2 + 4 + 2, 0x40); + + this->systemState = Endian::hostDoubleWord( + Endian::hostWord(buf[this->headerSize + 5], buf[this->headerSize + 4]), + Endian::hostWord(buf[this->headerSize + 3], buf[this->headerSize + 2]) ); } @@ -411,8 +409,8 @@ namespace rl buf[3] = 0x46; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 2 + 2, 0x46); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 2 + 2, 0x46); ::std::int16_t temperature = Endian::hostWord(buf[9], buf[8]); @@ -432,11 +430,11 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x25; - ::std::memcpy(&buf[this->HEADER_SIZE], &widthMilli, sizeof(widthMilli)); - ::std::memcpy(&buf[this->HEADER_SIZE + 4], &speedMilli, sizeof(speedMilli)); + ::std::memcpy(&buf[this->headerSize], &widthMilli, sizeof(widthMilli)); + ::std::memcpy(&buf[this->headerSize + 4], &speedMilli, sizeof(speedMilli)); - this->send(buf.data(), this->HEADER_SIZE + 8 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x25); + this->send(buf.data(), this->headerSize + 8 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x25); } // Perform necessary homing motion for calibration. @@ -450,11 +448,11 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x20; - buf[this->HEADER_SIZE] = direction; + buf[this->headerSize] = direction; - this->send(buf.data(), this->HEADER_SIZE + 1 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x20); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x20); // wait for completion message + this->send(buf.data(), this->headerSize + 1 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x20); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x20); // wait for completion message } void @@ -472,8 +470,8 @@ namespace rl buf[4] |= 1; } - this->send(buf.data(), this->HEADER_SIZE + 1 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x37); + this->send(buf.data(), this->headerSize + 1 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x37); } void @@ -489,24 +487,24 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x21; - buf[this->HEADER_SIZE] = 0x00; + buf[this->headerSize] = 0x00; if (doRelativeMovement) { - buf[this->HEADER_SIZE] |= 1; + buf[this->headerSize] |= 1; } if (doStopOnBlock) { - buf[this->HEADER_SIZE] |= 2; + buf[this->headerSize] |= 2; } - ::std::memcpy(&buf[this->HEADER_SIZE + 1], &widthMilli, sizeof(widthMilli)); - ::std::memcpy(&buf[this->HEADER_SIZE + 4 + 1], &speedMilli, sizeof(speedMilli)); + ::std::memcpy(&buf[this->headerSize + 1], &widthMilli, sizeof(widthMilli)); + ::std::memcpy(&buf[this->headerSize + 4 + 1], &speedMilli, sizeof(speedMilli)); - this->send(buf.data(), this->HEADER_SIZE + 9 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x21); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x21); // wait for completion + this->send(buf.data(), this->headerSize + 9 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x21); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x21); // wait for completion } void @@ -522,11 +520,11 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x26; - ::std::memcpy(&buf[this->HEADER_SIZE], &widthMilli, sizeof(widthMilli)); - ::std::memcpy(&buf[this->HEADER_SIZE + 4], &speedMilli, sizeof(speedMilli)); + ::std::memcpy(&buf[this->headerSize], &widthMilli, sizeof(widthMilli)); + ::std::memcpy(&buf[this->headerSize + 4], &speedMilli, sizeof(speedMilli)); - this->send(buf.data(), this->HEADER_SIZE + 8 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x26); + this->send(buf.data(), this->headerSize + 8 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x26); } void @@ -540,10 +538,10 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x30; - ::std::memcpy(&buf[this->HEADER_SIZE], &accelerationMilli, sizeof(accelerationMilli)); + ::std::memcpy(&buf[this->headerSize], &accelerationMilli, sizeof(accelerationMilli)); - this->send(buf.data(), this->HEADER_SIZE + 4 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x30); + this->send(buf.data(), this->headerSize + 4 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x30); this->acceleration = acceleration; } @@ -557,10 +555,10 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x32; - ::std::memcpy(&buf[this->HEADER_SIZE], &force, sizeof(force)); + ::std::memcpy(&buf[this->headerSize], &force, sizeof(force)); - this->send(buf.data(), this->HEADER_SIZE + 4 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x32); + this->send(buf.data(), this->headerSize + 4 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x32); this->forceLimit = force; } @@ -576,11 +574,11 @@ namespace rl ::std::array<::std::uint8_t, 64> buf; buf[3] = 0x34; - ::std::memcpy(&buf[this->HEADER_SIZE], &limitMinusMilli, sizeof(limitMinusMilli)); - ::std::memcpy(&buf[this->HEADER_SIZE] + 4, &limitPlusMilli, sizeof(limitPlusMilli)); + ::std::memcpy(&buf[this->headerSize], &limitMinusMilli, sizeof(limitMinusMilli)); + ::std::memcpy(&buf[this->headerSize] + 4, &limitPlusMilli, sizeof(limitPlusMilli)); - this->send(buf.data(), this->HEADER_SIZE + 8 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x34); + this->send(buf.data(), this->headerSize + 8 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x34); this->limitMinus = limitMinus; this->limitPlus = limitPlus; @@ -595,8 +593,8 @@ namespace rl buf[3] = 0x22; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x22); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x22); } void @@ -608,8 +606,8 @@ namespace rl buf[3] = 0x38; - this->send(buf.data(), this->HEADER_SIZE + 0 + 2); - this->recv(buf.data(), this->HEADER_SIZE + 2 + 0 + 2, 0x38); + this->send(buf.data(), this->headerSize + 0 + 2); + this->recv(buf.data(), this->headerSize + 2 + 0 + 2, 0x38); } float @@ -630,8 +628,8 @@ namespace rl return this->forceLimit; } - WeissWsg50::GraspingState - WeissWsg50::getGraspingState() const + ::std::uint8_t + WeissWsg50::getGraspingStateBits() const { return this->graspingState; } @@ -648,8 +646,8 @@ namespace rl return this->speed; } - WeissWsg50::SystemState - WeissWsg50::getSystemState() const + ::std::uint32_t + WeissWsg50::getSystemStateBits() const { return this->systemState; } @@ -740,11 +738,11 @@ namespace rl switch (code) { - case WeissException::CODE_SUCCESS: + case WeissException::Code::success: break; - case WeissException::CODE_COMMAND_PENDING: + case WeissException::Code::commandPending: break; - case WeissException::CODE_AXIS_BLOCKED: + case WeissException::Code::axisBlocked: break; default: // ::std::cerr << "Debug: error: " << error << ::std::endl; @@ -778,15 +776,13 @@ namespace rl switch (buf[3]) { case 0x40: - this->systemState = static_cast( - Endian::hostDoubleWord( - Endian::hostWord(buf[11], buf[10]), - Endian::hostWord(buf[9], buf[8]) - ) + this->systemState = Endian::hostDoubleWord( + Endian::hostWord(buf[11], buf[10]), + Endian::hostWord(buf[9], buf[8]) ); break; case 0x41: - this->graspingState = static_cast(buf[8]); + this->graspingState = buf[8]; break; case 0x43: ::std::memcpy(&this->openingWidth, &buf[8], sizeof(this->openingWidth)); @@ -846,7 +842,7 @@ namespace rl buf[1] = 0xAA; buf[2] = 0xAA; - ::std::uint16_t length = len - this->HEADER_SIZE - 2; + ::std::uint16_t length = len - this->headerSize - 2; buf[4] = Endian::hostLowByte(length); buf[5] = Endian::hostHighByte(length); diff --git a/src/rl/hal/WeissWsg50.h b/src/rl/hal/WeissWsg50.h index 633be51a..647bfea0 100644 --- a/src/rl/hal/WeissWsg50.h +++ b/src/rl/hal/WeissWsg50.h @@ -53,39 +53,39 @@ namespace rl class RL_HAL_EXPORT WeissWsg50 : public CyclicDevice, public Gripper { public: - enum GraspingState + enum class GraspingState { - GRASPING_STATE_IDLE = 0, - GRASPING_STATE_GRIPPING = 1, - GRASPING_STATE_NO_PART_FOUND = 2, - GRASPING_STATE_PART_LOST = 3, - GRASPING_STATE_HOLDING = 4, - GRASPING_STATE_RELEASING = 5, - GRASPING_STATE_POSITIONING = 6, - GRASPING_STATE_ERROR = 7 + idle = 0, + gripping = 1, + noPartFound = 2, + partLost = 3, + holding = 4, + releasing = 5, + positioning = 6, + error = 7 }; - enum SystemState + enum class SystemState { - SYSTEM_STATE_SCRIPT_FAILURE = 1048576, - SYSTEM_STATE_SCRIPT_RUNNING = 524288, - SYSTEM_STATE_COMMAND_FAILURE = 262144, - SYSTEM_STATE_FINGER_FAULT = 131072, - SYSTEM_STATE_CURRENT_FAULT = 65536, - SYSTEM_STATE_POWER_FAULT = 32768, - SYSTEM_STATE_TEMPERATURE_FAULT = 16384, - SYSTEM_STATE_TEMPERATURE_WARNING = 8192, - SYSTEM_STATE_FAST_STOP = 4096, - SYSTEM_STATE_FORCE_CONTROL_MODE = 512, - SYSTEM_STATE_OVERDRIVE_MODE = 256, - SYSTEM_STATE_TARGET_POSITION_REACHED = 128, - SYSTEM_STATE_AXIS_STOPPED = 64, - SYSTEM_STATE_SOFT_LIMIT_PLUS = 32, - SYSTEM_STATE_SOFT_LIMIT_MINUS = 16, - SYSTEM_STATE_AXIS_BLOCKED_PLUS = 8, - SYSTEM_STATE_AXIS_BLOCKED_MINUS = 4, - SYSTEM_STATE_MOVING = 2, - SYSTEM_STATE_REFERENCED = 1 + referenced = 1, + moving = 2, + axisBlockedMinus = 4, + axisBlockedPlus = 8, + softLimitMinus = 16, + softLimitPlus = 32, + axisStopped = 64, + targetPositionReached = 128, + overdriveMode = 256, + forceControlMode = 512, + fastStop = 4096, + temperatureWarning = 8192, + temperatureFault = 16384, + powerFault = 32768, + currentFault = 65536, + fingerFault = 131072, + commandFailure = 262144, + scriptRunning = 524288, + scriptFailure = 1048576 }; /** @@ -206,7 +206,7 @@ namespace rl */ float getForceLimit() const; - GraspingState getGraspingState() const; + ::std::uint8_t getGraspingStateBits() const; /** * @return [m] @@ -218,7 +218,7 @@ namespace rl */ float getSpeed() const; - SystemState getSystemState() const; + ::std::uint32_t getSystemStateBits() const; void halt(); @@ -247,7 +247,7 @@ namespace rl void send(::std::uint8_t* buf, const ::std::size_t& len); - static const ::std::size_t HEADER_SIZE = 6; + static constexpr ::std::size_t headerSize = 6; float acceleration; @@ -265,7 +265,7 @@ namespace rl float forceOverdrive; - GraspingState graspingState; + ::std::uint8_t graspingState; float limitMinus; @@ -285,7 +285,7 @@ namespace rl float stroke; - SystemState systemState; + ::std::uint32_t systemState; }; } } diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index 1fd17701..1e08fd4c 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -39,9 +39,9 @@ namespace rl { Puma::Puma() : Kinematics(), - arm(ARM_LEFT), - elbow(ELBOW_ABOVE), - wrist(WRIST_NONFLIP) + arm(Arm::left), + elbow(Elbow::above), + wrist(Wrist::nonflip) { } @@ -72,9 +72,9 @@ namespace rl { assert(q.size() == this->getDof()); - int arm = this->arm; - int elbow = this->elbow; - int wrist = this->wrist; + int arm = static_cast(this->arm); + int elbow = static_cast(this->elbow); + int wrist = static_cast(this->wrist); ::rl::math::Real myeps = 1e-9; @@ -282,11 +282,11 @@ namespace rl if (myq(4) < 0) { - wrist = WRIST_FLIP; + wrist = Wrist::flip; } else { - wrist = WRIST_NONFLIP; + wrist = Wrist::nonflip; } ::rl::math::Real c2 = this->cos(myq(1)); @@ -307,28 +307,28 @@ namespace rl if (tmp < 0) { - arm = ARM_LEFT; + arm = Arm::left; if (tmp2 < 0) { - elbow = ELBOW_BELOW; + elbow = Elbow::below; } else { - elbow = ELBOW_ABOVE; + elbow = Elbow::above; } } else { - arm = ARM_RIGHT; + arm = Arm::right; if (tmp2 < 0) { - elbow = ELBOW_ABOVE; + elbow = Elbow::above; } else { - elbow = ELBOW_BELOW; + elbow = Elbow::below; } } } diff --git a/src/rl/kin/Puma.h b/src/rl/kin/Puma.h index a794c4ad..c7114eff 100644 --- a/src/rl/kin/Puma.h +++ b/src/rl/kin/Puma.h @@ -39,22 +39,22 @@ namespace rl class RL_KIN_EXPORT Puma : public Kinematics { public: - enum Arm + enum class Arm { - ARM_LEFT = -1, - ARM_RIGHT = 1 + left = -1, + right = 1 }; - enum Elbow + enum class Elbow { - ELBOW_ABOVE = 1, - ELBOW_BELOW = -1 + above = 1, + below = -1 }; - enum Wrist + enum class Wrist { - WRIST_FLIP = 1, - WRIST_NONFLIP = -1 + flip = 1, + nonflip = -1 }; Puma(); diff --git a/src/rl/kin/Rhino.cpp b/src/rl/kin/Rhino.cpp index 94025546..8f329bed 100644 --- a/src/rl/kin/Rhino.cpp +++ b/src/rl/kin/Rhino.cpp @@ -39,8 +39,8 @@ namespace rl { Rhino::Rhino() : Kinematics(), - arm(ARM_LEFT), - elbow(ELBOW_ABOVE) + arm(Arm::left), + elbow(Elbow::above) { } @@ -65,8 +65,8 @@ namespace rl { assert(q.size() == this->getDof()); - int arm = this->arm; - int elbow = this->elbow; + int arm = static_cast(this->arm); + int elbow = static_cast(this->elbow); ::rl::math::Real a1 = this->joints[0]->a; ::rl::math::Real a2 = this->joints[1]->a; @@ -203,28 +203,28 @@ namespace rl if (tmp < 0) { - arm = ARM_RIGHT; + arm = Arm::right; if (tmp2 < 0) { - elbow = ELBOW_ABOVE; + elbow = Elbow::above; } else { - elbow = ELBOW_BELOW; + elbow = Elbow::below; } } else { - arm = ARM_LEFT; + arm = Arm::left; if (tmp2 < 0) { - elbow = ELBOW_BELOW; + elbow = Elbow::below; } else { - elbow = ELBOW_ABOVE; + elbow = Elbow::above; } } } diff --git a/src/rl/kin/Rhino.h b/src/rl/kin/Rhino.h index 8803d4bf..e2cf13ee 100644 --- a/src/rl/kin/Rhino.h +++ b/src/rl/kin/Rhino.h @@ -39,16 +39,16 @@ namespace rl class RL_KIN_EXPORT Rhino : public Kinematics { public: - enum Arm + enum class Arm { - ARM_LEFT = -1, - ARM_RIGHT = 1 + left = -1, + right = 1 }; - enum Elbow + enum class Elbow { - ELBOW_ABOVE = 1, - ELBOW_BELOW = -1 + above = 1, + below = -1 }; Rhino(); diff --git a/src/rl/math/CircularVector2.h b/src/rl/math/CircularVector2.h index 377c26f9..c39b605c 100644 --- a/src/rl/math/CircularVector2.h +++ b/src/rl/math/CircularVector2.h @@ -160,8 +160,8 @@ namespace rl */ Vector2 operator()(const Real& x, const ::std::size_t& derivative = 0) const { - assert(x >= this->lower() - FUNCTION_BOUNDARY); - assert(x <= this->upper() + FUNCTION_BOUNDARY); + assert(x >= this->lower() - this->functionBoundary); + assert(x <= this->upper() + this->functionBoundary); assert(derivative <= 2 && "Circular: higher derivatives not implemented"); Real c = this->angle / this->x1; diff --git a/src/rl/math/CircularVector3.h b/src/rl/math/CircularVector3.h index ef18d1b1..dd28104c 100644 --- a/src/rl/math/CircularVector3.h +++ b/src/rl/math/CircularVector3.h @@ -166,8 +166,8 @@ namespace rl */ Vector3 operator()(const Real& x, const ::std::size_t& derivative = 0) const { - assert(x >= this->lower() - FUNCTION_BOUNDARY); - assert(x <= this->upper() + FUNCTION_BOUNDARY); + assert(x >= this->lower() - this->functionBoundary); + assert(x <= this->upper() + this->functionBoundary); assert(derivative <= 2 && "Circular: higher derivatives not implemented"); Real c = this->angle / this->x1; diff --git a/src/rl/math/Function.h b/src/rl/math/Function.h index 47527986..83dcdedf 100644 --- a/src/rl/math/Function.h +++ b/src/rl/math/Function.h @@ -86,7 +86,7 @@ namespace rl * * Some functions are only defined in the interval [lower(), upper()], * and fail to evaluate outside of - * [lower() - FUNCTION_BOUNDARY, upper() + FUNCTION_BOUNDARY]. + * [lower() - functionBoundary, upper() + functionBoundary]. * In Debug mode, this is signaled by failing asserts. * In Release mode, the function is evaluated if algebraically possible, * or will return an empty ArrayX otherwise. @@ -99,6 +99,8 @@ namespace rl virtual T operator()(const Real& x, const ::std::size_t& derivative = 0) const = 0; protected: + static constexpr Real functionBoundary = static_cast(1.0e-8); + Real x0; Real x1; @@ -106,8 +108,6 @@ namespace rl private: }; - - static const Real FUNCTION_BOUNDARY = static_cast(1.0e-8); } } diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index cf623a3e..c0ffc8d6 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -349,8 +349,8 @@ namespace rl } else { - assert(x > this->lower() - FUNCTION_BOUNDARY); - assert(x < this->upper() + FUNCTION_BOUNDARY); + assert(x > this->lower() - this->functionBoundary); + assert(x < this->upper() + this->functionBoundary); T y = this->c[this->degree()]; diff --git a/src/rl/math/PolynomialQuaternion.h b/src/rl/math/PolynomialQuaternion.h index 02704e58..48e649da 100644 --- a/src/rl/math/PolynomialQuaternion.h +++ b/src/rl/math/PolynomialQuaternion.h @@ -233,8 +233,8 @@ namespace rl Vector3 eval(const Real& x) const { - assert(x > this->lower() - FUNCTION_BOUNDARY); - assert(x < this->upper() + FUNCTION_BOUNDARY); + assert(x > this->lower() - this->functionBoundary); + assert(x < this->upper() + this->functionBoundary); Vector3 axis = Vector3::Zero(); diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 1c1686b6..25407bcf 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -1257,8 +1257,8 @@ namespace rl T operator()(const Real& x, const ::std::size_t& derivative = 0) const { - assert(x >= this->lower() - FUNCTION_BOUNDARY); - assert(x <= this->upper() + FUNCTION_BOUNDARY); + assert(x >= this->lower() - this->functionBoundary); + assert(x <= this->upper() + this->functionBoundary); assert(this->polynomials.size() > 0); Real x0 = this->lower(); diff --git a/src/rl/math/SplineQuaternion.h b/src/rl/math/SplineQuaternion.h index 73f54d2b..b6784b08 100644 --- a/src/rl/math/SplineQuaternion.h +++ b/src/rl/math/SplineQuaternion.h @@ -288,8 +288,8 @@ namespace rl Quaternion operator()(const Real& x, const ::std::size_t& derivative = 0) const { - assert(x >= this->lower() - FUNCTION_BOUNDARY); - assert(x <= this->upper() + FUNCTION_BOUNDARY); + assert(x >= this->lower() - this->functionBoundary); + assert(x <= this->upper() + this->functionBoundary); assert(this->polynomials.size() > 0); Real x0 = this->lower(); diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index 5f57c505..0908b1ef 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -34,7 +34,7 @@ namespace rl JacobianInverseKinematics::JacobianInverseKinematics(Kinematic* kinematic) : IterativeInverseKinematics(kinematic), delta(::std::numeric_limits<::rl::math::Real>::infinity()), - method(METHOD_SVD), + method(Method::svd), randDistribution(0, 1), randEngine(::std::random_device()()) { @@ -116,15 +116,15 @@ namespace rl switch (this->method) { - case METHOD_DLS: + case Method::dls: this->kinematic->calculateJacobianInverse(0, false); dq = this->kinematic->getJacobianInverse() * dx; break; - case METHOD_SVD: + case Method::svd: this->kinematic->calculateJacobianInverse(0, true); dq = this->kinematic->getJacobianInverse() * dx; break; - case METHOD_TRANSPOSE: + case Method::transpose: { ::rl::math::Vector tmp = this->kinematic->getJacobian() * this->kinematic->getJacobian().transpose() * dx; ::rl::math::Real alpha = dx.dot(tmp) / tmp.dot(tmp); diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index 3b8edc01..277e8622 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -48,11 +48,11 @@ namespace rl class RL_MDL_EXPORT JacobianInverseKinematics : public IterativeInverseKinematics { public: - enum Method + enum class Method { - METHOD_DLS, - METHOD_SVD, - METHOD_TRANSPOSE + dls, + svd, + transpose }; JacobianInverseKinematics(Kinematic* kinematic); diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index 8fd6930b..7d1705bf 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -42,7 +42,7 @@ namespace rl ::rl::math::Vector3::Constant(::std::numeric_limits<::rl::math::Real>::max()) ), goal(), - greedy(GREEDY_SPACE), + greedy(Greedy::space), model(nullptr), radius(0), range(::std::numeric_limits<::rl::math::Real>::max()), @@ -189,13 +189,13 @@ namespace rl { switch (this->greedy) { - case GREEDY_DISTANCE: + case Greedy::distance: sphere.priority = (*this->goal - *sphere.center).norm() - sphere.radius; break; - case GREEDY_SOURCE_DISTANCE: + case Greedy::sourceDistance: sphere.priority = (*this->goal - *sphere.center).norm() - sphere.radius + top.radiusSum; break; - case GREEDY_SPACE: + case Greedy::space: sphere.priority = 1 / sphere.radius; break; default: diff --git a/src/rl/plan/WorkspaceSphereExplorer.h b/src/rl/plan/WorkspaceSphereExplorer.h index f2410880..0615e700 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.h +++ b/src/rl/plan/WorkspaceSphereExplorer.h @@ -57,11 +57,11 @@ namespace rl class RL_PLAN_EXPORT WorkspaceSphereExplorer { public: - enum Greedy + enum class Greedy { - GREEDY_DISTANCE, - GREEDY_SOURCE_DISTANCE, - GREEDY_SPACE + distance, + sourceDistance, + space }; WorkspaceSphereExplorer(); diff --git a/tests/rlEetTest/rlEetTest.cpp b/tests/rlEetTest/rlEetTest.cpp index ae558b3c..4eea0c31 100644 --- a/tests/rlEetTest/rlEetTest.cpp +++ b/tests/rlEetTest/rlEetTest.cpp @@ -141,7 +141,7 @@ main(int argc, char** argv) sampler.seed(0); explorer.goal = &explorerGoal; - explorer.greedy = rl::plan::WorkspaceSphereExplorer::GREEDY_SPACE; + explorer.greedy = rl::plan::WorkspaceSphereExplorer::Greedy::space; explorer.model = &model; explorer.radius = 0.025; explorer.range = 45; diff --git a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp index 90c6d7b6..6a4e1aba 100644 --- a/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp +++ b/tests/rlInverseKinematicsMdlTest/rlInverseKinematicsMdlTest.cpp @@ -56,18 +56,18 @@ main(int argc, char** argv) std::shared_ptr jacobianSvd = std::make_shared(kinematics.get()); jacobianSvd->seed(0); - jacobianSvd->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_SVD); - ik.push_back(std::make_pair(jacobianSvd, "rl::mdl::JacobianInverseKinematics::METHOD_SVD")); + jacobianSvd->setMethod(rl::mdl::JacobianInverseKinematics::Method::svd); + ik.push_back(std::make_pair(jacobianSvd, "rl::mdl::JacobianInverseKinematics::Method::svd")); std::shared_ptr jacobianDls = std::make_shared(kinematics.get()); jacobianDls->seed(0); - jacobianDls->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_DLS); - ik.push_back(std::make_pair(jacobianDls, "rl::mdl::JacobianInverseKinematics::METHOD_DLS")); + jacobianDls->setMethod(rl::mdl::JacobianInverseKinematics::Method::dls); + ik.push_back(std::make_pair(jacobianDls, "rl::mdl::JacobianInverseKinematics::Method::dls")); std::shared_ptr jacobianTranspose = std::make_shared(kinematics.get()); jacobianTranspose->seed(0); - jacobianTranspose->setMethod(rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE); - ik.push_back(std::make_pair(jacobianTranspose, "rl::mdl::JacobianInverseKinematics::METHOD_TRANSPOSE")); + jacobianTranspose->setMethod(rl::mdl::JacobianInverseKinematics::Method::transpose); + ik.push_back(std::make_pair(jacobianTranspose, "rl::mdl::JacobianInverseKinematics::Method::transpose")); #ifdef RL_MDL_NLOPT std::shared_ptr nlopt = std::make_shared(kinematics.get()); From 50cd81e672e2157a21f769105ec19ab7069b95f9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 13 Jul 2020 00:20:13 +0200 Subject: [PATCH 400/546] Add transition variables and mark them as deprecated --- src/rl/hal/Dc1394Camera.cpp | 91 ++++++++++++++++++++++++ src/rl/hal/Dc1394Camera.h | 91 ++++++++++++++++++++++++ src/rl/hal/LeuzeRs4.cpp | 9 +++ src/rl/hal/LeuzeRs4.h | 9 +++ src/rl/hal/MitsubishiH7.cpp | 4 ++ src/rl/hal/MitsubishiH7.h | 4 ++ src/rl/hal/MitsubishiR3.cpp | 12 ++++ src/rl/hal/MitsubishiR3.h | 12 ++++ src/rl/hal/RobotiqModelC.cpp | 33 +++++++++ src/rl/hal/RobotiqModelC.h | 33 +++++++++ src/rl/hal/SchmersalLss300.cpp | 8 +++ src/rl/hal/SchmersalLss300.h | 8 +++ src/rl/hal/Serial.cpp | 59 +++++++++++++++ src/rl/hal/Serial.h | 59 +++++++++++++++ src/rl/hal/SickLms200.cpp | 25 +++++++ src/rl/hal/SickLms200.h | 25 +++++++ src/rl/hal/Socket.cpp | 10 +++ src/rl/hal/Socket.h | 10 +++ src/rl/hal/UniversalRobotsDashboard.cpp | 24 +++++++ src/rl/hal/UniversalRobotsDashboard.h | 24 +++++++ src/rl/hal/UniversalRobotsRealtime.cpp | 60 ++++++++++++++++ src/rl/hal/UniversalRobotsRealtime.h | 60 ++++++++++++++++ src/rl/hal/UniversalRobotsRtde.cpp | 58 +++++++++++++++ src/rl/hal/UniversalRobotsRtde.h | 58 +++++++++++++++ src/rl/hal/WeissException.cpp | 32 +++++++++ src/rl/hal/WeissException.h | 32 +++++++++ src/rl/hal/WeissKms40.cpp | 20 ++++++ src/rl/hal/WeissKms40.h | 20 ++++++ src/rl/hal/WeissWsg50.cpp | 29 ++++++++ src/rl/hal/WeissWsg50.h | 29 ++++++++ src/rl/kin/Puma.cpp | 9 +++ src/rl/kin/Puma.h | 9 +++ src/rl/kin/Rhino.cpp | 6 ++ src/rl/kin/Rhino.h | 6 ++ src/rl/mdl/JacobianInverseKinematics.cpp | 4 ++ src/rl/mdl/JacobianInverseKinematics.h | 4 ++ src/rl/plan/WorkspaceSphereExplorer.cpp | 4 ++ src/rl/plan/WorkspaceSphereExplorer.h | 4 ++ 38 files changed, 994 insertions(+) diff --git a/src/rl/hal/Dc1394Camera.cpp b/src/rl/hal/Dc1394Camera.cpp index 8595ef8f..690c2628 100644 --- a/src/rl/hal/Dc1394Camera.cpp +++ b/src/rl/hal/Dc1394Camera.cpp @@ -33,6 +33,97 @@ namespace rl { namespace hal { + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_MONO8; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_YUV411; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_YUV422; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_YUV444; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_RGB8; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_MONO16; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_RGB16; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_MONO16S; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_RGB16S; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_RAW8; + constexpr Dc1394Camera::ColorCoding Dc1394Camera::COLOR_CODING_RAW16; + + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_BRIGHTNESS; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_EXPOSURE; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_SHARPNESS; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_WHITE_BALANCE; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_HUE; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_SATURATION; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_GAMMA; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_SHUTTER; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_GAIN; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_IRIS; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_FOCUS; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_TEMPERATURE; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_TRIGGER; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_TRIGGER_DELAY; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_WHITE_SHADING; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_FRAME_RATE; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_ZOOM; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_PAN; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_TILT; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_OPTICAL_FILTER; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_CAPTURE_SIZE; + constexpr Dc1394Camera::Feature Dc1394Camera::FEATURE_CAPTURE_QUALITY; + + constexpr Dc1394Camera::FeatureMode Dc1394Camera::FEATURE_MODE_MANUAL; + constexpr Dc1394Camera::FeatureMode Dc1394Camera::FEATURE_MODE_AUTO; + constexpr Dc1394Camera::FeatureMode Dc1394Camera::FEATURE_MODE_ONE_PUSH_AUTO; + + constexpr Dc1394Camera::Framerate Dc1394Camera::FRAMERATE_1_875; + constexpr Dc1394Camera::Framerate Dc1394Camera::FRAMERATE_3_75; + constexpr Dc1394Camera::Framerate Dc1394Camera::FRAMERATE_7_5; + constexpr Dc1394Camera::Framerate Dc1394Camera::FRAMERATE_15; + constexpr Dc1394Camera::Framerate Dc1394Camera::FRAMERATE_30; + constexpr Dc1394Camera::Framerate Dc1394Camera::FRAMERATE_60; + constexpr Dc1394Camera::Framerate Dc1394Camera::FRAMERATE_120; + constexpr Dc1394Camera::Framerate Dc1394Camera::FRAMERATE_240; + + constexpr Dc1394Camera::IsoSpeed Dc1394Camera::ISO_SPEED_100; + constexpr Dc1394Camera::IsoSpeed Dc1394Camera::ISO_SPEED_200; + constexpr Dc1394Camera::IsoSpeed Dc1394Camera::ISO_SPEED_400; + constexpr Dc1394Camera::IsoSpeed Dc1394Camera::ISO_SPEED_800; + constexpr Dc1394Camera::IsoSpeed Dc1394Camera::ISO_SPEED_1600; + constexpr Dc1394Camera::IsoSpeed Dc1394Camera::ISO_SPEED_3200; + + constexpr Dc1394Camera::OperationMode Dc1394Camera::OPERATION_MODE_LEGACY; + constexpr Dc1394Camera::OperationMode Dc1394Camera::OPERATION_MODE_1394B; + + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_160x120_YUV444; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_320x240_YUV422; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_640x480_YUV411; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_640x480_YUV422; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_640x480_RGB8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_640x480_MONO8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_640x480_MONO16; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_800x600_YUV422; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_800x600_RGB8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_800x600_MONO8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1024x768_YUV422; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1024x768_RGB8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1024x768_MONO8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_800x600_MONO16; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1024x768_MONO16; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1280x960_YUV422; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1280x960_RGB8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1280x960_MONO8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1600x1200_YUV422; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1600x1200_RGB8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1600x1200_MONO8; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1280x960_MONO16; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_1600x1200_MONO16; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_EXIF; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_FORMAT7_0; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_FORMAT7_1; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_FORMAT7_2; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_FORMAT7_3; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_FORMAT7_4; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_FORMAT7_5; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_FORMAT7_6; + constexpr Dc1394Camera::VideoMode Dc1394Camera::VIDEO_MODE_FORMAT7_7; + Dc1394Camera::Dc1394Camera(const unsigned int& node) : Camera(), CyclicDevice(::std::chrono::nanoseconds::zero()), diff --git a/src/rl/hal/Dc1394Camera.h b/src/rl/hal/Dc1394Camera.h index f3f47da7..313ddd54 100644 --- a/src/rl/hal/Dc1394Camera.h +++ b/src/rl/hal/Dc1394Camera.h @@ -59,6 +59,18 @@ namespace rl raw16 }; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_MONO8 = ColorCoding::mono8; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_YUV411 = ColorCoding::yuv411; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_YUV422 = ColorCoding::yuv422; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_YUV444 = ColorCoding::yuv444; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_RGB8 = ColorCoding::rgb8; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_MONO16 = ColorCoding::mono16; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_RGB16 = ColorCoding::rgb16; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_MONO16S = ColorCoding::mono16; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_RGB16S = ColorCoding::rgb16s; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_RAW8 = ColorCoding::raw8; + RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_RAW16 = ColorCoding::raw16; + enum class Feature { brightness = ::DC1394_FEATURE_BRIGHTNESS, @@ -85,6 +97,29 @@ namespace rl captureQuality }; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_BRIGHTNESS = Feature::brightness; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_EXPOSURE = Feature::exposure; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_SHARPNESS = Feature::sharpness; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_WHITE_BALANCE = Feature::whiteBalance; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_HUE = Feature::hue; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_SATURATION = Feature::saturation; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_GAMMA = Feature::gamma; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_SHUTTER = Feature::shutter; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_GAIN = Feature::gain; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_IRIS = Feature::iris; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_FOCUS = Feature::focus; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_TEMPERATURE = Feature::temperature; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_TRIGGER = Feature::trigger; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_TRIGGER_DELAY = Feature::triggerDelay; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_WHITE_SHADING = Feature::whiteShading; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_FRAME_RATE = Feature::frameRate; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_ZOOM = Feature::zoom; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_PAN = Feature::pan; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_TILT = Feature::tilt; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_OPTICAL_FILTER = Feature::opticalFilter; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_CAPTURE_SIZE = Feature::captureSize; + RL_HAL_DEPRECATED static constexpr Feature FEATURE_CAPTURE_QUALITY = Feature::captureQuality; + enum class FeatureMode { manual = ::DC1394_FEATURE_MODE_MANUAL, @@ -92,6 +127,10 @@ namespace rl onePushAuto }; + RL_HAL_DEPRECATED static constexpr FeatureMode FEATURE_MODE_MANUAL = FeatureMode::manual; + RL_HAL_DEPRECATED static constexpr FeatureMode FEATURE_MODE_AUTO = FeatureMode::automatic; + RL_HAL_DEPRECATED static constexpr FeatureMode FEATURE_MODE_ONE_PUSH_AUTO = FeatureMode::onePushAuto; + enum class Framerate { f1_875 = ::DC1394_FRAMERATE_1_875, @@ -104,6 +143,15 @@ namespace rl f240 }; + RL_HAL_DEPRECATED static constexpr Framerate FRAMERATE_1_875 = Framerate::f1_875; + RL_HAL_DEPRECATED static constexpr Framerate FRAMERATE_3_75 = Framerate::f3_75; + RL_HAL_DEPRECATED static constexpr Framerate FRAMERATE_7_5 = Framerate::f7_5; + RL_HAL_DEPRECATED static constexpr Framerate FRAMERATE_15 = Framerate::f15; + RL_HAL_DEPRECATED static constexpr Framerate FRAMERATE_30 = Framerate::f30; + RL_HAL_DEPRECATED static constexpr Framerate FRAMERATE_60 = Framerate::f60; + RL_HAL_DEPRECATED static constexpr Framerate FRAMERATE_120 = Framerate::f120; + RL_HAL_DEPRECATED static constexpr Framerate FRAMERATE_240 = Framerate::f240; + enum class IsoSpeed { i100 = ::DC1394_ISO_SPEED_100, @@ -114,12 +162,22 @@ namespace rl i3200 }; + RL_HAL_DEPRECATED static constexpr IsoSpeed ISO_SPEED_100 = IsoSpeed::i100; + RL_HAL_DEPRECATED static constexpr IsoSpeed ISO_SPEED_200 = IsoSpeed::i200; + RL_HAL_DEPRECATED static constexpr IsoSpeed ISO_SPEED_400 = IsoSpeed::i400; + RL_HAL_DEPRECATED static constexpr IsoSpeed ISO_SPEED_800 = IsoSpeed::i800; + RL_HAL_DEPRECATED static constexpr IsoSpeed ISO_SPEED_1600 = IsoSpeed::i1600; + RL_HAL_DEPRECATED static constexpr IsoSpeed ISO_SPEED_3200 = IsoSpeed::i3200; + enum class OperationMode { legacy = ::DC1394_OPERATION_MODE_LEGACY, o1394b }; + RL_HAL_DEPRECATED static constexpr OperationMode OPERATION_MODE_LEGACY = OperationMode::legacy; + RL_HAL_DEPRECATED static constexpr OperationMode OPERATION_MODE_1394B = OperationMode::o1394b; + enum class VideoMode { v160x120_yuv444 = ::DC1394_VIDEO_MODE_160x120_YUV444, @@ -156,6 +214,39 @@ namespace rl format7_7 }; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_160x120_YUV444 = VideoMode::v160x120_yuv444; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_320x240_YUV422 = VideoMode::v320x240_yuv422; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_640x480_YUV411 = VideoMode::v640x480_yuv411; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_640x480_YUV422 = VideoMode::v640x480_yuv422; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_640x480_RGB8 = VideoMode::v640x480_rgb8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_640x480_MONO8 = VideoMode::v640x480_mono8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_640x480_MONO16 = VideoMode::v640x480_mono16; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_800x600_YUV422 = VideoMode::v800x600_yuv422; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_800x600_RGB8 = VideoMode::v800x600_rgb8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_800x600_MONO8 = VideoMode::v800x600_mono8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1024x768_YUV422 = VideoMode::v1024x768_yuv422; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1024x768_RGB8 = VideoMode::v1024x768_rgb8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1024x768_MONO8 = VideoMode::v1024x768_mono8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_800x600_MONO16 = VideoMode::v800x600_mono16; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1024x768_MONO16 = VideoMode::v1024x768_mono16; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1280x960_YUV422 = VideoMode::v1280x960_yuv422; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1280x960_RGB8 = VideoMode::v1280x960_rgb8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1280x960_MONO8 = VideoMode::v1280x960_mono8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1600x1200_YUV422 = VideoMode::v1600x1200_yuv422; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1600x1200_RGB8 = VideoMode::v1600x1200_rgb8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1600x1200_MONO8 = VideoMode::v1600x1200_mono8; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1280x960_MONO16 = VideoMode::v1280x960_mono16; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_1600x1200_MONO16 = VideoMode::v1600x1200_mono16; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_EXIF = VideoMode::exif; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_FORMAT7_0 = VideoMode::format7_0; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_FORMAT7_1 = VideoMode::format7_1; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_FORMAT7_2 = VideoMode::format7_2; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_FORMAT7_3 = VideoMode::format7_3; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_FORMAT7_4 = VideoMode::format7_4; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_FORMAT7_5 = VideoMode::format7_5; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_FORMAT7_6 = VideoMode::format7_6; + RL_HAL_DEPRECATED static constexpr VideoMode VIDEO_MODE_FORMAT7_7 = VideoMode::format7_7; + class Exception : public DeviceException { public: diff --git a/src/rl/hal/LeuzeRs4.cpp b/src/rl/hal/LeuzeRs4.cpp index cbac4107..c80807ef 100644 --- a/src/rl/hal/LeuzeRs4.cpp +++ b/src/rl/hal/LeuzeRs4.cpp @@ -37,6 +37,15 @@ namespace rl { namespace hal { + constexpr LeuzeRs4::BaudRate LeuzeRs4::BAUDRATE_4800BPS; + constexpr LeuzeRs4::BaudRate LeuzeRs4::BAUDRATE_9600BPS; + constexpr LeuzeRs4::BaudRate LeuzeRs4::BAUDRATE_19200BPS; + constexpr LeuzeRs4::BaudRate LeuzeRs4::BAUDRATE_38400BPS; + constexpr LeuzeRs4::BaudRate LeuzeRs4::BAUDRATE_57600BPS; + constexpr LeuzeRs4::BaudRate LeuzeRs4::BAUDRATE_115200BPS; + constexpr LeuzeRs4::BaudRate LeuzeRs4::BAUDRATE_345600BPS; + constexpr LeuzeRs4::BaudRate LeuzeRs4::BAUDRATE_625000BPS; + LeuzeRs4::LeuzeRs4( const ::std::string& filename, const BaudRate& baudRate, diff --git a/src/rl/hal/LeuzeRs4.h b/src/rl/hal/LeuzeRs4.h index 21f0595d..9abf0953 100644 --- a/src/rl/hal/LeuzeRs4.h +++ b/src/rl/hal/LeuzeRs4.h @@ -65,6 +65,15 @@ namespace rl b625000 }; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_4800BPS = BaudRate::b4800; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_9600BPS = BaudRate::b9600; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_19200BPS = BaudRate::b19200; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_38400BPS = BaudRate::b38400; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_57600BPS = BaudRate::b57600; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_115200BPS = BaudRate::b115200; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_345600BPS = BaudRate::b345600; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_625000BPS = BaudRate::b625000; + /** * @param[in] password String with 8 characters. */ diff --git a/src/rl/hal/MitsubishiH7.cpp b/src/rl/hal/MitsubishiH7.cpp index 016001f9..d49d4c61 100644 --- a/src/rl/hal/MitsubishiH7.cpp +++ b/src/rl/hal/MitsubishiH7.cpp @@ -35,6 +35,10 @@ namespace rl { namespace hal { + constexpr MitsubishiH7::Mode MitsubishiH7::MODE_JOINT; + constexpr MitsubishiH7::Mode MitsubishiH7::MODE_POSE; + constexpr MitsubishiH7::Mode MitsubishiH7::MODE_PULSE; + MitsubishiH7::MitsubishiH7( const ::std::size_t& dof, const ::std::string& addressServer, diff --git a/src/rl/hal/MitsubishiH7.h b/src/rl/hal/MitsubishiH7.h index ad56b31d..9de56014 100644 --- a/src/rl/hal/MitsubishiH7.h +++ b/src/rl/hal/MitsubishiH7.h @@ -62,6 +62,10 @@ namespace rl pulse = 2 }; + RL_HAL_DEPRECATED static constexpr Mode MODE_JOINT = Mode::joint; + RL_HAL_DEPRECATED static constexpr Mode MODE_POSE = Mode::pose; + RL_HAL_DEPRECATED static constexpr Mode MODE_PULSE = Mode::pulse; + MitsubishiH7( const ::std::size_t& dof, const ::std::string& addressServer, diff --git a/src/rl/hal/MitsubishiR3.cpp b/src/rl/hal/MitsubishiR3.cpp index 282468d7..62d71c76 100644 --- a/src/rl/hal/MitsubishiR3.cpp +++ b/src/rl/hal/MitsubishiR3.cpp @@ -35,6 +35,18 @@ namespace rl { namespace hal { + constexpr MitsubishiR3::HandSts MitsubishiR3::HANDSTS_NOTUSED; + constexpr MitsubishiR3::HandSts MitsubishiR3::HANDSTS_OPEN; + constexpr MitsubishiR3::HandSts MitsubishiR3::HANDSTS_CLOSED; + + constexpr MitsubishiR3::HandType MitsubishiR3::HANDTYPE_NOTUSED; + constexpr MitsubishiR3::HandType MitsubishiR3::HANDTYPE_SINGLE; + constexpr MitsubishiR3::HandType MitsubishiR3::HANDTYPE_DOUBLE; + + constexpr MitsubishiR3::TaskCond MitsubishiR3::TASKCOND_START; + constexpr MitsubishiR3::TaskCond MitsubishiR3::TASKCOND_ALWAYS; + constexpr MitsubishiR3::TaskCond MitsubishiR3::TASKCOND_ERROR; + MitsubishiR3::MitsubishiR3( const ::std::string& address, const unsigned short int& port diff --git a/src/rl/hal/MitsubishiR3.h b/src/rl/hal/MitsubishiR3.h index 3d33efb5..c5b1cc77 100644 --- a/src/rl/hal/MitsubishiR3.h +++ b/src/rl/hal/MitsubishiR3.h @@ -54,6 +54,10 @@ namespace rl closed = 2 }; + RL_HAL_DEPRECATED static constexpr HandSts HANDSTS_NOTUSED = HandSts::notused; + RL_HAL_DEPRECATED static constexpr HandSts HANDSTS_OPEN = HandSts::open; + RL_HAL_DEPRECATED static constexpr HandSts HANDSTS_CLOSED = HandSts::closed; + enum class HandType { notUsed = -1, @@ -63,6 +67,10 @@ namespace rl doubleSolenoid = 1 }; + RL_HAL_DEPRECATED static constexpr HandType HANDTYPE_NOTUSED = HandType::notUsed; + RL_HAL_DEPRECATED static constexpr HandType HANDTYPE_SINGLE = HandType::singleSolenoid; + RL_HAL_DEPRECATED static constexpr HandType HANDTYPE_DOUBLE = HandType::doubleSolenoid; + enum class TaskCond { /** START. */ @@ -73,6 +81,10 @@ namespace rl error }; + RL_HAL_DEPRECATED static constexpr TaskCond TASKCOND_START = TaskCond::start; + RL_HAL_DEPRECATED static constexpr TaskCond TASKCOND_ALWAYS = TaskCond::always; + RL_HAL_DEPRECATED static constexpr TaskCond TASKCOND_ERROR = TaskCond::error; + struct EditSts { /** Editing. */ diff --git a/src/rl/hal/RobotiqModelC.cpp b/src/rl/hal/RobotiqModelC.cpp index e53729d5..98623b29 100644 --- a/src/rl/hal/RobotiqModelC.cpp +++ b/src/rl/hal/RobotiqModelC.cpp @@ -34,6 +34,39 @@ namespace rl { namespace hal { + constexpr RobotiqModelC::ActionStatus RobotiqModelC::ACTION_STATUS_STOPPED; + constexpr RobotiqModelC::ActionStatus RobotiqModelC::ACTION_STATUS_GOING; + + constexpr RobotiqModelC::ActivationStatus RobotiqModelC::ACTIVATION_STATUS_RESET; + constexpr RobotiqModelC::ActivationStatus RobotiqModelC::ACTIVATION_STATUS_READY; + + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_NONE; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_UNKNOWN_1; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_UNKNOWN_2; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_UNKNOWN_3; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_UNKNOWN_4; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_NOTICE_ACTIVATION_DELAYED; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_NOTICE_MODE_DELAYED; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_NOTICE_ACTIVATION_NEEDED; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_WARNING_TEMPERATURE; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_WARNING_COMM_NOT_READY; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_WARNING_VOLTAGE; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_WARNING_AUTOMATIC_RELEASE; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_ERROR_INTERNAL; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_ERROR_ACTIVATION_FAULT; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_ERROR_MODE_FAULT; + constexpr RobotiqModelC::FaultStatus RobotiqModelC::FAULT_STATUS_ERROR_AUTOMATIC_RELEASE_COMPLETE; + + constexpr RobotiqModelC::GripperStatus RobotiqModelC::GRIPPER_STATUS_RESET; + constexpr RobotiqModelC::GripperStatus RobotiqModelC::GRIPPER_STATUS_ACTIVATING; + constexpr RobotiqModelC::GripperStatus RobotiqModelC::GRIPPER_STATUS_UNUSED; + constexpr RobotiqModelC::GripperStatus RobotiqModelC::GRIPPER_STATUS_READY; + + constexpr RobotiqModelC::ObjectStatus RobotiqModelC::OBJECT_STATUS_MOTION; + constexpr RobotiqModelC::ObjectStatus RobotiqModelC::OBJECT_STATUS_CONTACT_OPEN; + constexpr RobotiqModelC::ObjectStatus RobotiqModelC::OBJECT_STATUS_CONTACT_CLOSE; + constexpr RobotiqModelC::ObjectStatus RobotiqModelC::OBJECT_STATUS_MOTION_COMPLETE; + RobotiqModelC::RobotiqModelC(const ::std::string& filename) : CyclicDevice(::std::chrono::microseconds(5)), Gripper(), diff --git a/src/rl/hal/RobotiqModelC.h b/src/rl/hal/RobotiqModelC.h index 07d7b93a..af454f38 100644 --- a/src/rl/hal/RobotiqModelC.h +++ b/src/rl/hal/RobotiqModelC.h @@ -48,12 +48,18 @@ namespace rl going = 0x01 }; + RL_HAL_DEPRECATED static constexpr ActionStatus ACTION_STATUS_STOPPED = ActionStatus::stopped; + RL_HAL_DEPRECATED static constexpr ActionStatus ACTION_STATUS_GOING = ActionStatus::going; + enum class ActivationStatus { reset = 0x00, ready = 0x01 }; + RL_HAL_DEPRECATED static constexpr ActivationStatus ACTIVATION_STATUS_RESET = ActivationStatus::reset; + RL_HAL_DEPRECATED static constexpr ActivationStatus ACTIVATION_STATUS_READY = ActivationStatus::ready; + enum class FaultStatus { none = 0x00, @@ -74,6 +80,23 @@ namespace rl errorAutomaticReleaseComplete = 0x0f }; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_NONE = FaultStatus::none; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_UNKNOWN_1 = FaultStatus::unknown1; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_UNKNOWN_2 = FaultStatus::unknown2; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_UNKNOWN_3 = FaultStatus::unknown3; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_UNKNOWN_4 = FaultStatus::unknown4; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_NOTICE_ACTIVATION_DELAYED = FaultStatus::noticeActivationDelayed; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_NOTICE_MODE_DELAYED = FaultStatus::noticeModeDelayed; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_NOTICE_ACTIVATION_NEEDED = FaultStatus::noticeActivationNeeded; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_WARNING_TEMPERATURE = FaultStatus::warningTemperature; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_WARNING_COMM_NOT_READY = FaultStatus::warningCommNotReady; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_WARNING_VOLTAGE = FaultStatus::warningVoltage; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_WARNING_AUTOMATIC_RELEASE = FaultStatus::warningAutomaticRelease; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_ERROR_INTERNAL = FaultStatus::errorInternal; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_ERROR_ACTIVATION_FAULT = FaultStatus::errorActivationFault; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_ERROR_MODE_FAULT = FaultStatus::errorModeFault; + RL_HAL_DEPRECATED static constexpr FaultStatus FAULT_STATUS_ERROR_AUTOMATIC_RELEASE_COMPLETE = FaultStatus::errorAutomaticReleaseComplete; + enum class GripperStatus { reset = 0x00, @@ -82,6 +105,11 @@ namespace rl ready = 0x03 }; + RL_HAL_DEPRECATED static constexpr GripperStatus GRIPPER_STATUS_RESET = GripperStatus::reset; + RL_HAL_DEPRECATED static constexpr GripperStatus GRIPPER_STATUS_ACTIVATING = GripperStatus::activating; + RL_HAL_DEPRECATED static constexpr GripperStatus GRIPPER_STATUS_UNUSED = GripperStatus::unused; + RL_HAL_DEPRECATED static constexpr GripperStatus GRIPPER_STATUS_READY = GripperStatus::ready; + enum class ObjectStatus { motion = 0x00, @@ -90,6 +118,11 @@ namespace rl motionComplete = 0x03 }; + RL_HAL_DEPRECATED static constexpr ObjectStatus OBJECT_STATUS_MOTION = ObjectStatus::motion; + RL_HAL_DEPRECATED static constexpr ObjectStatus OBJECT_STATUS_CONTACT_OPEN = ObjectStatus::contactOpen; + RL_HAL_DEPRECATED static constexpr ObjectStatus OBJECT_STATUS_CONTACT_CLOSE = ObjectStatus::contactClose; + RL_HAL_DEPRECATED static constexpr ObjectStatus OBJECT_STATUS_MOTION_COMPLETE = ObjectStatus::motionComplete; + class Exception : public DeviceException { public: diff --git a/src/rl/hal/SchmersalLss300.cpp b/src/rl/hal/SchmersalLss300.cpp index 18bff07a..e2fd4d6b 100644 --- a/src/rl/hal/SchmersalLss300.cpp +++ b/src/rl/hal/SchmersalLss300.cpp @@ -37,6 +37,14 @@ namespace rl { namespace hal { + constexpr SchmersalLss300::BaudRate SchmersalLss300::BAUDRATE_9600BPS; + constexpr SchmersalLss300::BaudRate SchmersalLss300::BAUDRATE_19200BPS; + constexpr SchmersalLss300::BaudRate SchmersalLss300::BAUDRATE_38400BPS; + constexpr SchmersalLss300::BaudRate SchmersalLss300::BAUDRATE_57600BP; + + constexpr SchmersalLss300::Monitoring SchmersalLss300::MONITORING_CONTINUOUS; + constexpr SchmersalLss300::Monitoring SchmersalLss300::MONITORING_SINGLE; + SchmersalLss300::SchmersalLss300( const ::std::string& filename, const BaudRate& baudRate, diff --git a/src/rl/hal/SchmersalLss300.h b/src/rl/hal/SchmersalLss300.h index aeff25d0..1e3dd61e 100644 --- a/src/rl/hal/SchmersalLss300.h +++ b/src/rl/hal/SchmersalLss300.h @@ -65,12 +65,20 @@ namespace rl #endif }; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_9600BPS = BaudRate::b9600; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_19200BPS = BaudRate::b19200; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_38400BPS = BaudRate::b38400; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_57600BP = BaudRate::b57600; + enum class Monitoring { continuous, single }; + RL_HAL_DEPRECATED static constexpr Monitoring MONITORING_CONTINUOUS = Monitoring::continuous; + RL_HAL_DEPRECATED static constexpr Monitoring MONITORING_SINGLE = Monitoring::single; + /** * @param[in] password String with 8 characters comprising "0...9", "a...z", "A...Z", and "_". */ diff --git a/src/rl/hal/Serial.cpp b/src/rl/hal/Serial.cpp index b6c46851..e92f4ccc 100644 --- a/src/rl/hal/Serial.cpp +++ b/src/rl/hal/Serial.cpp @@ -56,6 +56,65 @@ namespace rl { namespace hal { + constexpr Serial::BaudRate Serial::BAUDRATE_110BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_300BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_600BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_1200BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_2400BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_4800BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_9600BPS; +#ifdef WIN32 + constexpr Serial::BaudRate Serial::BAUDRATE_14400BPS; +#endif // WIN32 + constexpr Serial::BaudRate Serial::BAUDRATE_19200BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_38400BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_57600BPS; +#ifdef __QNX__ + constexpr Serial::BaudRate Serial::BAUDRATE_115200BPS; +#else // __QNX__ + constexpr Serial::BaudRate Serial::BAUDRATE_115200BPS; +#endif // __QNX__ +#ifdef WIN32 + constexpr Serial::BaudRate Serial::BAUDRATE_128000BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_256000BPS; +#else // WIN32 +#ifndef __QNX__ + constexpr Serial::BaudRate Serial::BAUDRATE_230400BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_460800BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_500000BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_576000BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_921600BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_1000000BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_1152000BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_1500000BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_2000000BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_2500000BPS; +#ifdef __CYGWIN__ + constexpr Serial::BaudRate Serial::BAUDRATE_3000000BPS; +#else // __CYGWIN__ + constexpr Serial::BaudRate Serial::BAUDRATE_3000000BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_3500000BPS; + constexpr Serial::BaudRate Serial::BAUDRATE_4000000BPS; +#endif // __CYGWIN__ +#endif // __QNX__ +#endif // WIN32 + + constexpr Serial::DataBits Serial::DATABITS_5BITS; + constexpr Serial::DataBits Serial::DATABITS_6BITS; + constexpr Serial::DataBits Serial::DATABITS_7BITS; + constexpr Serial::DataBits Serial::DATABITS_8BITS; + + constexpr Serial::FlowControl Serial::FLOWCONTROL_OFF; + constexpr Serial::FlowControl Serial::FLOWCONTROL_RTSCTS; + constexpr Serial::FlowControl Serial::FLOWCONTROL_XONXOFF; + + constexpr Serial::Parity Serial::PARITY_EVENPARITY; + constexpr Serial::Parity Serial::PARITY_NOPARITY; + constexpr Serial::Parity Serial::PARITY_ODDPARITY; + + constexpr Serial::StopBits Serial::STOPBITS_1BIT; + constexpr Serial::StopBits Serial::STOPBITS_2BITS; + struct Serial::Impl { #ifdef WIN32 diff --git a/src/rl/hal/Serial.h b/src/rl/hal/Serial.h index 58844fea..602579f6 100644 --- a/src/rl/hal/Serial.h +++ b/src/rl/hal/Serial.h @@ -114,6 +114,49 @@ namespace rl #endif // WIN32 }; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_110BPS = BaudRate::b110; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_300BPS = BaudRate::b300; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_600BPS = BaudRate::b600; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_1200BPS = BaudRate::b1200; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_2400BPS = BaudRate::b2400; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_4800BPS = BaudRate::b4800; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_9600BPS = BaudRate::b9600; +#ifdef WIN32 + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_14400BPS = BaudRate::b14400; +#endif // WIN32 + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_19200BPS = BaudRate::b19200; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_38400BPS = BaudRate::b38400; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_57600BPS = BaudRate::b57600; +#ifdef __QNX__ + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_115200BPS = BaudRate::b115200; +#else // __QNX__ + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_115200BPS = BaudRate::b115200; +#endif // __QNX__ +#ifdef WIN32 + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_128000BPS = BaudRate::b128000; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_256000BPS = BaudRate::b256000; +#else // WIN32 +#ifndef __QNX__ + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_230400BPS = BaudRate::b230400; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_460800BPS = BaudRate::b460800; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_500000BPS = BaudRate::b500000; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_576000BPS = BaudRate::b576000; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_921600BPS = BaudRate::b921600; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_1000000BPS = BaudRate::b1000000; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_1152000BPS = BaudRate::b1152000; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_1500000BPS = BaudRate::b1500000; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_2000000BPS = BaudRate::b2000000; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_2500000BPS = BaudRate::b2500000; +#ifdef __CYGWIN__ + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_3000000BPS = BaudRate::b3000000; +#else // __CYGWIN__ + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_3000000BPS = BaudRate::b3000000; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_3500000BPS = BaudRate::b3500000; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_4000000BPS = BaudRate::b4000000; +#endif // __CYGWIN__ +#endif // __QNX__ +#endif // WIN32 + enum class DataBits { /** 5 data bits. */ @@ -126,6 +169,11 @@ namespace rl d8 }; + RL_HAL_DEPRECATED static constexpr DataBits DATABITS_5BITS = DataBits::d5; + RL_HAL_DEPRECATED static constexpr DataBits DATABITS_6BITS = DataBits::d6; + RL_HAL_DEPRECATED static constexpr DataBits DATABITS_7BITS = DataBits::d7; + RL_HAL_DEPRECATED static constexpr DataBits DATABITS_8BITS = DataBits::d8; + enum class FlowControl { /** No flow control. */ @@ -136,6 +184,10 @@ namespace rl xonxoff }; + RL_HAL_DEPRECATED static constexpr FlowControl FLOWCONTROL_OFF = FlowControl::off; + RL_HAL_DEPRECATED static constexpr FlowControl FLOWCONTROL_RTSCTS = FlowControl::rtscts; + RL_HAL_DEPRECATED static constexpr FlowControl FLOWCONTROL_XONXOFF = FlowControl::xonxoff; + enum class Parity { /** Even parity. */ @@ -146,6 +198,10 @@ namespace rl odd }; + RL_HAL_DEPRECATED static constexpr Parity PARITY_EVENPARITY = Parity::even; + RL_HAL_DEPRECATED static constexpr Parity PARITY_NOPARITY = Parity::none; + RL_HAL_DEPRECATED static constexpr Parity PARITY_ODDPARITY = Parity::odd; + enum class StopBits { /** 1 stop bit. */ @@ -154,6 +210,9 @@ namespace rl s2 }; + RL_HAL_DEPRECATED static constexpr StopBits STOPBITS_1BIT = StopBits::s1; + RL_HAL_DEPRECATED static constexpr StopBits STOPBITS_2BITS = StopBits::s2; + Serial( const ::std::string& filename, const BaudRate& baudRate = BaudRate::b9600, diff --git a/src/rl/hal/SickLms200.cpp b/src/rl/hal/SickLms200.cpp index fd3528fb..af1c9f71 100644 --- a/src/rl/hal/SickLms200.cpp +++ b/src/rl/hal/SickLms200.cpp @@ -38,6 +38,31 @@ namespace rl { namespace hal { + constexpr SickLms200::BaudRate SickLms200::BAUDRATE_9600BPS; + constexpr SickLms200::BaudRate SickLms200::BAUDRATE_19200BPS; +#if defined(WIN32) || defined(__QNX__) + constexpr SickLms200::BaudRate SickLms200::BAUDRATE_38400BPS; +#else // defined(WIN32) || defined(__QNX__) + constexpr SickLms200::BaudRate SickLms200::BAUDRATE_38400BPS; + constexpr SickLms200::BaudRate SickLms200::BAUDRATE_500000BPS; +#endif // defined(WIN32) || defined(__QNX__) + + constexpr SickLms200::Measuring SickLms200::MEASURING_8M; + constexpr SickLms200::Measuring SickLms200::MEASURING_16M; + constexpr SickLms200::Measuring SickLms200::MEASURING_32M; + constexpr SickLms200::Measuring SickLms200::MEASURING_80M; + constexpr SickLms200::Measuring SickLms200::MEASURING_160M; + constexpr SickLms200::Measuring SickLms200::MEASURING_320M; + + constexpr SickLms200::Monitoring SickLms200::MONITORING_CONTINUOUS; + constexpr SickLms200::Monitoring SickLms200::MONITORING_SINGLE; + + constexpr SickLms200::Variant SickLms200::VARIANT_100_25; + constexpr SickLms200::Variant SickLms200::VARIANT_100_50; + constexpr SickLms200::Variant SickLms200::VARIANT_100_100; + constexpr SickLms200::Variant SickLms200::VARIANT_180_50; + constexpr SickLms200::Variant SickLms200::VARIANT_180_100; + SickLms200::SickLms200( const ::std::string& filename, const BaudRate& baudRate, diff --git a/src/rl/hal/SickLms200.h b/src/rl/hal/SickLms200.h index 1a824f69..44d0df2b 100644 --- a/src/rl/hal/SickLms200.h +++ b/src/rl/hal/SickLms200.h @@ -61,6 +61,15 @@ namespace rl #endif // defined(WIN32) || defined(__QNX__) }; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_9600BPS = BaudRate::b9600; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_19200BPS = BaudRate::b19200; +#if defined(WIN32) || defined(__QNX__) + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_38400BPS = BaudRate::b38400; +#else // defined(WIN32) || defined(__QNX__) + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_38400BPS = BaudRate::b38400; + RL_HAL_DEPRECATED static constexpr BaudRate BAUDRATE_500000BPS = BaudRate::b500000; +#endif // defined(WIN32) || defined(__QNX__) + enum class Measuring { /** 8 meter. */ @@ -77,12 +86,22 @@ namespace rl m320 }; + RL_HAL_DEPRECATED static constexpr Measuring MEASURING_8M = Measuring::m8; + RL_HAL_DEPRECATED static constexpr Measuring MEASURING_16M = Measuring::m16; + RL_HAL_DEPRECATED static constexpr Measuring MEASURING_32M = Measuring::m32; + RL_HAL_DEPRECATED static constexpr Measuring MEASURING_80M = Measuring::m80; + RL_HAL_DEPRECATED static constexpr Measuring MEASURING_160M = Measuring::m160; + RL_HAL_DEPRECATED static constexpr Measuring MEASURING_320M = Measuring::m320; + enum class Monitoring { continuous, single }; + RL_HAL_DEPRECATED static constexpr Monitoring MONITORING_CONTINUOUS = Monitoring::continuous; + RL_HAL_DEPRECATED static constexpr Monitoring MONITORING_SINGLE = Monitoring::single; + enum class Variant { /** Angle = 100 degrees, resolution = 0.25 degrees. */ @@ -97,6 +116,12 @@ namespace rl v180_100 }; + RL_HAL_DEPRECATED static constexpr Variant VARIANT_100_25 = Variant::v100_25; + RL_HAL_DEPRECATED static constexpr Variant VARIANT_100_50 = Variant::v100_50; + RL_HAL_DEPRECATED static constexpr Variant VARIANT_100_100 = Variant::v100_100; + RL_HAL_DEPRECATED static constexpr Variant VARIANT_180_50 = Variant::v180_50; + RL_HAL_DEPRECATED static constexpr Variant VARIANT_180_100 = Variant::v180_100; + /** * @param[in] password String with 8 characters comprising "0...9", "a...z", "A...Z", and "_". */ diff --git a/src/rl/hal/Socket.cpp b/src/rl/hal/Socket.cpp index 3f4e6936..f95d8f3f 100644 --- a/src/rl/hal/Socket.cpp +++ b/src/rl/hal/Socket.cpp @@ -55,6 +55,16 @@ namespace rl { namespace hal { + constexpr Socket::Option Socket::OPTION_KEEPALIVE; + constexpr Socket::Option Socket::OPTION_MULTICAST_LOOP; + constexpr Socket::Option Socket::OPTION_MULTICAST_TTL; +#if defined(__APPLE__) || defined(__QNX__) || defined(WIN32) || defined(__CYGWIN__) + constexpr Socket::Option Socket::OPTION_NODELAY; +#else // __APPLE__ || __QNX__ || WIN32 || __CYGWIN__ + constexpr Socket::Option Socket::OPTION_NODELAY; + constexpr Socket::Option Socket::OPTION_QUICKACK; +#endif // __APPLE__ || __QNX__ || WIN32 || __CYGWIN__ + struct Socket::Address::Impl { ::sockaddr_storage addr; diff --git a/src/rl/hal/Socket.h b/src/rl/hal/Socket.h index 15a2c0c3..92b4df0b 100644 --- a/src/rl/hal/Socket.h +++ b/src/rl/hal/Socket.h @@ -96,6 +96,16 @@ namespace rl #endif // __APPLE__ || __QNX__ || WIN32 || __CYGWIN__ }; + RL_HAL_DEPRECATED static constexpr Option OPTION_KEEPALIVE = Option::keepalive; + RL_HAL_DEPRECATED static constexpr Option OPTION_MULTICAST_LOOP = Option::multicastLoop; + RL_HAL_DEPRECATED static constexpr Option OPTION_MULTICAST_TTL = Option::multicastTtl; +#if defined(__APPLE__) || defined(__QNX__) || defined(WIN32) || defined(__CYGWIN__) + RL_HAL_DEPRECATED static constexpr Option OPTION_NODELAY = Option::nodelay; +#else // __APPLE__ || __QNX__ || WIN32 || __CYGWIN__ + RL_HAL_DEPRECATED static constexpr Option OPTION_NODELAY = Option::nodelay; + RL_HAL_DEPRECATED static constexpr Option OPTION_QUICKACK = Option::quickack; +#endif // __APPLE__ || __QNX__ || WIN32 || __CYGWIN__ + Socket(const Socket& socket); virtual ~Socket(); diff --git a/src/rl/hal/UniversalRobotsDashboard.cpp b/src/rl/hal/UniversalRobotsDashboard.cpp index 67b38a4c..bc59affc 100644 --- a/src/rl/hal/UniversalRobotsDashboard.cpp +++ b/src/rl/hal/UniversalRobotsDashboard.cpp @@ -34,6 +34,30 @@ namespace rl { namespace hal { + constexpr UniversalRobotsDashboard::ProgramState UniversalRobotsDashboard::PROGRAM_STATE_STOPPED; + constexpr UniversalRobotsDashboard::ProgramState UniversalRobotsDashboard::PROGRAM_STATE_PLAYING; + constexpr UniversalRobotsDashboard::ProgramState UniversalRobotsDashboard::PROGRAM_STATE_PAUSED; + + constexpr UniversalRobotsDashboard::RobotMode UniversalRobotsDashboard::ROBOT_MODE_NO_CONTROLLER; + constexpr UniversalRobotsDashboard::RobotMode UniversalRobotsDashboard::ROBOT_MODE_DISCONNECTED; + constexpr UniversalRobotsDashboard::RobotMode UniversalRobotsDashboard::ROBOT_MODE_CONFIRM_SAFETY; + constexpr UniversalRobotsDashboard::RobotMode UniversalRobotsDashboard::ROBOT_MODE_BOOTING; + constexpr UniversalRobotsDashboard::RobotMode UniversalRobotsDashboard::ROBOT_MODE_POWER_OFF; + constexpr UniversalRobotsDashboard::RobotMode UniversalRobotsDashboard::ROBOT_MODE_POWER_ON; + constexpr UniversalRobotsDashboard::RobotMode UniversalRobotsDashboard::ROBOT_MODE_IDLE; + constexpr UniversalRobotsDashboard::RobotMode UniversalRobotsDashboard::ROBOT_MODE_BACKDRIVE; + constexpr UniversalRobotsDashboard::RobotMode UniversalRobotsDashboard::ROBOT_MODE_RUNNING; + + constexpr UniversalRobotsDashboard::SafetyMode UniversalRobotsDashboard::SAFETY_MODE_NORMAL; + constexpr UniversalRobotsDashboard::SafetyMode UniversalRobotsDashboard::SAFETY_MODE_REDUCED; + constexpr UniversalRobotsDashboard::SafetyMode UniversalRobotsDashboard::SAFETY_MODE_PROTECTIVE_STOP; + constexpr UniversalRobotsDashboard::SafetyMode UniversalRobotsDashboard::SAFETY_MODE_RECOVERY; + constexpr UniversalRobotsDashboard::SafetyMode UniversalRobotsDashboard::SAFETY_MODE_SAFEGUARD_STOP; + constexpr UniversalRobotsDashboard::SafetyMode UniversalRobotsDashboard::SAFETY_MODE_SYSTEM_EMERGENCY_STOP; + constexpr UniversalRobotsDashboard::SafetyMode UniversalRobotsDashboard::SAFETY_MODE_ROBOT_EMERGENCY_STOP; + constexpr UniversalRobotsDashboard::SafetyMode UniversalRobotsDashboard::SAFETY_MODE_VIOLATION; + constexpr UniversalRobotsDashboard::SafetyMode UniversalRobotsDashboard::SAFETY_MODE_FAULT; + UniversalRobotsDashboard::UniversalRobotsDashboard(const ::std::string& address) : Com(), socket(Socket::Tcp(Socket::Address::Ipv4(address, 29999))) diff --git a/src/rl/hal/UniversalRobotsDashboard.h b/src/rl/hal/UniversalRobotsDashboard.h index fe3e9871..1e0f35fd 100644 --- a/src/rl/hal/UniversalRobotsDashboard.h +++ b/src/rl/hal/UniversalRobotsDashboard.h @@ -50,6 +50,10 @@ namespace rl paused }; + RL_HAL_DEPRECATED static constexpr ProgramState PROGRAM_STATE_STOPPED = ProgramState::stopped; + RL_HAL_DEPRECATED static constexpr ProgramState PROGRAM_STATE_PLAYING = ProgramState::playing; + RL_HAL_DEPRECATED static constexpr ProgramState PROGRAM_STATE_PAUSED = ProgramState::paused; + enum class RobotMode { noController, @@ -63,6 +67,16 @@ namespace rl running }; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_NO_CONTROLLER = RobotMode::noController; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_DISCONNECTED = RobotMode::disconnected; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_CONFIRM_SAFETY = RobotMode::confirmSafety; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_BOOTING = RobotMode::booting; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_POWER_OFF = RobotMode::powerOff; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_POWER_ON = RobotMode::powerOn; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_IDLE = RobotMode::idle; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_BACKDRIVE = RobotMode::backdrive; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_RUNNING = RobotMode::running; + enum class SafetyMode { normal, @@ -76,6 +90,16 @@ namespace rl fault }; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_NORMAL = SafetyMode::normal; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_REDUCED = SafetyMode::reduced; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_PROTECTIVE_STOP = SafetyMode::protectiveStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_RECOVERY = SafetyMode::recovery; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_SAFEGUARD_STOP = SafetyMode::safeguardStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_SYSTEM_EMERGENCY_STOP = SafetyMode::systemEmergencyStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_ROBOT_EMERGENCY_STOP = SafetyMode::robotEmergencyStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_VIOLATION = SafetyMode::violation; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_FAULT = SafetyMode::fault; + UniversalRobotsDashboard(const ::std::string& address); virtual ~UniversalRobotsDashboard(); diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index ce66ec3b..1862fdd7 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -33,6 +33,66 @@ namespace rl { namespace hal { + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_RESET; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_SHUTTING_DOWN; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_PART_D_CALIBRATION; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_BACKDRIVE; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_POWER_OFF; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_NOT_RESPONDING; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_MOTOR_INITIALISATION; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_BOOTING; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_PART_D_CALIBRATION_ERROR; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_BOOTLOADER; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_CALIBRATION; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_VIOLATION; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_FAULT; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_RUNNING; + constexpr UniversalRobotsRealtime::JointMode UniversalRobotsRealtime::JOINT_MODE_IDLE; + + constexpr UniversalRobotsRealtime::ProgramState UniversalRobotsRealtime::PROGRAM_STATE_STOPPING; + constexpr UniversalRobotsRealtime::ProgramState UniversalRobotsRealtime::PROGRAM_STATE_STOPPED; + constexpr UniversalRobotsRealtime::ProgramState UniversalRobotsRealtime::PROGRAM_STATE_PLAYING; + constexpr UniversalRobotsRealtime::ProgramState UniversalRobotsRealtime::PROGRAM_STATE_PAUSING; + constexpr UniversalRobotsRealtime::ProgramState UniversalRobotsRealtime::PROGRAM_STATE_PAUSED; + constexpr UniversalRobotsRealtime::ProgramState UniversalRobotsRealtime::PROGRAM_STATE_RESUMING; + + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_NO_CONTROLLER; + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_DISCONNECTED; + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_CONFIRM_SAFETY; + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_BOOTING; + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_POWER_OFF; + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_POWER_ON; + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_IDLE; + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_BACKDRIVE; + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_RUNNING; + constexpr UniversalRobotsRealtime::RobotMode UniversalRobotsRealtime::ROBOT_MODE_UPDATING_FIRMWARE; + + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_NORMAL; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_REDUCED; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_PROTECTIVE_STOP; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_RECOVERY; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_SAFEGUARD_STOP; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_SYSTEM_EMERGENCY_STOP; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_ROBOT_EMERGENCY_STOP; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_VIOLATION; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_FAULT; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_VALIDATE_JOINT_ID; + constexpr UniversalRobotsRealtime::SafetyMode UniversalRobotsRealtime::SAFETY_MODE_UNDEFINED_SAFETY_MODE; + + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_NORMAL; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_REDUCED; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_PROTECTIVE_STOP; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_RECOVERY; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_SAFEGUARD_STOP; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_SYSTEM_EMERGENCY_STOP; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_ROBOT_EMERGENCY_STOP; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_VIOLATION; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_FAULT; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_VALIDATE_JOINT_ID; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_UNDEFINED_SAFETY_MODE; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_AUTOMATIC_MODE_SAFEGUARD_STOP; + constexpr UniversalRobotsRealtime::SafetyStatus UniversalRobotsRealtime::SAFETY_STATUS_SYSTEM_THREE_POSITION_ENABLING_STOP; + UniversalRobotsRealtime::UniversalRobotsRealtime(const ::std::string& address) : AxisController(6), DigitalInput(), diff --git a/src/rl/hal/UniversalRobotsRealtime.h b/src/rl/hal/UniversalRobotsRealtime.h index 18ca60a3..ca69e1e4 100644 --- a/src/rl/hal/UniversalRobotsRealtime.h +++ b/src/rl/hal/UniversalRobotsRealtime.h @@ -82,6 +82,22 @@ namespace rl idle = 255 }; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_RESET = JointMode::reset; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_SHUTTING_DOWN = JointMode::shuttingDown; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_PART_D_CALIBRATION = JointMode::partDCalibration; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_BACKDRIVE = JointMode::backdrive; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_POWER_OFF = JointMode::powerOff; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_NOT_RESPONDING = JointMode::notResponding; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_MOTOR_INITIALISATION = JointMode::motorInitialisation; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_BOOTING = JointMode::booting; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_PART_D_CALIBRATION_ERROR = JointMode::partDCalibrationError; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_BOOTLOADER = JointMode::bootloader; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_CALIBRATION = JointMode::calibration; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_VIOLATION = JointMode::violation; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_FAULT = JointMode::fault; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_RUNNING = JointMode::running; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_IDLE = JointMode::idle; + enum class ProgramState { stopping = 0, @@ -92,6 +108,13 @@ namespace rl resuming = 5 }; + RL_HAL_DEPRECATED static constexpr ProgramState PROGRAM_STATE_STOPPING = ProgramState::stopping; + RL_HAL_DEPRECATED static constexpr ProgramState PROGRAM_STATE_STOPPED = ProgramState::stopped; + RL_HAL_DEPRECATED static constexpr ProgramState PROGRAM_STATE_PLAYING = ProgramState::playing; + RL_HAL_DEPRECATED static constexpr ProgramState PROGRAM_STATE_PAUSING = ProgramState::pausing; + RL_HAL_DEPRECATED static constexpr ProgramState PROGRAM_STATE_PAUSED = ProgramState::paused; + RL_HAL_DEPRECATED static constexpr ProgramState PROGRAM_STATE_RESUMING = ProgramState::resuming; + enum class RobotMode { noController = -1, @@ -106,6 +129,17 @@ namespace rl updatingFirmware = 8 }; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_NO_CONTROLLER = RobotMode::noController; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_DISCONNECTED = RobotMode::disconnected; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_CONFIRM_SAFETY = RobotMode::confirmSafety; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_BOOTING = RobotMode::booting; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_POWER_OFF = RobotMode::powerOff; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_POWER_ON = RobotMode::powerOn; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_IDLE = RobotMode::idle; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_BACKDRIVE = RobotMode::backdrive; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_RUNNING = RobotMode::running; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_UPDATING_FIRMWARE = RobotMode::updatingFirmware; + enum class SafetyMode { normal = 1, @@ -121,6 +155,18 @@ namespace rl undefinedSafetyMode = 11 }; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_NORMAL = SafetyMode::normal; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_REDUCED = SafetyMode::reduced; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_PROTECTIVE_STOP = SafetyMode::protectiveStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_RECOVERY = SafetyMode::recovery; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_SAFEGUARD_STOP = SafetyMode::safeguardStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_SYSTEM_EMERGENCY_STOP = SafetyMode::systemEmergencyStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_ROBOT_EMERGENCY_STOP = SafetyMode::robotEmergencyStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_VIOLATION = SafetyMode::violation; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_FAULT = SafetyMode::fault; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_VALIDATE_JOINT_ID = SafetyMode::validateJointId; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_UNDEFINED_SAFETY_MODE = SafetyMode::undefinedSafetyMode; + enum class SafetyStatus { normal = 1, @@ -138,6 +184,20 @@ namespace rl systemThreePositionEnablingStop = 13 }; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_NORMAL = SafetyStatus::normal; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_REDUCED = SafetyStatus::reduced; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_PROTECTIVE_STOP = SafetyStatus::protectiveStop; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_RECOVERY = SafetyStatus::recovery; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_SAFEGUARD_STOP = SafetyStatus::safeguardStop; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_SYSTEM_EMERGENCY_STOP = SafetyStatus::systemEmergencyStop; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_ROBOT_EMERGENCY_STOP = SafetyStatus::robotEmergencyStop; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_VIOLATION = SafetyStatus::violation; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_FAULT = SafetyStatus::fault; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_VALIDATE_JOINT_ID = SafetyStatus::validateJointId; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_UNDEFINED_SAFETY_MODE = SafetyStatus::undefinedSafetyMode; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_AUTOMATIC_MODE_SAFEGUARD_STOP = SafetyStatus::automaticModeSafeguardStop; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_SYSTEM_THREE_POSITION_ENABLING_STOP = SafetyStatus::systemThreePositionEnablingStop; + UniversalRobotsRealtime(const ::std::string& address); virtual ~UniversalRobotsRealtime(); diff --git a/src/rl/hal/UniversalRobotsRtde.cpp b/src/rl/hal/UniversalRobotsRtde.cpp index 3d88569f..5fea6d65 100644 --- a/src/rl/hal/UniversalRobotsRtde.cpp +++ b/src/rl/hal/UniversalRobotsRtde.cpp @@ -36,6 +36,64 @@ namespace rl { namespace hal { + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_SHUTTING_DOWN; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_PART_D_CALIBRATION; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_BACKDRIVE; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_POWER_OFF; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_NOT_RESPONDING; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_MOTOR_INITIALISATION; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_BOOTING; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_PART_D_CALIBRATION_ERROR; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_BOOTLOADER; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_CALIBRATION; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_FAULT; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_RUNNING; + constexpr UniversalRobotsRtde::JointMode UniversalRobotsRtde::JOINT_MODE_IDLE_MODE; + + constexpr UniversalRobotsRtde::RobotMode UniversalRobotsRtde::ROBOT_MODE_DISCONNECTED; + constexpr UniversalRobotsRtde::RobotMode UniversalRobotsRtde::ROBOT_MODE_CONFIRM_SAFETY; + constexpr UniversalRobotsRtde::RobotMode UniversalRobotsRtde::ROBOT_MODE_BOOTING; + constexpr UniversalRobotsRtde::RobotMode UniversalRobotsRtde::ROBOT_MODE_POWER_OFF; + constexpr UniversalRobotsRtde::RobotMode UniversalRobotsRtde::ROBOT_MODE_POWER_ON; + constexpr UniversalRobotsRtde::RobotMode UniversalRobotsRtde::ROBOT_MODE_IDLE; + constexpr UniversalRobotsRtde::RobotMode UniversalRobotsRtde::ROBOT_MODE_BACKDRIVE; + constexpr UniversalRobotsRtde::RobotMode UniversalRobotsRtde::ROBOT_MODE_RUNNING; + constexpr UniversalRobotsRtde::RobotMode UniversalRobotsRtde::ROBOT_MODE_UPDATING_FIRMWARE; + + constexpr UniversalRobotsRtde::RobotStatus UniversalRobotsRtde::ROBOT_STATUS_POWER_ON; + constexpr UniversalRobotsRtde::RobotStatus UniversalRobotsRtde::ROBOT_STATUS_PROGRAM_RUNNING; + constexpr UniversalRobotsRtde::RobotStatus UniversalRobotsRtde::ROBOT_STATUS_TEACH_BUTTON_PRESSED; + constexpr UniversalRobotsRtde::RobotStatus UniversalRobotsRtde::ROBOT_STATUS_POWER_BUTTON_PRESSED; + + constexpr UniversalRobotsRtde::RuntimeState UniversalRobotsRtde::RUNTIME_STATE_STOPPING; + constexpr UniversalRobotsRtde::RuntimeState UniversalRobotsRtde::RUNTIME_STATE_STOPPED; + constexpr UniversalRobotsRtde::RuntimeState UniversalRobotsRtde::RUNTIME_STATE_PLAYING; + constexpr UniversalRobotsRtde::RuntimeState UniversalRobotsRtde::RUNTIME_STATE_PAUSING; + constexpr UniversalRobotsRtde::RuntimeState UniversalRobotsRtde::RUNTIME_STATE_PAUSED; + constexpr UniversalRobotsRtde::RuntimeState UniversalRobotsRtde::RUNTIME_STATE_RESUMING; + + constexpr UniversalRobotsRtde::SafetyMode UniversalRobotsRtde::SAFETY_MODE_NORMAL; + constexpr UniversalRobotsRtde::SafetyMode UniversalRobotsRtde::SAFETY_MODE_REDUCED; + constexpr UniversalRobotsRtde::SafetyMode UniversalRobotsRtde::SAFETY_MODE_PROTECTIVE_STOP; + constexpr UniversalRobotsRtde::SafetyMode UniversalRobotsRtde::SAFETY_MODE_RECOVERY; + constexpr UniversalRobotsRtde::SafetyMode UniversalRobotsRtde::SAFETY_MODE_SAFEGUARD_STOP; + constexpr UniversalRobotsRtde::SafetyMode UniversalRobotsRtde::SAFETY_MODE_SYSTEM_EMERGENCY_STOP; + constexpr UniversalRobotsRtde::SafetyMode UniversalRobotsRtde::SAFETY_MODE_ROBOT_EMERGENCY_STOP; + constexpr UniversalRobotsRtde::SafetyMode UniversalRobotsRtde::SAFETY_MODE_VIOLATION; + constexpr UniversalRobotsRtde::SafetyMode UniversalRobotsRtde::SAFETY_MODE_FAULT; + + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_NORMAL_MODE; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_REDUCED_MODE; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_PROTECTIVE_STOPPED; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_RECOVERY_MODE; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_SAFEGUARD_STOPPED; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_SYSTEM_EMERGENCY_STOPPED; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_ROBOT_EMERGENCY_STOPPED; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_EMERGENCY_STOPPED; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_VIOLATION; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_FAULT; + constexpr UniversalRobotsRtde::SafetyStatus UniversalRobotsRtde::SAFETY_STATUS_STOPPED_DUE_TO_SAFETY; + UniversalRobotsRtde::UniversalRobotsRtde(const ::std::string& address, const ::std::chrono::nanoseconds& updateRate) : AxisController(6), CyclicDevice(updateRate), diff --git a/src/rl/hal/UniversalRobotsRtde.h b/src/rl/hal/UniversalRobotsRtde.h index 0e5c9448..152ea574 100644 --- a/src/rl/hal/UniversalRobotsRtde.h +++ b/src/rl/hal/UniversalRobotsRtde.h @@ -92,6 +92,20 @@ namespace rl idleMode = 255 }; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_SHUTTING_DOWN = JointMode::shuttingDown; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_PART_D_CALIBRATION = JointMode::partDCalibration; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_BACKDRIVE = JointMode::backdrive; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_POWER_OFF = JointMode::powerOff; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_NOT_RESPONDING = JointMode::notResponding; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_MOTOR_INITIALISATION = JointMode::motorInitialisation; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_BOOTING = JointMode::booting; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_PART_D_CALIBRATION_ERROR = JointMode::partDCalibrationError; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_BOOTLOADER = JointMode::bootloader; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_CALIBRATION = JointMode::calibration; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_FAULT = JointMode::fault; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_RUNNING = JointMode::running; + RL_HAL_DEPRECATED static constexpr JointMode JOINT_MODE_IDLE_MODE = JointMode::idleMode; + enum class RobotMode { disconnected = 0, @@ -105,6 +119,16 @@ namespace rl updatingFirmware = 8 }; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_DISCONNECTED = RobotMode::disconnected; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_CONFIRM_SAFETY = RobotMode::confirmSafety; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_BOOTING = RobotMode::booting; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_POWER_OFF = RobotMode::powerOff; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_POWER_ON = RobotMode::powerOn; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_IDLE = RobotMode::idle; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_BACKDRIVE = RobotMode::backdrive; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_RUNNING = RobotMode::running; + RL_HAL_DEPRECATED static constexpr RobotMode ROBOT_MODE_UPDATING_FIRMWARE = RobotMode::updatingFirmware; + enum class RobotStatus { powerOn = 1, @@ -113,6 +137,11 @@ namespace rl powerButtonPressed = 8 }; + RL_HAL_DEPRECATED static constexpr RobotStatus ROBOT_STATUS_POWER_ON = RobotStatus::powerOn; + RL_HAL_DEPRECATED static constexpr RobotStatus ROBOT_STATUS_PROGRAM_RUNNING = RobotStatus::programRunning; + RL_HAL_DEPRECATED static constexpr RobotStatus ROBOT_STATUS_TEACH_BUTTON_PRESSED = RobotStatus::teachButtonPressed; + RL_HAL_DEPRECATED static constexpr RobotStatus ROBOT_STATUS_POWER_BUTTON_PRESSED = RobotStatus::powerButtonPressed; + enum class RuntimeState { stopping = 0, @@ -123,6 +152,13 @@ namespace rl resuming = 5 }; + RL_HAL_DEPRECATED static constexpr RuntimeState RUNTIME_STATE_STOPPING = RuntimeState::stopping; + RL_HAL_DEPRECATED static constexpr RuntimeState RUNTIME_STATE_STOPPED = RuntimeState::stopped; + RL_HAL_DEPRECATED static constexpr RuntimeState RUNTIME_STATE_PLAYING = RuntimeState::playing; + RL_HAL_DEPRECATED static constexpr RuntimeState RUNTIME_STATE_PAUSING = RuntimeState::pausing; + RL_HAL_DEPRECATED static constexpr RuntimeState RUNTIME_STATE_PAUSED = RuntimeState::paused; + RL_HAL_DEPRECATED static constexpr RuntimeState RUNTIME_STATE_RESUMING = RuntimeState::resuming; + enum class SafetyMode { normal = 1, @@ -136,6 +172,16 @@ namespace rl fault = 9 }; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_NORMAL = SafetyMode::normal; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_REDUCED = SafetyMode::reduced; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_PROTECTIVE_STOP = SafetyMode::protectiveStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_RECOVERY = SafetyMode::recovery; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_SAFEGUARD_STOP = SafetyMode::safeguardStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_SYSTEM_EMERGENCY_STOP = SafetyMode::systemEmergencyStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_ROBOT_EMERGENCY_STOP = SafetyMode::robotEmergencyStop; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_VIOLATION = SafetyMode::violation; + RL_HAL_DEPRECATED static constexpr SafetyMode SAFETY_MODE_FAULT = SafetyMode::fault; + enum class SafetyStatus { normalMode = 1, @@ -151,6 +197,18 @@ namespace rl stoppedDueToSafety = 1024 }; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_NORMAL_MODE = SafetyStatus::normalMode; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_REDUCED_MODE = SafetyStatus::reducedMode; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_PROTECTIVE_STOPPED = SafetyStatus::protectiveStopped; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_RECOVERY_MODE = SafetyStatus::recoveryMode; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_SAFEGUARD_STOPPED = SafetyStatus::safeguardStopped; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_SYSTEM_EMERGENCY_STOPPED = SafetyStatus::systemEmergencyStopped; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_ROBOT_EMERGENCY_STOPPED = SafetyStatus::robotEmergencyStopped; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_EMERGENCY_STOPPED = SafetyStatus::emergencyStopped; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_VIOLATION = SafetyStatus::violation; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_FAULT = SafetyStatus::fault; + RL_HAL_DEPRECATED static constexpr SafetyStatus SAFETY_STATUS_STOPPED_DUE_TO_SAFETY = SafetyStatus::stoppedDueToSafety; + UniversalRobotsRtde(const ::std::string& address, const ::std::chrono::nanoseconds& updateRate = ::std::chrono::milliseconds(8)); virtual ~UniversalRobotsRtde(); diff --git a/src/rl/hal/WeissException.cpp b/src/rl/hal/WeissException.cpp index 74f8369e..391893f1 100644 --- a/src/rl/hal/WeissException.cpp +++ b/src/rl/hal/WeissException.cpp @@ -30,6 +30,38 @@ namespace rl { namespace hal { + constexpr WeissException::Code WeissException::CODE_SUCCESS; + constexpr WeissException::Code WeissException::CODE_NOT_AVAILABLE; + constexpr WeissException::Code WeissException::CODE_NO_SENSOR; + constexpr WeissException::Code WeissException::CODE_NOT_INITIALIZED; + constexpr WeissException::Code WeissException::CODE_ALREADY_RUNNING; + constexpr WeissException::Code WeissException::CODE_FEATURE_NOT_SUPPORTED; + constexpr WeissException::Code WeissException::CODE_INCONSISTENT_DATA; + constexpr WeissException::Code WeissException::CODE_TIMEOUT; + constexpr WeissException::Code WeissException::CODE_READ_ERROR; + constexpr WeissException::Code WeissException::CODE_WRITE_ERROR; + constexpr WeissException::Code WeissException::CODE_INSUFFICIENT_RESOURCES; + constexpr WeissException::Code WeissException::CODE_CHECKSUM_ERROR; + constexpr WeissException::Code WeissException::CODE_NO_PARAM_EXPECTED; + constexpr WeissException::Code WeissException::CODE_NOT_ENOUGH_PARAMS; + constexpr WeissException::Code WeissException::CODE_COMMAND_UNKNOWN; + constexpr WeissException::Code WeissException::CODE_COMMAND_FORMAT_ERROR; + constexpr WeissException::Code WeissException::CODE_ACCESS_DENIED; + constexpr WeissException::Code WeissException::CODE_ALREADY_OPEN; + constexpr WeissException::Code WeissException::CODE_COMMAND_FAILED; + constexpr WeissException::Code WeissException::CODE_COMMAND_ABORTED; + constexpr WeissException::Code WeissException::CODE_INVALID_HANDLE; + constexpr WeissException::Code WeissException::CODE_NOT_FOUND; + constexpr WeissException::Code WeissException::CODE_NOT_OPEN; + constexpr WeissException::Code WeissException::CODE_IO_ERROR; + constexpr WeissException::Code WeissException::CODE_INVALID_PARAMETER; + constexpr WeissException::Code WeissException::CODE_INDEX_OUT_OF_BOUNDS; + constexpr WeissException::Code WeissException::CODE_COMMAND_PENDING; + constexpr WeissException::Code WeissException::CODE_OVERRUN; + constexpr WeissException::Code WeissException::CODE_RANGE_ERROR; + constexpr WeissException::Code WeissException::CODE_AXIS_BLOCKED; + constexpr WeissException::Code WeissException::CODE_FILE_EXISTS; + WeissException::WeissException(const Code& code) : DeviceException(""), code(code) diff --git a/src/rl/hal/WeissException.h b/src/rl/hal/WeissException.h index d7951695..fc6904be 100644 --- a/src/rl/hal/WeissException.h +++ b/src/rl/hal/WeissException.h @@ -71,6 +71,38 @@ namespace rl fileExists = 30 }; + RL_HAL_DEPRECATED static constexpr Code CODE_SUCCESS = Code::success; + RL_HAL_DEPRECATED static constexpr Code CODE_NOT_AVAILABLE = Code::notAvailable; + RL_HAL_DEPRECATED static constexpr Code CODE_NO_SENSOR = Code::noSensor; + RL_HAL_DEPRECATED static constexpr Code CODE_NOT_INITIALIZED = Code::notInitialized; + RL_HAL_DEPRECATED static constexpr Code CODE_ALREADY_RUNNING = Code::alreadyRunning; + RL_HAL_DEPRECATED static constexpr Code CODE_FEATURE_NOT_SUPPORTED = Code::featureNotSupported; + RL_HAL_DEPRECATED static constexpr Code CODE_INCONSISTENT_DATA = Code::inconsistentData; + RL_HAL_DEPRECATED static constexpr Code CODE_TIMEOUT = Code::timeout; + RL_HAL_DEPRECATED static constexpr Code CODE_READ_ERROR = Code::readError; + RL_HAL_DEPRECATED static constexpr Code CODE_WRITE_ERROR = Code::writeError; + RL_HAL_DEPRECATED static constexpr Code CODE_INSUFFICIENT_RESOURCES = Code::insufficientResources; + RL_HAL_DEPRECATED static constexpr Code CODE_CHECKSUM_ERROR = Code::checksumError; + RL_HAL_DEPRECATED static constexpr Code CODE_NO_PARAM_EXPECTED = Code::noParamExpected; + RL_HAL_DEPRECATED static constexpr Code CODE_NOT_ENOUGH_PARAMS = Code::notEnoughParams; + RL_HAL_DEPRECATED static constexpr Code CODE_COMMAND_UNKNOWN = Code::commandUnknown; + RL_HAL_DEPRECATED static constexpr Code CODE_COMMAND_FORMAT_ERROR = Code::commandFormatError; + RL_HAL_DEPRECATED static constexpr Code CODE_ACCESS_DENIED = Code::accessDenied; + RL_HAL_DEPRECATED static constexpr Code CODE_ALREADY_OPEN = Code::alreadyOpen; + RL_HAL_DEPRECATED static constexpr Code CODE_COMMAND_FAILED = Code::commandFailed; + RL_HAL_DEPRECATED static constexpr Code CODE_COMMAND_ABORTED = Code::commandAborted; + RL_HAL_DEPRECATED static constexpr Code CODE_INVALID_HANDLE = Code::invalidHandle; + RL_HAL_DEPRECATED static constexpr Code CODE_NOT_FOUND = Code::notFound; + RL_HAL_DEPRECATED static constexpr Code CODE_NOT_OPEN = Code::notOpen; + RL_HAL_DEPRECATED static constexpr Code CODE_IO_ERROR = Code::ioError; + RL_HAL_DEPRECATED static constexpr Code CODE_INVALID_PARAMETER = Code::invalidParameter; + RL_HAL_DEPRECATED static constexpr Code CODE_INDEX_OUT_OF_BOUNDS = Code::indexOutOfBounds; + RL_HAL_DEPRECATED static constexpr Code CODE_COMMAND_PENDING = Code::commandPending; + RL_HAL_DEPRECATED static constexpr Code CODE_OVERRUN = Code::overrun; + RL_HAL_DEPRECATED static constexpr Code CODE_RANGE_ERROR = Code::rangeError; + RL_HAL_DEPRECATED static constexpr Code CODE_AXIS_BLOCKED = Code::axisBlocked; + RL_HAL_DEPRECATED static constexpr Code CODE_FILE_EXISTS = Code::fileExists; + WeissException(const Code& code); virtual ~WeissException() throw(); diff --git a/src/rl/hal/WeissKms40.cpp b/src/rl/hal/WeissKms40.cpp index f92473ea..d05215de 100644 --- a/src/rl/hal/WeissKms40.cpp +++ b/src/rl/hal/WeissKms40.cpp @@ -34,6 +34,26 @@ namespace rl { namespace hal { + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_SCRIPT_FAILURE; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_CMD_FAILURE; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_POWER_FAULT; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_TEMP_FAULT; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_CALIBRATION_FAULT; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_OVERRUN_MZ; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_OVERRUN_MY; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_OVERRUN_MX; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_OVERRUN_FZ; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_OVERRUN_FY; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_OVERRUN_FX; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_TEMP_WARNING; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_CALIBRATION_EXPIRED; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_SCRIPT_RUNNING; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_DAQ_RUNNING; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_FILTER_ENABLED; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_TARA; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_STABLE; + constexpr WeissKms40::SystemState WeissKms40::SYSTEM_STATE_CALIBRATION_VALID; + WeissKms40::WeissKms40( const ::std::string& address, const unsigned short int& port, diff --git a/src/rl/hal/WeissKms40.h b/src/rl/hal/WeissKms40.h index 3b8e92f7..523ceb74 100644 --- a/src/rl/hal/WeissKms40.h +++ b/src/rl/hal/WeissKms40.h @@ -73,6 +73,26 @@ namespace rl scriptFailure = 1073741824 }; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_SCRIPT_FAILURE = SystemState::scriptFailure; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_CMD_FAILURE = SystemState::cmdFailure; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_POWER_FAULT = SystemState::powerFault; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_TEMP_FAULT = SystemState::tempFault; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_CALIBRATION_FAULT = SystemState::calibrationFault; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_OVERRUN_MZ = SystemState::overrunMx; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_OVERRUN_MY = SystemState::overrunMy; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_OVERRUN_MX = SystemState::overrunMz; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_OVERRUN_FZ = SystemState::overrunFx; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_OVERRUN_FY = SystemState::overrunFy; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_OVERRUN_FX = SystemState::overrunFz; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_TEMP_WARNING = SystemState::tempWarning; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_CALIBRATION_EXPIRED = SystemState::calibrationExpired; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_SCRIPT_RUNNING = SystemState::scriptRunning; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_DAQ_RUNNING = SystemState::daqRunning; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_FILTER_ENABLED = SystemState::filterEnabled; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_TARA = SystemState::tara; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_STABLE = SystemState::stable; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_CALIBRATION_VALID = SystemState::calibrationValid; + /** * @param[in] address TCP hostname * @param[in] port TCP port diff --git a/src/rl/hal/WeissWsg50.cpp b/src/rl/hal/WeissWsg50.cpp index e2818775..0040b3fb 100644 --- a/src/rl/hal/WeissWsg50.cpp +++ b/src/rl/hal/WeissWsg50.cpp @@ -79,6 +79,35 @@ namespace rl { namespace hal { + constexpr WeissWsg50::GraspingState WeissWsg50::GRASPING_STATE_IDLE; + constexpr WeissWsg50::GraspingState WeissWsg50::GRASPING_STATE_GRIPPING; + constexpr WeissWsg50::GraspingState WeissWsg50::GRASPING_STATE_NO_PART_FOUND; + constexpr WeissWsg50::GraspingState WeissWsg50::GRASPING_STATE_PART_LOST; + constexpr WeissWsg50::GraspingState WeissWsg50::GRASPING_STATE_HOLDING; + constexpr WeissWsg50::GraspingState WeissWsg50::GRASPING_STATE_RELEASING; + constexpr WeissWsg50::GraspingState WeissWsg50::GRASPING_STATE_POSITIONING; + constexpr WeissWsg50::GraspingState WeissWsg50::GRASPING_STATE_ERROR; + + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_SCRIPT_FAILURE; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_SCRIPT_RUNNING; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_COMMAND_FAILURE; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_FINGER_FAULT; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_CURRENT_FAULT; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_POWER_FAULT; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_TEMPERATURE_FAULT; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_TEMPERATURE_WARNING; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_FAST_STOP; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_FORCE_CONTROL_MODE; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_OVERDRIVE_MODE; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_TARGET_POSITION_REACHED; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_AXIS_STOPPED; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_SOFT_LIMIT_PLUS; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_SOFT_LIMIT_MINUS; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_AXIS_BLOCKED_PLUS; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_AXIS_BLOCKED_MINUS; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_MOVING; + constexpr WeissWsg50::SystemState WeissWsg50::SYSTEM_STATE_REFERENCED; + WeissWsg50::WeissWsg50( const ::std::string& address, const unsigned short int& port, diff --git a/src/rl/hal/WeissWsg50.h b/src/rl/hal/WeissWsg50.h index 647bfea0..d4252496 100644 --- a/src/rl/hal/WeissWsg50.h +++ b/src/rl/hal/WeissWsg50.h @@ -65,6 +65,15 @@ namespace rl error = 7 }; + RL_HAL_DEPRECATED static constexpr GraspingState GRASPING_STATE_IDLE = GraspingState::idle; + RL_HAL_DEPRECATED static constexpr GraspingState GRASPING_STATE_GRIPPING = GraspingState::gripping; + RL_HAL_DEPRECATED static constexpr GraspingState GRASPING_STATE_NO_PART_FOUND = GraspingState::noPartFound; + RL_HAL_DEPRECATED static constexpr GraspingState GRASPING_STATE_PART_LOST = GraspingState::partLost; + RL_HAL_DEPRECATED static constexpr GraspingState GRASPING_STATE_HOLDING = GraspingState::holding; + RL_HAL_DEPRECATED static constexpr GraspingState GRASPING_STATE_RELEASING = GraspingState::releasing; + RL_HAL_DEPRECATED static constexpr GraspingState GRASPING_STATE_POSITIONING = GraspingState::positioning; + RL_HAL_DEPRECATED static constexpr GraspingState GRASPING_STATE_ERROR = GraspingState::error; + enum class SystemState { referenced = 1, @@ -88,6 +97,26 @@ namespace rl scriptFailure = 1048576 }; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_SCRIPT_FAILURE = SystemState::scriptFailure; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_SCRIPT_RUNNING = SystemState::scriptRunning; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_COMMAND_FAILURE = SystemState::commandFailure; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_FINGER_FAULT = SystemState::fingerFault; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_CURRENT_FAULT = SystemState::currentFault; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_POWER_FAULT = SystemState::powerFault; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_TEMPERATURE_FAULT = SystemState::temperatureFault; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_TEMPERATURE_WARNING = SystemState::temperatureWarning; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_FAST_STOP = SystemState::fastStop; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_FORCE_CONTROL_MODE = SystemState::forceControlMode; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_OVERDRIVE_MODE = SystemState::overdriveMode; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_TARGET_POSITION_REACHED = SystemState::targetPositionReached; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_AXIS_STOPPED = SystemState::axisStopped; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_SOFT_LIMIT_PLUS = SystemState::softLimitPlus; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_SOFT_LIMIT_MINUS = SystemState::softLimitMinus; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_AXIS_BLOCKED_PLUS = SystemState::axisBlockedPlus; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_AXIS_BLOCKED_MINUS = SystemState::axisBlockedMinus; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_MOVING = SystemState::moving; + RL_HAL_DEPRECATED static constexpr SystemState SYSTEM_STATE_REFERENCED = SystemState::referenced; + /** * @param[in] address TCP hostname * @param[in] port TCP port diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index 1e08fd4c..cb879046 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -37,6 +37,15 @@ namespace rl { namespace kin { + constexpr Puma::Arm Puma::ARM_LEFT; + constexpr Puma::Arm Puma::ARM_RIGHT; + + constexpr Puma::Elbow Puma::ELBOW_ABOVE; + constexpr Puma::Elbow Puma::ELBOW_BELOW; + + constexpr Puma::Wrist Puma::WRIST_FLIP; + constexpr Puma::Wrist Puma::WRIST_NONFLIP; + Puma::Puma() : Kinematics(), arm(Arm::left), diff --git a/src/rl/kin/Puma.h b/src/rl/kin/Puma.h index c7114eff..e65f5ca4 100644 --- a/src/rl/kin/Puma.h +++ b/src/rl/kin/Puma.h @@ -45,18 +45,27 @@ namespace rl right = 1 }; + RL_KIN_DEPRECATED static constexpr Arm ARM_LEFT = Arm::left; + RL_KIN_DEPRECATED static constexpr Arm ARM_RIGHT = Arm::right; + enum class Elbow { above = 1, below = -1 }; + RL_KIN_DEPRECATED static constexpr Elbow ELBOW_ABOVE = Elbow::above; + RL_KIN_DEPRECATED static constexpr Elbow ELBOW_BELOW = Elbow::below; + enum class Wrist { flip = 1, nonflip = -1 }; + RL_KIN_DEPRECATED static constexpr Wrist WRIST_FLIP = Wrist::flip; + RL_KIN_DEPRECATED static constexpr Wrist WRIST_NONFLIP = Wrist::nonflip; + Puma(); virtual ~Puma(); diff --git a/src/rl/kin/Rhino.cpp b/src/rl/kin/Rhino.cpp index 8f329bed..f75bc0d1 100644 --- a/src/rl/kin/Rhino.cpp +++ b/src/rl/kin/Rhino.cpp @@ -37,6 +37,12 @@ namespace rl { namespace kin { + constexpr Rhino::Arm Rhino::ARM_LEFT; + constexpr Rhino::Arm Rhino::ARM_RIGHT; + + constexpr Rhino::Elbow Rhino::ELBOW_ABOVE; + constexpr Rhino::Elbow Rhino::ELBOW_BELOW; + Rhino::Rhino() : Kinematics(), arm(Arm::left), diff --git a/src/rl/kin/Rhino.h b/src/rl/kin/Rhino.h index e2cf13ee..c8badf62 100644 --- a/src/rl/kin/Rhino.h +++ b/src/rl/kin/Rhino.h @@ -45,12 +45,18 @@ namespace rl right = 1 }; + RL_KIN_DEPRECATED static constexpr Arm ARM_LEFT = Arm::left; + RL_KIN_DEPRECATED static constexpr Arm ARM_RIGHT = Arm::right; + enum class Elbow { above = 1, below = -1 }; + RL_KIN_DEPRECATED static constexpr Elbow ELBOW_ABOVE = Elbow::above; + RL_KIN_DEPRECATED static constexpr Elbow ELBOW_BELOW = Elbow::below; + Rhino(); virtual ~Rhino(); diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index 0908b1ef..040302da 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -31,6 +31,10 @@ namespace rl { namespace mdl { + constexpr JacobianInverseKinematics::Method JacobianInverseKinematics::METHOD_DLS; + constexpr JacobianInverseKinematics::Method JacobianInverseKinematics::METHOD_SVD; + constexpr JacobianInverseKinematics::Method JacobianInverseKinematics::METHOD_TRANSPOSE; + JacobianInverseKinematics::JacobianInverseKinematics(Kinematic* kinematic) : IterativeInverseKinematics(kinematic), delta(::std::numeric_limits<::rl::math::Real>::infinity()), diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index 277e8622..b053e23b 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -55,6 +55,10 @@ namespace rl transpose }; + RL_MDL_DEPRECATED static constexpr Method METHOD_DLS = Method::dls; + RL_MDL_DEPRECATED static constexpr Method METHOD_SVD = Method::svd; + RL_MDL_DEPRECATED static constexpr Method METHOD_TRANSPOSE = Method::transpose; + JacobianInverseKinematics(Kinematic* kinematic); virtual ~JacobianInverseKinematics(); diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index 7d1705bf..32ef7edf 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -36,6 +36,10 @@ namespace rl { namespace plan { + constexpr WorkspaceSphereExplorer::Greedy WorkspaceSphereExplorer::GREEDY_DISTANCE; + constexpr WorkspaceSphereExplorer::Greedy WorkspaceSphereExplorer::GREEDY_SOURCE_DISTANCE; + constexpr WorkspaceSphereExplorer::Greedy WorkspaceSphereExplorer::GREEDY_SPACE; + WorkspaceSphereExplorer::WorkspaceSphereExplorer() : boundingBox( ::rl::math::Vector3::Constant(-::std::numeric_limits<::rl::math::Real>::max()), diff --git a/src/rl/plan/WorkspaceSphereExplorer.h b/src/rl/plan/WorkspaceSphereExplorer.h index 0615e700..2337da96 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.h +++ b/src/rl/plan/WorkspaceSphereExplorer.h @@ -64,6 +64,10 @@ namespace rl space }; + RL_PLAN_DEPRECATED static constexpr Greedy GREEDY_DISTANCE = Greedy::distance; + RL_PLAN_DEPRECATED static constexpr Greedy GREEDY_SOURCE_DISTANCE = Greedy::sourceDistance; + RL_PLAN_DEPRECATED static constexpr Greedy GREEDY_SPACE = Greedy::space; + WorkspaceSphereExplorer(); virtual ~WorkspaceSphereExplorer(); From 92d8e764c9a1970671d0b36389da9d41afa24b33 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 12 Jul 2020 22:47:06 +0200 Subject: [PATCH 401/546] Use vector instead of variable length array --- demos/rlCameraDemo/rlCameraDemo.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/demos/rlCameraDemo/rlCameraDemo.cpp b/demos/rlCameraDemo/rlCameraDemo.cpp index d93a742d..6937f928 100644 --- a/demos/rlCameraDemo/rlCameraDemo.cpp +++ b/demos/rlCameraDemo/rlCameraDemo.cpp @@ -48,19 +48,19 @@ main(int argc, char** argv) dc1394.setFeatureMode(rl::hal::Dc1394Camera::Feature::shutter, rl::hal::Dc1394Camera::FeatureMode::automatic); dc1394.setFeatureMode(rl::hal::Dc1394Camera::Feature::whiteBalance, rl::hal::Dc1394Camera::FeatureMode::automatic); - unsigned char image[dc1394.getSize()]; + std::vector image(dc1394.getSize()); for (unsigned int i = 0; i < 1; ++i) { dc1394.step(); - dc1394.grab(image); + dc1394.grab(image.data()); std::stringstream filename; filename << "image" << i << ".pgm"; FILE* imagefile = fopen(filename.str().c_str(), "w"); fprintf(imagefile, "P6\n%u %u\n255\n", dc1394.getWidth(), dc1394.getHeight()); - fwrite(image, 1, dc1394.getSize(), imagefile); + fwrite(image.data(), 1, image.size(), imagefile); fclose(imagefile); } From 643d578f79e8ca3be0cafb3272abab375bf63165 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 12 Jul 2020 22:48:32 +0200 Subject: [PATCH 402/546] Remove extra semicolon --- demos/rlCoachKin/SoGradientBackground.cpp | 2 +- demos/rlCoachMdl/SoGradientBackground.cpp | 2 +- demos/rlCollisionDemo/SoGradientBackground.cpp | 2 +- demos/rlPlanDemo/SoGradientBackground.cpp | 2 +- demos/rlSimulator/SoGradientBackground.cpp | 2 +- extras/wrlview/SoGradientBackground.cpp | 2 +- src/rl/hal/WeissException.h | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/demos/rlCoachKin/SoGradientBackground.cpp b/demos/rlCoachKin/SoGradientBackground.cpp index bd1d852f..b50675d2 100644 --- a/demos/rlCoachKin/SoGradientBackground.cpp +++ b/demos/rlCoachKin/SoGradientBackground.cpp @@ -38,7 +38,7 @@ #include "SoGradientBackground.h" -SO_NODE_SOURCE(SoGradientBackground); +SO_NODE_SOURCE(SoGradientBackground) SoGradientBackground::SoGradientBackground() : SoNode(), diff --git a/demos/rlCoachMdl/SoGradientBackground.cpp b/demos/rlCoachMdl/SoGradientBackground.cpp index bd1d852f..b50675d2 100644 --- a/demos/rlCoachMdl/SoGradientBackground.cpp +++ b/demos/rlCoachMdl/SoGradientBackground.cpp @@ -38,7 +38,7 @@ #include "SoGradientBackground.h" -SO_NODE_SOURCE(SoGradientBackground); +SO_NODE_SOURCE(SoGradientBackground) SoGradientBackground::SoGradientBackground() : SoNode(), diff --git a/demos/rlCollisionDemo/SoGradientBackground.cpp b/demos/rlCollisionDemo/SoGradientBackground.cpp index bd1d852f..b50675d2 100644 --- a/demos/rlCollisionDemo/SoGradientBackground.cpp +++ b/demos/rlCollisionDemo/SoGradientBackground.cpp @@ -38,7 +38,7 @@ #include "SoGradientBackground.h" -SO_NODE_SOURCE(SoGradientBackground); +SO_NODE_SOURCE(SoGradientBackground) SoGradientBackground::SoGradientBackground() : SoNode(), diff --git a/demos/rlPlanDemo/SoGradientBackground.cpp b/demos/rlPlanDemo/SoGradientBackground.cpp index bd1d852f..b50675d2 100644 --- a/demos/rlPlanDemo/SoGradientBackground.cpp +++ b/demos/rlPlanDemo/SoGradientBackground.cpp @@ -38,7 +38,7 @@ #include "SoGradientBackground.h" -SO_NODE_SOURCE(SoGradientBackground); +SO_NODE_SOURCE(SoGradientBackground) SoGradientBackground::SoGradientBackground() : SoNode(), diff --git a/demos/rlSimulator/SoGradientBackground.cpp b/demos/rlSimulator/SoGradientBackground.cpp index bd1d852f..b50675d2 100644 --- a/demos/rlSimulator/SoGradientBackground.cpp +++ b/demos/rlSimulator/SoGradientBackground.cpp @@ -38,7 +38,7 @@ #include "SoGradientBackground.h" -SO_NODE_SOURCE(SoGradientBackground); +SO_NODE_SOURCE(SoGradientBackground) SoGradientBackground::SoGradientBackground() : SoNode(), diff --git a/extras/wrlview/SoGradientBackground.cpp b/extras/wrlview/SoGradientBackground.cpp index bd1d852f..b50675d2 100644 --- a/extras/wrlview/SoGradientBackground.cpp +++ b/extras/wrlview/SoGradientBackground.cpp @@ -38,7 +38,7 @@ #include "SoGradientBackground.h" -SO_NODE_SOURCE(SoGradientBackground); +SO_NODE_SOURCE(SoGradientBackground) SoGradientBackground::SoGradientBackground() : SoNode(), diff --git a/src/rl/hal/WeissException.h b/src/rl/hal/WeissException.h index fc6904be..2ac92138 100644 --- a/src/rl/hal/WeissException.h +++ b/src/rl/hal/WeissException.h @@ -116,7 +116,7 @@ namespace rl private: Code code; }; - }; + } } #endif // RL_HAL_WEISSEXCEPTION_H From 3364695a9b944c609a93d53df79fae69d78f0478 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 16 Jul 2020 18:10:14 +0200 Subject: [PATCH 403/546] Remove unused variables --- src/rl/math/Spline.h | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/rl/math/Spline.h b/src/rl/math/Spline.h index 25407bcf..d8a0db46 100644 --- a/src/rl/math/Spline.h +++ b/src/rl/math/Spline.h @@ -113,7 +113,6 @@ namespace rl assert(TypeTraits::size(y[0]) == TypeTraits::size(yd1)); ::std::size_t n = y.size(); - ::std::size_t dim = TypeTraits::size(y[0]); const Container2& a = y; Container1 h(n - 1); @@ -355,7 +354,6 @@ namespace rl parabolicIntervalNext = ::std::min(parabolicIntervalNext, parabolicIntervalNextNext); Real deltaXPrev = x[i] - x[i - 1]; Real deltaXNext = x[i + 1] - x[i]; - Real deltaXNextNext = x[i + 2] - x[i + 1]; Real linearInterval = deltaXNext - (parabolicIntervalPrev/2) - (parabolicIntervalNext/2); assert(deltaXPrev > parabolicIntervalPrev && deltaXNext > parabolicIntervalNext); T ydPrev = (y[i] - y[i - 1]) / deltaXPrev; @@ -502,7 +500,6 @@ namespace rl quarticIntervalNext = ::std::min(quarticIntervalNext, quarticIntervalNextNext); Real deltaXPrev = x[i] - x[i - 1]; Real deltaXNext = x[i + 1] - x[i]; - Real deltaXNextNext = x[i + 2] - x[i + 1]; Real linearInterval = deltaXNext - (quarticIntervalPrev/2) - (quarticIntervalNext/2); assert(deltaXPrev > quarticIntervalPrev && deltaXNext > quarticIntervalNext); T ydPrev = (y[i] - y[i - 1]) / deltaXPrev; @@ -649,7 +646,6 @@ namespace rl sexticIntervalNext = ::std::min(sexticIntervalNext, sexticIntervalNextNext); Real deltaXPrev = x[i] - x[i - 1]; Real deltaXNext = x[i + 1] - x[i]; - Real deltaXNextNext = x[i + 2] - x[i + 1]; Real linearInterval = deltaXNext - (sexticIntervalPrev/2) - (sexticIntervalNext/2); assert(deltaXPrev > sexticIntervalPrev && deltaXNext > sexticIntervalNext); T ydPrev = (y[i] - y[i - 1]) / deltaXPrev; From 9ea16f834d3b31d4eed28f6a338dd8060e271610 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 22 Jul 2020 17:44:22 +0200 Subject: [PATCH 404/546] Update loop variable --- src/rl/hal/RobotiqModelC.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/hal/RobotiqModelC.cpp b/src/rl/hal/RobotiqModelC.cpp index 98623b29..66f59b2d 100644 --- a/src/rl/hal/RobotiqModelC.cpp +++ b/src/rl/hal/RobotiqModelC.cpp @@ -107,7 +107,7 @@ namespace rl { checksum ^= buf[i]; - for (::std::size_t i = 8; i != 0; --i) + for (::std::size_t j = 0; j < 8; ++j) { if (checksum & 0x0001) { From d2c3c49ba89909e4563d618a51f1bf5bca531659 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 22 Jul 2020 18:00:27 +0200 Subject: [PATCH 405/546] Update documentation --- src/rl/mainpage.dox | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/rl/mainpage.dox b/src/rl/mainpage.dox index 290fb761..036a6ef7 100644 --- a/src/rl/mainpage.dox +++ b/src/rl/mainpage.dox @@ -48,7 +48,8 @@ For first time users, please have a look at our = 1.46)") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "boost-devel >= 1.46") endif() -if(Boost_REGEX_LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libboost-regex-dev (>= 1.46)") -endif() -if(Boost_SYSTEM_LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libboost-system-dev (>= 1.46)") -endif() -if(Boost_THREAD_LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libboost-thread-dev (>= 1.46)") -endif() if(BULLET_INCLUDE_DIRS AND BULLET_BULLETCOLLISION_LIBRARY_RELEASE AND BULLET_BULLETDYNAMICS_LIBRARY_RELEASE AND BULLET_BULLETSOFTBODY_LIBRARY_RELEASE AND BULLET_LINEARMATH_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libbullet-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "bullet-devel") @@ -202,11 +193,8 @@ if(FCL_INCLUDE_DIRS AND FCL_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libfcl-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "fcl-devel") endif() -if(libdc1394_V1_INCLUDE_DIRS AND libdc1394_V1_LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libdc1394-13-dev") -endif() -if(libdc1394_V2_INCLUDE_DIRS AND libdc1394_V2_LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libdc1394-22-dev") +if(libdc1394_INCLUDE_DIRS AND libdc1394_LIBRARY_RELEASE) + list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libdc1394-dev | libdc1394-22-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libdc1394-devel") endif() if(LIBLZMA_INCLUDE_DIRS AND LIBLZMA_LIBRARY_RELEASE) @@ -221,19 +209,15 @@ if(LIBXSLT_INCLUDE_DIRS AND LIBXSLT_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libxslt1-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libxslt-devel") endif() -if(NLopt_INCLUDE_DIRS AND NLopt_LIBRARY_RELEASE) +if(NLOPT_INCLUDE_DIRS AND NLOPT_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libnlopt-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "NLopt-devel") endif() if(ODE_INCLUDE_DIRS AND ODE_LIBRARY_RELEASE) - if(ODE_USE_DOUBLE_PRECISION) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libode-dev") - else() - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libode-sp-dev") - endif() + list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libode-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "ode-devel") endif() -if(zlib_INCLUDE_DIRS AND zlib_LIBRARY_RELEASE) +if(ZLIB_INCLUDE_DIRS AND ZLIB_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "zlib1g-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "zlib-devel") endif() From cba76ed3e54676d430205a0dfdf03ce33ed3850c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 26 Jul 2020 16:27:40 +0200 Subject: [PATCH 407/546] Support scaling in URDF meshes --- src/rl/sg/UrdfFactory.cpp | 24 ++++++++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index f20de20f..336ddcb5 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -38,6 +38,7 @@ #include #include #include +#include #include #include #include @@ -350,6 +351,29 @@ ::std::cout << "\tmesh filename: " << meshFilename << ::std::endl; { ::SoVRMLIndexedFaceSet* vrmlIndexedFaceSet = static_cast<::SoVRMLIndexedFaceSet*>(vrmlShape->geometry.getValue()); vrmlIndexedFaceSet->convex.setValue(false); + + ::SoVRMLCoordinate* vrmlCoordinate = static_cast<::SoVRMLCoordinate*>(vrmlIndexedFaceSet->coord.getValue()); + + if (!shapes[k].getProperty("scale").empty()) + { + ::SbVec3f scale(1.0f, 1.0f, 1.0f); + + ::std::vector<::std::string> scales; + ::std::string scaleProperty = shapes[k].getProperty("scale"); + ::boost::split(scales, scaleProperty, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); +::std::cout << "\tscale: " << scales[0] << " " << scales[1] << " " << scales[2] << ::std::endl; + scale.setValue(::std::stof(scales[0]), ::std::stof(scales[1]), ::std::stof(scales[2])); + + for (int m = 0; m < vrmlCoordinate->point.getNum(); ++m) + { + vrmlCoordinate->point.set1Value( + m, + vrmlCoordinate->point[m][0] * scale[0], + vrmlCoordinate->point[m][1] * scale[1], + vrmlCoordinate->point[m][2] * scale[2] + ); + } + } } } From c1f3094576efbf6fe1e2803b80c474bca29579d4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 19 Oct 2020 17:21:59 +0200 Subject: [PATCH 408/546] Skip Iconv version info on older CMake versions --- cmake/FindIconv.cmake | 28 +++++++++++++++------------- 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/cmake/FindIconv.cmake b/cmake/FindIconv.cmake index 75d604a8..21798458 100644 --- a/cmake/FindIconv.cmake +++ b/cmake/FindIconv.cmake @@ -39,20 +39,22 @@ if(Iconv_INCLUDE_DIRS AND NOT Iconv_LIBRARIES) endif() endif() -if(Iconv_INCLUDE_DIRS AND EXISTS "${Iconv_INCLUDE_DIRS}/iconv.h") - file(STRINGS "${Iconv_INCLUDE_DIRS}/iconv.h" _Iconv_VERSION_DEFINE REGEX "#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F][0-9A-F][0-9A-F].*") - string(REGEX REPLACE "#define[\t ]+_LIBICONV_VERSION[\t ]+0x([0-9A-F][0-9A-F])[0-9A-F][0-9A-F].*" "\\1" _Iconv_VERSION_MAJOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") - string(REGEX REPLACE "#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F]([0-9A-F][0-9A-F]).*" "\\1" _Iconv_VERSION_MINOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") - - if(NOT _Iconv_VERSION_MAJOR_HEXADECIMAL STREQUAL "" AND NOT _Iconv_VERSION_MINOR_HEXADECIMAL STREQUAL "") - math(EXPR Iconv_VERSION_MAJOR "0x${_Iconv_VERSION_MAJOR_HEXADECIMAL}" OUTPUT_FORMAT DECIMAL) - math(EXPR Iconv_VERSION_MINOR "0x${_Iconv_VERSION_MINOR_HEXADECIMAL}" OUTPUT_FORMAT DECIMAL) - set(Iconv_VERSION "${Iconv_VERSION_MAJOR}.${Iconv_VERSION_MINOR}") +if(NOT CMAKE_VERSION VERSION_LESS 3.13) + if(Iconv_INCLUDE_DIRS AND EXISTS "${Iconv_INCLUDE_DIRS}/iconv.h") + file(STRINGS "${Iconv_INCLUDE_DIRS}/iconv.h" _Iconv_VERSION_DEFINE REGEX "#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F][0-9A-F][0-9A-F].*") + string(REGEX REPLACE "#define[\t ]+_LIBICONV_VERSION[\t ]+0x([0-9A-F][0-9A-F])[0-9A-F][0-9A-F].*" "\\1" _Iconv_VERSION_MAJOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") + string(REGEX REPLACE "#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F]([0-9A-F][0-9A-F]).*" "\\1" _Iconv_VERSION_MINOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") + + if(NOT _Iconv_VERSION_MAJOR_HEXADECIMAL STREQUAL "" AND NOT _Iconv_VERSION_MINOR_HEXADECIMAL STREQUAL "") + math(EXPR Iconv_VERSION_MAJOR "0x${_Iconv_VERSION_MAJOR_HEXADECIMAL}" OUTPUT_FORMAT DECIMAL) + math(EXPR Iconv_VERSION_MINOR "0x${_Iconv_VERSION_MINOR_HEXADECIMAL}" OUTPUT_FORMAT DECIMAL) + set(Iconv_VERSION "${Iconv_VERSION_MAJOR}.${Iconv_VERSION_MINOR}") + endif() + + unset(_Iconv_VERSION_DEFINE) + unset(_Iconv_VERSION_MAJOR_HEXADECIMAL) + unset(_Iconv_VERSION_MINOR_HEXADECIMAL) endif() - - unset(_Iconv_VERSION_DEFINE) - unset(_Iconv_VERSION_MAJOR_HEXADECIMAL) - unset(_Iconv_VERSION_MINOR_HEXADECIMAL) endif() if(Iconv_IS_BUILT_IN) From e20b03a8e97b6619d137b07ea134b1be3862e674 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 13 Nov 2020 15:43:39 +0100 Subject: [PATCH 409/546] Add libccd and fcl ExternalProject --- 3rdparty/CMakeLists.txt | 4 ++++ 3rdparty/fcl/CMakeLists.txt | 15 +++++++++++++++ 3rdparty/libccd/CMakeLists.txt | 16 ++++++++++++++++ 3 files changed, 35 insertions(+) create mode 100644 3rdparty/fcl/CMakeLists.txt create mode 100644 3rdparty/libccd/CMakeLists.txt diff --git a/3rdparty/CMakeLists.txt b/3rdparty/CMakeLists.txt index 39802d03..604c49fc 100644 --- a/3rdparty/CMakeLists.txt +++ b/3rdparty/CMakeLists.txt @@ -36,6 +36,7 @@ add_subdirectory(atidaq) add_subdirectory(boost) add_subdirectory(bullet) add_subdirectory(eigen) +add_subdirectory(libccd) add_subdirectory(libiconv) add_subdirectory(nlopt) add_subdirectory(ode) @@ -45,6 +46,7 @@ add_subdirectory(solid) add_subdirectory(xz) add_subdirectory(zlib) +add_subdirectory(fcl) add_subdirectory(libxml2) add_subdirectory(coin3d/coin) @@ -59,6 +61,8 @@ set( "${CMAKE_CURRENT_BINARY_DIR}/coin3d/simage/simage-prefix/src/simage-build;simage;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/coin3d/soqt/soqt-prefix/src/soqt-build;soqt;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/eigen/eigen-prefix/src/eigen-build;eigen;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/fcl/fcl-prefix/src/fcl-build;fcl;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/libccd/libccd-prefix/src/libccd-build;libccd;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/libiconv/libiconv-prefix/src/libiconv-build;libiconv;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/libxml2/libxml2-prefix/src/libxml2-build;libxml2;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/libxslt/libxslt-prefix/src/libxslt-build;libxslt;ALL;/" diff --git a/3rdparty/fcl/CMakeLists.txt b/3rdparty/fcl/CMakeLists.txt new file mode 100644 index 00000000..1aca2eeb --- /dev/null +++ b/3rdparty/fcl/CMakeLists.txt @@ -0,0 +1,15 @@ +include(ExternalProject) + +list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) + +ExternalProject_Add( + fcl + DEPENDS libccd + #GIT_REPOSITORY git://github.com/flexible-collision-library/fcl.git + #GIT_TAG 0.6.1 + URL https://github.com/flexible-collision-library/fcl/archive/0.6.1.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/fcl-0.6.1.tar.gz + URL_MD5 1fbb2c6132f5a492e970e6be37a89632 + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_DEBUG_POSTFIX=d -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_TESTING=OFF + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) diff --git a/3rdparty/libccd/CMakeLists.txt b/3rdparty/libccd/CMakeLists.txt new file mode 100644 index 00000000..2f956a4f --- /dev/null +++ b/3rdparty/libccd/CMakeLists.txt @@ -0,0 +1,16 @@ +cmake_minimum_required(VERSION 2.8.11) + +project(libccd) + +include(ExternalProject) + +ExternalProject_Add( + libccd + #GIT_REPOSITORY git://github.com/danfis/libccd.git + #GIT_TAG v2.1 + URL https://github.com/danfis/libccd/archive/v2.1.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/libccd-2.1.tar.gz + URL_MD5 fe8ea5024956044a3af6bcbab312950f + CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_DEBUG_POSTFIX=d -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DENABLE_DOUBLE_PRECISION=ON + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) From 994f63f5c72c5dece04ef77fd79e10909a7268cf Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 13 Nov 2020 15:22:36 +0100 Subject: [PATCH 410/546] Update 3rdparty CMake files --- 3rdparty/CMakeLists.txt | 57 +- 3rdparty/atidaq/CMakeLists.txt | 37 +- 3rdparty/atidaq/CMakeLists.txt.in | 183 ----- 3rdparty/atidaq/atidaq-config.cmake.in | 13 - 3rdparty/atidaq/atidaq.patch | 24 - 3rdparty/boost/CMakeLists.txt | 21 +- 3rdparty/bullet/CMakeLists.txt | 16 - 3rdparty/bullet3/CMakeLists.txt | 31 + 3rdparty/coin/CMakeLists.txt | 25 + 3rdparty/coin3d/coin/CMakeLists.txt | 17 - 3rdparty/coin3d/cpack.d/CMakeLists.txt | 13 - 3rdparty/coin3d/simage/CMakeLists.txt | 15 - 3rdparty/coin3d/soanydata/CMakeLists.txt | 13 - 3rdparty/coin3d/sogui/CMakeLists.txt | 13 - 3rdparty/coin3d/soqt/CMakeLists.txt | 19 - 3rdparty/eigen/CMakeLists.txt | 16 - 3rdparty/eigen3/CMakeLists.txt | 28 + 3rdparty/fcl/CMakeLists.txt | 24 +- 3rdparty/gperf/CMakeLists.txt | 21 + 3rdparty/libccd/CMakeLists.txt | 23 +- 3rdparty/libiconv/CMakeLists.txt | 39 +- 3rdparty/libiconv/CMakeLists.txt.in | 896 ---------------------- 3rdparty/libiconv/config.h.cmake.in | 926 ----------------------- 3rdparty/libiconv/iconv-config.cmake.in | 38 - 3rdparty/libiconv/libiconv-1.15.patch | 29 - 3rdparty/libxml2/CMakeLists.txt | 30 +- 3rdparty/libxslt/CMakeLists.txt | 29 +- 3rdparty/nlopt/CMakeLists.txt | 42 +- 3rdparty/ode/CMakeLists.txt | 40 +- 3rdparty/patch.exe.manifest | 10 - 3rdparty/pqp/CMakeLists.txt | 28 +- 3rdparty/simage/CMakeLists.txt | 24 + 3rdparty/solid/CMakeLists.txt | 14 - 3rdparty/solid3/CMakeLists.txt | 26 + 3rdparty/soqt/CMakeLists.txt | 25 + 3rdparty/xz/CMakeLists.txt | 32 +- 3rdparty/zlib/CMakeLists.txt | 29 +- 37 files changed, 435 insertions(+), 2431 deletions(-) delete mode 100644 3rdparty/atidaq/CMakeLists.txt.in delete mode 100644 3rdparty/atidaq/atidaq-config.cmake.in delete mode 100644 3rdparty/atidaq/atidaq.patch delete mode 100644 3rdparty/bullet/CMakeLists.txt create mode 100644 3rdparty/bullet3/CMakeLists.txt create mode 100644 3rdparty/coin/CMakeLists.txt delete mode 100644 3rdparty/coin3d/coin/CMakeLists.txt delete mode 100644 3rdparty/coin3d/cpack.d/CMakeLists.txt delete mode 100644 3rdparty/coin3d/simage/CMakeLists.txt delete mode 100644 3rdparty/coin3d/soanydata/CMakeLists.txt delete mode 100644 3rdparty/coin3d/sogui/CMakeLists.txt delete mode 100644 3rdparty/coin3d/soqt/CMakeLists.txt delete mode 100644 3rdparty/eigen/CMakeLists.txt create mode 100644 3rdparty/eigen3/CMakeLists.txt create mode 100644 3rdparty/gperf/CMakeLists.txt delete mode 100644 3rdparty/libiconv/CMakeLists.txt.in delete mode 100644 3rdparty/libiconv/config.h.cmake.in delete mode 100644 3rdparty/libiconv/iconv-config.cmake.in delete mode 100644 3rdparty/libiconv/libiconv-1.15.patch delete mode 100644 3rdparty/patch.exe.manifest create mode 100644 3rdparty/simage/CMakeLists.txt delete mode 100644 3rdparty/solid/CMakeLists.txt create mode 100644 3rdparty/solid3/CMakeLists.txt create mode 100644 3rdparty/soqt/CMakeLists.txt diff --git a/3rdparty/CMakeLists.txt b/3rdparty/CMakeLists.txt index 604c49fc..a4fd7e06 100644 --- a/3rdparty/CMakeLists.txt +++ b/3rdparty/CMakeLists.txt @@ -3,64 +3,41 @@ cmake_minimum_required(VERSION 2.8.11) project(3rdparty) include(ExternalProject) +include(GNUInstallDirs) -if(WIN32) - ExternalProject_Add( - patch - URL https://downloads.sourceforge.net/project/gnuwin32/patch/2.5.9-7/patch-2.5.9-7-bin.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/patch-2.5.9-7-bin.zip - URL_MD5 b9c8b31d62f4b2e4f1887bbb63e8a905 - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND - ${CMAKE_COMMAND} -E copy /bin/patch.exe ${CMAKE_CURRENT_BINARY_DIR}/patch.exe && - ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/patch.exe.manifest ${CMAKE_CURRENT_BINARY_DIR}/patch.exe.manifest - ) - set(PATCH_EXECUTABLE ${CMAKE_CURRENT_BINARY_DIR}/patch.exe) -else() - ExternalProject_Add( - patch - SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR} - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" - ) - set(PATCH_EXECUTABLE patch) -endif() +option(BUILD_SHARED_LIBS "Build shared libraries" ON) -add_subdirectory(coin3d/cpack.d) -add_subdirectory(coin3d/soanydata) -add_subdirectory(coin3d/sogui) +list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) add_subdirectory(atidaq) add_subdirectory(boost) -add_subdirectory(bullet) -add_subdirectory(eigen) +add_subdirectory(bullet3) +add_subdirectory(coin) +add_subdirectory(eigen3) +add_subdirectory(gperf) add_subdirectory(libccd) -add_subdirectory(libiconv) add_subdirectory(nlopt) add_subdirectory(ode) add_subdirectory(pqp) -add_subdirectory(coin3d/simage) -add_subdirectory(solid) +add_subdirectory(simage) +add_subdirectory(solid3) add_subdirectory(xz) add_subdirectory(zlib) add_subdirectory(fcl) +add_subdirectory(libiconv) +add_subdirectory(soqt) + add_subdirectory(libxml2) -add_subdirectory(coin3d/coin) add_subdirectory(libxslt) -add_subdirectory(coin3d/soqt) set( CPACK_INSTALL_CMAKE_PROJECTS "${CMAKE_CURRENT_BINARY_DIR}/atidaq/atidaq-prefix/src/atidaq-build;atidaq;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/bullet/bullet-prefix/src/bullet-build;bullet;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/coin3d/coin/coin-prefix/src/coin-build;coin;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/coin3d/simage/simage-prefix/src/simage-build;simage;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/coin3d/soqt/soqt-prefix/src/soqt-build;soqt;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/eigen/eigen-prefix/src/eigen-build;eigen;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/bullet3/bullet3-prefix/src/bullet3-build;bullet3;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/coin/coin-prefix/src/coin-build;coin;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/eigen3/eigen3-prefix/src/eigen3-build;eigen3;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/fcl/fcl-prefix/src/fcl-build;fcl;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/libccd/libccd-prefix/src/libccd-build;libccd;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/libiconv/libiconv-prefix/src/libiconv-build;libiconv;ALL;/" @@ -69,7 +46,9 @@ set( "${CMAKE_CURRENT_BINARY_DIR}/nlopt/nlopt-prefix/src/nlopt-build;nlopt;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/ode/ode-prefix/src/ode-build;ode;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/pqp/pqp-prefix/src/pqp-build;pqp;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/solid/solid-prefix/src/solid-build;solid;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/simage/simage-prefix/src/simage-build;simage;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/solid3/solid3-prefix/src/solid3-build;solid3;ALL;/" + "${CMAKE_CURRENT_BINARY_DIR}/soqt/soqt-prefix/src/soqt-build;soqt;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/xz/xz-prefix/src/xz-build;xz;ALL;/" "${CMAKE_CURRENT_BINARY_DIR}/zlib/zlib-prefix/src/zlib-build;zlib;ALL;/" ) diff --git a/3rdparty/atidaq/CMakeLists.txt b/3rdparty/atidaq/CMakeLists.txt index 1db2abdc..22411bef 100644 --- a/3rdparty/atidaq/CMakeLists.txt +++ b/3rdparty/atidaq/CMakeLists.txt @@ -1,23 +1,22 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(atidaq) - -include(ExternalProject) - -if(NOT WIN32) - set(PATCH_BINARY "--binary") -endif() - ExternalProject_Add( atidaq - DEPENDS patch - URL http://www.ati-ia.com/library/software/daq_ft/ATIDAQ%20C%20Library.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/ATIDAQ%20C%20Library.zip - URL_MD5 02c26650792927a09202196c574522cd - PATCH_COMMAND - ${PATCH_EXECUTABLE} -p1 -t -N ${PATCH_BINARY} < ${CMAKE_CURRENT_SOURCE_DIR}/atidaq.patch && - ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/atidaq-config.cmake.in /atidaq-config.cmake.in && - ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/CMakeLists.txt.in /CMakeLists.txt - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + #GIT_REPOSITORY https://github.com/roboticslibrary/atidaq.git + #GIT_TAG cmake-1.0.6 + URL https://github.com/roboticslibrary/atidaq/archive/cmake-1.0.6.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/atidaq-cmake-1.0.6.tar.gz + URL_MD5 23efd8412e30a06e9c433ab5e7ed2e20 + CMAKE_ARGS + -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + atidaq license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /readme.txt ${CMAKE_INSTALL_FULL_DATADIR}/atidaq/readme.txt +) diff --git a/3rdparty/atidaq/CMakeLists.txt.in b/3rdparty/atidaq/CMakeLists.txt.in deleted file mode 100644 index 3c5a5383..00000000 --- a/3rdparty/atidaq/CMakeLists.txt.in +++ /dev/null @@ -1,183 +0,0 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(atidaq) - -include(CMakePackageConfigHelpers) -include(GNUInstallDirs) - -set(VERSION_MAJOR 1) -set(VERSION_MINOR 0) -set(VERSION_PATCH 7) -set(VERSION ${VERSION_MAJOR}.${VERSION_MINOR}.${VERSION_PATCH}) - -if(WIN32) - set(BUILD_SHARED_LIBS OFF) -else() - option(BUILD_SHARED_LIBS "Build shared libraries" ON) -endif() - -set( - HDRS - ATIDAQ/ascii.h - ATIDAQ/asciitab.h - ATIDAQ/dom.h - ATIDAQ/ftconfig.h - ATIDAQ/ftrt.h - ATIDAQ/ftsharedrt.h - ATIDAQ/iasciitab.h - ATIDAQ/latin1tab.h - ATIDAQ/nametab.h - ATIDAQ/stack.h - ATIDAQ/utf8tab.h - ATIDAQ/xmldef.h - ATIDAQ/xmlparse.h - ATIDAQ/xmlrole.h - ATIDAQ/xmltok.h - ATIDAQ/xmltok_impl.h -) - -set( - SRCS - ATIDAQ/dom.c - ATIDAQ/expatls.c - ATIDAQ/ftconfig.c - ATIDAQ/ftrt.c - ATIDAQ/node.c - ATIDAQ/stack.c - ATIDAQ/xmlparse.c - ATIDAQ/xmlrole.c - ATIDAQ/xmltok.c -) - -add_library(atidaq ${HDRS} ${SRCS}) - -target_include_directories( - atidaq - INTERFACE - $ - $/${CMAKE_INSTALL_INCLUDEDIR}> -) - -if(UNIX) - target_link_libraries(atidaq m) -endif() - -set_target_properties(atidaq PROPERTIES DEBUG_POSTFIX d VERSION ${VERSION}) - -install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/atidaq COMPONENT development) - -install( - TARGETS atidaq - EXPORT atidaq - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime -) - -if(BUILD_SHARED_LIBS) - install( - TARGETS atidaq - EXPORT atidaq - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY - ) -endif() - -if(MSVC AND BUILD_SHARED_LIBS AND ${CMAKE_MAJOR_VERSION} GREATER 2 AND ${CMAKE_MINOR_VERSION} GREATER 0) - install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) -endif() - -add_executable(calinfo Samples/calinfo.c) -target_link_libraries(calinfo atidaq) - -install( - TARGETS calinfo - COMPONENT programs - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} -) - -add_executable(ftconvert Samples/ftconvert.c) -target_link_libraries(ftconvert atidaq) - -install( - TARGETS ftconvert - COMPONENT programs - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} -) - -configure_package_config_file( - atidaq-config.cmake.in atidaq-config.cmake - INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/atidaq-${VERSION} -) - -install( - FILES ${CMAKE_CURRENT_BINARY_DIR}/atidaq-config.cmake - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/atidaq-${VERSION} - COMPONENT development -) - -write_basic_package_version_file( - ${CMAKE_CURRENT_BINARY_DIR}/atidaq-config-version.cmake - VERSION ${VERSION} - COMPATIBILITY ExactVersion -) - -install( - FILES ${CMAKE_CURRENT_BINARY_DIR}/atidaq-config-version.cmake - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/atidaq-${VERSION} - COMPONENT development -) - -install( - EXPORT atidaq - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/atidaq-${VERSION} - NAMESPACE atidaq:: - FILE atidaq-export.cmake - COMPONENT development -) - -set(CPACK_COMPONENT_DEVELOPMENT_DEPENDS runtime) -set(CPACK_COMPONENT_PROGRAMS_DEPENDS runtime) -set(CPACK_DEB_COMPONENT_INSTALL ON) -set(CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libatidaq") -set(CPACK_DEBIAN_DEVELOPMENT_PACKAGE_NAME "libatidaq-dev") -set(CPACK_DEBIAN_DEVELOPMENT_PACKAGE_SECTION "libdevel") -set(CPACK_DEBIAN_PACKAGE_HOMEPAGE "http://www.ati-ia.com/Products/ft/software/daq_software.aspx") -set(CPACK_DEBIAN_PACKAGE_NAME "libatidaq") -set(CPACK_DEBIAN_PACKAGE_SECTION "devel") -set(CPACK_DEBIAN_PROGRAMS_PACKAGE_DEPENDS "libatidaq") -set(CPACK_DEBIAN_PROGRAMS_PACKAGE_NAME "libatidaq-utils") -set(CPACK_DEBIAN_PROGRAMS_PACKAGE_SECTION "utils") -set(CPACK_DEBIAN_RUNTIME_PACKAGE_NAME "libatidaq") -set(CPACK_DEBIAN_RUNTIME_PACKAGE_RECOMMENDS "libatidaq-utils") -set(CPACK_DEBIAN_RUNTIME_PACKAGE_SECTION "libs") -set(CPACK_NSIS_PACKAGE_NAME "ATIDAQ ${VERSION}") -set(CPACK_NSIS_URL_INFO_ABOUT ${CPACK_DEBIAN_PACKAGE_HOMEPAGE}) -set(CPACK_PACKAGE_CONTACT "info@ati-ia.com") -set(CPACK_PACKAGE_DISPLAY_NAME "ATIDAQ ${VERSION}") -set(CPACK_PACKAGE_INSTALL_DIRECTORY "ATIDAQ-${VERSION}") -set(CPACK_PACKAGE_NAME "atidaq") -set(CPACK_PACKAGE_VERSION ${VERSION}) -set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) -set(CPACK_PACKAGE_VERSION_MINOR ${VERSION_MINOR}) -set(CPACK_PACKAGE_VERSION_PATCH ${VERSION_PATCH}) -set(CPACK_RESOURCE_FILE_LICENSE ${CMAKE_CURRENT_SOURCE_DIR}/readme.txt) -set(CPACK_RPM_COMPONENT_INSTALL ON) -set(CPACK_RPM_development_PACKAGE_NAME "atidaq-devel") -set(CPACK_RPM_development_PACKAGE_REQUIRES "atidaq") -set(CPACK_RPM_PACKAGE_GROUP "Development/Libraries") -set(CPACK_RPM_PACKAGE_NAME "atidaq") -set(CPACK_RPM_PACKAGE_URL ${CPACK_DEBIAN_PACKAGE_HOMEPAGE}) -set(CPACK_RPM_programs_PACKAGE_NAME "atidaq-utils") -set(CPACK_RPM_programs_PACKAGE_REQUIRES "atidaq") -set(CPACK_RPM_runtime_PACKAGE_NAME "atidaq") -set(CPACK_RPM_runtime_PACKAGE_SUGGESTS "atidaq-utils") - -if(WIN32 AND CMAKE_SIZEOF_VOID_P EQUAL 8) - set(CPACK_NSIS_INSTALL_ROOT "$PROGRAMFILES64") -endif() - -include(CPack) diff --git a/3rdparty/atidaq/atidaq-config.cmake.in b/3rdparty/atidaq/atidaq-config.cmake.in deleted file mode 100644 index d0b918a1..00000000 --- a/3rdparty/atidaq/atidaq-config.cmake.in +++ /dev/null @@ -1,13 +0,0 @@ -set(ATIDAQ_VERSION "@VERSION@") -set(ATIDAQ_VERSION_MAJOR "@VERSION_MAJOR@") -set(ATIDAQ_VERSION_MINOR "@VERSION_MINOR@") -set(ATIDAQ_VERSION_PATCH "@VERSION_PATCH@") - -@PACKAGE_INIT@ - -include("${CMAKE_CURRENT_LIST_DIR}/atidaq-export.cmake") - -set(ATIDAQ_DEFINITIONS "") -set(ATIDAQ_INCLUDE_DIRS "") -set(ATIDAQ_LIBRARY_DIRS "") -set(ATIDAQ_LIBRARIES "atidaq::atidaq") diff --git a/3rdparty/atidaq/atidaq.patch b/3rdparty/atidaq/atidaq.patch deleted file mode 100644 index c2a529b5..00000000 --- a/3rdparty/atidaq/atidaq.patch +++ /dev/null @@ -1,24 +0,0 @@ -diff -Naur ATIDAQ%20C%20Library.orig/Samples/calinfo.c ATIDAQ%20C%20Library/Samples/calinfo.c ---- ATIDAQ%20C%20Library.orig/Samples/calinfo.c 2013-06-17 15:28:44.974930600 +0200 -+++ ATIDAQ%20C%20Library/Samples/calinfo.c 2015-11-14 15:52:05.938150000 +0100 -@@ -29,7 +29,7 @@ - - #include - #include --#include "..\ATIDAQ\ftconfig.h" -+#include "../ATIDAQ/ftconfig.h" - - int main(int argc, char *argv[]) { - char *calfilepath; // name of calibration file -diff -Naur ATIDAQ%20C%20Library.orig/Samples/ftconvert.c ATIDAQ%20C%20Library/Samples/ftconvert.c ---- ATIDAQ%20C%20Library.orig/Samples/ftconvert.c 2013-06-17 15:28:44.993932500 +0200 -+++ ATIDAQ%20C%20Library/Samples/ftconvert.c 2015-11-14 15:52:01.514088300 +0100 -@@ -32,7 +32,7 @@ - - #include - #include --#include "..\atidaq\ftconfig.h" -+#include "../ATIDAQ/ftconfig.h" - - int main(int argc, char *argv[]) { - char *calfilepath; // name of calibration file diff --git a/3rdparty/boost/CMakeLists.txt b/3rdparty/boost/CMakeLists.txt index 5c019f55..5b19875f 100644 --- a/3rdparty/boost/CMakeLists.txt +++ b/3rdparty/boost/CMakeLists.txt @@ -1,17 +1,18 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(boost) - -include(ExternalProject) -include(GNUInstallDirs) - ExternalProject_Add( boost - URL https://dl.bintray.com/boostorg/release/1.73.0/source/boost_1_73_0.7z - #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_73_0.7z - URL_MD5 b647977d33441b17e9276ce37309008f + URL + https://sourceforge.net/projects/boost/files/boost/1.74.0/boost_1_74_0.7z/download + https://dl.bintray.com/boostorg/release/1.74.0/source/boost_1_74_0.7z + #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_74_0.7z + URL_MD5 3d513f8830c3c8aa308d782e740c4931 CONFIGURE_COMMAND "" BUILD_COMMAND "" BUILD_IN_SOURCE 1 INSTALL_COMMAND ${CMAKE_COMMAND} -E copy_directory /boost ${CMAKE_INSTALL_FULL_INCLUDEDIR}/boost ) + +ExternalProject_Add_Step( + boost license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE_1_0.txt ${CMAKE_INSTALL_FULL_DATADIR}/boost/LICENSE_1_0.txt +) diff --git a/3rdparty/bullet/CMakeLists.txt b/3rdparty/bullet/CMakeLists.txt deleted file mode 100644 index c7f3b475..00000000 --- a/3rdparty/bullet/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(bullet) - -include(ExternalProject) - -ExternalProject_Add( - bullet - #GIT_REPOSITORY git://github.com/bulletphysics/bullet3.git - #GIT_TAG 2.88 - URL https://github.com/roboticslibrary/bullet3/archive/patch.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/bullet3-2.88.tar.gz - #URL_MD5 d389e7235f00c66abf257bb7b21477ac - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_BULLET2_DEMOS=OFF -DBUILD_CPU_DEMOS=OFF -DBUILD_EXTRAS=ON -DBUILD_OPENGL3_DEMOS=OFF -DBUILD_PYBULLET=OFF -DBUILD_UNIT_TESTS=OFF -DINSTALL_EXTRA_LIBS=ON -DINSTALL_LIBS=ON -DUSE_MSVC_RUNTIME_LIBRARY_DLL=ON - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) diff --git a/3rdparty/bullet3/CMakeLists.txt b/3rdparty/bullet3/CMakeLists.txt new file mode 100644 index 00000000..58ae3c94 --- /dev/null +++ b/3rdparty/bullet3/CMakeLists.txt @@ -0,0 +1,31 @@ +ExternalProject_Add( + bullet3 + #GIT_REPOSITORY https://github.com/bulletphysics/bullet3.git + #GIT_TAG 3.06 + URL https://github.com/bulletphysics/bullet3/archive/3.06.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/bullet3-3.06.tar.gz + URL_MD5 369407bb68a2d8898789a280acb067ac + CMAKE_ARGS + -DBUILD_BULLET2_DEMOS=OFF + -DBUILD_CPU_DEMOS=OFF + -DBUILD_EXTRAS=ON + -DBUILD_OPENGL3_DEMOS=OFF + -DBUILD_PYBULLET=OFF + -DBUILD_UNIT_TESTS=OFF + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DINSTALL_EXTRA_LIBS=ON + -DINSTALL_LIBS=ON + -DUSE_DOUBLE_PRECISION=ON + -DUSE_MSVC_RUNTIME_LIBRARY_DLL=ON + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) + +ExternalProject_Add_Step( + bullet3 license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE.txt ${CMAKE_INSTALL_FULL_DATADIR}/bullet/LICENSE.txt +) diff --git a/3rdparty/coin/CMakeLists.txt b/3rdparty/coin/CMakeLists.txt new file mode 100644 index 00000000..f7fb89e0 --- /dev/null +++ b/3rdparty/coin/CMakeLists.txt @@ -0,0 +1,25 @@ +ExternalProject_Add( + coin + DEPENDS boost + #GIT_REPOSITORY https://github.com/coin3d/coin.git + #GIT_TAG Coin-4.0.0 + URL https://github.com/coin3d/coin/releases/download/Coin-4.0.0/coin-4.0.0-src.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/coin-4.0.0-src.tar.gz + URL_MD5 2377d11b38c8eddd92d8bb240f5bf4ee + CMAKE_ARGS + -DCOIN_BUILD_DOCUMENTATION=OFF + -DCOIN_BUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DCOIN_BUILD_TESTS=OFF + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) + +ExternalProject_Add_Step( + coin license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/Coin/COPYING +) diff --git a/3rdparty/coin3d/coin/CMakeLists.txt b/3rdparty/coin3d/coin/CMakeLists.txt deleted file mode 100644 index 60dc3790..00000000 --- a/3rdparty/coin3d/coin/CMakeLists.txt +++ /dev/null @@ -1,17 +0,0 @@ -include(ExternalProject) - -list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) - -ExternalProject_Add( - coin - DEPENDS boost cpack.d simage - #GIT_REPOSITORY https://github.com/coin3d/coin - #GIT_TAG Coin-4.0.0 - URL https://github.com/coin3d/coin/archive/Coin-4.0.0.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/coin-Coin-4.0.0.zip - URL_MD5 390c3db9cd5bb6644a20c7f88f37aaa2 - PATCH_COMMAND - ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DCOIN_BUILD_DOCUMENTATION=OFF -DCOIN_BUILD_TESTS=OFF - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) diff --git a/3rdparty/coin3d/cpack.d/CMakeLists.txt b/3rdparty/coin3d/cpack.d/CMakeLists.txt deleted file mode 100644 index e4dc681c..00000000 --- a/3rdparty/coin3d/cpack.d/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -include(ExternalProject) - -ExternalProject_Add( - cpack.d - #GIT_REPOSITORY https://bitbucket.org/Coin3D/cpack.d - #GIT_TAG b9ddb8116dd1bf98f2b1c858693c8b55cb80cad5 - URL https://github.com/coin3d/cpack.d/archive/b9ddb8116dd1bf98f2b1c858693c8b55cb80cad5.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/cpack.d-b9ddb8116dd1bf98f2b1c858693c8b55cb80cad5.zip - URL_MD5 35a40474754869bf86693349d00f49e2 - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" -) diff --git a/3rdparty/coin3d/simage/CMakeLists.txt b/3rdparty/coin3d/simage/CMakeLists.txt deleted file mode 100644 index ede3fedd..00000000 --- a/3rdparty/coin3d/simage/CMakeLists.txt +++ /dev/null @@ -1,15 +0,0 @@ -include(ExternalProject) - -ExternalProject_Add( - simage - DEPENDS cpack.d - #GIT_REPOSITORY https://github.com/coin3d/simage - #GIT_TAG simage-1.8.0 - URL https://github.com/coin3d/simage/archive/simage-1.8.0.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/simage-simage-1.8.0.tar.bz2 - URL_MD5 0d517db68d839dec57eff95226245d46 - PATCH_COMMAND - ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) diff --git a/3rdparty/coin3d/soanydata/CMakeLists.txt b/3rdparty/coin3d/soanydata/CMakeLists.txt deleted file mode 100644 index 7a9117bd..00000000 --- a/3rdparty/coin3d/soanydata/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -include(ExternalProject) - -ExternalProject_Add( - soanydata - #GIT_REPOSITORY https://github.com/coin3d/soanydata - #GIT_TAG 3ff6e9203fbb0cc08a2bdf209212b7ef4d78a1f2 - URL https://github.com/coin3d/soanydata/archive/3ff6e9203fbb0cc08a2bdf209212b7ef4d78a1f2.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/soanydata-3ff6e9203fbb0cc08a2bdf209212b7ef4d78a1f2.zip - URL_MD5 17c8b33000f58fdb99d943e559d8fa21 - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" -) diff --git a/3rdparty/coin3d/sogui/CMakeLists.txt b/3rdparty/coin3d/sogui/CMakeLists.txt deleted file mode 100644 index 18508e60..00000000 --- a/3rdparty/coin3d/sogui/CMakeLists.txt +++ /dev/null @@ -1,13 +0,0 @@ -include(ExternalProject) - -ExternalProject_Add( - sogui - #GIT_REPOSITORY https://github.com/coin3d/sogui - #GIT_TAG fb79af47cff89f0f3657501601a7ea5c11968b17 - URL https://github.com/coin3d/sogui/archive/fb79af47cff89f0f3657501601a7ea5c11968b17.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/sogui-fb79af47cff89f0f3657501601a7ea5c11968b17 - URL_MD5 2352490aadfd6612cb5e8aa7f619f12e - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" -) diff --git a/3rdparty/coin3d/soqt/CMakeLists.txt b/3rdparty/coin3d/soqt/CMakeLists.txt deleted file mode 100644 index a110fe2e..00000000 --- a/3rdparty/coin3d/soqt/CMakeLists.txt +++ /dev/null @@ -1,19 +0,0 @@ -include(ExternalProject) - -list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) - -ExternalProject_Add( - soqt - DEPENDS coin cpack.d soanydata sogui - #GIT_REPOSITORY https://github.com/coin3d/soqt - #GIT_TAG SoQt-1.6.0 - URL https://github.com/coin3d/soqt/archive/SoQt-1.6.0.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/soqt-SoQt-1.6.0.zip - URL_MD5 856c38b464a4986f39fbc52f86a1f4a0 - PATCH_COMMAND - ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../cpack.d/cpack.d-prefix/src/cpack.d /cpack.d && - ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../soanydata/soanydata-prefix/src/soanydata /data && - ${CMAKE_COMMAND} -E copy_directory ${CMAKE_CURRENT_BINARY_DIR}/../sogui/sogui-prefix/src/sogui /src/Inventor/Qt/common - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DSOQT_BUILD_DOCUMENTATION=OFF - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) diff --git a/3rdparty/eigen/CMakeLists.txt b/3rdparty/eigen/CMakeLists.txt deleted file mode 100644 index 52468250..00000000 --- a/3rdparty/eigen/CMakeLists.txt +++ /dev/null @@ -1,16 +0,0 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(eigen) - -include(ExternalProject) - -ExternalProject_Add( - eigen - #GIT_REPOSITORY https://gitlab.com/libeigen/eigen.git - #GIT_TAG 3.3.7 - URL https://gitlab.com/libeigen/eigen/-/archive/3.3.7/eigen-3.3.7.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/eigen-3.3.7.tar.gz - URL_MD5 9e30f67e8531477de4117506fe44669b - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_TESTING=OFF -DEIGEN_TEST_NOQT=ON - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) diff --git a/3rdparty/eigen3/CMakeLists.txt b/3rdparty/eigen3/CMakeLists.txt new file mode 100644 index 00000000..700eff2d --- /dev/null +++ b/3rdparty/eigen3/CMakeLists.txt @@ -0,0 +1,28 @@ +ExternalProject_Add( + eigen3 + #GIT_REPOSITORY https://gitlab.com/libeigen/eigen.git + #GIT_TAG 3.3.8 + URL https://gitlab.com/libeigen/eigen/-/archive/3.3.8/eigen-3.3.8.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/eigen-3.3.8.tar.gz + URL_MD5 dc352b8c98797c71470b58b52fa8a4ce + CMAKE_ARGS + -DBUILD_TESTING=OFF + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DEIGEN_TEST_NOQT=ON + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) + +ExternalProject_Add_Step( + eigen3 license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.BSD ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.BSD + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.GPL ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.GPL + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.LGPL ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.LGPL + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.MINPACK ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.MINPACK + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.MPL2 ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.MPL2 + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.README ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.README +) diff --git a/3rdparty/fcl/CMakeLists.txt b/3rdparty/fcl/CMakeLists.txt index 1aca2eeb..5ff9fe32 100644 --- a/3rdparty/fcl/CMakeLists.txt +++ b/3rdparty/fcl/CMakeLists.txt @@ -1,15 +1,23 @@ -include(ExternalProject) - -list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) - ExternalProject_Add( fcl - DEPENDS libccd - #GIT_REPOSITORY git://github.com/flexible-collision-library/fcl.git + DEPENDS eigen3 libccd + #GIT_REPOSITORY https://github.com/flexible-collision-library/fcl.git #GIT_TAG 0.6.1 - URL https://github.com/flexible-collision-library/fcl/archive/0.6.1.tar.gz + URL https://github.com/flexible-collision-library/fcl/archive/v0.6.1.tar.gz #URL ${CMAKE_CURRENT_SOURCE_DIR}/fcl-0.6.1.tar.gz URL_MD5 1fbb2c6132f5a492e970e6be37a89632 - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_DEBUG_POSTFIX=d -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_TESTING=OFF + CMAKE_ARGS + -DBUILD_TESTING=OFF + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + fcl license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/fcl/LICENSE +) diff --git a/3rdparty/gperf/CMakeLists.txt b/3rdparty/gperf/CMakeLists.txt new file mode 100644 index 00000000..3ab2264f --- /dev/null +++ b/3rdparty/gperf/CMakeLists.txt @@ -0,0 +1,21 @@ +ExternalProject_Add( + gperf + #GIT_REPOSITORY https://github.com/roboticslibrary/gperf.git + #GIT_TAG cmake-3.1 + URL https://github.com/roboticslibrary/gperf/archive/cmake-3.1.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/gperf-cmake-3.1.tar.gz + URL_MD5 ccdc42c8b534061030d49bb9cae9cfd5 + CMAKE_ARGS + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) + +ExternalProject_Add_Step( + gperf license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/gperf/COPYING +) diff --git a/3rdparty/libccd/CMakeLists.txt b/3rdparty/libccd/CMakeLists.txt index 2f956a4f..0de5c5c0 100644 --- a/3rdparty/libccd/CMakeLists.txt +++ b/3rdparty/libccd/CMakeLists.txt @@ -1,16 +1,23 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(libccd) - -include(ExternalProject) - ExternalProject_Add( libccd - #GIT_REPOSITORY git://github.com/danfis/libccd.git + #GIT_REPOSITORY https://github.com/danfis/libccd.git #GIT_TAG v2.1 URL https://github.com/danfis/libccd/archive/v2.1.tar.gz #URL ${CMAKE_CURRENT_SOURCE_DIR}/libccd-2.1.tar.gz URL_MD5 fe8ea5024956044a3af6bcbab312950f - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_DEBUG_POSTFIX=d -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DENABLE_DOUBLE_PRECISION=ON + CMAKE_ARGS + -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DENABLE_DOUBLE_PRECISION=ON INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + libccd license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /BSD-LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/libccd/BSD-LICENSE +) diff --git a/3rdparty/libiconv/CMakeLists.txt b/3rdparty/libiconv/CMakeLists.txt index bc696d90..6b6636af 100644 --- a/3rdparty/libiconv/CMakeLists.txt +++ b/3rdparty/libiconv/CMakeLists.txt @@ -1,22 +1,25 @@ -include(ExternalProject) - -if(WIN32) - set(PATCH_BINARY "--binary") -endif() - ExternalProject_Add( libiconv - DEPENDS patch - #GIT_REPOSITORY git://git.savannah.gnu.org/libiconv.git - #GIT_TAG v1.15 - URL http://ftp.gnu.org/pub/gnu/libiconv/libiconv-1.15.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/libiconv-1.15.tar.gz - URL_MD5 ace8b5f2db42f7b3b3057585e80d9808 - PATCH_COMMAND - ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/CMakeLists.txt.in /CMakeLists.txt && - ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/config.h.cmake.in /config.h.cmake.in && - ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/iconv-config.cmake.in /iconv-config.cmake.in && - ${PATCH_EXECUTABLE} -p1 -t -N ${PATCH_BINARY} < ${CMAKE_CURRENT_SOURCE_DIR}/libiconv-1.15.patch - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + DEPENDS gperf + #GIT_REPOSITORY https://github.com/roboticslibrary/libiconv.git + #GIT_TAG cmake-1.16 + URL https://github.com/roboticslibrary/libiconv/archive/cmake-1.16.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/libiconv-cmake-1.16.tar.gz + URL_MD5 6d6ac0413d86ef2f3e6cdf38b7a5369c + CMAKE_ARGS + -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + libiconv license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/libiconv/COPYING + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.LIB ${CMAKE_INSTALL_FULL_DATADIR}/libiconv/COPYING.LIB + COMMAND ${CMAKE_COMMAND} -E copy /README ${CMAKE_INSTALL_FULL_DATADIR}/libiconv/README +) diff --git a/3rdparty/libiconv/CMakeLists.txt.in b/3rdparty/libiconv/CMakeLists.txt.in deleted file mode 100644 index 2b6736c7..00000000 --- a/3rdparty/libiconv/CMakeLists.txt.in +++ /dev/null @@ -1,896 +0,0 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(libiconv) - -include(CheckCCompilerFlag) -include(CheckCSourceCompiles) -include(CheckCSourceRuns) -include(CheckFunctionExists) -include(CheckIncludeFiles) -include(CheckSymbolExists) -include(CheckTypeSize) -include(CMakePackageConfigHelpers) -include(GNUInstallDirs) -include(TestBigEndian) - -function(CHECK_RAW_SYMBOL_EXISTS SYMBOL FILES VARIABLE) - foreach(FILE ${FILES}) - list(APPEND SOURCE "#include <${FILE}>\n") - endforeach() - list(APPEND SOURCE "int main()\n{\n#undef ${SYMBOL}\n(void) ${SYMBOL};\nreturn 0;\n}") - check_c_source_compiles("${SOURCE}" "${VARIABLE}") -endfunction() - -set(VERSION_MAJOR 1) -set(VERSION_MINOR 15) -set(VERSION ${VERSION_MAJOR}.${VERSION_MINOR}) - -option(BUILD_SHARED_LIBS "Build shared libraries" ON) -option(LIBICONV_ENABLE_EXTRA "Enable a few rarely used encodings" OFF) -option(LIBICONV_ENABLE_NLS "Translate program messages to user's native language" OFF) -option(LIBICONV_ENABLE_RELOCATABLE "Install a package that can be moved in the file system" ON) - -check_type_size("ptrdiff_t" BITSIZEOF_PTRDIFF_T) -set(CMAKE_EXTRA_INCLUDE_FILES "signal.h") -check_type_size("sig_atomic_t" BITSIZEOF_SIG_ATOMIC_T) -unset(CMAKE_EXTRA_INCLUDE_FILES) -check_type_size("size_t" BITSIZEOF_SIZE_T) -check_type_size("wchar_t" BITSIZEOF_WCHAR_T) -check_type_size("wint_t" BITSIZEOF_WINT_T) -#CRAY_STACKSEG_END -#C_ALLOCA -#DOUBLE_SLASH_IS_DISTINCT_ROOT -check_symbol_exists(EILSEQ "errno.h" HAVE_EILSEQ) -if(NOT HAVE_EILSEQ) - set(EILSEQ "ENOENT") -endif() -set(ENABLE_EXTRA ${LIBICONV_ENABLE_EXTRA}) -set(ENABLE_NLS ${LIBICONV_ENABLE_NLS}) -set(ENABLE_RELOCATABLE ${LIBICONV_ENABLE_RELOCATABLE}) -check_c_source_runs(" - #include - static void exception_handler(int sig) { exit (1); } - static void nocrash_init(void) - { - #ifdef SIGSEGV - signal (SIGSEGV, exception_handler); - #endif - #ifdef SIGBUS - signal (SIGBUS, exception_handler); - #endif - } - #include - #include - int main() - { - int result = 0; - { - char *name = realpath(\"${CMAKE_CURRENT_SOURCE_DIR}/CMakeLists.txt\", NULL); - if (!(name && *name == '/')) result |= 1; - } - { - char *name = realpath(\"conftest.b/../conftest.a\", NULL); - if (name != NULL) result |= 2; - } - { - char *name = realpath(\"${CMAKE_CURRENT_SOURCE_DIR}/CMakeLists.txt/\", NULL); - if (name != NULL) result |= 4; - } - { - char *name1 = realpath(\".\", NULL); - char *name2 = realpath(\"${CMAKE_CURRENT_BINARY_DIR}/CMakeFiles//./..\", NULL); - if (strcmp(name1, name2) != 0) result |= 8; - } - return result; - } -" FUNC_REALPATH_WORKS) -set(GNULIB_CANONICALIZE_LGPL ON) -#GNULIB_SIGPIPE -check_c_source_runs(" - #include - int main() { if (!*strerror(-2)) return 1; return 0; } -" GNULIB_STRERROR) -set(GNULIB_TEST_CANONICALIZE_FILE_NAME 1) -set(GNULIB_TEST_ENVIRON ON) -set(GNULIB_TEST_LSTAT ON) -set(GNULIB_TEST_READ ON) -set(GNULIB_TEST_READLINK ON) -set(GNULIB_TEST_REALPATH ON) -set(GNULIB_TEST_SIGPROCMASK ON) -set(GNULIB_TEST_STAT ON) -set(GNULIB_TEST_STRERROR ON) -check_symbol_exists(alloca "alloca.h" HAVE_ALLOCA) -check_include_files(alloca.h HAVE_ALLOCA_H) -#HAVE_CANONICALIZE_FILE_NAME -check_c_source_compiles(" - #include - int main() { CFLocaleCopyCurrent(); return 0; } -" HAVE_CFLOCALECOPYCURRENT) -check_c_source_compiles(" - #include - int main() { CFPreferencesCopyAppValue(NULL, NULL); return 0; } -" HAVE_CFPREFERENCESCOPYAPPVALUE) -check_function_exists(dcgettext HAVE_DCGETTEXT) -check_symbol_exists(clearerr_unlocked "stdio.h" HAVE_DECL_CLEARERR_UNLOCKED) -check_symbol_exists(feof_unlocked "stdio.h" HAVE_DECL_FEOF_UNLOCKED) -check_symbol_exists(ferror_unlocked "stdio.h" HAVE_DECL_FERROR_UNLOCKED) -check_symbol_exists(fflush_unlocked "stdio.h" HAVE_DECL_FFLUSH_UNLOCKED) -check_symbol_exists(fgets_unlocked "stdio.h" HAVE_DECL_FGETS_UNLOCKED) -check_symbol_exists(fputc_unlocked "stdio.h" HAVE_DECL_FPUTC_UNLOCKED) -check_symbol_exists(fputs_unlocked "stdio.h" HAVE_DECL_FPUTS_UNLOCKED) -check_symbol_exists(fread_unlocked "stdio.h" HAVE_DECL_FREAD_UNLOCKED) -check_symbol_exists(fwrite_unlocked "stdio.h" HAVE_DECL_FWRITE_UNLOCKED) -check_symbol_exists(getchar_unlocked "stdio.h" HAVE_DECL_GETCHAR_UNLOCKED) -check_symbol_exists(getc_unlocked "stdio.h" HAVE_DECL_GETC_UNLOCKED) -check_symbol_exists(program_invocation_name "errno.h" HAVE_DECL_PROGRAM_INVOCATION_NAME) -check_symbol_exists(program_invocation_short_name "errno.h" HAVE_DECL_PROGRAM_INVOCATION_SHORT_NAME) -check_symbol_exists(putchar_unlocked "stdio.h" HAVE_DECL_PUTCHAR_UNLOCKED) -check_symbol_exists(putc_unlocked "stdio.h" HAVE_DECL_PUTC_UNLOCKED) -check_symbol_exists(setenv "stdlib.h" HAVE_DECL_SETENV) -check_symbol_exists(strerror_r "string.h" HAVE_DECL_STRERROR_R) -check_include_files(dlfcn.h HAVE_DLFCN_H) -check_c_source_compiles(" - #include - extern struct { int foo; } environ; - int main() { environ.foo = 1; return 0; } -" HAVE_ENVIRON_DECL) -check_function_exists(getcwd HAVE_GETCWD) -check_function_exists(getc_unlocked HAVE_GETC_UNLOCKED) -check_function_exists(iconv HAVE_ICONV) -check_include_files(inttypes.h HAVE_INTTYPES_H) -check_c_source_compiles(" - #include - int main() { char* cs = nl_langinfo(CODESET); return !cs; } -" HAVE_LANGINFO_CODESET) -check_type_size("long long int" LONG_LONG_INT) -check_function_exists(lstat HAVE_LSTAT) -check_include_files(mach-o/dyld.h HAVE_MACH_O_DYLD_H) -check_function_exists(mbrtowc HAVE_MBRTOWC) -check_function_exists(mbsinit HAVE_MBSINIT) -check_c_source_compiles(" - #include - #include - #include - #include - int main() { mbstate_t x; return sizeof x; } -" HAVE_MBSTATE_T) -check_function_exists(memmove HAVE_MEMMOVE) -check_include_files(memory.h HAVE_MEMORY_H) -foreach( - FUNCTION - "chown" "dup2" "dup3" "endusershell" "environ" "euidaccess" "faccessat" "fchdir" - "fchownat" "fsync" "ftruncate" "getcwd" "getdomainname" "getdtablesize" "getgroups" - "gethostname" "getlogin" "getlogin_r" "getpagesize" "getusershell" "group_member" "lchown" - "link" "linkat" "lseek" "pipe" "pipe2" "pread" "pwrite" "readlink" "readlinkat" "rmdir" - "setusershell" "sleep" "symlink" "symlinkat" "ttyname_r" "unlink" "unlinkat" "usleep" -) - string(TOUPPER ${FUNCTION} FUNCTION_UPPER) - check_c_source_compiles(" - #include - #if !(defined(__GLIBC__) && !defined(__UCLIBC__)) - #include - #include - #include - #if (defined(_WIN32) || defined(__WIN32__)) && !defined(__CYGWIN__) - #include - #endif - #endif - int main () { - #undef ${FUNCTION} - (void) ${FUNCTION}; return 0; - } - " HAVE_RAW_DECL_${FUNCTION_UPPER}) -endforeach() -foreach(FUNCTION "dprintf" "fpurge" "fseeko" "ftello" "getdelim" "getline" "popen" "renameat" "snprintf" "tmpfile" "vdprintf" "vsnprintf") - string(TOUPPER ${FUNCTION} FUNCTION_UPPER) - check_raw_symbol_exists(${FUNCTION} "stdio.h" HAVE_RAW_DECL_${FUNCTION_UPPER}) -endforeach() -foreach(FUNCTION "fchmodat" "fstatat" "futimens" "lchmod" "lstat" "mkdirat" "mkfifo" "mkfifoat" "mknod" "mknodat" "stat" "utimensat") - string(TOUPPER ${FUNCTION} FUNCTION_UPPER) - check_raw_symbol_exists(${FUNCTION} "sys/stat.h" HAVE_RAW_DECL_${FUNCTION_UPPER}) -endforeach() -foreach(FUNCTION "fcntl" "openat") - string(TOUPPER ${FUNCTION} FUNCTION_UPPER) - check_raw_symbol_exists(${FUNCTION} "fcntl.h" HAVE_RAW_DECL_${FUNCTION_UPPER}) -endforeach() -foreach(FUNCTION "ffsl" "ffsll" "memmem" "mempcpy" "memrchr" "rawmemchr" "stpcpy" "stpncpy" "strcasestr" "strchrnul" "strdup" "strerror_r" "strncat" "strndup" "strnlen" "strpbrk" "strsep" "strsignal" "strtok_r" "strverscmp") - string(TOUPPER ${FUNCTION} FUNCTION_UPPER) - check_raw_symbol_exists(${FUNCTION} "string.h" HAVE_RAW_DECL_${FUNCTION_UPPER}) -endforeach() -foreach(FUNCTION "pthread_sigmask" "sigaction" "sigaddset" "sigdelset" "sigemptyset" "sigfillset" "sigismember" "sigpending" "sigprocmask") - string(TOUPPER ${FUNCTION} FUNCTION_UPPER) - check_raw_symbol_exists(${FUNCTION} "signal.h" HAVE_RAW_DECL_${FUNCTION_UPPER}) -endforeach() -check_function_exists(readlink HAVE_READLINK) -check_function_exists(readlinkat HAVE_READLINKAT) -check_function_exists(realpath HAVE_REALPATH) -check_include_files(search.h HAVE_SEARCH_H) -check_function_exists(setenv HAVE_SETENV) -check_function_exists(setlocale HAVE_SETLOCALE) -#HAVE_SIGNED_SIG_ATOMIC_T -#HAVE_SIGNED_WCHAR_T -#HAVE_SIGNED_WINT_T -check_symbol_exists(sigset_t "signal.h;sys/types.h" HAVE_SIGSET_T) -check_include_files(stdint.h HAVE_STDINT_H) -check_include_files(stdlib.h HAVE_STDLIB_H) -check_function_exists(strerror_r HAVE_STRERROR_R) -check_include_files(strings.h HAVE_STRINGS_H) -check_include_files(string.h HAVE_STRING_H) -check_include_files(sys/bitypes.h HAVE_SYS_BITYPES_H) -check_include_files(sys/inttypes.h HAVE_SYS_INTTYPES_H) -check_include_files(sys/loadavg.h HAVE_SYS_LOADAVG_H) -check_include_files(sys/param.h HAVE_SYS_PARAM_H) -check_include_files(sys/socket.h HAVE_SYS_SOCKET_H) -check_include_files(sys/stat.h HAVE_SYS_STAT_H) -check_include_files(sys/time.h HAVE_SYS_TIME_H) -check_include_files(sys/types.h HAVE_SYS_TYPES_H) -check_function_exists(tsearch HAVE_TSEARCH) -check_include_files(unistd.h HAVE_UNISTD_H) -check_type_size("unsigned long long int" UNSIGNED_LONG_LONG_INT) -check_c_compiler_flag("-fvisibility=hidden -Werror" HAVE_VISIBILITY) -check_include_files(wchar.h HAVE_WCHAR_H) -check_type_size(wchar_t WCHAR_T) -check_function_exists(wcrtomb HAVE_WCRTOMB) -check_include_files(winsock2.h HAVE_WINSOCK2_H) -check_c_source_runs(" - #include - #include - #include - #include - #ifndef O_NOATIME - #define O_NOATIME 0 - #endif - #ifndef O_NOFOLLOW - #define O_NOFOLLOW 0 - #endif - static int const constants[] = { O_CREAT, O_EXCL, O_NOCTTY, O_TRUNC, O_APPEND, O_NONBLOCK, O_SYNC, O_ACCMODE, O_RDONLY, O_RDWR, O_WRONLY }; - int main() - { - int status = !constants; - { - static char const sym[] = \"conftest.sym\"; - if (symlink(\".\", sym) != 0 || close(open(sym, O_RDONLY | O_NOFOLLOW)) == 0) - status |= 32; - unlink(sym); - } - { - static char const file[] = \"${CMAKE_CURRENT_SOURCE_DIR}/CMakeLists.txt\"; - int fd = open(file, O_RDONLY | O_NOATIME); - char c; struct stat st0, st1; - if (fd < 0 || fstat(fd, &st0) != 0 || sleep(1) != 0 || read(fd, &c, 1) != 1 || close(fd) != 0 || stat(file, &st1) != 0 || st0.st_atime != st1.st_atime) - status |= 64; - } - return status; - } -" HAVE_WORKING_O_NOATIME_O_NOFOLLOW) -if(HAVE_WORKING_O_NOATIME_O_NOFOLLOW) - set(HAVE_WORKING_O_NOATIME 1) - set(HAVE_WORKING_O_NOFOLLOW 1) -elseif(HAVE_WORKING_O_NOATIME_O_NOFOLLOW_EXITCODE EQUAL "32") - set(HAVE_WORKING_O_NOATIME 1) - set(HAVE_WORKING_O_NOFOLLOW 0) -elseif(HAVE_WORKING_O_NOATIME_O_NOFOLLOW_EXITCODE EQUAL "64") - set(HAVE_WORKING_O_NOATIME 0) - set(HAVE_WORKING_O_NOFOLLOW 1) -else() - set(HAVE_WORKING_O_NOATIME 0) - set(HAVE_WORKING_O_NOFOLLOW 0) -endif() -check_type_size("_Bool" _BOOL) -check_c_source_compiles(" - #include - int main() { _NSGetExecutablePath(NULL, NULL); return 0; } -" HAVE__NSGETEXECUTABLEPATH) -check_c_source_compiles(" - #include - #include - extern - #ifdef __cplusplus - \"C\" - #endif - #if defined(__STDC__) || defined(__cplusplus) - size_t iconv(iconv_t cd, char** inbuf, size_t* inbytesleft, char** outbuf, size_t* outbytesleft); - #else - size_t iconv(); - #endif - int main() { return 0; } -" ICONV_CONST_TEST) -if(NOT ICONV_CONST_TEST) - set(ICONV_CONST "const") -endif() -set(INSTALLPREFIX ${CMAKE_INSTALL_PREFIX}) -if(UNIX) - execute_process(COMMAND "${CMAKE_COMMAND}" "-E" "create_symlink" "${CMAKE_CURRENT_SOURCE_DIR}/CMakeLists.txt" "${CMAKE_CURRENT_BINARY_DIR}/conftest.sym") - check_c_source_runs(" - #include - int main() { struct stat sbuf; return lstat(\"${CMAKE_CURRENT_BINARY_DIR}/conftest.sym/\", &sbuf) == 0; } - " LSTAT_FOLLOWS_SLASHED_SYMLINK) -endif() -#LT_OBJDIR -#NO_MINUS_C_MINUS_O -set(PACKAGE "libiconv") -set(PACKAGE_BUGREPORT "bug-gnu-libiconv@gnu.org") -set(PACKAGE_NAME "libiconv") -set(PACKAGE_STRING "libiconv ${VERSION}") -set(PACKAGE_TARNAME "libiconv") -set(PACKAGE_URL "https://www.gnu.org/software/libiconv/") -set(PACKAGE_VERSION ${VERSION}) -#PTRDIFF_T_SUFFIX -#READLINK_TRAILING_SLASH_BUG -check_c_source_runs(" - #include - #include - int main() { - int result = 0; - char *str; errno = 0; str = strerror(0); - if (!*str) result |= 1; - if (errno) result |= 2; - if (strstr(str, \"nknown\") || strstr(str, \"ndefined\")) result |= 4; - return result; - } -" HAVE_WORKING_STRERROR_0) -if(HAVE_WORKING_STRERROR_0) - set(REPLACE_STRERROR_0 OFF) -else() - set(REPLACE_STRERROR_0 ON) -endif() -#SIG_ATOMIC_T_SUFFIX -#SIZE_T_SUFFIX -#STACK_DIRECTION -check_c_source_compiles(" - #include - #include - #if defined(S_ISBLK) && defined(S_IFDIR) - extern char c1[S_ISBLK (S_IFDIR) ? -1 : 1]; - #endif - #if defined(S_ISBLK) && defined(S_IFCHR) - extern char c2[S_ISBLK (S_IFCHR) ? -1 : 1]; - #endif - #if defined(S_ISLNK) && defined(S_IFREG) - extern char c3[S_ISLNK (S_IFREG) ? -1 : 1]; - #endif - #if defined(S_ISSOCK) && defined(S_IFREG) - extern char c4[S_ISSOCK (S_IFREG) ? -1 : 1]; - #endif - int main() { return 0; } -" STAT_MACROS_WORKING) -if(STAT_MACROS_WORKING) - set(STAT_MACROS_BROKEN OFF) -else() - set(STAT_MACROS_BROKEN ON) -endif() -check_include_files("assert.h;ctype.h;errno.h;float.h;limits.h;locale.h;math.h;setjmp.h;signal.h;stdarg.h;stddef.h;stdio.h;stdlib.h;string.h;time.h" STDC_HEADERS) -check_c_source_runs(" - extern char *strerror_r(); - int main() { char buf[100]; char x = *strerror_r(0, buf, sizeof buf); return !isalpha(x); } -" STRERROR_R_CHAR_P) -#USER_LABEL_PREFIX -#USE_UNLOCKED_IO -#WCHAR_T_SUFFIX -#WINT_T_SUFFIX -test_big_endian(WORDS_BIGENDIAN) -if(WORDS_BIGENDIAN) - set(WORDS_LITTLEENDIAN OFF) -else() - set(WORDS_LITTLEENDIAN ON) -endif() -check_include_files(minix/config.h HAVE_MINIX_CONFIG_H) -#_XOPEN_SOURCE -set(_ALL_SOURCE ON) -set(_DARWIN_C_SOURCE ON) -set(_GNU_SOURCE ON) -set(_POSIX_PTHREAD_SEMANTICS ON) -set(_TANDEM_SOURCE ON) -check_c_source_compiles(" - #define __EXTENSIONS__ 1 - int main() { return 0; } -" __EXTENSIONS__) -check_type_size("gid_t" GID_T) -if(NOT HAVE_GID_T) - set(gid_t "int") -endif() -set(inline "") -foreach(INLINE_KEYWORD "__inline" "__inline__" "inline") - check_c_source_compiles(" - typedef int foo_t; - static ${INLINE_KEYWORD} foo_t static_foo() { return 0; } - ${INLINE_KEYWORD} foo_t foo() { return 0; } - int main() { return 0; } - " HAVE_INLINE_KEYWORD) - if(HAVE_INLINE_KEYWORD) - set(inline ${INLINE_KEYWORD}) - endif() -endforeach() -if("x${inline}" STREQUAL "xinline") - unset(inline) -endif() -if(NOT HAVE_MBSTATE_T) - set(mbstate_t "int") -endif() -check_type_size("nlink_t" NLINK_T) -if(NOT HAVE_NLINK_T) - set(NLINK_T "int") -endif() -set(restrict "") -foreach(RESTRICT_KEYWORD "__restrict" "__restrict__" "_Restrict" "restrict") - check_c_source_compiles(" - typedef int* int_ptr; - int foo (int_ptr ${RESTRICT_KEYWORD} ip) { return ip[0]; } - int main() { int s[1]; int* ${RESTRICT_KEYWORD} t = s; t[0] = 0; return foo(t); } - " HAVE_RESTRICT_KEYWORD) - if(HAVE_RESTRICT_KEYWORD) - set(restrict ${RESTRICT_KEYWORD}) - endif() -endforeach() -if("x${restrict}" STREQUAL "xrestrict") - unset(restrict) -endif() -check_type_size("size_t" SIZE_T) -if(NOT HAVE_SIZE_T) - set(size_t "unsigned int") -endif() -check_type_size("ssize_t" SSIZE_T) -if(NOT HAVE_SSIZE_T) - set(ssize_t "int") -endif() -check_type_size("uid_t" UID_T) -if(NOT HAVE_UID_T) - set(uid_t "int") -endif() - -if(HAVE_LSTAT) - if(UNIX) - execute_process(COMMAND "${CMAKE_COMMAND}" "-E" "create_symlink" "${CMAKE_CURRENT_SOURCE_DIR}/CMakeLists.txt" "${CMAKE_CURRENT_BINARY_DIR}/conftest.sym") - endif() - list(APPEND CMAKE_REQUIRED_DEFINITIONS -DHAVE_LSTAT) -endif() -check_c_source_runs(" - #include - int main() { - int result = 0; - struct stat st; - if (!stat(\"${CMAKE_CURRENT_SOURCE_DIR}/CMakeLists.txt/\", &st)) result |= 1; - #if HAVE_LSTAT - if (!stat(\"${CMAKE_CURRENT_BINARY_DIR}/conftest.sym/\", &st)) result |= 2; - #endif - return result; - } -" HAVE_WORKING_FUNC_STAT_DIR_FILE) -if(HAVE_WORKING_FUNC_STAT_DIR_FILE) - set(REPLACE_FUNC_STAT_DIR OFF) - set(REPLACE_FUNC_STAT_FILE OFF) -else() - set(REPLACE_FUNC_STAT_DIR ON) - set(REPLACE_FUNC_STAT_FILE ON) -endif() -unset(CMAKE_REQUIRED_DEFINITIONS) - -foreach( - FUNCTION - "_Exit" "atoll" "canonicalize_file_name" "getloadavg" "getsubopt" "grantpt" "initstat_r" - "mkdtemp" "mkostemp" "mkostemps" "mkstemp" "mkstemps" "ptsname" "random_r" "realpath" - "rpmatch" "setenv" "setstate_r" "srandom_r" "strtod" "strtoll" "strtoull" "unlockpt" "unsetenv" -) - string(TOUPPER ${FUNCTION} FUNCTION_UPPER) - set(FILES "stdlib.h") - if(HAVE_SYS_LOADAVG_H) - list(APPEND FILES "sys/loadavg.h") - endif() - if(HAVE_RANDOM_H) - list(APPEND FILES "random.h") - endif() - check_raw_symbol_exists(${FUNCTION} ${FILES} HAVE_RAW_DECL_${FUNCTION_UPPER}) -endforeach() - -if(STDC_HEADERS) - list(APPEND CMAKE_REQUIRED_DEFINITIONS -DSTDC_HEADERS) -endif() -if(HAVE_STDLIB_H) - list(APPEND CMAKE_REQUIRED_DEFINITIONS -DHAVE_STDLIB_H) -endif() -check_c_source_compiles(" - #if defined(STDC_HEADERS) || defined(HAVE_STDLIB_H) - #include - #endif - int main() { return !malloc(0); } -" MALLOC_0_IS_NONNULL) -unset(CMAKE_REQUIRED_DEFINITIONS) - -if(HAVE_MINIX_CONFIG_H) - set(_MINIX ON) - set(_POSIX_1_SOURCE ON) - set(_POSIX_SOURCE ON) -endif() - -configure_file(config.h.cmake.in config.h @ONLY) - -if(HAVE_MBSTATE_T) - set(USE_MBSTATE_T 1) -else() - set(USE_MBSTATE_T 0) -endif() - -if(HAVE_VISIBILTY) - list(APPEND CMAKE_C_FLAGS "-fvisibility=hidden") - list(APPEND CMAKE_CXX_FLAGS "-fvisibility=hidden") - set(HAVE_VISIBILITY 1) -else() - set(HAVE_VISIBILITY 0) -endif() - -if(HAVE_WCHAR_T) - set(BROKEN_WCHAR_H 0) - set(HAVE_WCHAR_T 1) -else() - set(BROKEN_WCHAR_H 1) - set(HAVE_WCHAR_T 0) -endif() - -if(HAVE_WINSOCK2_H) - set(UNISTD_H_HAVE_WINSOCK2_H 1) - set(SYS_IOCTL_H_HAVE_WINSOCK2_H 1) -else() - set(UNISTD_H_HAVE_WINSOCK2_H 0) - set(SYS_IOCTL_H_HAVE_WINSOCK2_H 0) -endif() - -configure_file(include/iconv.h.build.in include/iconv.h @ONLY) -configure_file(libcharset/include/localcharset.h.build.in include/localcharset.h @ONLY) - -if(BUILD_SHARED_LIBS AND MSVC) - set(DLL_VARIABLE "__declspec (dllimport)") -endif() - -configure_file(include/iconv.h.in include/iconv.h.inst @ONLY) -configure_file(libcharset/include/libcharset.h.in include/libcharset.h @ONLY) - -add_library( - Charset - libcharset/lib/localcharset.c - libcharset/lib/relocatable.c -) - -target_compile_definitions( - Charset - PRIVATE - BUILDING_LIBCHARSET - HAVE_CONFIG_H - IN_LIBRARY - INSTALLDIR="${CMAKE_INSTALL_LIBDIR}" - LIBDIR="${CMAKE_INSTALL_LIBDIR}" - NO_XMALLOC - relocate=libcharset_relocate - set_relocation_prefix=libcharset_set_relocation_prefix -) - -if(BUILD_SHARED_LIBS) - target_compile_definitions(Charset PRIVATE _DLL BUILDING_DLL) -endif() - -if(LIBICONV_ENABLE_EXTRA) - target_compile_definitions(Charset PRIVATE ENABLE_EXTRA=1) -else() - target_compile_definitions(Charset PRIVATE ENABLE_EXTRA=0) -endif() - -if(LIBICONV_ENABLE_NLS) - target_compile_definitions(Charset PRIVATE ENABLE_NLS=1) -else() - target_compile_definitions(Charset PRIVATE ENABLE_NLS=0) -endif() - -if(LIBICONV_ENABLE_RELOCATABLE) - target_compile_definitions(Charset PRIVATE ENABLE_RELOCATABLE=1) -else() - target_compile_definitions(Charset PRIVATE ENABLE_RELOCATABLE=0) -endif() - -target_include_directories( - Charset - PUBLIC - $ - $ - $/${CMAKE_INSTALL_INCLUDEDIR}> -) - -set_target_properties( - Charset - PROPERTIES - IMPORT_PREFIX lib - OUTPUT_NAME charset - POSITION_INDEPENDENT_CODE ON - PREFIX lib - VERSION ${VERSION} -) - -if(WIN32) - if(BUILD_SHARED_LIBS) - set_target_properties( - Charset - PROPERTIES - DEBUG_POSTFIX d - ) - else() - set_target_properties( - Charset - PROPERTIES - DEBUG_POSTFIX sd - MINSIZEREL_POSTFIX s - RELEASE_POSTFIX s - RELWITHDEBINFO_POSTFIX s - ) - endif() -endif() - -add_library( - Iconv - lib/iconv.c - lib/relocatable.c - libcharset/lib/localcharset.c -) - -target_compile_definitions( - Iconv - PRIVATE - BUILDING_LIBICONV - HAVE_CONFIG_H - IN_LIBRARY - INSTALLDIR="${CMAKE_INSTALL_LIBDIR}" - LIBDIR="${CMAKE_INSTALL_LIBDIR}" - NO_XMALLOC - relocate=libiconv_relocate - set_relocation_prefix=libiconv_set_relocation_prefix -) - -if(BUILD_SHARED_LIBS) - target_compile_definitions(Iconv PRIVATE _DLL BUILDING_DLL) -endif() - -if(LIBICONV_ENABLE_EXTRA) - target_compile_definitions(Iconv PRIVATE ENABLE_EXTRA=1) -else() - target_compile_definitions(Iconv PRIVATE ENABLE_EXTRA=0) -endif() - -if(LIBICONV_ENABLE_NLS) - target_compile_definitions(Iconv PRIVATE ENABLE_NLS=1) -else() - target_compile_definitions(Iconv PRIVATE ENABLE_NLS=0) -endif() - -if(LIBICONV_ENABLE_RELOCATABLE) - target_compile_definitions(Iconv PRIVATE ENABLE_RELOCATABLE=1) -else() - target_compile_definitions(Iconv PRIVATE ENABLE_RELOCATABLE=0) -endif() - -target_include_directories( - Iconv - PUBLIC - $ - $ - $/${CMAKE_INSTALL_INCLUDEDIR}> -) - -target_link_libraries(Iconv Charset) - -set_target_properties( - Iconv - PROPERTIES - IMPORT_PREFIX lib - OUTPUT_NAME iconv - POSITION_INDEPENDENT_CODE ON - PREFIX lib - VERSION ${VERSION} -) - -if(WIN32) - if(BUILD_SHARED_LIBS) - set_target_properties( - Iconv - PROPERTIES - DEBUG_POSTFIX d - ) - else() - set_target_properties( - Iconv - PROPERTIES - DEBUG_POSTFIX sd - MINSIZEREL_POSTFIX s - RELEASE_POSTFIX s - RELWITHDEBINFO_POSTFIX s - ) - endif() -endif() - -install(FILES ${CMAKE_CURRENT_BINARY_DIR}/include/iconv.h.inst DESTINATION ${CMAKE_INSTALL_INCLUDEDIR} RENAME iconv.h COMPONENT development) - -install( - TARGETS Charset Iconv - EXPORT Iconv - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime -) - -if(BUILD_SHARED_LIBS) - install( - TARGETS Charset Iconv - EXPORT Iconv - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY - ) -endif() - -if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) - install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) - install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) -endif() - -#configure_file(srclib/stdbool.in.h include/stdbool.h @ONLY) -#configure_file(srclib/unistd.in.h include/unistd.h @ONLY) -#configure_file(srclib/unitypes.in.h include/unitypes.h @ONLY) -#configure_file(srclib/uniwidth.in.h include/uniwidth.h @ONLY) -# -#add_executable( -# iconv -# src/iconv.c -# srclib/allocator.c -# srclib/areadlink.c -# srclib/canonicalize-lgpl.c -# srclib/careadlinkat.c -# srclib/c-ctype.c -# srclib/error.c -# srclib/lstat.c -# srclib/malloca.c -# srclib/memmove.c -# srclib/progname.c -# srclib/progreloc.c -# srclib/read.c -# srclib/readlink.c -# srclib/relocwrapper.c -# srclib/safe-read.c -# srclib/setenv.c -# srclib/sigprocmask.c -# srclib/stat.c -# srclib/stdio-write.c -# srclib/strerror.c -# srclib/strerror-override.c -# srclib/xmalloc.c -# srclib/xreadlink.c -# srclib/xstrdup.c -#) -# -#target_compile_definitions( -# iconv -# PRIVATE -# EXEEXT="${CMAKE_EXECUTABLE_SUFFIX}" -# INSTALLDIR="${CMAKE_INSTALL_BINDIR}" -# INSTALLPREFIX="${CMAKE_INSTALL_PREFIX}" -# LIBPATHVAR="" -# LIBDIRS="" -# LOCALEDIR="${CMAKE_INSTALL_LOCALEDIR}" -# NO_XMALLOC -#) -# -#if(LIBICONV_ENABLE_EXTRA) -# target_compile_definitions(iconv PRIVATE ENABLE_EXTRA=1) -#else() -# target_compile_definitions(iconv PRIVATE ENABLE_EXTRA=0) -#endif() -# -#if(LIBICONV_ENABLE_NLS) -# target_compile_definitions(iconv PRIVATE ENABLE_NLS=1) -#else() -# target_compile_definitions(iconv PRIVATE ENABLE_NLS=0) -#endif() -# -#if(LIBICONV_ENABLE_RELOCATABLE) -# target_compile_definitions(iconv PRIVATE ENABLE_RELOCATABLE=1) -#else() -# target_compile_definitions(iconv PRIVATE ENABLE_RELOCATABLE=0) -#endif() -# -#target_include_directories( -# iconv -# PUBLIC -# $ -# $ -# $ -#) -# -#target_link_libraries(iconv Iconv) -# -#install( -# TARGETS iconv -# COMPONENT programs -# ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} -# LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} -# RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} -#) - -install(FILES man/iconv.1 DESTINATION ${CMAKE_INSTALL_MANDIR}/man1 COMPONENT documentation) -install(FILES man/iconv.3 DESTINATION ${CMAKE_INSTALL_MANDIR}/man3 COMPONENT documentation) -install(FILES man/iconv_close.3 DESTINATION ${CMAKE_INSTALL_MANDIR}/man3 COMPONENT documentation) -install(FILES man/iconv_open.3 DESTINATION ${CMAKE_INSTALL_MANDIR}/man3 COMPONENT documentation) -install(FILES man/iconv_open_into.3 DESTINATION ${CMAKE_INSTALL_MANDIR}/man3 COMPONENT documentation) -install(FILES man/iconvctl.3 DESTINATION ${CMAKE_INSTALL_MANDIR}/man3 COMPONENT documentation) - -install(FILES man/iconv.1.html DESTINATION ${CMAKE_INSTALL_DATADIR}/doc/libiconv COMPONENT documentation) -install(FILES man/iconv.3.html DESTINATION ${CMAKE_INSTALL_DATADIR}/doc/libiconv COMPONENT documentation) -install(FILES man/iconv_close.3.html DESTINATION ${CMAKE_INSTALL_DATADIR}/doc/libiconv COMPONENT documentation) -install(FILES man/iconv_open.3.html DESTINATION ${CMAKE_INSTALL_DATADIR}/doc/libiconv COMPONENT documentation) -install(FILES man/iconv_open_into.3.html DESTINATION ${CMAKE_INSTALL_DATADIR}/doc/libiconv COMPONENT documentation) -install(FILES man/iconvctl.3.html DESTINATION ${CMAKE_INSTALL_DATADIR}/doc/libiconv COMPONENT documentation) - -configure_package_config_file( - iconv-config.cmake.in iconv-config.cmake - INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/iconv-${VERSION} -) - -install( - FILES ${CMAKE_CURRENT_BINARY_DIR}/iconv-config.cmake - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/iconv-${VERSION} -) - -write_basic_package_version_file( - ${CMAKE_CURRENT_BINARY_DIR}/iconv-config-version.cmake - VERSION ${VERSION} - COMPATIBILITY ExactVersion -) - -install( - FILES ${CMAKE_CURRENT_BINARY_DIR}/iconv-config-version.cmake - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/iconv-${VERSION} - COMPONENT development -) - -install( - EXPORT Iconv - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/iconv-${VERSION} - NAMESPACE Iconv:: - FILE iconv-export.cmake - COMPONENT development -) - -set(CPACK_COMPONENT_DEVELOPMENT_DEPENDS runtime) -set(CPACK_DEB_COMPONENT_INSTALL ON) -set(CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "${PACKAGE_TARNAME}") -set(CPACK_DEBIAN_DEVELOPMENT_PACKAGE_NAME "libiconv-dev") -set(CPACK_DEBIAN_DEVELOPMENT_PACKAGE_SECTION "libdevel") -set(CPACK_DEBIAN_DOCUMENTATION_PACKAGE_NAME "libiconv-doc") -set(CPACK_DEBIAN_DOCUMENTATION_PACKAGE_SECTION "doc") -set(CPACK_DEBIAN_PACKAGE_HOMEPAGE ${PACKAGE_URL}) -set(CPACK_DEBIAN_PACKAGE_NAME ${PACKAGE_TARNAME}) -set(CPACK_DEBIAN_PACKAGE_SECTION "devel") -#set(CPACK_DEBIAN_PROGRAMS_PACKAGE_DEPENDS "${PACKAGE_TARNAME}") -#set(CPACK_DEBIAN_PROGRAMS_PACKAGE_NAME "${PACKAGE_TARNAME}-utils") -#set(CPACK_DEBIAN_PROGRAMS_PACKAGE_SECTION "utils") -set(CPACK_DEBIAN_RUNTIME_PACKAGE_NAME "${PACKAGE_TARNAME}") -#set(CPACK_DEBIAN_RUNTIME_PACKAGE_RECOMMENDS "${PACKAGE_TARNAME}-programs") -set(CPACK_DEBIAN_RUNTIME_PACKAGE_SECTION "libs") -set(CPACK_NSIS_PACKAGE_NAME ${PACKAGE_STRING}) -set(CPACK_NSIS_URL_INFO_ABOUT ${PACKAGE_URL}) -set(CPACK_PACKAGE_CONTACT ${PACKAGE_BUGREPORT}) -set(CPACK_PACKAGE_DISPLAY_NAME ${PACKAGE_STRING}) -set(CPACK_PACKAGE_INSTALL_DIRECTORY "${PACKAGE_TARNAME}-${PACKAGE_VERSION}") -set(CPACK_PACKAGE_NAME ${PACKAGE_TARNAME}) -set(CPACK_PACKAGE_VERSION ${PACKAGE_VERSION}) -set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) -set(CPACK_PACKAGE_VERSION_MINOR ${VERSION_MINOR}) -set(CPACK_RESOURCE_FILE_LICENSE ${CMAKE_CURRENT_SOURCE_DIR}/COPYING) -set(CPACK_RPM_COMPONENT_INSTALL ON) -set(CPACK_RPM_development_PACKAGE_NAME "${PACKAGE_TARNAME}-devel") -set(CPACK_RPM_development_PACKAGE_REQUIRES "${PACKAGE_TARNAME}") -set(CPACK_RPM_PACKAGE_GROUP "Development/Libraries") -set(CPACK_RPM_PACKAGE_LICENSE "GPL") -set(CPACK_RPM_PACKAGE_NAME ${PACKAGE_TARNAME}) -set(CPACK_RPM_PACKAGE_URL ${PACKAGE_URL}) -set(CPACK_RPM_programs_PACKAGE_NAME "${PACKAGE_NAME}-utils") -set(CPACK_RPM_programs_PACKAGE_REQUIRES "${PACKAGE_NAME}") -#set(CPACK_RPM_runtime_PACKAGE_SUGGESTS "${PACKAGE_NAME}-utils") - -if(WIN32 AND CMAKE_SIZEOF_VOID_P EQUAL 8) - set(CPACK_NSIS_INSTALL_ROOT "$PROGRAMFILES64") -endif() - -include(CPack) diff --git a/3rdparty/libiconv/config.h.cmake.in b/3rdparty/libiconv/config.h.cmake.in deleted file mode 100644 index 1137ef93..00000000 --- a/3rdparty/libiconv/config.h.cmake.in +++ /dev/null @@ -1,926 +0,0 @@ -/* config.h.in. Generated from configure.ac by autoheader. */ - -/* Define to the number of bits in type 'ptrdiff_t'. */ -#cmakedefine BITSIZEOF_PTRDIFF_T @BITSIZEOF_PTRDIFF_T@ - -/* Define to the number of bits in type 'sig_atomic_t'. */ -#cmakedefine BITSIZEOF_SIG_ATOMIC_T @BITSIZEOF_SIG_ATOMIC_T@ - -/* Define to the number of bits in type 'size_t'. */ -#cmakedefine BITSIZEOF_SIZE_T @BITSIZEOF_SIZE_T@ - -/* Define to the number of bits in type 'wchar_t'. */ -#cmakedefine BITSIZEOF_WCHAR_T @BITSIZEOF_WCHAR_T@ - -/* Define to the number of bits in type 'wint_t'. */ -#cmakedefine BITSIZEOF_WINT_T @BITSIZEOF_WINT_T@ - -/* Define to one of `_getb67', `GETB67', `getb67' for Cray-2 and Cray-YMP - systems. This function is required for `alloca.c' support on those systems. - */ -#cmakedefine CRAY_STACKSEG_END @CRAY_STACKSEG_END@ - -/* Define to 1 if using `alloca.c'. */ -#cmakedefine C_ALLOCA 1 - -/* Define to 1 if // is a file system root distinct from /. */ -#cmakedefine DOUBLE_SLASH_IS_DISTINCT_ROOT 1 - -/* Define as good substitute value for EILSEQ. */ -#cmakedefine EILSEQ @ELISEQ@ - -/* Define to 1 to enable a few rarely used encodings. */ -#cmakedefine ENABLE_EXTRA 1 - -/* Define to 1 if translation of program messages to the user's native - language is requested. */ -#cmakedefine ENABLE_NLS 1 - -/* Define to 1 if the package shall run at any location in the file system. */ -#cmakedefine ENABLE_RELOCATABLE 1 - -/* Define to 1 if realpath() can malloc memory, always gives an absolute path, - and handles trailing slash correctly. */ -#cmakedefine FUNC_REALPATH_WORKS 1 - -/* Define to a C preprocessor expression that evaluates to 1 or 0, depending - whether the gnulib module canonicalize-lgpl shall be considered present. */ -#cmakedefine GNULIB_CANONICALIZE_LGPL 1 - -/* Define to a C preprocessor expression that evaluates to 1 or 0, depending - whether the gnulib module sigpipe shall be considered present. */ -#cmakedefine GNULIB_SIGPIPE 1 - -/* Define to a C preprocessor expression that evaluates to 1 or 0, depending - whether the gnulib module strerror shall be considered present. */ -#cmakedefine GNULIB_STRERROR 1 - -/* Define to 1 when the gnulib module canonicalize_file_name should be tested. - */ -#cmakedefine GNULIB_TEST_CANONICALIZE_FILE_NAME @GNULIB_TEST_CANONICALIZE_FILE_NAME@ - -/* Define to 1 when the gnulib module environ should be tested. */ -#cmakedefine GNULIB_TEST_ENVIRON 1 - -/* Define to 1 when the gnulib module lstat should be tested. */ -#cmakedefine GNULIB_TEST_LSTAT 1 - -/* Define to 1 when the gnulib module read should be tested. */ -#cmakedefine GNULIB_TEST_READ 1 - -/* Define to 1 when the gnulib module readlink should be tested. */ -#cmakedefine GNULIB_TEST_READLINK 1 - -/* Define to 1 when the gnulib module realpath should be tested. */ -#cmakedefine GNULIB_TEST_REALPATH 1 - -/* Define to 1 when the gnulib module sigprocmask should be tested. */ -#cmakedefine GNULIB_TEST_SIGPROCMASK 1 - -/* Define to 1 when the gnulib module stat should be tested. */ -#cmakedefine GNULIB_TEST_STAT 1 - -/* Define to 1 when the gnulib module strerror should be tested. */ -#cmakedefine GNULIB_TEST_STRERROR 1 - -/* Define to 1 if you have `alloca', as a function or macro. */ -#cmakedefine HAVE_ALLOCA 1 - -/* Define to 1 if you have and it should be used (not on Ultrix). - */ -#cmakedefine HAVE_ALLOCA_H 1 - -/* Define to 1 if you have the `canonicalize_file_name' function. */ -#cmakedefine HAVE_CANONICALIZE_FILE_NAME 1 - -/* Define to 1 if you have the MacOS X function CFLocaleCopyCurrent in the - CoreFoundation framework. */ -#cmakedefine HAVE_CFLOCALECOPYCURRENT 1 - -/* Define to 1 if you have the MacOS X function CFPreferencesCopyAppValue in - the CoreFoundation framework. */ -#cmakedefine HAVE_CFPREFERENCESCOPYAPPVALUE 1 - -/* Define if the GNU dcgettext() function is already present or preinstalled. - */ -#cmakedefine HAVE_DCGETTEXT 1 - -/* Define to 1 if you have the declaration of `clearerr_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_CLEARERR_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `feof_unlocked', and to 0 if you - don't. */ -#cmakedefine HAVE_DECL_FEOF_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `ferror_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_FERROR_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `fflush_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_FFLUSH_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `fgets_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_FGETS_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `fputc_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_FPUTC_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `fputs_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_FPUTS_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `fread_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_FREAD_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `fwrite_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_FWRITE_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `getchar_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_GETCHAR_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `getc_unlocked', and to 0 if you - don't. */ -#cmakedefine HAVE_DECL_GETC_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `program_invocation_name', and - to 0 if you don't. */ -#cmakedefine HAVE_DECL_PROGRAM_INVOCATION_NAME 1 - -/* Define to 1 if you have the declaration of `program_invocation_short_name', - and to 0 if you don't. */ -#cmakedefine HAVE_DECL_PROGRAM_INVOCATION_SHORT_NAME 1 - -/* Define to 1 if you have the declaration of `putchar_unlocked', and to 0 if - you don't. */ -#cmakedefine HAVE_DECL_PUTCHAR_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `putc_unlocked', and to 0 if you - don't. */ -#cmakedefine HAVE_DECL_PUTC_UNLOCKED 1 - -/* Define to 1 if you have the declaration of `setenv', and to 0 if you don't. - */ -#cmakedefine HAVE_DECL_SETENV 1 - -/* Define to 1 if you have the declaration of `strerror_r', and to 0 if you - don't. */ -#cmakedefine HAVE_DECL_STRERROR_R 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_DLFCN_H 1 - -/* Define if you have the declaration of environ. */ -#cmakedefine HAVE_ENVIRON_DECL 1 - -/* Define to 1 if you have the `getcwd' function. */ -#cmakedefine HAVE_GETCWD 1 - -/* Define to 1 if you have the `getc_unlocked' function. */ -#cmakedefine HAVE_GETC_UNLOCKED 1 - -/* Define if the GNU gettext() function is already present or preinstalled. */ -#cmakedefine HAVE_GETTEXT 1 - -/* Define if you have the iconv() function and it works. */ -#cmakedefine HAVE_ICONV 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_INTTYPES_H 1 - -/* Define if you have and nl_langinfo(CODESET). */ -#cmakedefine HAVE_LANGINFO_CODESET 1 - -/* Define to 1 if the system has the type `long long int'. */ -#cmakedefine HAVE_LONG_LONG_INT 1 - -/* Define to 1 if you have the `lstat' function. */ -#cmakedefine HAVE_LSTAT 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_MACH_O_DYLD_H 1 - -/* Define to 1 if you have the `mbrtowc' function. */ -#cmakedefine HAVE_MBRTOWC 1 - -/* Define to 1 if you have the `mbsinit' function. */ -#cmakedefine HAVE_MBSINIT 1 - -/* Define to 1 if declares mbstate_t. */ -#cmakedefine HAVE_MBSTATE_T 1 - -/* Define to 1 if you have the `memmove' function. */ -#cmakedefine HAVE_MEMMOVE 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_MEMORY_H 1 - -/* Define to 1 if atoll is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_ATOLL 1 - -/* Define to 1 if canonicalize_file_name is declared even after undefining - macros. */ -#cmakedefine HAVE_RAW_DECL_CANONICALIZE_FILE_NAME 1 - -/* Define to 1 if chown is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_CHOWN 1 - -/* Define to 1 if dprintf is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_DPRINTF 1 - -/* Define to 1 if dup2 is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_DUP2 1 - -/* Define to 1 if dup3 is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_DUP3 1 - -/* Define to 1 if endusershell is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_ENDUSERSHELL 1 - -/* Define to 1 if environ is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_ENVIRON 1 - -/* Define to 1 if euidaccess is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_EUIDACCESS 1 - -/* Define to 1 if faccessat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FACCESSAT 1 - -/* Define to 1 if fchdir is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FCHDIR 1 - -/* Define to 1 if fchmodat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FCHMODAT 1 - -/* Define to 1 if fchownat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FCHOWNAT 1 - -/* Define to 1 if fcntl is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FCNTL 1 - -/* Define to 1 if ffsl is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FFSL 1 - -/* Define to 1 if ffsll is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FFSLL 1 - -/* Define to 1 if fpurge is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FPURGE 1 - -/* Define to 1 if fseeko is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FSEEKO 1 - -/* Define to 1 if fstatat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FSTATAT 1 - -/* Define to 1 if fsync is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FSYNC 1 - -/* Define to 1 if ftello is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FTELLO 1 - -/* Define to 1 if ftruncate is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FTRUNCATE 1 - -/* Define to 1 if futimens is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_FUTIMENS 1 - -/* Define to 1 if getcwd is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETCWD 1 - -/* Define to 1 if getdelim is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETDELIM 1 - -/* Define to 1 if getdomainname is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETDOMAINNAME 1 - -/* Define to 1 if getdtablesize is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETDTABLESIZE 1 - -/* Define to 1 if getgroups is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETGROUPS 1 - -/* Define to 1 if gethostname is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETHOSTNAME 1 - -/* Define to 1 if getline is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETLINE 1 - -/* Define to 1 if getloadavg is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETLOADAVG 1 - -/* Define to 1 if getlogin is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETLOGIN 1 - -/* Define to 1 if getlogin_r is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETLOGIN_R 1 - -/* Define to 1 if getpagesize is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETPAGESIZE 1 - -/* Define to 1 if getsubopt is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETSUBOPT 1 - -/* Define to 1 if getusershell is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GETUSERSHELL 1 - -/* Define to 1 if grantpt is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GRANTPT 1 - -/* Define to 1 if group_member is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_GROUP_MEMBER 1 - -/* Define to 1 if initstat_r is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_INITSTAT_R 1 - -/* Define to 1 if lchmod is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_LCHMOD 1 - -/* Define to 1 if lchown is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_LCHOWN 1 - -/* Define to 1 if link is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_LINK 1 - -/* Define to 1 if linkat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_LINKAT 1 - -/* Define to 1 if lseek is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_LSEEK 1 - -/* Define to 1 if lstat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_LSTAT 1 - -/* Define to 1 if memmem is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MEMMEM 1 - -/* Define to 1 if mempcpy is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MEMPCPY 1 - -/* Define to 1 if memrchr is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MEMRCHR 1 - -/* Define to 1 if mkdirat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKDIRAT 1 - -/* Define to 1 if mkdtemp is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKDTEMP 1 - -/* Define to 1 if mkfifo is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKFIFO 1 - -/* Define to 1 if mkfifoat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKFIFOAT 1 - -/* Define to 1 if mknod is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKNOD 1 - -/* Define to 1 if mknodat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKNODAT 1 - -/* Define to 1 if mkostemp is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKOSTEMP 1 - -/* Define to 1 if mkostemps is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKOSTEMPS 1 - -/* Define to 1 if mkstemp is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKSTEMP 1 - -/* Define to 1 if mkstemps is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_MKSTEMPS 1 - -/* Define to 1 if openat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_OPENAT 1 - -/* Define to 1 if pipe is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_PIPE 1 - -/* Define to 1 if pipe2 is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_PIPE2 1 - -/* Define to 1 if popen is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_POPEN 1 - -/* Define to 1 if pread is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_PREAD 1 - -/* Define to 1 if pthread_sigmask is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_PTHREAD_SIGMASK 1 - -/* Define to 1 if ptsname is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_PTSNAME 1 - -/* Define to 1 if pwrite is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_PWRITE 1 - -/* Define to 1 if random_r is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_RANDOM_R 1 - -/* Define to 1 if rawmemchr is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_RAWMEMCHR 1 - -/* Define to 1 if readlink is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_READLINK 1 - -/* Define to 1 if readlinkat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_READLINKAT 1 - -/* Define to 1 if realpath is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_REALPATH 1 - -/* Define to 1 if renameat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_RENAMEAT 1 - -/* Define to 1 if rmdir is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_RMDIR 1 - -/* Define to 1 if rpmatch is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_RPMATCH 1 - -/* Define to 1 if setenv is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SETENV 1 - -/* Define to 1 if setstate_r is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SETSTATE_R 1 - -/* Define to 1 if setusershell is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SETUSERSHELL 1 - -/* Define to 1 if sigaction is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SIGACTION 1 - -/* Define to 1 if sigaddset is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SIGADDSET 1 - -/* Define to 1 if sigdelset is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SIGDELSET 1 - -/* Define to 1 if sigemptyset is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SIGEMPTYSET 1 - -/* Define to 1 if sigfillset is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SIGFILLSET 1 - -/* Define to 1 if sigismember is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SIGISMEMBER 1 - -/* Define to 1 if sigpending is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SIGPENDING 1 - -/* Define to 1 if sigprocmask is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SIGPROCMASK 1 - -/* Define to 1 if sleep is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SLEEP 1 - -/* Define to 1 if snprintf is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SNPRINTF 1 - -/* Define to 1 if srandom_r is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SRANDOM_R 1 - -/* Define to 1 if stat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STAT 1 - -/* Define to 1 if stpcpy is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STPCPY 1 - -/* Define to 1 if stpncpy is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STPNCPY 1 - -/* Define to 1 if strcasestr is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRCASESTR 1 - -/* Define to 1 if strchrnul is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRCHRNUL 1 - -/* Define to 1 if strdup is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRDUP 1 - -/* Define to 1 if strerror_r is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRERROR_R 1 - -/* Define to 1 if strncat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRNCAT 1 - -/* Define to 1 if strndup is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRNDUP 1 - -/* Define to 1 if strnlen is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRNLEN 1 - -/* Define to 1 if strpbrk is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRPBRK 1 - -/* Define to 1 if strsep is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRSEP 1 - -/* Define to 1 if strsignal is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRSIGNAL 1 - -/* Define to 1 if strtod is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRTOD 1 - -/* Define to 1 if strtok_r is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRTOK_R 1 - -/* Define to 1 if strtoll is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRTOLL 1 - -/* Define to 1 if strtoull is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRTOULL 1 - -/* Define to 1 if strverscmp is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_STRVERSCMP 1 - -/* Define to 1 if symlink is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SYMLINK 1 - -/* Define to 1 if symlinkat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_SYMLINKAT 1 - -/* Define to 1 if tmpfile is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_TMPFILE 1 - -/* Define to 1 if ttyname_r is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_TTYNAME_R 1 - -/* Define to 1 if unlink is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_UNLINK 1 - -/* Define to 1 if unlinkat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_UNLINKAT 1 - -/* Define to 1 if unlockpt is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_UNLOCKPT 1 - -/* Define to 1 if unsetenv is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_UNSETENV 1 - -/* Define to 1 if usleep is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_USLEEP 1 - -/* Define to 1 if utimensat is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_UTIMENSAT 1 - -/* Define to 1 if vdprintf is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_VDPRINTF 1 - -/* Define to 1 if vsnprintf is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL_VSNPRINTF 1 - -/* Define to 1 if _Exit is declared even after undefining macros. */ -#cmakedefine HAVE_RAW_DECL__EXIT 1 - -/* Define to 1 if you have the `readlink' function. */ -#cmakedefine HAVE_READLINK 1 - -/* Define to 1 if you have the `readlinkat' function. */ -#cmakedefine HAVE_READLINKAT 1 - -/* Define to 1 if you have the `realpath' function. */ -#cmakedefine HAVE_REALPATH 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_SEARCH_H 1 - -/* Define to 1 if you have the `setenv' function. */ -#cmakedefine HAVE_SETENV 1 - -/* Define to 1 if you have the `setlocale' function. */ -#cmakedefine HAVE_SETLOCALE 1 - -/* Define to 1 if 'sig_atomic_t' is a signed integer type. */ -#cmakedefine HAVE_SIGNED_SIG_ATOMIC_T 1 - -/* Define to 1 if 'wchar_t' is a signed integer type. */ -#cmakedefine HAVE_SIGNED_WCHAR_T 1 - -/* Define to 1 if 'wint_t' is a signed integer type. */ -#cmakedefine HAVE_SIGNED_WINT_T 1 - -/* Define to 1 if the system has the type `sigset_t'. */ -#cmakedefine HAVE_SIGSET_T 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_STDINT_H 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_STDLIB_H 1 - -/* Define to 1 if you have the `strerror_r' function. */ -#cmakedefine HAVE_STRERROR_R 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_STRINGS_H 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_STRING_H 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_SYS_BITYPES_H 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_SYS_INTTYPES_H 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_SYS_PARAM_H 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_SYS_SOCKET_H 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_SYS_STAT_H 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_SYS_TIME_H 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_SYS_TYPES_H 1 - -/* Define to 1 if you have the `tsearch' function. */ -#cmakedefine HAVE_TSEARCH 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_UNISTD_H 1 - -/* Define to 1 if the system has the type `unsigned long long int'. */ -#cmakedefine HAVE_UNSIGNED_LONG_LONG_INT 1 - -/* Define to 1 or 0, depending whether the compiler supports simple visibility - declarations. */ -#cmakedefine HAVE_VISIBILITY 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_WCHAR_H 1 - -/* Define if you have the 'wchar_t' type. */ -#cmakedefine HAVE_WCHAR_T 1 - -/* Define to 1 if you have the `wcrtomb' function. */ -#cmakedefine HAVE_WCRTOMB 1 - -/* Define to 1 if you have the header file. */ -#cmakedefine HAVE_WINSOCK2_H 1 - -/* Define to 1 if O_NOATIME works. */ -#define HAVE_WORKING_O_NOATIME @HAVE_WORKING_O_NOATIME@ - -/* Define to 1 if O_NOFOLLOW works. */ -#define HAVE_WORKING_O_NOFOLLOW @HAVE_WORKING_O_NOFOLLOW@ - -/* Define to 1 if the system has the type `_Bool'. */ -#cmakedefine HAVE__BOOL 1 - -/* Define to 1 if you have the `_NSGetExecutablePath' function. */ -#cmakedefine HAVE__NSGETEXECUTABLEPATH 1 - -/* Define as const if the declaration of iconv() needs const. */ -#define ICONV_CONST @ICONV_CONST@ - -/* Define to the value of ${prefix}, as a string. */ -#cmakedefine INSTALLPREFIX "@INSTALLPREFIX@" - -/* Define to 1 if `lstat' dereferences a symlink specified with a trailing - slash. */ -#cmakedefine LSTAT_FOLLOWS_SLASHED_SYMLINK 1 - -/* Define to the sub-directory in which libtool stores uninstalled libraries. - */ -#cmakedefine LT_OBJDIR "@LT_OBJDIR@" - -/* If malloc(0) is != NULL, define this to 1. Otherwise define this to 0. */ -#cmakedefine MALLOC_0_IS_NONNULL 1 - -/* Define to 1 if your C compiler doesn't accept -c and -o together. */ -#cmakedefine NO_MINUS_C_MINUS_O 1 - -/* Name of package */ -#define PACKAGE "@PACKAGE@" - -/* Define to the address where bug reports for this package should be sent. */ -#define PACKAGE_BUGREPORT "@PACKAGE_BUGREPORT@" - -/* Define to the full name of this package. */ -#define PACKAGE_NAME "@PACKAGE_NAME@" - -/* Define to the full name and version of this package. */ -#define PACKAGE_STRING "@PACKAGE_STRING@" - -/* Define to the one symbol short name of this package. */ -#define PACKAGE_TARNAME "@PACKAGE_TARNAME@" - -/* Define to the home page for this package. */ -#define PACKAGE_URL "@PACKAGE_URL@" - -/* Define to the version of this package. */ -#define PACKAGE_VERSION "@PACKAGE_VERSION@" - -/* Define to l, ll, u, ul, ull, etc., as suitable for constants of type - 'ptrdiff_t'. */ -#cmakedefine PTRDIFF_T_SUFFIX @PTRDIFF_T_SUFFIX@ - -/* Define to 1 if readlink fails to recognize a trailing slash. */ -#cmakedefine READLINK_TRAILING_SLASH_BUG 1 - -/* Define to 1 if stat needs help when passed a directory name with a trailing - slash */ -#cmakedefine REPLACE_FUNC_STAT_DIR 1 - -/* Define to 1 if stat needs help when passed a file name with a trailing - slash */ -#cmakedefine REPLACE_FUNC_STAT_FILE 1 - -/* Define to 1 if strerror(0) does not return a message implying success. */ -#cmakedefine REPLACE_STRERROR_0 1 - -/* Define to l, ll, u, ul, ull, etc., as suitable for constants of type - 'sig_atomic_t'. */ -#cmakedefine SIG_ATOMIC_T_SUFFIX @SIG_ATOMIC_T_SUFFIX@ - -/* Define to l, ll, u, ul, ull, etc., as suitable for constants of type - 'size_t'. */ -#cmakedefine SIZE_T_SUFFIX @SIZE_T_SUFFIX@ - -/* If using the C implementation of alloca, define if you know the - direction of stack growth for your system; otherwise it will be - automatically deduced at runtime. - STACK_DIRECTION > 0 => grows toward higher addresses - STACK_DIRECTION < 0 => grows toward lower addresses - STACK_DIRECTION = 0 => direction of growth unknown */ -#cmakedefine STACK_DIRECTION @STACK_DIRECTION@ - -/* Define to 1 if the `S_IS*' macros in do not work properly. */ -#cmakedefine STAT_MACROS_BROKEN 1 - -/* Define to 1 if you have the ANSI C header files. */ -#cmakedefine STDC_HEADERS 1 - -/* Define to 1 if strerror_r returns char *. */ -#cmakedefine STRERROR_R_CHAR_P 1 - -/* Define to the prefix of C symbols at the assembler and linker level, either - an underscore or empty. */ -#define USER_LABEL_PREFIX @USER_LABEL_PREFIX@ - -/* Define to 1 if you want getc etc. to use unlocked I/O if available. - Unlocked I/O can improve performance in unithreaded apps, but it is not - safe for multithreaded apps. */ -#cmakedefine USE_UNLOCKED_IO 1 - -/* Version number of package */ -#define VERSION "@VERSION@" - -/* Define to l, ll, u, ul, ull, etc., as suitable for constants of type - 'wchar_t'. */ -#cmakedefine WCHAR_T_SUFFIX @WCHAR_T_SUFFIX@ - -/* Define to l, ll, u, ul, ull, etc., as suitable for constants of type - 'wint_t'. */ -#cmakedefine WINT_T_SUFFIX @WINT_T_SUFFIX@ - -/* Define if the machine's byte ordering is little endian. */ -#cmakedefine WORDS_LITTLEENDIAN 1 - -/* Define to 1 if on MINIX. */ -#cmakedefine _MINIX 1 - -/* The _Noreturn keyword of draft C1X. */ -#ifndef _Noreturn -# if (3 <= __GNUC__ || (__GNUC__ == 2 && 8 <= __GNUC_MINOR__) \ - || 0x5110 <= __SUNPRO_C) -# define _Noreturn __attribute__ ((__noreturn__)) -# elif 1200 <= _MSC_VER -# define _Noreturn __declspec (noreturn) -# else -# define _Noreturn -# endif -#endif - - -/* Define to 2 if the system does not provide POSIX.1 features except with - this defined. */ -#cmakedefine _POSIX_1_SOURCE 2 - -/* Define to 1 if you need to in order for `stat' and other things to work. */ -#cmakedefine _POSIX_SOURCE 1 - -/* Define to 500 only on HP-UX. */ -#cmakedefine _XOPEN_SOURCE 500 - -/* Enable extensions on AIX 3, Interix. */ -#ifndef _ALL_SOURCE -#cmakedefine _ALL_SOURCE 1 -#endif -/* Enable general extensions on MacOS X. */ -#ifndef _DARWIN_C_SOURCE -#cmakedefine _DARWIN_C_SOURCE 1 -#endif -/* Enable GNU extensions on systems that have them. */ -#ifndef _GNU_SOURCE -#cmakedefine _GNU_SOURCE 1 -#endif -/* Enable threading extensions on Solaris. */ -#ifndef _POSIX_PTHREAD_SEMANTICS -#cmakedefine _POSIX_PTHREAD_SEMANTICS 1 -#endif -/* Enable extensions on HP NonStop. */ -#ifndef _TANDEM_SOURCE -#cmakedefine _TANDEM_SOURCE 1 -#endif -/* Enable general extensions on Solaris. */ -#ifndef __EXTENSIONS__ -#cmakedefine __EXTENSIONS__ 1 -#endif - - -/* Define to `int' if doesn't define. */ -#cmakedefine gid_t @gid_t@ - -/* Define to `__inline__' or `__inline' if that's what the C compiler - calls it, or to nothing if 'inline' is not supported under any name. */ -#ifndef __cplusplus -#cmakedefine inline @inline@ -#endif - -/* Work around a bug in Apple GCC 4.0.1 build 5465: In C99 mode, it supports - the ISO C 99 semantics of 'extern inline' (unlike the GNU C semantics of - earlier versions), but does not display it by setting __GNUC_STDC_INLINE__. - __APPLE__ && __MACH__ test for MacOS X. - __APPLE_CC__ tests for the Apple compiler and its version. - __STDC_VERSION__ tests for the C99 mode. */ -#if defined __APPLE__ && defined __MACH__ && __APPLE_CC__ >= 5465 && !defined __cplusplus && __STDC_VERSION__ >= 199901L && !defined __GNUC_STDC_INLINE__ -# define __GNUC_STDC_INLINE__ 1 -#endif - -/* Define to a type if does not define. */ -#cmakedefine mbstate_t @mbstate_t@ - -/* Define to the type of st_nlink in struct stat, or a supertype. */ -#cmakedefine nlink_t @nlink_t@ - -/* Define to the equivalent of the C99 'restrict' keyword, or to - nothing if this is not supported. Do not define if restrict is - supported directly. */ -#cmakedefine restrict @restrict@ -/* Work around a bug in Sun C++: it does not support _Restrict or - __restrict__, even though the corresponding Sun C compiler ends up with - "#define restrict _Restrict" or "#define restrict __restrict__" in the - previous line. Perhaps some future version of Sun C++ will work with - restrict; if so, hopefully it defines __RESTRICT like Sun C does. */ -#if defined __SUNPRO_CC && !defined __RESTRICT -# define _Restrict -# define __restrict__ -#endif - -/* Define to `unsigned int' if does not define. */ -#cmakedefine size_t @size_t@ - -/* Define as a signed type of the same size as size_t. */ -#cmakedefine ssize_t @ssize_t@ - -/* Define to `int' if doesn't define. */ -#cmakedefine uid_t @uid_t@ - -/* Define as a marker that can be attached to declarations that might not - be used. This helps to reduce warnings, such as from - GCC -Wunused-parameter. */ -#if __GNUC__ >= 3 || (__GNUC__ == 2 && __GNUC_MINOR__ >= 7) -# define _GL_UNUSED __attribute__ ((__unused__)) -#else -# define _GL_UNUSED -#endif -/* The name _UNUSED_PARAMETER_ is an earlier spelling, although the name - is a misnomer outside of parameter lists. */ -#define _UNUSED_PARAMETER_ _GL_UNUSED - -/* The __pure__ attribute was added in gcc 2.96. */ -#if __GNUC__ > 2 || (__GNUC__ == 2 && __GNUC_MINOR__ >= 96) -# define _GL_ATTRIBUTE_PURE __attribute__ ((__pure__)) -#else -# define _GL_ATTRIBUTE_PURE /* empty */ -#endif - -/* The __const__ attribute was added in gcc 2.95. */ -#if __GNUC__ > 2 || (__GNUC__ == 2 && __GNUC_MINOR__ >= 95) -# define _GL_ATTRIBUTE_CONST __attribute__ ((__const__)) -#else -# define _GL_ATTRIBUTE_CONST /* empty */ -#endif - - - -/* On Windows, variables that may be in a DLL must be marked specially. */ -#if defined _MSC_VER && defined _DLL -# define DLL_VARIABLE __declspec (dllimport) -#else -# define DLL_VARIABLE -#endif - diff --git a/3rdparty/libiconv/iconv-config.cmake.in b/3rdparty/libiconv/iconv-config.cmake.in deleted file mode 100644 index 84023c6e..00000000 --- a/3rdparty/libiconv/iconv-config.cmake.in +++ /dev/null @@ -1,38 +0,0 @@ -set(Iconv_VERSION "@VERSION@") -set(Iconv_VERSION_MAJOR "@VERSION_MAJOR@") -set(Iconv_VERSION_MINOR "@VERSION_MINOR@") - -@PACKAGE_INIT@ - -include("${CMAKE_CURRENT_LIST_DIR}/iconv-export.cmake") - -set(Iconv_DEFINITIONS "") -set(Iconv_INCLUDE_DIRS "${PACKAGE_PREFIX_DIR}/@CMAKE_INSTALL_INCLUDEDIR@") -set(Iconv_LIBRARY_DIRS "${PACKAGE_PREFIX_DIR}/@CMAKE_INSTALL_LIBDIR@") - -macro(select_library_location target basename) - foreach(property IN ITEMS IMPORTED_LOCATION IMPORTED_IMPLIB) - get_target_property(${basename}_${property}_DEBUG ${target} ${property}_DEBUG) - get_target_property(${basename}_${property}_MINSIZEREL ${target} ${property}_MINSIZEREL) - get_target_property(${basename}_${property}_RELEASE ${target} ${property}_RELEASE) - get_target_property(${basename}_${property}_RELWITHDEBINFO ${target} ${property}_RELWITHDEBINFO) - - if(${basename}_${property}_DEBUG AND ${basename}_${property}_RELEASE) - set(${basename}_LIBRARIES debug ${${basename}_${property}_DEBUG} optimized ${${basename}_${property}_RELEASE}) - elseif(${basename}_${property}_DEBUG AND ${basename}_${property}_RELWITHDEBINFO) - set(${basename}_LIBRARIES debug ${${basename}_${property}_DEBUG} optimized ${${basename}_${property}_RELWITHDEBINFO}) - elseif(${basename}_${property}_DEBUG AND ${basename}_${property}_MINSIZEREL) - set(${basename}_LIBRARIES debug ${${basename}_${property}_DEBUG} optimized ${${basename}_${property}_MINSIZEREL}) - elseif(${basename}_${property}_RELEASE) - set(${basename}_LIBRARIES ${${basename}_${property}_RELEASE}) - elseif(${basename}_${property}_RELWITHDEBINFO) - set(${basename}_LIBRARIES ${${basename}_${property}_RELWITHDEBINFO}) - elseif(${basename}_${property}_MINSIZEREL) - set(${basename}_LIBRARIES ${${basename}_${property}_MINSIZEREL}) - elseif(${basename}_${property}_DEBUG) - set(${basename}_LIBRARIES ${${basename}_${property}_DEBUG}) - endif() - endforeach() -endmacro() - -select_library_location(Iconv::Iconv Iconv) diff --git a/3rdparty/libiconv/libiconv-1.15.patch b/3rdparty/libiconv/libiconv-1.15.patch deleted file mode 100644 index cd8deb23..00000000 --- a/3rdparty/libiconv/libiconv-1.15.patch +++ /dev/null @@ -1,29 +0,0 @@ -diff -Naur libiconv-1.15.orig/include/iconv.h.build.in libiconv-1.15/include/iconv.h.build.in ---- libiconv-1.15.orig/include/iconv.h.build.in 2017-01-01 15:02:55.000000000 -0800 -+++ libiconv-1.15/include/iconv.h.build.in 2017-09-23 21:04:49.271114700 -0700 -@@ -24,10 +24,12 @@ - - #if @HAVE_VISIBILITY@ && BUILDING_LIBICONV - #define LIBICONV_DLL_EXPORTED __attribute__((__visibility__("default"))) -+#elif defined _MSC_VER && BUILDING_LIBICONV -+#define LIBICONV_DLL_EXPORTED __declspec(dllexport) - #else - #define LIBICONV_DLL_EXPORTED - #endif --extern LIBICONV_DLL_EXPORTED @DLL_VARIABLE@ int _libiconv_version; /* Likewise */ -+extern LIBICONV_DLL_EXPORTED int _libiconv_version; /* Likewise */ - - /* We would like to #include any system header file which could define - iconv_t, 1. in order to eliminate the risk that the user gets compilation -diff -Naur libiconv-1.15.orig/libcharset/include/localcharset.h.build.in libiconv-1.15/libcharset/include/localcharset.h.build.in ---- libiconv-1.15.orig/libcharset/include/localcharset.h.build.in 2017-01-01 15:03:39.000000000 -0800 -+++ libiconv-1.15/libcharset/include/localcharset.h.build.in 2017-09-23 21:04:49.271114700 -0700 -@@ -20,6 +20,8 @@ - - #if @HAVE_VISIBILITY@ && BUILDING_LIBCHARSET - #define LIBCHARSET_DLL_EXPORTED __attribute__((__visibility__("default"))) -+#elif defined _MSC_VER && BUILDING_LIBCHARSET -+#define LIBCHARSET_DLL_EXPORTED __declspec(dllexport) - #else - #define LIBCHARSET_DLL_EXPORTED - #endif diff --git a/3rdparty/libxml2/CMakeLists.txt b/3rdparty/libxml2/CMakeLists.txt index f80c8549..1a73ae14 100644 --- a/3rdparty/libxml2/CMakeLists.txt +++ b/3rdparty/libxml2/CMakeLists.txt @@ -1,15 +1,25 @@ -include(ExternalProject) - -list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) - ExternalProject_Add( libxml2 DEPENDS libiconv xz zlib - #GIT_REPOSITORY git://git.gnome.org/libxml2 - #GIT_TAG v2.9.5 - URL https://github.com/roboticslibrary/libxml2/archive/patch.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/libxml2-2.9.5.tar.gz - #URL_MD5 5ce0da9bdaa267b40c4ca36d35363b8b - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DLIBXML2_WITH_PYTHON=OFF + #GIT_REPOSITORY https://gitlab.gnome.org/GNOME/libxml2.git + #GIT_TAG e7ff2efc5db1cf47bb3e8b3c2731228109c25b3b + URL https://gitlab.gnome.org/GNOME/libxml2/-/archive/e7ff2efc5db1cf47bb3e8b3c2731228109c25b3b/libxml2-e7ff2efc5db1cf47bb3e8b3c2731228109c25b3b.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/libxml2-e7ff2efc5db1cf47bb3e8b3c2731228109c25b3b.tar.gz + URL_MD5 685cb865cc0ddc25db1b749a57ac805f + CMAKE_ARGS + -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DLIBXML2_WITH_PYTHON=OFF + -DLIBXML2_WITH_TESTS=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + libxml2 license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /Copyright ${CMAKE_INSTALL_FULL_DATADIR}/libxml2/Copyright +) diff --git a/3rdparty/libxslt/CMakeLists.txt b/3rdparty/libxslt/CMakeLists.txt index 8b8ef2c8..c0702239 100644 --- a/3rdparty/libxslt/CMakeLists.txt +++ b/3rdparty/libxslt/CMakeLists.txt @@ -1,15 +1,24 @@ -include(ExternalProject) - -list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) - ExternalProject_Add( libxslt DEPENDS libxml2 - #GIT_REPOSITORY git://git.gnome.org/libxslt - #GIT_TAG v1.1.30 - URL https://github.com/roboticslibrary/libxslt/archive/patch.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/libxslt-1.1.30.tar.gz - #URL_MD5 d41d8cd98f00b204e9800998ecf8427e - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DLIBXSLT_WITH_PYTHON=OFF + #GIT_REPOSITORY https://gitlab.gnome.org/GNOME/libxslt.git + #GIT_TAG e68b39eaeee2c778b4ae5ceee399f80052e2936e + URL https://gitlab.gnome.org/GNOME/libxslt/-/archive/e68b39eaeee2c778b4ae5ceee399f80052e2936e/libxslt-e68b39eaeee2c778b4ae5ceee399f80052e2936e.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/libxslt-e68b39eaeee2c778b4ae5ceee399f80052e2936e.tar.gz + URL_MD5 445b5ddf7f95baf2c9b3d532702d2d1a + CMAKE_ARGS + -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DLIBXSLT_WITH_PYTHON=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + libxslt license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /Copyright ${CMAKE_INSTALL_FULL_DATADIR}/libxslt/Copyright +) diff --git a/3rdparty/nlopt/CMakeLists.txt b/3rdparty/nlopt/CMakeLists.txt index 89651557..abdb9282 100644 --- a/3rdparty/nlopt/CMakeLists.txt +++ b/3rdparty/nlopt/CMakeLists.txt @@ -1,16 +1,38 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(nlopt) - -include(ExternalProject) - ExternalProject_Add( nlopt #GIT_REPOSITORY https://github.com/stevengj/nlopt.git #GIT_TAG 2.6.2 - URL https://github.com/stevengj/nlopt/archive/v2.6.2.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/nlopt-2.6.2.zip - URL_MD5 3c7b0f560b6f1b547a1f71badc93db11 - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_DEBUG_POSTFIX=d -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DBUILD_SHARED_LIBS=ON -DNLOPT_GUILE=OFF -DNLOPT_MATLAB=OFF -DNLOPT_OCTAVE=OFF -DNLOPT_PYTHON=OFF -DNLOPT_SWIG=OFF -DNLOPT_TESTS=OFF + URL https://github.com/stevengj/nlopt/archive/v2.6.2.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/nlopt-2.6.2.tar.gz + URL_MD5 0163425f2ad26288391ce8f6a1fc418f + CMAKE_ARGS + -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_DEBUG_POSTFIX=d + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DNLOPT_GUILE=OFF + -DNLOPT_MATLAB=OFF + -DNLOPT_OCTAVE=OFF + -DNLOPT_PYTHON=OFF + -DNLOPT_SWIG=OFF + -DNLOPT_TESTS=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + nlopt license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/COPYING + COMMAND ${CMAKE_COMMAND} -E copy /src/algs/ags/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/ags/COPYRIGHT + COMMAND ${CMAKE_COMMAND} -E copy /src/algs/bobyqa/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/bobyqa/COPYRIGHT + COMMAND ${CMAKE_COMMAND} -E copy /src/algs/cobyla/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/cobyla/COPYRIGHT + COMMAND ${CMAKE_COMMAND} -E copy /src/algs/direct/COPYING ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/direct/COPYING + COMMAND ${CMAKE_COMMAND} -E copy /src/algs/esch/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/esch/COPYRIGHT + COMMAND ${CMAKE_COMMAND} -E copy /src/algs/luksan/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/luksan/COPYRIGHT + COMMAND ${CMAKE_COMMAND} -E copy /src/algs/newuoa/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/newuoa/COPYRIGHT + COMMAND ${CMAKE_COMMAND} -E copy /src/algs/slsqp/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/slsqp/COPYRIGHT + COMMAND ${CMAKE_COMMAND} -E copy /src/algs/stogo/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/stogo/COPYRIGHT +) diff --git a/3rdparty/ode/CMakeLists.txt b/3rdparty/ode/CMakeLists.txt index 0d2f977e..8da8bb65 100644 --- a/3rdparty/ode/CMakeLists.txt +++ b/3rdparty/ode/CMakeLists.txt @@ -1,16 +1,34 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(ode) - -include(ExternalProject) - ExternalProject_Add( ode #GIT_REPOSITORY https://bitbucket.org/odedevs/ode.git - #GIT_TAG 0.16.1 - URL https://bitbucket.org/odedevs/ode/downloads/ode-0.16.1.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/ode-0.16.1.tar.gz - URL_MD5 0af3efe98f19163c04083c554afff629 - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} -DODE_WITH_DEMOS=OFF -DODE_WITH_TESTS=OFF + #GIT_TAG 0.16.2 + URL https://bitbucket.org/odedevs/ode/downloads/ode-0.16.2.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/ode-0.16.2.tar.gz + URL_MD5 13426ae292f4dd007a1b8483b08ecc8d + CMAKE_ARGS + -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DODE_WITH_DEMOS=OFF + -DODE_WITH_TESTS=OFF INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + ode license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/ode/COPYING + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/LICENSE.TXT + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE-BSD.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/LICENSE-BSD.TXT + COMMAND ${CMAKE_COMMAND} -E copy /GIMPACT/GIMPACT-LICENSE-BSD.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/GIMPACT/GIMPACT-LICENSE-BSD.TXT + COMMAND ${CMAKE_COMMAND} -E copy /GIMPACT/GIMPACT-LICENSE-LGPL.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/GIMPACT/GIMPACT-LICENSE-LGPL.TXT + COMMAND ${CMAKE_COMMAND} -E copy /libccd/BSD-LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/ode/libccd/BSD-LICENSE + COMMAND ${CMAKE_COMMAND} -E copy /OPCODE/COPYING ${CMAKE_INSTALL_FULL_DATADIR}/ode/OPCODE/COPYING + COMMAND ${CMAKE_COMMAND} -E copy /ou/LICENSE.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/ou/LICENSE.TXT + COMMAND ${CMAKE_COMMAND} -E copy /ou/LICENSE-BSD.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/ou/LICENSE-BSD.TXT + COMMAND ${CMAKE_COMMAND} -E copy /ou/LICENSE-LESSER.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/ou/LICENSE-LESSER.TXT + COMMAND ${CMAKE_COMMAND} -E copy /ou/LICENSE-ZLIB.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/ou/LICENSE-ZLIB.TXT +) diff --git a/3rdparty/patch.exe.manifest b/3rdparty/patch.exe.manifest deleted file mode 100644 index 63dce3b5..00000000 --- a/3rdparty/patch.exe.manifest +++ /dev/null @@ -1,10 +0,0 @@ - - - - - - - - - - diff --git a/3rdparty/pqp/CMakeLists.txt b/3rdparty/pqp/CMakeLists.txt index f3cd2e43..c1af8d85 100644 --- a/3rdparty/pqp/CMakeLists.txt +++ b/3rdparty/pqp/CMakeLists.txt @@ -1,14 +1,22 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(pqp) - -include(ExternalProject) - ExternalProject_Add( pqp - URL https://github.com/roboticslibrary/PQP/archive/patch.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/pqp-1.3.tar.gz - #URL_MD5 f710e24a62db763d61d08667439d46fd - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + #GIT_REPOSITORY https://github.com/GammaUNC/PQP.git + #GIT_TAG 713de5b70dd1849b915f6412330078a9814e01ab + URL https://github.com/GammaUNC/PQP/archive/713de5b70dd1849b915f6412330078a9814e01ab.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/PQP-713de5b70dd1849b915f6412330078a9814e01ab.tar.gz + URL_MD5 8d975c00fd3795344790e68831395ac6 + CMAKE_ARGS + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + INSTALL_COMMAND ${CMAKE_COMMAND} -E copy /LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/pqp/LICENSE INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + pqp license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/pqp/LICENSE +) diff --git a/3rdparty/simage/CMakeLists.txt b/3rdparty/simage/CMakeLists.txt new file mode 100644 index 00000000..e9fb2334 --- /dev/null +++ b/3rdparty/simage/CMakeLists.txt @@ -0,0 +1,24 @@ +ExternalProject_Add( + simage + #GIT_REPOSITORY https://github.com/coin3d/simage.git + #GIT_TAG simage-1.8.0 + URL https://github.com/coin3d/simage/releases/download/simage-1.8.0/simage-1.8.0-src.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/simage-1.8.0-src.tar.gz + URL_MD5 a1810e0c2a1c9c7a6c191198bd8465bc + CMAKE_ARGS + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DSIMAGE_BUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) + +ExternalProject_Add_Step( + simage license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/simage/COPYING + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/simage/LICENSE + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE.mpeg2enc ${CMAKE_INSTALL_FULL_DATADIR}/simage/LICENSE.mpeg2enc +) diff --git a/3rdparty/solid/CMakeLists.txt b/3rdparty/solid/CMakeLists.txt deleted file mode 100644 index 8877733e..00000000 --- a/3rdparty/solid/CMakeLists.txt +++ /dev/null @@ -1,14 +0,0 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(solid) - -include(ExternalProject) - -ExternalProject_Add( - solid - URL https://github.com/dtecta/solid3/archive/master.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/solid-3.5.8.zip - #URL_MD5 d5fb3dcfcc0cf322abaac9109959d4d4 - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) diff --git a/3rdparty/solid3/CMakeLists.txt b/3rdparty/solid3/CMakeLists.txt new file mode 100644 index 00000000..45785cab --- /dev/null +++ b/3rdparty/solid3/CMakeLists.txt @@ -0,0 +1,26 @@ +ExternalProject_Add( + solid3 + #GIT_REPOSITORY https://github.com/dtecta/solid3.git + #GIT_TAG cbac1402da5df65e7239558a6c04feb736e54b27 + URL https://github.com/dtecta/solid3/archive/cbac1402da5df65e7239558a6c04feb736e54b27.zip + #URL ${CMAKE_CURRENT_SOURCE_DIR}/solid3-cbac1402da5df65e7239558a6c04feb736e54b27.tar.gz + URL_MD5 b566a0732d8c267b0d65b461914d6fc0 + CMAKE_ARGS + -DBUILD_EXAMPLES=OFF + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DDYNAMIC_SOLID=${BUILD_SHARED_LIBS} + -DUSE_DOUBLES=ON + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) + +ExternalProject_Add_Step( + solid3 license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE_GPL.txt ${CMAKE_INSTALL_FULL_DATADIR}/solid3/LICENSE_GPL.txt + COMMAND ${CMAKE_COMMAND} -E copy /LICENSE_QPL.txt ${CMAKE_INSTALL_FULL_DATADIR}/solid3/LICENSE_QPL.txt + COMMAND ${CMAKE_COMMAND} -E copy /README.md ${CMAKE_INSTALL_FULL_DATADIR}/solid3/README.md +) diff --git a/3rdparty/soqt/CMakeLists.txt b/3rdparty/soqt/CMakeLists.txt new file mode 100644 index 00000000..9fb1ed35 --- /dev/null +++ b/3rdparty/soqt/CMakeLists.txt @@ -0,0 +1,25 @@ +ExternalProject_Add( + soqt + DEPENDS coin + #GIT_REPOSITORY https://github.com/coin3d/soqt.git + #GIT_TAG SoQt-1.6.0 + URL https://github.com/coin3d/soqt/releases/download/SoQt-1.6.0/soqt-1.6.0-src.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/soqt-SoQt-1.6.0.zip + URL_MD5 724996aedad2a33760dc36f08ceeda22 + CMAKE_ARGS + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + -DSOQT_BUILD_DOCUMENTATION=OFF + -DSOQT_BUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DSOQT_BUILD_TESTS=OFF + INSTALL_DIR ${CMAKE_INSTALL_PREFIX} +) + +ExternalProject_Add_Step( + soqt license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/SoQt/COPYING +) diff --git a/3rdparty/xz/CMakeLists.txt b/3rdparty/xz/CMakeLists.txt index eaa3338e..7cdeaf63 100644 --- a/3rdparty/xz/CMakeLists.txt +++ b/3rdparty/xz/CMakeLists.txt @@ -1,16 +1,26 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(xz) - -include(ExternalProject) - ExternalProject_Add( xz #GIT_REPOSITORY https://git.tukaani.org/xz.git - #GIT_TAG v5.2.3 - URL https://github.com/roboticslibrary/xz/archive/patch.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/xz-5.2.3.tar.gz - #URL_MD5 ef68674fb47a8b8e741b34e429d86e9d - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + #GIT_TAG 90457dbe3e5717660f5b81f8c604860fc5137c0c + URL https://github.com/roboticslibrary/xz/archive/90457dbe3e5717660f5b81f8c604860fc5137c0c.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/xz-90457dbe3e5717660f5b81f8c604860fc5137c0c.tar.gz + URL_MD5 d6db20de0d42be75505a4c179b611101 + CMAKE_ARGS + -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_DEBUG_POSTFIX=d + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + xz license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/xz/COPYING + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.GPLv2 ${CMAKE_INSTALL_FULL_DATADIR}/xz/COPYING.GPLv2 + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.GPLv3 ${CMAKE_INSTALL_FULL_DATADIR}/xz/COPYING.GPLv3 + COMMAND ${CMAKE_COMMAND} -E copy /COPYING.LGPLv2.1 ${CMAKE_INSTALL_FULL_DATADIR}/xz/COPYING.LGPLv2.1 +) diff --git a/3rdparty/zlib/CMakeLists.txt b/3rdparty/zlib/CMakeLists.txt index 22a4938d..1f0c8fb0 100644 --- a/3rdparty/zlib/CMakeLists.txt +++ b/3rdparty/zlib/CMakeLists.txt @@ -1,16 +1,21 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(zlib) - -include(ExternalProject) - ExternalProject_Add( zlib - #GIT_REPOSITORY git://github.com/madler/zlib.git - #GIT_TAG v1.2.8 - URL https://github.com/roboticslibrary/zlib/archive/patch.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/zlib-1.2.8.tar.gz - #URL_MD5 44d667c142d7cda120332623eab69f40 - CMAKE_ARGS -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} + #GIT_REPOSITORY https://github.com/madler/zlib.git + #GIT_TAG v1.2.11 + URL https://github.com/madler/zlib/archive/v1.2.11.tar.gz + #URL ${CMAKE_CURRENT_SOURCE_DIR}/zlib-1.2.11.tar.gz + URL_MD5 0095d2d2d1f3442ce1318336637b695f + CMAKE_ARGS + -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} + -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} + -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} + -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} + -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} INSTALL_DIR ${CMAKE_INSTALL_PREFIX} ) + +ExternalProject_Add_Step( + zlib license + DEPENDEES build + COMMAND ${CMAKE_COMMAND} -E copy /README ${CMAKE_INSTALL_FULL_DATADIR}/zlib/README +) From 136d0c86bb0608ad4f36a3b9e1132abc0629e89c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 18 Nov 2020 16:52:19 +0100 Subject: [PATCH 411/546] Add verify step to path planning demos and tests --- demos/rlPrmDemo/rlPrmDemo.cpp | 9 +++++++++ demos/rlRrtDemo/rlRrtDemo.cpp | 9 +++++++++ tests/rlEetTest/rlEetTest.cpp | 9 +++++++++ tests/rlPrmTest/rlPrmTest.cpp | 9 +++++++++ 4 files changed, 36 insertions(+) diff --git a/demos/rlPrmDemo/rlPrmDemo.cpp b/demos/rlPrmDemo/rlPrmDemo.cpp index 6f61cebe..05f10952 100644 --- a/demos/rlPrmDemo/rlPrmDemo.cpp +++ b/demos/rlPrmDemo/rlPrmDemo.cpp @@ -137,6 +137,15 @@ main(int argc, char** argv) std::cout << "start: " << start.transpose() * rl::math::constants::rad2deg << std::endl;; std::cout << "goal: " << goal.transpose() * rl::math::constants::rad2deg << std::endl;; + std::cout << "verify() ... " << std::endl;; + bool verified = planner.verify(); + std::cout << "verify() " << (verified ? "true" : "false") << std::endl; + + if (!verified) + { + return EXIT_FAILURE; + } + std::cout << "construct() ... " << std::endl;; std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); planner.construct(15); diff --git a/demos/rlRrtDemo/rlRrtDemo.cpp b/demos/rlRrtDemo/rlRrtDemo.cpp index d4f0b125..7bcce277 100644 --- a/demos/rlRrtDemo/rlRrtDemo.cpp +++ b/demos/rlRrtDemo/rlRrtDemo.cpp @@ -135,6 +135,15 @@ main(int argc, char** argv) std::cout << "start: " << start.transpose() * rl::math::constants::rad2deg << std::endl;; std::cout << "goal: " << goal.transpose() * rl::math::constants::rad2deg << std::endl;; + std::cout << "verify() ... " << std::endl;; + bool verified = planner.verify(); + std::cout << "verify() " << (verified ? "true" : "false") << std::endl; + + if (!verified) + { + return EXIT_FAILURE; + } + std::cout << "solve() ... " << std::endl;; std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); bool solved = planner.solve(); diff --git a/tests/rlEetTest/rlEetTest.cpp b/tests/rlEetTest/rlEetTest.cpp index 4eea0c31..c5208d2d 100644 --- a/tests/rlEetTest/rlEetTest.cpp +++ b/tests/rlEetTest/rlEetTest.cpp @@ -178,6 +178,15 @@ main(int argc, char** argv) sampler.model = &model; + std::cout << "verify() ... " << std::endl;; + bool verified = planner.verify(); + std::cout << "verify() " << (verified ? "true" : "false") << std::endl; + + if (!verified) + { + return EXIT_FAILURE; + } + std::cout << "solve() ... " << std::endl;; std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); bool solved = planner.solve(); diff --git a/tests/rlPrmTest/rlPrmTest.cpp b/tests/rlPrmTest/rlPrmTest.cpp index e3c66499..9d0b6141 100644 --- a/tests/rlPrmTest/rlPrmTest.cpp +++ b/tests/rlPrmTest/rlPrmTest.cpp @@ -167,6 +167,15 @@ main(int argc, char** argv) planner.duration = std::chrono::seconds(20); + std::cout << "verify() ... " << std::endl;; + bool verified = planner.verify(); + std::cout << "verify() " << (verified ? "true" : "false") << std::endl; + + if (!verified) + { + return EXIT_FAILURE; + } + std::cout << "construct() ... " << std::endl;; std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); planner.construct(15); From a877e2e3a39fc21725d6605960b9fb69ae4bc6f8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 18 Nov 2020 17:20:31 +0100 Subject: [PATCH 412/546] Update deprecated GitHub Actions commands --- .github/workflows/ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 293078ee..0bccf71a 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -92,7 +92,7 @@ jobs: run: | cmake -E make_directory ${{ runner.workspace }}/build - name: Update PATH - run: echo ::add-path::${{ matrix.path }} + run: echo "${{ matrix.path }}" >> $GITHUB_PATH - name: Configure CMake working-directory: ${{ runner.workspace }}/build run: | From dd2564ff36b59eeff6378c8723ea1a87562844be Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 28 Nov 2020 23:10:14 +0100 Subject: [PATCH 413/546] Use NAMELINK_COMPONENT in CMake install --- src/rl/hal/CMakeLists.txt | 29 +++++++++++++++++++---------- src/rl/kin/CMakeLists.txt | 29 +++++++++++++++++++---------- src/rl/mdl/CMakeLists.txt | 29 +++++++++++++++++++---------- src/rl/plan/CMakeLists.txt | 29 +++++++++++++++++++---------- src/rl/sg/CMakeLists.txt | 29 +++++++++++++++++++---------- 5 files changed, 95 insertions(+), 50 deletions(-) diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 2f7a0cf9..e4b49c92 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -267,20 +267,29 @@ endif() install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/hal COMPONENT development) -install( - TARGETS hal - EXPORT rl - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime -) - -if(BUILD_SHARED_LIBS) +if(NOT CMAKE_VERSION VERSION_LESS 3.12) + install( + TARGETS hal + EXPORT rl + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_COMPONENT development + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime + ) +else() install( TARGETS hal EXPORT rl - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime ) + if(BUILD_SHARED_LIBS) + install( + TARGETS hal + EXPORT rl + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ) + endif() endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index 9f8736d6..40220a1f 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -96,20 +96,29 @@ endif() install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/kin COMPONENT development) -install( - TARGETS kin - EXPORT rl - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime -) - -if(BUILD_SHARED_LIBS) +if(NOT CMAKE_VERSION VERSION_LESS 3.12) install( TARGETS kin EXPORT rl - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_COMPONENT development + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime ) +else() + install( + TARGETS kin + EXPORT rl + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime + ) + if(BUILD_SHARED_LIBS) + install( + TARGETS kin + EXPORT rl + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ) + endif() endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 0bc21b17..4cb9b63e 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -146,20 +146,29 @@ endif() install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/mdl COMPONENT development) -install( - TARGETS mdl - EXPORT rl - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime -) - -if(BUILD_SHARED_LIBS) +if(NOT CMAKE_VERSION VERSION_LESS 3.12) install( TARGETS mdl EXPORT rl - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_COMPONENT development + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime ) +else() + install( + TARGETS mdl + EXPORT rl + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime + ) + if(BUILD_SHARED_LIBS) + install( + TARGETS mdl + EXPORT rl + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ) + endif() endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index 3d19736e..5fb57415 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -157,20 +157,29 @@ endif() install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/plan COMPONENT development) -install( - TARGETS plan - EXPORT rl - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime -) - -if(BUILD_SHARED_LIBS) +if(NOT CMAKE_VERSION VERSION_LESS 3.12) install( TARGETS plan EXPORT rl - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_COMPONENT development + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime ) +else() + install( + TARGETS plan + EXPORT rl + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime + ) + if(BUILD_SHARED_LIBS) + install( + TARGETS plan + EXPORT rl + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ) + endif() endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index a3acafd0..9ecd9da9 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -304,20 +304,29 @@ if(MSVC) endif() endif() -install( - TARGETS sg - EXPORT rl - ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP - RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime -) - -if(BUILD_SHARED_LIBS) +if(NOT CMAKE_VERSION VERSION_LESS 3.12) install( TARGETS sg EXPORT rl - LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_COMPONENT development + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime ) +else() + install( + TARGETS sg + EXPORT rl + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime + ) + if(BUILD_SHARED_LIBS) + install( + TARGETS sg + EXPORT rl + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development NAMELINK_ONLY + ) + endif() endif() if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) From c072561f3b1068314df318f2cc8d67bdb9f19901 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 29 Nov 2020 19:19:57 +0100 Subject: [PATCH 414/546] Add headers to interface targets on CMake 3.19 --- src/rl/math/CMakeLists.txt | 4 +++- src/rl/std/CMakeLists.txt | 4 +++- src/rl/util/CMakeLists.txt | 4 +++- src/rl/xml/CMakeLists.txt | 4 +++- 4 files changed, 12 insertions(+), 4 deletions(-) diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index d229bf4a..b95d4599 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -62,7 +62,9 @@ set( ) list(APPEND HDRS ${SPATIAL_HDRS}) -if(NOT CMAKE_VERSION VERSION_LESS 3.0) +if(NOT CMAKE_VERSION VERSION_LESS 3.19) + add_library(math INTERFACE ${HDRS}) +elseif(NOT CMAKE_VERSION VERSION_LESS 3.0) add_library(math INTERFACE) add_custom_target(math_sources SOURCES ${HDRS}) else() diff --git a/src/rl/std/CMakeLists.txt b/src/rl/std/CMakeLists.txt index 0c97f1a0..b4140d5a 100644 --- a/src/rl/std/CMakeLists.txt +++ b/src/rl/std/CMakeLists.txt @@ -5,7 +5,9 @@ set( memory.h ) -if(NOT CMAKE_VERSION VERSION_LESS 3.0) +if(NOT CMAKE_VERSION VERSION_LESS 3.19) + add_library(std INTERFACE ${HDRS}) +elseif(NOT CMAKE_VERSION VERSION_LESS 3.0) add_library(std INTERFACE) add_custom_target(std_sources SOURCES ${HDRS}) else() diff --git a/src/rl/util/CMakeLists.txt b/src/rl/util/CMakeLists.txt index 68fe056e..b48b5dcb 100644 --- a/src/rl/util/CMakeLists.txt +++ b/src/rl/util/CMakeLists.txt @@ -39,7 +39,9 @@ if(RL_BUILD_UTIL_XENOMAI) list(APPEND HDRS ${XENOMAI_HDRS}) endif() -if(NOT CMAKE_VERSION VERSION_LESS 3.0) +if(NOT CMAKE_VERSION VERSION_LESS 3.19) + add_library(util INTERFACE ${HDRS}) +elseif(NOT CMAKE_VERSION VERSION_LESS 3.0) add_library(util INTERFACE) add_custom_target(util_sources SOURCES ${HDRS}) else() diff --git a/src/rl/xml/CMakeLists.txt b/src/rl/xml/CMakeLists.txt index 9367a244..accb1634 100644 --- a/src/rl/xml/CMakeLists.txt +++ b/src/rl/xml/CMakeLists.txt @@ -21,7 +21,9 @@ set( Stylesheet.h ) -if(NOT CMAKE_VERSION VERSION_LESS 3.0) +if(NOT CMAKE_VERSION VERSION_LESS 3.19) + add_library(xml INTERFACE ${HDRS}) +elseif(NOT CMAKE_VERSION VERSION_LESS 3.0) add_library(xml INTERFACE) add_custom_target(xml_sources SOURCES ${HDRS}) else() From 593ec79d0c6e86d855b6b4a941f87055d1c9dbad Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 29 Nov 2020 22:38:02 +0100 Subject: [PATCH 415/546] Separate 3rdparty CMake files from source --- 3rdparty/CMakeLists.txt | 134 ------------------------------- 3rdparty/atidaq/CMakeLists.txt | 22 ----- 3rdparty/boost/CMakeLists.txt | 18 ----- 3rdparty/bullet3/CMakeLists.txt | 31 ------- 3rdparty/coin/CMakeLists.txt | 25 ------ 3rdparty/eigen3/CMakeLists.txt | 28 ------- 3rdparty/fcl/CMakeLists.txt | 23 ------ 3rdparty/gperf/CMakeLists.txt | 21 ----- 3rdparty/libccd/CMakeLists.txt | 23 ------ 3rdparty/libiconv/CMakeLists.txt | 25 ------ 3rdparty/libxml2/CMakeLists.txt | 25 ------ 3rdparty/libxslt/CMakeLists.txt | 24 ------ 3rdparty/nlopt/CMakeLists.txt | 38 --------- 3rdparty/ode/CMakeLists.txt | 34 -------- 3rdparty/pqp/CMakeLists.txt | 22 ----- 3rdparty/simage/CMakeLists.txt | 24 ------ 3rdparty/solid3/CMakeLists.txt | 26 ------ 3rdparty/soqt/CMakeLists.txt | 25 ------ 3rdparty/xz/CMakeLists.txt | 26 ------ 3rdparty/zlib/CMakeLists.txt | 21 ----- 20 files changed, 615 deletions(-) delete mode 100644 3rdparty/CMakeLists.txt delete mode 100644 3rdparty/atidaq/CMakeLists.txt delete mode 100644 3rdparty/boost/CMakeLists.txt delete mode 100644 3rdparty/bullet3/CMakeLists.txt delete mode 100644 3rdparty/coin/CMakeLists.txt delete mode 100644 3rdparty/eigen3/CMakeLists.txt delete mode 100644 3rdparty/fcl/CMakeLists.txt delete mode 100644 3rdparty/gperf/CMakeLists.txt delete mode 100644 3rdparty/libccd/CMakeLists.txt delete mode 100644 3rdparty/libiconv/CMakeLists.txt delete mode 100644 3rdparty/libxml2/CMakeLists.txt delete mode 100644 3rdparty/libxslt/CMakeLists.txt delete mode 100644 3rdparty/nlopt/CMakeLists.txt delete mode 100644 3rdparty/ode/CMakeLists.txt delete mode 100644 3rdparty/pqp/CMakeLists.txt delete mode 100644 3rdparty/simage/CMakeLists.txt delete mode 100644 3rdparty/solid3/CMakeLists.txt delete mode 100644 3rdparty/soqt/CMakeLists.txt delete mode 100644 3rdparty/xz/CMakeLists.txt delete mode 100644 3rdparty/zlib/CMakeLists.txt diff --git a/3rdparty/CMakeLists.txt b/3rdparty/CMakeLists.txt deleted file mode 100644 index a4fd7e06..00000000 --- a/3rdparty/CMakeLists.txt +++ /dev/null @@ -1,134 +0,0 @@ -cmake_minimum_required(VERSION 2.8.11) - -project(3rdparty) - -include(ExternalProject) -include(GNUInstallDirs) - -option(BUILD_SHARED_LIBS "Build shared libraries" ON) - -list(INSERT CMAKE_PREFIX_PATH 0 ${CMAKE_INSTALL_PREFIX}) - -add_subdirectory(atidaq) -add_subdirectory(boost) -add_subdirectory(bullet3) -add_subdirectory(coin) -add_subdirectory(eigen3) -add_subdirectory(gperf) -add_subdirectory(libccd) -add_subdirectory(nlopt) -add_subdirectory(ode) -add_subdirectory(pqp) -add_subdirectory(simage) -add_subdirectory(solid3) -add_subdirectory(xz) -add_subdirectory(zlib) - -add_subdirectory(fcl) -add_subdirectory(libiconv) -add_subdirectory(soqt) - -add_subdirectory(libxml2) - -add_subdirectory(libxslt) - -set( - CPACK_INSTALL_CMAKE_PROJECTS - "${CMAKE_CURRENT_BINARY_DIR}/atidaq/atidaq-prefix/src/atidaq-build;atidaq;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/bullet3/bullet3-prefix/src/bullet3-build;bullet3;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/coin/coin-prefix/src/coin-build;coin;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/eigen3/eigen3-prefix/src/eigen3-build;eigen3;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/fcl/fcl-prefix/src/fcl-build;fcl;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/libccd/libccd-prefix/src/libccd-build;libccd;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/libiconv/libiconv-prefix/src/libiconv-build;libiconv;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/libxml2/libxml2-prefix/src/libxml2-build;libxml2;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/libxslt/libxslt-prefix/src/libxslt-build;libxslt;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/nlopt/nlopt-prefix/src/nlopt-build;nlopt;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/ode/ode-prefix/src/ode-build;ode;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/pqp/pqp-prefix/src/pqp-build;pqp;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/simage/simage-prefix/src/simage-build;simage;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/solid3/solid3-prefix/src/solid3-build;solid3;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/soqt/soqt-prefix/src/soqt-build;soqt;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/xz/xz-prefix/src/xz-build;xz;ALL;/" - "${CMAKE_CURRENT_BINARY_DIR}/zlib/zlib-prefix/src/zlib-build;zlib;ALL;/" -) - -set( - CPACK_INSTALLED_DIRECTORIES - ${CMAKE_CURRENT_BINARY_DIR}/boost/boost-prefix/src/boost/boost ${CMAKE_INSTALL_INCLUDEDIR}/boost -) - -set(CPACK_PACKAGE_VERSION_MAJOR 0) -set(CPACK_PACKAGE_VERSION_MINOR 7) -set(CPACK_PACKAGE_VERSION_PATCH 0) - -set(CPACK_PACKAGE_VERSION ${CPACK_PACKAGE_VERSION_MAJOR}.${CPACK_PACKAGE_VERSION_MINOR}.${CPACK_PACKAGE_VERSION_PATCH}) - -if(MSVC) - if(CMAKE_CXX_COMPILER_VERSION MATCHES "^([0-9]+)\\.([0-9])([0-9]*)\\.([0-9]+)\\.") - if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 18) - math(EXPR LINKER_VERSION_MAJOR "${CMAKE_MATCH_1} - 5") - else() - math(EXPR LINKER_VERSION_MAJOR "${CMAKE_MATCH_1} - 6") - endif() - set(PLATFORM_TOOLSET_MAJOR ${LINKER_VERSION_MAJOR}) - set(PLATFORM_TOOLSET_MINOR ${CMAKE_MATCH_2}) - set(LINKER_VERSION "${LINKER_VERSION_MAJOR}.${CMAKE_MATCH_2}${CMAKE_MATCH_3}.${CMAKE_MATCH_4}") - endif() - if(CMAKE_CL_64) - set(CPACK_PACKAGE_FILE_NAME "rl-3rdparty-${CPACK_PACKAGE_VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-x64") - set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${CPACK_PACKAGE_VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\x64") - set(CPACK_PACKAGE_NAME "Robotics Library ${CPACK_PACKAGE_VERSION} Third-Party Dependencies - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (x64)") - else() - set(CPACK_PACKAGE_FILE_NAME "rl-3rdparty-${CPACK_PACKAGE_VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-x86") - set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${CPACK_PACKAGE_VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\x86") - set(CPACK_PACKAGE_NAME "Robotics Library ${CPACK_PACKAGE_VERSION} Third-Party Dependencies - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (x86)") - endif() -else() - set(CPACK_PACKAGE_FILE_NAME "rl-3rdparty-${CPACK_PACKAGE_VERSION}-${CMAKE_SYSTEM_NAME}") - set(CPACK_PACKAGE_INSTALL_DIRECTORY "rl-${CPACK_PACKAGE_VERSION}") - set(CPACK_PACKAGE_NAME "Robotics Library ${CPACK_PACKAGE_VERSION} Third-Party Dependencies") -endif() - -set(CPACK_DEBIAN_PACKAGE_HOMEPAGE "https://www.roboticslibrary.org/contact") -set(CPACK_DEBIAN_PACKAGE_NAME "librl-3rdparty") -set(CPACK_DEBIAN_PACKAGE_SECTION "devel") -set(CPACK_NSIS_DISPLAY_NAME ${CPACK_PACKAGE_NAME}) -set(CPACK_NSIS_EXECUTABLES_DIRECTORY ${CMAKE_INSTALL_BINDIR}) -set(CPACK_NSIS_HELP_LINK "https://www.roboticslibrary.org/contact") -set(CPACK_NSIS_INSTALLED_ICON_NAME Uninstall.exe) -set(CPACK_NSIS_MODIFY_PATH ON) -set(CPACK_NSIS_MUI_ICON ${CMAKE_CURRENT_SOURCE_DIR}/../robotics-library.ico) -set(CPACK_NSIS_MUI_UNIICON ${CMAKE_CURRENT_SOURCE_DIR}/../robotics-library.ico) -set(CPACK_NSIS_PACKAGE_NAME ${CPACK_PACKAGE_NAME}) -set(CPACK_NSIS_URL_INFO_ABOUT "https://www.roboticslibrary.org/contact") -set(CPACK_PACKAGE_CONTACT "Robotics Library Team ") -set(CPACK_PACKAGE_VENDOR "Robotics Library") -set(CPACK_PROJECT_CONFIG_FILE ${CMAKE_CURRENT_SOURCE_DIR}/CPackProjectConfig.cmake) -set(CPACK_RPM_PACKAGE_GROUP "Development/Libraries") -set(CPACK_RPM_PACKAGE_NAME "rl-3rdparty") -set(CPACK_RPM_PACKAGE_SUMMARY "Robotics Library Third-Party Dependencies") -set(CPACK_RPM_PACKAGE_URL "https://www.roboticslibrary.org/contact") -set(CPACK_WIX_EXTENSIONS "WiXUtilExtension") -set( - CPACK_WIX_EXTRA_SOURCES - ${CMAKE_CURRENT_BINARY_DIR}/WixExtra.wxs - ${CMAKE_CURRENT_SOURCE_DIR}/../cmake/WixUI_FeatureTreeNoLicense.wxs -) -set(CPACK_WIX_PATCH_FILE ${CMAKE_CURRENT_BINARY_DIR}/WixPatch.xml) -set(CPACK_WIX_PRODUCT_ICON ${CMAKE_CURRENT_SOURCE_DIR}/../robotics-library.ico) -set(CPACK_WIX_PROGRAM_MENU_FOLDER ${CPACK_PACKAGE_NAME}) -set(CPACK_WIX_PROPERTY_ARPHELPLINK "https://www.roboticslibrary.org/contact") -set(CPACK_WIX_PROPERTY_ARPURLINFOABOUT "https://www.roboticslibrary.org/") -set(CPACK_WIX_ROOT_FEATURE_TITLE "Robotics Library Third-Party Dependencies") -set(CPACK_WIX_UI_BANNER ${CMAKE_CURRENT_SOURCE_DIR}/../cmake/WixUIBanner.bmp) -set(CPACK_WIX_UI_DIALOG ${CMAKE_CURRENT_SOURCE_DIR}/../cmake/WixUIDialog.bmp) -set(CPACK_WIX_UI_REF "WixUI_FeatureTreeNoLicense") - -configure_file(../cmake/WixExtra.wxs.in ${CMAKE_CURRENT_BINARY_DIR}/WixExtra.wxs) -configure_file(../cmake/WixPatch.xml.in ${CMAKE_CURRENT_BINARY_DIR}/WixPatch.xml) - -set(CMAKE_INSTALL_SYSTEM_RUNTIME_COMPONENT system) -include(InstallRequiredSystemLibraries) - -include(CPack) diff --git a/3rdparty/atidaq/CMakeLists.txt b/3rdparty/atidaq/CMakeLists.txt deleted file mode 100644 index 22411bef..00000000 --- a/3rdparty/atidaq/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -ExternalProject_Add( - atidaq - #GIT_REPOSITORY https://github.com/roboticslibrary/atidaq.git - #GIT_TAG cmake-1.0.6 - URL https://github.com/roboticslibrary/atidaq/archive/cmake-1.0.6.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/atidaq-cmake-1.0.6.tar.gz - URL_MD5 23efd8412e30a06e9c433ab5e7ed2e20 - CMAKE_ARGS - -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - atidaq license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /readme.txt ${CMAKE_INSTALL_FULL_DATADIR}/atidaq/readme.txt -) diff --git a/3rdparty/boost/CMakeLists.txt b/3rdparty/boost/CMakeLists.txt deleted file mode 100644 index 5b19875f..00000000 --- a/3rdparty/boost/CMakeLists.txt +++ /dev/null @@ -1,18 +0,0 @@ -ExternalProject_Add( - boost - URL - https://sourceforge.net/projects/boost/files/boost/1.74.0/boost_1_74_0.7z/download - https://dl.bintray.com/boostorg/release/1.74.0/source/boost_1_74_0.7z - #URL ${CMAKE_CURRENT_SOURCE_DIR}/boost_1_74_0.7z - URL_MD5 3d513f8830c3c8aa308d782e740c4931 - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - BUILD_IN_SOURCE 1 - INSTALL_COMMAND ${CMAKE_COMMAND} -E copy_directory /boost ${CMAKE_INSTALL_FULL_INCLUDEDIR}/boost -) - -ExternalProject_Add_Step( - boost license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE_1_0.txt ${CMAKE_INSTALL_FULL_DATADIR}/boost/LICENSE_1_0.txt -) diff --git a/3rdparty/bullet3/CMakeLists.txt b/3rdparty/bullet3/CMakeLists.txt deleted file mode 100644 index 58ae3c94..00000000 --- a/3rdparty/bullet3/CMakeLists.txt +++ /dev/null @@ -1,31 +0,0 @@ -ExternalProject_Add( - bullet3 - #GIT_REPOSITORY https://github.com/bulletphysics/bullet3.git - #GIT_TAG 3.06 - URL https://github.com/bulletphysics/bullet3/archive/3.06.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/bullet3-3.06.tar.gz - URL_MD5 369407bb68a2d8898789a280acb067ac - CMAKE_ARGS - -DBUILD_BULLET2_DEMOS=OFF - -DBUILD_CPU_DEMOS=OFF - -DBUILD_EXTRAS=ON - -DBUILD_OPENGL3_DEMOS=OFF - -DBUILD_PYBULLET=OFF - -DBUILD_UNIT_TESTS=OFF - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DINSTALL_EXTRA_LIBS=ON - -DINSTALL_LIBS=ON - -DUSE_DOUBLE_PRECISION=ON - -DUSE_MSVC_RUNTIME_LIBRARY_DLL=ON - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - bullet3 license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE.txt ${CMAKE_INSTALL_FULL_DATADIR}/bullet/LICENSE.txt -) diff --git a/3rdparty/coin/CMakeLists.txt b/3rdparty/coin/CMakeLists.txt deleted file mode 100644 index f7fb89e0..00000000 --- a/3rdparty/coin/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -ExternalProject_Add( - coin - DEPENDS boost - #GIT_REPOSITORY https://github.com/coin3d/coin.git - #GIT_TAG Coin-4.0.0 - URL https://github.com/coin3d/coin/releases/download/Coin-4.0.0/coin-4.0.0-src.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/coin-4.0.0-src.tar.gz - URL_MD5 2377d11b38c8eddd92d8bb240f5bf4ee - CMAKE_ARGS - -DCOIN_BUILD_DOCUMENTATION=OFF - -DCOIN_BUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DCOIN_BUILD_TESTS=OFF - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - coin license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/Coin/COPYING -) diff --git a/3rdparty/eigen3/CMakeLists.txt b/3rdparty/eigen3/CMakeLists.txt deleted file mode 100644 index 700eff2d..00000000 --- a/3rdparty/eigen3/CMakeLists.txt +++ /dev/null @@ -1,28 +0,0 @@ -ExternalProject_Add( - eigen3 - #GIT_REPOSITORY https://gitlab.com/libeigen/eigen.git - #GIT_TAG 3.3.8 - URL https://gitlab.com/libeigen/eigen/-/archive/3.3.8/eigen-3.3.8.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/eigen-3.3.8.tar.gz - URL_MD5 dc352b8c98797c71470b58b52fa8a4ce - CMAKE_ARGS - -DBUILD_TESTING=OFF - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DEIGEN_TEST_NOQT=ON - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - eigen3 license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.BSD ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.BSD - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.GPL ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.GPL - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.LGPL ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.LGPL - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.MINPACK ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.MINPACK - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.MPL2 ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.MPL2 - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.README ${CMAKE_INSTALL_FULL_DATADIR}/eigen3/COPYING.README -) diff --git a/3rdparty/fcl/CMakeLists.txt b/3rdparty/fcl/CMakeLists.txt deleted file mode 100644 index 5ff9fe32..00000000 --- a/3rdparty/fcl/CMakeLists.txt +++ /dev/null @@ -1,23 +0,0 @@ -ExternalProject_Add( - fcl - DEPENDS eigen3 libccd - #GIT_REPOSITORY https://github.com/flexible-collision-library/fcl.git - #GIT_TAG 0.6.1 - URL https://github.com/flexible-collision-library/fcl/archive/v0.6.1.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/fcl-0.6.1.tar.gz - URL_MD5 1fbb2c6132f5a492e970e6be37a89632 - CMAKE_ARGS - -DBUILD_TESTING=OFF - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - fcl license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/fcl/LICENSE -) diff --git a/3rdparty/gperf/CMakeLists.txt b/3rdparty/gperf/CMakeLists.txt deleted file mode 100644 index 3ab2264f..00000000 --- a/3rdparty/gperf/CMakeLists.txt +++ /dev/null @@ -1,21 +0,0 @@ -ExternalProject_Add( - gperf - #GIT_REPOSITORY https://github.com/roboticslibrary/gperf.git - #GIT_TAG cmake-3.1 - URL https://github.com/roboticslibrary/gperf/archive/cmake-3.1.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/gperf-cmake-3.1.tar.gz - URL_MD5 ccdc42c8b534061030d49bb9cae9cfd5 - CMAKE_ARGS - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - gperf license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/gperf/COPYING -) diff --git a/3rdparty/libccd/CMakeLists.txt b/3rdparty/libccd/CMakeLists.txt deleted file mode 100644 index 0de5c5c0..00000000 --- a/3rdparty/libccd/CMakeLists.txt +++ /dev/null @@ -1,23 +0,0 @@ -ExternalProject_Add( - libccd - #GIT_REPOSITORY https://github.com/danfis/libccd.git - #GIT_TAG v2.1 - URL https://github.com/danfis/libccd/archive/v2.1.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/libccd-2.1.tar.gz - URL_MD5 fe8ea5024956044a3af6bcbab312950f - CMAKE_ARGS - -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DENABLE_DOUBLE_PRECISION=ON - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - libccd license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /BSD-LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/libccd/BSD-LICENSE -) diff --git a/3rdparty/libiconv/CMakeLists.txt b/3rdparty/libiconv/CMakeLists.txt deleted file mode 100644 index 6b6636af..00000000 --- a/3rdparty/libiconv/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -ExternalProject_Add( - libiconv - DEPENDS gperf - #GIT_REPOSITORY https://github.com/roboticslibrary/libiconv.git - #GIT_TAG cmake-1.16 - URL https://github.com/roboticslibrary/libiconv/archive/cmake-1.16.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/libiconv-cmake-1.16.tar.gz - URL_MD5 6d6ac0413d86ef2f3e6cdf38b7a5369c - CMAKE_ARGS - -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - libiconv license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/libiconv/COPYING - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.LIB ${CMAKE_INSTALL_FULL_DATADIR}/libiconv/COPYING.LIB - COMMAND ${CMAKE_COMMAND} -E copy /README ${CMAKE_INSTALL_FULL_DATADIR}/libiconv/README -) diff --git a/3rdparty/libxml2/CMakeLists.txt b/3rdparty/libxml2/CMakeLists.txt deleted file mode 100644 index 1a73ae14..00000000 --- a/3rdparty/libxml2/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -ExternalProject_Add( - libxml2 - DEPENDS libiconv xz zlib - #GIT_REPOSITORY https://gitlab.gnome.org/GNOME/libxml2.git - #GIT_TAG e7ff2efc5db1cf47bb3e8b3c2731228109c25b3b - URL https://gitlab.gnome.org/GNOME/libxml2/-/archive/e7ff2efc5db1cf47bb3e8b3c2731228109c25b3b/libxml2-e7ff2efc5db1cf47bb3e8b3c2731228109c25b3b.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/libxml2-e7ff2efc5db1cf47bb3e8b3c2731228109c25b3b.tar.gz - URL_MD5 685cb865cc0ddc25db1b749a57ac805f - CMAKE_ARGS - -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DLIBXML2_WITH_PYTHON=OFF - -DLIBXML2_WITH_TESTS=OFF - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - libxml2 license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /Copyright ${CMAKE_INSTALL_FULL_DATADIR}/libxml2/Copyright -) diff --git a/3rdparty/libxslt/CMakeLists.txt b/3rdparty/libxslt/CMakeLists.txt deleted file mode 100644 index c0702239..00000000 --- a/3rdparty/libxslt/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -ExternalProject_Add( - libxslt - DEPENDS libxml2 - #GIT_REPOSITORY https://gitlab.gnome.org/GNOME/libxslt.git - #GIT_TAG e68b39eaeee2c778b4ae5ceee399f80052e2936e - URL https://gitlab.gnome.org/GNOME/libxslt/-/archive/e68b39eaeee2c778b4ae5ceee399f80052e2936e/libxslt-e68b39eaeee2c778b4ae5ceee399f80052e2936e.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/libxslt-e68b39eaeee2c778b4ae5ceee399f80052e2936e.tar.gz - URL_MD5 445b5ddf7f95baf2c9b3d532702d2d1a - CMAKE_ARGS - -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DLIBXSLT_WITH_PYTHON=OFF - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - libxslt license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /Copyright ${CMAKE_INSTALL_FULL_DATADIR}/libxslt/Copyright -) diff --git a/3rdparty/nlopt/CMakeLists.txt b/3rdparty/nlopt/CMakeLists.txt deleted file mode 100644 index abdb9282..00000000 --- a/3rdparty/nlopt/CMakeLists.txt +++ /dev/null @@ -1,38 +0,0 @@ -ExternalProject_Add( - nlopt - #GIT_REPOSITORY https://github.com/stevengj/nlopt.git - #GIT_TAG 2.6.2 - URL https://github.com/stevengj/nlopt/archive/v2.6.2.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/nlopt-2.6.2.tar.gz - URL_MD5 0163425f2ad26288391ce8f6a1fc418f - CMAKE_ARGS - -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_DEBUG_POSTFIX=d - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DNLOPT_GUILE=OFF - -DNLOPT_MATLAB=OFF - -DNLOPT_OCTAVE=OFF - -DNLOPT_PYTHON=OFF - -DNLOPT_SWIG=OFF - -DNLOPT_TESTS=OFF - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - nlopt license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/COPYING - COMMAND ${CMAKE_COMMAND} -E copy /src/algs/ags/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/ags/COPYRIGHT - COMMAND ${CMAKE_COMMAND} -E copy /src/algs/bobyqa/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/bobyqa/COPYRIGHT - COMMAND ${CMAKE_COMMAND} -E copy /src/algs/cobyla/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/cobyla/COPYRIGHT - COMMAND ${CMAKE_COMMAND} -E copy /src/algs/direct/COPYING ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/direct/COPYING - COMMAND ${CMAKE_COMMAND} -E copy /src/algs/esch/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/esch/COPYRIGHT - COMMAND ${CMAKE_COMMAND} -E copy /src/algs/luksan/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/luksan/COPYRIGHT - COMMAND ${CMAKE_COMMAND} -E copy /src/algs/newuoa/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/newuoa/COPYRIGHT - COMMAND ${CMAKE_COMMAND} -E copy /src/algs/slsqp/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/slsqp/COPYRIGHT - COMMAND ${CMAKE_COMMAND} -E copy /src/algs/stogo/COPYRIGHT ${CMAKE_INSTALL_FULL_DATADIR}/nlopt/stogo/COPYRIGHT -) diff --git a/3rdparty/ode/CMakeLists.txt b/3rdparty/ode/CMakeLists.txt deleted file mode 100644 index 8da8bb65..00000000 --- a/3rdparty/ode/CMakeLists.txt +++ /dev/null @@ -1,34 +0,0 @@ -ExternalProject_Add( - ode - #GIT_REPOSITORY https://bitbucket.org/odedevs/ode.git - #GIT_TAG 0.16.2 - URL https://bitbucket.org/odedevs/ode/downloads/ode-0.16.2.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/ode-0.16.2.tar.gz - URL_MD5 13426ae292f4dd007a1b8483b08ecc8d - CMAKE_ARGS - -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DODE_WITH_DEMOS=OFF - -DODE_WITH_TESTS=OFF - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - ode license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/ode/COPYING - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/LICENSE.TXT - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE-BSD.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/LICENSE-BSD.TXT - COMMAND ${CMAKE_COMMAND} -E copy /GIMPACT/GIMPACT-LICENSE-BSD.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/GIMPACT/GIMPACT-LICENSE-BSD.TXT - COMMAND ${CMAKE_COMMAND} -E copy /GIMPACT/GIMPACT-LICENSE-LGPL.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/GIMPACT/GIMPACT-LICENSE-LGPL.TXT - COMMAND ${CMAKE_COMMAND} -E copy /libccd/BSD-LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/ode/libccd/BSD-LICENSE - COMMAND ${CMAKE_COMMAND} -E copy /OPCODE/COPYING ${CMAKE_INSTALL_FULL_DATADIR}/ode/OPCODE/COPYING - COMMAND ${CMAKE_COMMAND} -E copy /ou/LICENSE.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/ou/LICENSE.TXT - COMMAND ${CMAKE_COMMAND} -E copy /ou/LICENSE-BSD.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/ou/LICENSE-BSD.TXT - COMMAND ${CMAKE_COMMAND} -E copy /ou/LICENSE-LESSER.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/ou/LICENSE-LESSER.TXT - COMMAND ${CMAKE_COMMAND} -E copy /ou/LICENSE-ZLIB.TXT ${CMAKE_INSTALL_FULL_DATADIR}/ode/ou/LICENSE-ZLIB.TXT -) diff --git a/3rdparty/pqp/CMakeLists.txt b/3rdparty/pqp/CMakeLists.txt deleted file mode 100644 index c1af8d85..00000000 --- a/3rdparty/pqp/CMakeLists.txt +++ /dev/null @@ -1,22 +0,0 @@ -ExternalProject_Add( - pqp - #GIT_REPOSITORY https://github.com/GammaUNC/PQP.git - #GIT_TAG 713de5b70dd1849b915f6412330078a9814e01ab - URL https://github.com/GammaUNC/PQP/archive/713de5b70dd1849b915f6412330078a9814e01ab.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/PQP-713de5b70dd1849b915f6412330078a9814e01ab.tar.gz - URL_MD5 8d975c00fd3795344790e68831395ac6 - CMAKE_ARGS - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_COMMAND ${CMAKE_COMMAND} -E copy /LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/pqp/LICENSE - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - pqp license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/pqp/LICENSE -) diff --git a/3rdparty/simage/CMakeLists.txt b/3rdparty/simage/CMakeLists.txt deleted file mode 100644 index e9fb2334..00000000 --- a/3rdparty/simage/CMakeLists.txt +++ /dev/null @@ -1,24 +0,0 @@ -ExternalProject_Add( - simage - #GIT_REPOSITORY https://github.com/coin3d/simage.git - #GIT_TAG simage-1.8.0 - URL https://github.com/coin3d/simage/releases/download/simage-1.8.0/simage-1.8.0-src.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/simage-1.8.0-src.tar.gz - URL_MD5 a1810e0c2a1c9c7a6c191198bd8465bc - CMAKE_ARGS - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DSIMAGE_BUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - simage license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/simage/COPYING - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE ${CMAKE_INSTALL_FULL_DATADIR}/simage/LICENSE - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE.mpeg2enc ${CMAKE_INSTALL_FULL_DATADIR}/simage/LICENSE.mpeg2enc -) diff --git a/3rdparty/solid3/CMakeLists.txt b/3rdparty/solid3/CMakeLists.txt deleted file mode 100644 index 45785cab..00000000 --- a/3rdparty/solid3/CMakeLists.txt +++ /dev/null @@ -1,26 +0,0 @@ -ExternalProject_Add( - solid3 - #GIT_REPOSITORY https://github.com/dtecta/solid3.git - #GIT_TAG cbac1402da5df65e7239558a6c04feb736e54b27 - URL https://github.com/dtecta/solid3/archive/cbac1402da5df65e7239558a6c04feb736e54b27.zip - #URL ${CMAKE_CURRENT_SOURCE_DIR}/solid3-cbac1402da5df65e7239558a6c04feb736e54b27.tar.gz - URL_MD5 b566a0732d8c267b0d65b461914d6fc0 - CMAKE_ARGS - -DBUILD_EXAMPLES=OFF - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DDYNAMIC_SOLID=${BUILD_SHARED_LIBS} - -DUSE_DOUBLES=ON - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - solid3 license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE_GPL.txt ${CMAKE_INSTALL_FULL_DATADIR}/solid3/LICENSE_GPL.txt - COMMAND ${CMAKE_COMMAND} -E copy /LICENSE_QPL.txt ${CMAKE_INSTALL_FULL_DATADIR}/solid3/LICENSE_QPL.txt - COMMAND ${CMAKE_COMMAND} -E copy /README.md ${CMAKE_INSTALL_FULL_DATADIR}/solid3/README.md -) diff --git a/3rdparty/soqt/CMakeLists.txt b/3rdparty/soqt/CMakeLists.txt deleted file mode 100644 index 9fb1ed35..00000000 --- a/3rdparty/soqt/CMakeLists.txt +++ /dev/null @@ -1,25 +0,0 @@ -ExternalProject_Add( - soqt - DEPENDS coin - #GIT_REPOSITORY https://github.com/coin3d/soqt.git - #GIT_TAG SoQt-1.6.0 - URL https://github.com/coin3d/soqt/releases/download/SoQt-1.6.0/soqt-1.6.0-src.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/soqt-SoQt-1.6.0.zip - URL_MD5 724996aedad2a33760dc36f08ceeda22 - CMAKE_ARGS - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - -DSOQT_BUILD_DOCUMENTATION=OFF - -DSOQT_BUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DSOQT_BUILD_TESTS=OFF - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - soqt license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/SoQt/COPYING -) diff --git a/3rdparty/xz/CMakeLists.txt b/3rdparty/xz/CMakeLists.txt deleted file mode 100644 index 7cdeaf63..00000000 --- a/3rdparty/xz/CMakeLists.txt +++ /dev/null @@ -1,26 +0,0 @@ -ExternalProject_Add( - xz - #GIT_REPOSITORY https://git.tukaani.org/xz.git - #GIT_TAG 90457dbe3e5717660f5b81f8c604860fc5137c0c - URL https://github.com/roboticslibrary/xz/archive/90457dbe3e5717660f5b81f8c604860fc5137c0c.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/xz-90457dbe3e5717660f5b81f8c604860fc5137c0c.tar.gz - URL_MD5 d6db20de0d42be75505a4c179b611101 - CMAKE_ARGS - -DBUILD_SHARED_LIBS=${BUILD_SHARED_LIBS} - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_DEBUG_POSTFIX=d - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - xz license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /COPYING ${CMAKE_INSTALL_FULL_DATADIR}/xz/COPYING - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.GPLv2 ${CMAKE_INSTALL_FULL_DATADIR}/xz/COPYING.GPLv2 - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.GPLv3 ${CMAKE_INSTALL_FULL_DATADIR}/xz/COPYING.GPLv3 - COMMAND ${CMAKE_COMMAND} -E copy /COPYING.LGPLv2.1 ${CMAKE_INSTALL_FULL_DATADIR}/xz/COPYING.LGPLv2.1 -) diff --git a/3rdparty/zlib/CMakeLists.txt b/3rdparty/zlib/CMakeLists.txt deleted file mode 100644 index 1f0c8fb0..00000000 --- a/3rdparty/zlib/CMakeLists.txt +++ /dev/null @@ -1,21 +0,0 @@ -ExternalProject_Add( - zlib - #GIT_REPOSITORY https://github.com/madler/zlib.git - #GIT_TAG v1.2.11 - URL https://github.com/madler/zlib/archive/v1.2.11.tar.gz - #URL ${CMAKE_CURRENT_SOURCE_DIR}/zlib-1.2.11.tar.gz - URL_MD5 0095d2d2d1f3442ce1318336637b695f - CMAKE_ARGS - -DCMAKE_BUILD_TYPE=${CMAKE_BUILD_TYPE} - -DCMAKE_CFG_INTDIR=${CMAKE_CFG_INTDIR} - -DCMAKE_INSTALL_PREFIX=${CMAKE_INSTALL_PREFIX} - -DCMAKE_PREFIX_PATH=${CMAKE_PREFIX_PATH} - -DCMAKE_TRY_COMPILE_CONFIGURATION=${CMAKE_TRY_COMPILE_CONFIGURATION} - INSTALL_DIR ${CMAKE_INSTALL_PREFIX} -) - -ExternalProject_Add_Step( - zlib license - DEPENDEES build - COMMAND ${CMAKE_COMMAND} -E copy /README ${CMAKE_INSTALL_FULL_DATADIR}/zlib/README -) From 8504de1bfb4cae8cd89749481bb96fdff8f3e317 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Nov 2020 18:15:59 +0100 Subject: [PATCH 416/546] Update minimum required CMake version --- CMakeLists.txt | 2 +- extras/CMakeLists.txt | 8 -------- src/rl/hal/CMakeLists.txt | 16 +++++++--------- src/rl/kin/CMakeLists.txt | 16 +++++++--------- src/rl/mdl/CMakeLists.txt | 16 +++++++--------- src/rl/plan/CMakeLists.txt | 16 +++++++--------- src/rl/sg/CMakeLists.txt | 16 +++++++--------- 7 files changed, 36 insertions(+), 54 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index fffc4bf5..4353f2fa 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 2.8.11) +cmake_minimum_required(VERSION 2.8.12) if(POLICY CMP0072) cmake_policy(SET CMP0072 NEW) diff --git a/extras/CMakeLists.txt b/extras/CMakeLists.txt index e8bc8936..be5c1eb7 100644 --- a/extras/CMakeLists.txt +++ b/extras/CMakeLists.txt @@ -1,11 +1,3 @@ -cmake_minimum_required(VERSION 2.8.11) - -if(POLICY CMP0072) - cmake_policy(SET CMP0072 NEW) -endif() - -project(extras) - add_subdirectory(byu2wrl) add_subdirectory(csv2wrl) add_subdirectory(tris2wrl) diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index e4b49c92..2d013b74 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -236,15 +236,13 @@ set_target_properties( VERSION ${VERSION} ) -if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) - set_target_properties( - hal - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden - VISIBILITY_INLINES_HIDDEN ON - ) -endif() +set_target_properties( + hal + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON +) if(MSVC) if(BUILD_SHARED_LIBS) diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index 40220a1f..611944cf 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -65,15 +65,13 @@ set_target_properties( VERSION ${VERSION} ) -if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) - set_target_properties( - kin - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden - VISIBILITY_INLINES_HIDDEN ON - ) -endif() +set_target_properties( + kin + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON +) if(MSVC) if(BUILD_SHARED_LIBS) diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 4cb9b63e..37b234c6 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -115,15 +115,13 @@ set_target_properties( VERSION ${VERSION} ) -if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) - set_target_properties( - mdl - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden - VISIBILITY_INLINES_HIDDEN ON - ) -endif() +set_target_properties( + mdl + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON +) if(MSVC) if(BUILD_SHARED_LIBS) diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index 5fb57415..5e4bac91 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -126,15 +126,13 @@ set_target_properties( VERSION ${VERSION} ) -if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) - set_target_properties( - plan - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden - VISIBILITY_INLINES_HIDDEN ON - ) -endif() +set_target_properties( + plan + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON +) if(MSVC) if(BUILD_SHARED_LIBS) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 9ecd9da9..8dad22cc 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -275,15 +275,13 @@ set_target_properties( VERSION ${VERSION} ) -if(NOT CMAKE_VERSION VERSION_LESS 2.8.12) - set_target_properties( - sg - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden - VISIBILITY_INLINES_HIDDEN ON - ) -endif() +set_target_properties( + sg + PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden + VISIBILITY_INLINES_HIDDEN ON +) if(MSVC) if(BUILD_SHARED_LIBS) From 27f0eb10de07fe7cc8cf192cb67add711a11568d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 30 Nov 2020 19:10:41 +0100 Subject: [PATCH 417/546] Use CMake policy CMP0042 to enable MACOSX_RPATH by default --- CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 4353f2fa..1c55ac52 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,5 +1,9 @@ cmake_minimum_required(VERSION 2.8.12) +if(POLICY CMP0042) + cmake_policy(SET CMP0042 NEW) +endif() + if(POLICY CMP0072) cmake_policy(SET CMP0072 NEW) endif() From c8e6adabc5cd0d27333655d54f2d34362bd3c5a2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 7 Dec 2020 00:16:48 +0100 Subject: [PATCH 418/546] Update CI workflow --- .github/workflows/ci.yml | 39 +++++++++++++++++++++------------------ 1 file changed, 21 insertions(+), 18 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 0bccf71a..af7051dd 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -8,6 +8,7 @@ on: - master jobs: build: + name: Build runs-on: ${{ matrix.os }} strategy: fail-fast: false @@ -33,7 +34,8 @@ jobs: CMAKE_PREFIX_PATH: ${{ matrix.cmake_prefix_path }} CXX: ${{ matrix.cxx }} steps: - - uses: actions/checkout@v1 + - name: Checkout repository + uses: actions/checkout@v2 - if: matrix.os == 'macos-latest' name: Set up Tap run: | @@ -83,25 +85,26 @@ jobs: libxml2-dev libxslt1-dev ninja-build + - name: Update environment variables + run: | + echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV + echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV + echo "${{ matrix.path }}" >> $GITHUB_PATH - name: Cache compiler - uses: actions/cache@v1 + uses: actions/cache@v2 with: - path: ~/.ccache - key: ${{ runner.os }}-${{ matrix.cc }}-ccache - - name: Create build directory - run: | - cmake -E make_directory ${{ runner.workspace }}/build - - name: Update PATH - run: echo "${{ matrix.path }}" >> $GITHUB_PATH + path: ${{ runner.workspace }}/.ccache + key: ${{ matrix.name }}-ccache - name: Configure CMake - working-directory: ${{ runner.workspace }}/build - run: | - cmake -G Ninja -D CMAKE_BUILD_TYPE=RelWithDebInfo $GITHUB_WORKSPACE + run: > + cmake + -G Ninja + -D CMAKE_BUILD_TYPE=RelWithDebInfo + -S $GITHUB_WORKSPACE + -B $RUNNER_WORKSPACE/rl-build - name: Build - working-directory: ${{ runner.workspace }}/build - run: | - cmake --build . + working-directory: ${{ runner.workspace }}/rl-build + run: cmake --build . - name: Test - working-directory: ${{ runner.workspace }}/build - run: | - ctest --output-on-failure + working-directory: ${{ runner.workspace }}/rl-build + run: ctest --output-on-failure From cdfdd5328e9f84b895098a57bdb86b75e436d5ac Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 7 Dec 2020 00:17:01 +0100 Subject: [PATCH 419/546] Add CodeQL workflow --- .github/workflows/codeql.yml | 56 ++++++++++++++++++++++++++++++++++++ 1 file changed, 56 insertions(+) create mode 100644 .github/workflows/codeql.yml diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml new file mode 100644 index 00000000..bef7cea6 --- /dev/null +++ b/.github/workflows/codeql.yml @@ -0,0 +1,56 @@ +name: CodeQL +on: + push: + branches: + - master + pull_request: + branches: + - master + schedule: + - cron: '30 14 * * 2' +jobs: + analyze: + name: Analyze + runs-on: ubuntu-latest + steps: + - name: Checkout repository + uses: actions/checkout@v2 + - name: Set up PPA + run: | + sudo apt-get install -y software-properties-common + sudo apt-add-repository -y -u ppa:roblib/ppa + - name: Install dependencies + run: > + sudo apt-get install -y + build-essential + cmake + libboost-dev + libbullet-dev + libcomedi-dev + libdc1394-22-dev + libeigen3-dev + libfcl-dev + libnlopt-dev + libode-dev + libsimage-dev + libsolid3d-dev + libsoqt-dev + libxml2-dev + libxslt1-dev + ninja-build + - name: Initialize CodeQL + uses: github/codeql-action/init@v1 + with: + languages: cpp + - name: Configure CMake + run: > + cmake + -G Ninja + -D CMAKE_BUILD_TYPE=Release + -S $GITHUB_WORKSPACE + -B $RUNNER_WORKSPACE/rl-build + - name: Build + working-directory: ${{ runner.workspace }}/rl-build + run: cmake --build . + - name: Perform CodeQL analysis + uses: github/codeql-action/analyze@v1 From cb5b2deb6600f8d35e9ac386138e832c49626878 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 8 Dec 2020 00:08:34 +0100 Subject: [PATCH 420/546] Add MSYS2 to CI workflow --- .github/workflows/ci.yml | 52 ++++++++++++++++++++++++++++++++-------- 1 file changed, 42 insertions(+), 10 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index af7051dd..cb3985b3 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -13,24 +13,29 @@ jobs: strategy: fail-fast: false matrix: - name: [macos-latest, ubuntu-latest-clang, ubuntu-latest-gcc] + name: + - macos-latest + - ubuntu-latest-clang + - ubuntu-latest-gcc + - windows-latest-msys2 include: - name: macos-latest cmake_prefix_path: /usr/local/opt/qt/lib/cmake os: macos-latest - path: /usr/local/opt/ccache/libexec - name: ubuntu-latest-clang cc: clang cxx: clang++ os: ubuntu-latest - path: /usr/lib/ccache - name: ubuntu-latest-gcc cc: gcc cxx: g++ os: ubuntu-latest - path: /usr/lib/ccache + - name: windows-latest-msys2 + os: windows-latest env: CC: ${{ matrix.cc }} + CMAKE_C_COMPILER_LAUNCHER: ccache + CMAKE_CXX_COMPILER_LAUNCHER: ccache CMAKE_PREFIX_PATH: ${{ matrix.cmake_prefix_path }} CXX: ${{ matrix.cxx }} steps: @@ -38,8 +43,7 @@ jobs: uses: actions/checkout@v2 - if: matrix.os == 'macos-latest' name: Set up Tap - run: | - brew tap roboticslibrary/rl + run: brew tap roboticslibrary/rl - if: matrix.os == 'ubuntu-latest' name: Set up PPA run: | @@ -85,11 +89,39 @@ jobs: libxml2-dev libxslt1-dev ninja-build - - name: Update environment variables + - if: matrix.name == 'windows-latest-msys2' + name: Set up MSYS2 + uses: msys2/setup-msys2@v2 + with: + install: >- + mingw-w64-x86_64-boost + mingw-w64-x86_64-bullet + mingw-w64-x86_64-ccache + mingw-w64-x86_64-cmake + mingw-w64-x86_64-coin + mingw-w64-x86_64-eigen3 + mingw-w64-x86_64-gcc + mingw-w64-x86_64-libxml2 + mingw-w64-x86_64-libxslt + mingw-w64-x86_64-ninja + mingw-w64-x86_64-nlopt + mingw-w64-x86_64-ode + mingw-w64-x86_64-pqp + mingw-w64-x86_64-qt5 + mingw-w64-x86_64-solid3 + mingw-w64-x86_64-soqt + update: true + - if: matrix.name != 'windows-latest-msys2' + name: Update environment variables run: | echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV - echo "${{ matrix.path }}" >> $GITHUB_PATH + - if: matrix.name == 'windows-latest-msys2' + name: Update environment variables for MSYS2 + run: | + Write-Output "CCACHE_BASEDIR=${{ runner.workspace }}" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append + Write-Output "CCACHE_DIR=${{ runner.workspace }}\.ccache" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append + Write-Output (msys2 -c "cygpath -w /mingw64/bin") | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append - name: Cache compiler uses: actions/cache@v2 with: @@ -100,8 +132,8 @@ jobs: cmake -G Ninja -D CMAKE_BUILD_TYPE=RelWithDebInfo - -S $GITHUB_WORKSPACE - -B $RUNNER_WORKSPACE/rl-build + -S ${{ github.workspace }} + -B ${{ runner.workspace }}/rl-build - name: Build working-directory: ${{ runner.workspace }}/rl-build run: cmake --build . From e069d223c2ca8d3c87d9b5880007f3c13196f3f7 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 16 Dec 2020 00:01:28 +0100 Subject: [PATCH 421/546] Initialize Coin3D in scene graph factories --- src/rl/sg/UrdfFactory.cpp | 4 ++++ src/rl/sg/XmlFactory.cpp | 2 ++ 2 files changed, 6 insertions(+) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 336ddcb5..c503339a 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -35,6 +35,7 @@ #ifdef HAVE_SOSTLFILEKIT_H #include #endif +#include #include #include #include @@ -91,6 +92,9 @@ namespace rl throw Exception("rl::sg::UrdfFactory::load() - URDF is missing robot node"); } + ::SoDB::init(); + ::SoNodeKit::init(); + for (int i = 0; i < robots.size(); ++i) { ::rl::xml::Path path(document, robots[i]); diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp index 1872b42f..bc282d2f 100644 --- a/src/rl/sg/XmlFactory.cpp +++ b/src/rl/sg/XmlFactory.cpp @@ -80,6 +80,8 @@ namespace rl throw Exception("rl::sg::XmlFactory::load() - No scenes found in file '" + filename + "'"); } + ::SoDB::init(); + for (int i = 0; i < ::std::min(1, scenes.size()); ++i) { ::rl::xml::Path path(document, scenes[i]); From 90d27198049d129ec3f0eeaf9b162ca24e74206d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 20 Dec 2020 18:25:07 +0100 Subject: [PATCH 422/546] Use QCommandLineParser on Qt 5.2 and higher --- demos/rlCollisionDemo/MainWindow.cpp | 166 +++++++++----- demos/rlCollisionDemo/MainWindow.h | 2 + demos/rlPlanDemo/MainWindow.cpp | 315 +++++++++++++++++++-------- demos/rlPlanDemo/MainWindow.h | 2 + 4 files changed, 339 insertions(+), 146 deletions(-) diff --git a/demos/rlCollisionDemo/MainWindow.cpp b/demos/rlCollisionDemo/MainWindow.cpp index f46716a9..514e714d 100644 --- a/demos/rlCollisionDemo/MainWindow.cpp +++ b/demos/rlCollisionDemo/MainWindow.cpp @@ -44,6 +44,10 @@ #include #include +#if QT_VERSION >= 0x050200 +#include +#endif + #ifdef RL_SG_BULLET #include #endif // RL_SG_BULLET @@ -91,64 +95,18 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoDB::init(); SoGradientBackground::initClass(); - QStringList engines; -#ifdef RL_SG_FCL - engines.push_back("fcl"); - this->engine = "fcl"; -#endif // RL_SG_FCL -#ifdef RL_SG_ODE - engines.push_back("ode"); - this->engine = "ode"; -#endif // RL_SG_ODE -#ifdef RL_SG_PQP - engines.push_back("pqp"); - this->engine = "pqp"; -#endif // RL_SG_PQP -#ifdef RL_SG_BULLET - engines.push_back("bullet"); - this->engine = "bullet"; -#endif // RL_SG_BULLET -#ifdef RL_SG_SOLID - engines.push_back("solid"); - this->engine = "solid"; -#endif // RL_SG_SOLID - engines.sort(); + this->parseCommandLine(); - QRegExp bodyRegExp("--body=(\\d*)"); - QRegExp engineRegExp("--engine=(" + engines.join("|") + ")"); - QRegExp helpRegExp("--help"); - QRegExp modelRegExp("--model=(\\d*)"); - - for (int i = 1; i < QApplication::arguments().size(); ++i) + if (this->filename.isEmpty()) { - if (-1 != bodyRegExp.indexIn(QApplication::arguments()[i])) - { - this->body = bodyRegExp.cap(1).toInt(); - } - else if (-1 != engineRegExp.indexIn(QApplication::arguments()[i])) - { - this->engine = engineRegExp.cap(1); - } - else if (-1 != helpRegExp.indexIn(QApplication::arguments()[i])) - { - QMessageBox::information(this, "Usage", "rlCollisionDemo [SCENEFILE] [--engine=" + engines.join("|") + "] [--help] [--model=MODEL] [--body=BODY]"); - exit(0); - } - else if (-1 != modelRegExp.indexIn(QApplication::arguments()[i])) - { - this->model = modelRegExp.cap(1).toInt(); - } - else + this->filename = QFileDialog::getOpenFileName(this, "", this->filename, "All Formats (*.xml)"); + + if (this->filename.isEmpty()) { - this->filename = QApplication::arguments()[i]; + exit(EXIT_FAILURE); } } - while (this->filename.isEmpty()) - { - this->filename = QFileDialog::getOpenFileName(this, "", this->filename, "All Formats (*.xml)"); - } - this->resize(1024, 768); #ifdef RL_SG_BULLET @@ -315,6 +273,110 @@ MainWindow::instance() return MainWindow::singleton; } +void +MainWindow::parseCommandLine() +{ + QStringList engines; +#ifdef RL_SG_FCL + engines.push_back("fcl"); + this->engine = "fcl"; +#endif // RL_SG_FCL +#ifdef RL_SG_ODE + engines.push_back("ode"); + this->engine = "ode"; +#endif // RL_SG_ODE +#ifdef RL_SG_PQP + engines.push_back("pqp"); + this->engine = "pqp"; +#endif // RL_SG_PQP +#ifdef RL_SG_BULLET + engines.push_back("bullet"); + this->engine = "bullet"; +#endif // RL_SG_BULLET +#ifdef RL_SG_SOLID + engines.push_back("solid"); + this->engine = "solid"; +#endif // RL_SG_SOLID + engines.sort(); + +#if QT_VERSION >= 0x050200 + QCommandLineOption bodyOption(QStringList("body"), "Sets active body.", "body"); + QCommandLineOption engineOption(QStringList("engine"), "Sets collision engine.", engines.join("|")); + QCommandLineOption modelOption(QStringList("model"), "Sets model of active body.", "model"); + + QCommandLineParser parser; + parser.addOption(bodyOption); + parser.addOption(engineOption); + const QCommandLineOption helpOption = parser.addHelpOption(); + parser.addOption(modelOption); + parser.addPositionalArgument("filename", "", "[filename]"); + + parser.process(QCoreApplication::arguments()); + + if (parser.isSet(bodyOption)) + { + bool ok; + this->body = parser.value(bodyOption).toUInt(&ok); + + if (!ok) + { + parser.showHelp(); + } + } + + if (parser.isSet(modelOption)) + { + bool ok; + this->model = parser.value(modelOption).toUInt(&ok); + + if (!ok) + { + parser.showHelp(); + } + } + + if (parser.positionalArguments().size() > 1) + { + parser.showHelp(); + } + + if (!parser.positionalArguments().empty()) + { + this->filename = parser.positionalArguments()[0]; + } +#else + QRegExp bodyRegExp("--body=(\\d*)"); + QRegExp engineRegExp("--engine=(" + engines.join("|") + ")"); + QRegExp helpRegExp("--help"); + QRegExp modelRegExp("--model=(\\d*)"); + + for (int i = 1; i < QApplication::arguments().size(); ++i) + { + if (-1 != bodyRegExp.indexIn(QApplication::arguments()[i])) + { + this->body = bodyRegExp.cap(1).toUInt(); + } + else if (-1 != engineRegExp.indexIn(QApplication::arguments()[i])) + { + this->engine = engineRegExp.cap(1); + } + else if (-1 != helpRegExp.indexIn(QApplication::arguments()[i])) + { + QMessageBox::information(this, "Usage", "rlCollisionDemo [--body=] [--engine=<" + engines.join("|") + ">] [--help] [--model=] [filename]"); + exit(0); + } + else if (-1 != modelRegExp.indexIn(QApplication::arguments()[i])) + { + this->model = modelRegExp.cap(1).toUInt(); + } + else + { + this->filename = QApplication::arguments()[i]; + } + } +#endif +} + void MainWindow::test() { diff --git a/demos/rlCollisionDemo/MainWindow.h b/demos/rlCollisionDemo/MainWindow.h index ea766cfc..517c44bd 100644 --- a/demos/rlCollisionDemo/MainWindow.h +++ b/demos/rlCollisionDemo/MainWindow.h @@ -58,6 +58,8 @@ class MainWindow : public QMainWindow MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); private: + void parseCommandLine(); + std::size_t body; SoVRMLCoordinate* depthCoordinate; diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index c4e825fd..cceb9f05 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -38,7 +38,6 @@ #include #include #include -#include #include #include #include @@ -82,6 +81,10 @@ #include #include +#if QT_VERSION >= 0x050200 +#include +#endif + #ifdef RL_SG_BULLET #include #endif // RL_SG_BULLET @@ -262,103 +265,16 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QObject::connect(this->thread, SIGNAL(statusChanged(const QString&)), this->statusBar(), SLOT(showMessage(const QString&))); - QStringList engines; -#ifdef RL_SG_FCL - engines.push_back("fcl"); - this->engine = "fcl"; -#endif // RL_SG_FCL -#ifdef RL_SG_ODE - engines.push_back("ode"); - this->engine = "ode"; -#endif // RL_SG_ODE -#ifdef RL_SG_PQP - engines.push_back("pqp"); - this->engine = "pqp"; -#endif // RL_SG_PQP -#ifdef RL_SG_BULLET - engines.push_back("bullet"); - this->engine = "bullet"; -#endif // RL_SG_BULLET -#ifdef RL_SG_SOLID - engines.push_back("solid"); - this->engine = "solid"; -#endif // RL_SG_SOLID - engines.sort(); - - QRegExp backgroundRegExp("--background=(\\S*)"); - QRegExp engineRegExp("--engine=(" + engines.join("|") + ")"); - QRegExp helpRegExp("--help"); - QRegExp heightRegExp("--height=(\\d*)"); - QRegExp quitRegExp("--enable-quit"); - QRegExp seedRegExp("--seed=(\\d*)"); - QRegExp viewerRegExp("--disable-viewer"); - QRegExp waitRegExp("--disable-wait"); - QRegExp widthRegExp("--width=(\\d*)"); - - int width = 1024; - int height = 768; - - bool doSetMinimumSize = false; - - for (int i = 1; i < QApplication::arguments().size(); ++i) - { - if (-1 != backgroundRegExp.indexIn(QApplication::arguments()[i])) - { - this->viewer->setBackgroundColor(backgroundRegExp.cap(1)); - } - else if (-1 != engineRegExp.indexIn(QApplication::arguments()[i])) - { - this->engine = engineRegExp.cap(1); - } - else if (-1 != helpRegExp.indexIn(QApplication::arguments()[i])) - { - QMessageBox::information(this, "Usage", "rlPlanDemo [PLANFILE] [--background=COLOR] [--engine=" + engines.join("|") + "] [--help] [--disable-viewer] [--disable-wait] [--enable-quit] [--seed=SEED] [--width=WIDTH] [--height=HEIGHT]"); - exit(EXIT_SUCCESS); - } - else if (-1 != heightRegExp.indexIn(QApplication::arguments()[i])) - { - height = heightRegExp.cap(1).toInt(); - doSetMinimumSize = true; - } - else if (-1 != quitRegExp.indexIn(QApplication::arguments()[i])) - { - this->thread->quit = true; - } - else if (-1 != seedRegExp.indexIn(QApplication::arguments()[i])) - { - this->seed = seedRegExp.cap(1).toUInt(); - } - else if (-1 != viewerRegExp.indexIn(QApplication::arguments()[i])) - { - QObject::disconnect(this->toggleViewActiveAction, SIGNAL(toggled(bool)), this, SLOT(toggleViewActive(bool))); - this->toggleViewActiveAction->setChecked(false); - QObject::connect(this->toggleViewActiveAction, SIGNAL(toggled(bool)), this, SLOT(toggleViewActive(bool))); - } - else if (-1 != waitRegExp.indexIn(QApplication::arguments()[i])) - { - this->wait = false; - } - else if (-1 != widthRegExp.indexIn(QApplication::arguments()[i])) - { - width = widthRegExp.cap(1).toInt(); - doSetMinimumSize = true; - } - else - { - this->filename = QApplication::arguments()[i]; - } - } - - this->resize(width, height); - - if (doSetMinimumSize) - { - this->viewer->setMinimumSize(width, height); - } + this->parseCommandLine(); if (this->filename.isEmpty()) { this->open(); + + if (this->filename.isEmpty()) + { + exit(EXIT_FAILURE); + } } else { @@ -1962,6 +1878,217 @@ MainWindow::open() } } +void +MainWindow::parseCommandLine() +{ + QStringList engines; +#ifdef RL_SG_FCL + engines.push_back("fcl"); + this->engine = "fcl"; +#endif // RL_SG_FCL +#ifdef RL_SG_ODE + engines.push_back("ode"); + this->engine = "ode"; +#endif // RL_SG_ODE +#ifdef RL_SG_PQP + engines.push_back("pqp"); + this->engine = "pqp"; +#endif // RL_SG_PQP +#ifdef RL_SG_BULLET + engines.push_back("bullet"); + this->engine = "bullet"; +#endif // RL_SG_BULLET +#ifdef RL_SG_SOLID + engines.push_back("solid"); + this->engine = "solid"; +#endif // RL_SG_SOLID + engines.sort(); + + int width = 1024; + int height = 768; + + bool doSetMinimumSize = false; + +#if QT_VERSION >= 0x050200 + QCommandLineOption backgroundOption(QStringList("background"), "Sets background color of 3D viewer.", "color"); + QCommandLineOption disableViewerOption(QStringList("disable-viewer"), "Disables viewer during planning."); + QCommandLineOption disableWaitOption(QStringList("disable-wait"), "Disables wait before planning."); + QCommandLineOption enableQuitOption(QStringList("enable-quit"), "Exits after planning."); + QCommandLineOption engineOption(QStringList("engine"), "Sets collision engine.", engines.join("|")); + QCommandLineOption heightOption(QStringList("height"), "Sets minimum height of 3D viewer.", "height"); + QCommandLineOption seedOption(QStringList("seed"), "Sets seed value.", "seed"); + QCommandLineOption widthOption(QStringList("width"), "Sets minimum width of 3D viewer.", "width"); + + QCommandLineParser parser; + parser.addOption(backgroundOption); + parser.addOption(disableViewerOption); + parser.addOption(disableWaitOption); + parser.addOption(enableQuitOption); + parser.addOption(engineOption); + parser.addOption(heightOption); + QCommandLineOption helpOption = parser.addHelpOption(); + parser.addOption(seedOption); + parser.addOption(widthOption); + parser.addPositionalArgument("filename", "", "[filename]"); + + parser.process(QCoreApplication::arguments()); + + if (parser.isSet(backgroundOption)) + { + QString background = parser.value(backgroundOption); + + if (!QColor::isValidColor(background)) + { + parser.showHelp(); + } + + this->viewer->setBackgroundColor(QColor(background)); + } + + if (parser.isSet(disableViewerOption)) + { + QObject::disconnect(this->toggleViewActiveAction, SIGNAL(toggled(bool)), this, SLOT(toggleViewActive(bool))); + this->toggleViewActiveAction->setChecked(false); + QObject::connect(this->toggleViewActiveAction, SIGNAL(toggled(bool)), this, SLOT(toggleViewActive(bool))); + } + + if (parser.isSet(disableWaitOption)) + { + this->wait = false; + } + + if (parser.isSet(enableQuitOption)) + { + this->thread->quit = true; + } + + if (parser.isSet(engineOption)) + { + QString engine = parser.value(engineOption); + + if (!engines.contains(engine, Qt::CaseInsensitive)) + { + parser.showHelp(); + } + + this->engine = engine; + } + + if (parser.isSet(heightOption)) + { + bool ok; + height = parser.value(heightOption).toInt(&ok); + + if (!ok) + { + parser.showHelp(); + } + + doSetMinimumSize = true; + } + + if (parser.isSet(seedOption)) + { + bool ok; + this->seed = parser.value(seedOption).toUInt(&ok); + + if (!ok) + { + parser.showHelp(); + } + } + + if (parser.isSet(widthOption)) + { + bool ok; + width = parser.value(widthOption).toInt(&ok); + + if (!ok) + { + parser.showHelp(); + } + + doSetMinimumSize = true; + } + + if (parser.positionalArguments().size() > 1) + { + parser.showHelp(); + } + + if (!parser.positionalArguments().empty()) + { + this->filename = parser.positionalArguments()[0]; + } +#else + QRegExp backgroundRegExp("--background=(\\S*)"); + QRegExp engineRegExp("--engine=(" + engines.join("|") + ")"); + QRegExp helpRegExp("--help"); + QRegExp heightRegExp("--height=(\\d*)"); + QRegExp quitRegExp("--enable-quit"); + QRegExp seedRegExp("--seed=(\\d*)"); + QRegExp viewerRegExp("--disable-viewer"); + QRegExp waitRegExp("--disable-wait"); + QRegExp widthRegExp("--width=(\\d*)"); + + for (int i = 1; i < QApplication::arguments().size(); ++i) + { + if (-1 != backgroundRegExp.indexIn(QApplication::arguments()[i])) + { + this->viewer->setBackgroundColor(backgroundRegExp.cap(1)); + } + else if (-1 != engineRegExp.indexIn(QApplication::arguments()[i])) + { + this->engine = engineRegExp.cap(1); + } + else if (-1 != helpRegExp.indexIn(QApplication::arguments()[i])) + { + QMessageBox::information(this, "Usage", "rlPlanDemo [--background=] [--disable-viewer] [--disable-wait] [--enable-quit] [--engine=<" + engines.join("|") + ">] [--height=] [--help] [--seed=] [--width=] [filename]"); + exit(EXIT_SUCCESS); + } + else if (-1 != heightRegExp.indexIn(QApplication::arguments()[i])) + { + height = heightRegExp.cap(1).toInt(); + doSetMinimumSize = true; + } + else if (-1 != quitRegExp.indexIn(QApplication::arguments()[i])) + { + this->thread->quit = true; + } + else if (-1 != seedRegExp.indexIn(QApplication::arguments()[i])) + { + this->seed = seedRegExp.cap(1).toUInt(); + } + else if (-1 != viewerRegExp.indexIn(QApplication::arguments()[i])) + { + QObject::disconnect(this->toggleViewActiveAction, SIGNAL(toggled(bool)), this, SLOT(toggleViewActive(bool))); + this->toggleViewActiveAction->setChecked(false); + QObject::connect(this->toggleViewActiveAction, SIGNAL(toggled(bool)), this, SLOT(toggleViewActive(bool))); + } + else if (-1 != waitRegExp.indexIn(QApplication::arguments()[i])) + { + this->wait = false; + } + else if (-1 != widthRegExp.indexIn(QApplication::arguments()[i])) + { + width = widthRegExp.cap(1).toInt(); + doSetMinimumSize = true; + } + else + { + this->filename = QApplication::arguments()[i]; + } + } +#endif + + this->resize(width, height); + + if (doSetMinimumSize) + { + this->viewer->setMinimumSize(width, height); + } +} + void MainWindow::reset() { diff --git a/demos/rlPlanDemo/MainWindow.h b/demos/rlPlanDemo/MainWindow.h index 066818ea..4d2ded7b 100644 --- a/demos/rlPlanDemo/MainWindow.h +++ b/demos/rlPlanDemo/MainWindow.h @@ -191,6 +191,8 @@ public slots: void load(const QString& filename); + void parseCommandLine(); + ConfigurationDelegate* configurationDelegate; QDockWidget* configurationDockWidget; From ebe53b1f22b6c2054bc327b34c684c879bb7ef43 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 20 Dec 2020 18:33:25 +0100 Subject: [PATCH 423/546] Update deprecated Qt classes and functions --- demos/rlPlanDemo/MainWindow.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index cceb9f05..fe1b7ac7 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -2147,8 +2147,13 @@ MainWindow::savePdf() QPrinter printer; printer.setOutputFileName(filename); printer.setOutputFormat(QPrinter::PdfFormat); +#if QT_VERSION >= 0x050E00 + printer.setPageMargins(QMarginsF(0, 0, 0, 0), QPageLayout::Millimeter); + printer.setPageSize(QPageSize(this->configurationSpaceScene->sceneRect().size(), QPageSize::Millimeter)); +#else printer.setPageMargins(0, 0, 0, 0, QPrinter::Millimeter); printer.setPaperSize(this->configurationSpaceScene->sceneRect().size(), QPrinter::Millimeter); +#endif QPainter painter(&printer); From 9a7a2b888fbab9b5b45bced11271fa2928ccec4b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 20 Dec 2020 23:30:07 +0100 Subject: [PATCH 424/546] Enable alpha channel and sample buffers --- demos/rlCoachMdl/MainWindow.cpp | 5 +++++ demos/rlSimulator/MainWindow.cpp | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index b85d540c..36308a4d 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -76,6 +76,11 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoDB::init(); SoGradientBackground::initClass(); + QGLFormat format; + format.setAlpha(true); + format.setSampleBuffers(true); + QGLFormat::setDefaultFormat(format); + std::shared_ptr geometryFactory; std::string geometryFilename = QApplication::arguments()[1].toStdString(); diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index f922b02b..41b20536 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -112,6 +112,11 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoDB::init(); SoGradientBackground::initClass(); + QGLFormat format; + format.setAlpha(true); + format.setSampleBuffers(true); + QGLFormat::setDefaultFormat(format); + this->scene = std::make_shared(); rl::sg::XmlFactory geometryFactory; geometryFactory.load(QApplication::arguments()[1].toStdString(), this->scene.get()); From 7c4454978300adfbbccd040dbeaa159b42c1ab2f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 11 Aug 2020 11:52:32 +0200 Subject: [PATCH 425/546] Fix whitespace --- src/rl/hal/CyclicDevice.cpp | 2 +- src/rl/hal/Dc1394Camera.h | 22 +++++++++++----------- src/rl/kin/Revolute.cpp | 4 ++-- src/rl/math/SplineQuaternion.h | 4 ++-- src/rl/mdl/UrdfFactory.cpp | 2 +- src/rl/sg/UrdfFactory.cpp | 2 +- src/rl/xml/Node.h | 2 +- 7 files changed, 19 insertions(+), 19 deletions(-) diff --git a/src/rl/hal/CyclicDevice.cpp b/src/rl/hal/CyclicDevice.cpp index 1f22ef73..04bece1d 100644 --- a/src/rl/hal/CyclicDevice.cpp +++ b/src/rl/hal/CyclicDevice.cpp @@ -41,7 +41,7 @@ namespace rl } ::std::chrono::nanoseconds - CyclicDevice::getUpdateRate() const + CyclicDevice::getUpdateRate() const { return this->updateRate; } diff --git a/src/rl/hal/Dc1394Camera.h b/src/rl/hal/Dc1394Camera.h index 313ddd54..0341a0ea 100644 --- a/src/rl/hal/Dc1394Camera.h +++ b/src/rl/hal/Dc1394Camera.h @@ -46,17 +46,17 @@ namespace rl public: enum class ColorCoding { - mono8 = ::DC1394_COLOR_CODING_MONO8, - yuv411, - yuv422, - yuv444, - rgb8, - mono16, - rgb16, - mono16s, - rgb16s, - raw8, - raw16 + mono8 = ::DC1394_COLOR_CODING_MONO8, + yuv411, + yuv422, + yuv444, + rgb8, + mono16, + rgb16, + mono16s, + rgb16s, + raw8, + raw16 }; RL_HAL_DEPRECATED static constexpr ColorCoding COLOR_CODING_MONO8 = ColorCoding::mono8; diff --git a/src/rl/kin/Revolute.cpp b/src/rl/kin/Revolute.cpp index 5982e06a..71fb8645 100644 --- a/src/rl/kin/Revolute.cpp +++ b/src/rl/kin/Revolute.cpp @@ -44,13 +44,13 @@ namespace rl } ::rl::math::Units - Revolute::getPositionUnit() const + Revolute::getPositionUnit() const { return ::rl::math::Units::radian; } ::rl::math::Units - Revolute::getSpeedUnit() const + Revolute::getSpeedUnit() const { return ::rl::math::Units::radianPerSecond; } diff --git a/src/rl/math/SplineQuaternion.h b/src/rl/math/SplineQuaternion.h index b6784b08..3afb147e 100644 --- a/src/rl/math/SplineQuaternion.h +++ b/src/rl/math/SplineQuaternion.h @@ -120,8 +120,8 @@ namespace rl for (::std::size_t i = 2; i < n - 1; ++i) { - b[i] -= c[i - 1] * a[i] / b[i - 1]; - d[i] -= (a[i] / b[i - 1]) * B(e[i - 1], dtheta[i - 1], d[i - 1]); + b[i] -= c[i - 1] * a[i] / b[i - 1]; + d[i] -= (a[i] / b[i - 1]) * B(e[i - 1], dtheta[i - 1], d[i - 1]); } if (n > 2) diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 74b5bb18..8dfa0c49 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -190,7 +190,7 @@ ::std::cout << "\tchild: " << child->getName() << ::std::endl; fixed->x.linear() = ::rl::math::AngleAxis( ::boost::lexical_cast<::rl::math::Real>(rpy[2]), - ::rl::math::Vector3::UnitZ() + ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( ::boost::lexical_cast<::rl::math::Real>(rpy[1]), ::rl::math::Vector3::UnitY() diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index c503339a..4f0e5ecb 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -418,7 +418,7 @@ ::std::cout << "\torigin rpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << : origin.linear() = ::rl::math::AngleAxis( ::boost::lexical_cast<::rl::math::Real>(rpy[2]), - ::rl::math::Vector3::UnitZ() + ::rl::math::Vector3::UnitZ() ) * ::rl::math::AngleAxis( ::boost::lexical_cast<::rl::math::Real>(rpy[1]), ::rl::math::Vector3::UnitY() diff --git a/src/rl/xml/Node.h b/src/rl/xml/Node.h index 422df9dd..733bbec0 100644 --- a/src/rl/xml/Node.h +++ b/src/rl/xml/Node.h @@ -112,7 +112,7 @@ namespace rl { ::boost::shared_array<::xmlChar> content( ::xmlNodeGetContent(this->node), - ::xmlFree + ::xmlFree ); return nullptr != content.get() ? reinterpret_cast(content.get()) : ::std::string(); From fca4287e8050c49164cbe93090db839a851ae5d9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 11 Aug 2020 12:29:23 +0200 Subject: [PATCH 426/546] Add protected function for setting the update rate --- src/rl/hal/CyclicDevice.cpp | 6 ++++++ src/rl/hal/CyclicDevice.h | 1 + 2 files changed, 7 insertions(+) diff --git a/src/rl/hal/CyclicDevice.cpp b/src/rl/hal/CyclicDevice.cpp index 04bece1d..b723eca8 100644 --- a/src/rl/hal/CyclicDevice.cpp +++ b/src/rl/hal/CyclicDevice.cpp @@ -45,5 +45,11 @@ namespace rl { return this->updateRate; } + + void + CyclicDevice::setUpdateRate(const ::std::chrono::nanoseconds& updateRate) + { + this->updateRate = updateRate; + } } } diff --git a/src/rl/hal/CyclicDevice.h b/src/rl/hal/CyclicDevice.h index 1a85d3ab..f7a0aac1 100644 --- a/src/rl/hal/CyclicDevice.h +++ b/src/rl/hal/CyclicDevice.h @@ -50,6 +50,7 @@ namespace rl virtual void step() = 0; protected: + void setUpdateRate(const ::std::chrono::nanoseconds& updateRate); private: ::std::chrono::nanoseconds updateRate; From 8240b1744cbb52f0bfac3bb95b89d05b4e5e58e5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 26 Aug 2020 17:24:43 +0200 Subject: [PATCH 427/546] Add checkboxes for selecting IK goals --- demos/rlCoachMdl/MainWindow.cpp | 3 +++ demos/rlCoachMdl/MainWindow.h | 2 ++ demos/rlCoachMdl/OperationalModel.cpp | 38 ++++++++++++++++++++++----- 3 files changed, 37 insertions(+), 6 deletions(-) diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index 36308a4d..33555520 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -53,6 +53,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : ikIterationsSpinBox(new QSpinBox(this)), ikJacobianComboBox(new QComboBox(this)), kinematicModels(), + operationalGoals(), operationalModels(), scene(), configurationDelegates(), @@ -116,6 +117,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : for (std::size_t i = 0; i < this->kinematicModels.size(); ++i) { + this->operationalGoals.push_back(std::vector(this->kinematicModels[i]->getOperationalDof(), true)); + ConfigurationDelegate* configurationDelegate = new ConfigurationDelegate(this); configurationDelegate->id = i; this->configurationDelegates.push_back(configurationDelegate); diff --git a/demos/rlCoachMdl/MainWindow.h b/demos/rlCoachMdl/MainWindow.h index fae808d9..dfe079f3 100644 --- a/demos/rlCoachMdl/MainWindow.h +++ b/demos/rlCoachMdl/MainWindow.h @@ -71,6 +71,8 @@ class MainWindow : public QMainWindow std::vector> kinematicModels; + std::vector> operationalGoals; + std::vector operationalModels; std::shared_ptr scene; diff --git a/demos/rlCoachMdl/OperationalModel.cpp b/demos/rlCoachMdl/OperationalModel.cpp index f8154262..9f95ab3b 100644 --- a/demos/rlCoachMdl/OperationalModel.cpp +++ b/demos/rlCoachMdl/OperationalModel.cpp @@ -82,6 +82,16 @@ OperationalModel::data(const QModelIndex& index, int role) const switch (role) { + case Qt::CheckStateRole: + switch (index.column()) + { + case 0: + return MainWindow::instance()->operationalGoals[this->id][index.row()] ? Qt::Checked : Qt::Unchecked; + break; + default: + break; + } + break; case Qt::DisplayRole: switch (index.column()) { @@ -134,6 +144,11 @@ OperationalModel::flags(const QModelIndex &index) const return Qt::NoItemFlags; } + if (0 == index.column()) + { + return QAbstractItemModel::flags(index) | Qt::ItemIsEditable | Qt::ItemIsUserCheckable; + } + return QAbstractItemModel::flags(index) | Qt::ItemIsEditable; } @@ -199,7 +214,19 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r return false; } - if (index.isValid() && Qt::EditRole == role) + if (!index.isValid()) + { + return false; + } + + if (Qt::CheckStateRole == role) + { + if (0 == index.column()) + { + MainWindow::instance()->operationalGoals[this->id][index.row()] = value.value(); + } + } + else if (Qt::EditRole == role) { if (rl::mdl::Kinematic* kinematic = dynamic_cast(MainWindow::instance()->kinematicModels[this->id].get())) { @@ -272,14 +299,13 @@ OperationalModel::setData(const QModelIndex& index, const QVariant& value, int r } #endif -#if 0 - ik->addGoal(transform, index.row()); -#else for (std::size_t i = 0; i < kinematic->getOperationalDof(); ++i) { - ik->addGoal(i == index.row() ? transform : kinematic->getOperationalPosition(i), i); + if (MainWindow::instance()->operationalGoals[this->id][i]) + { + ik->addGoal(i == index.row() ? transform : kinematic->getOperationalPosition(i), i); + } } -#endif std::chrono::steady_clock::time_point start = std::chrono::steady_clock::now(); bool solved = ik->solve(); From 9c438ffc7415f5423a87043e31659e1c72ac2987 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 26 Aug 2020 17:33:52 +0200 Subject: [PATCH 428/546] Add getter for operational frames --- src/rl/mdl/Model.cpp | 8 ++++++++ src/rl/mdl/Model.h | 2 ++ 2 files changed, 10 insertions(+) diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index a2d17474..d9d93b7b 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -353,6 +353,14 @@ namespace rl return this->tree[this->leaves[i]]->f; } + Frame* + Model::getOperationalFrame(const ::std::size_t& i) const + { + assert(i < this->getOperationalDof()); + + return this->tree[this->leaves[i]].get(); + } + const ::rl::math::Transform& Model::getOperationalPosition(const ::std::size_t& i) const { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 488161a5..8e4e696a 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -119,6 +119,8 @@ namespace rl const ::rl::math::ForceVector& getOperationalForce(const ::std::size_t& i) const; + Frame* getOperationalFrame(const ::std::size_t& i) const; + const ::rl::math::Transform& getOperationalPosition(const ::std::size_t& i) const; const ::rl::math::MotionVector& getOperationalVelocity(const ::std::size_t& i) const; From 629eae86af08f67d0ee836ccb7437bd05763c47b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 26 Aug 2020 17:34:47 +0200 Subject: [PATCH 429/546] Update row label to use name of frame --- demos/rlCoachMdl/OperationalModel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/rlCoachMdl/OperationalModel.cpp b/demos/rlCoachMdl/OperationalModel.cpp index 9f95ab3b..66040a3e 100644 --- a/demos/rlCoachMdl/OperationalModel.cpp +++ b/demos/rlCoachMdl/OperationalModel.cpp @@ -189,7 +189,7 @@ OperationalModel::headerData(int section, Qt::Orientation orientation, int role) if (Qt::DisplayRole == role && Qt::Vertical == orientation) { - return section; + return QString::fromStdString(MainWindow::instance()->kinematicModels[this->id]->getOperationalFrame(section)->getName()); } return QVariant(); From e8cb75e64cff48d162497a9bb1935a4f4cb98ba1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 3 Sep 2020 15:41:14 +0200 Subject: [PATCH 430/546] Upgrade Doxygen configuration --- doc/Doxyfile.in | 81 ++++++++++++++++++++++++++++++++++--------------- 1 file changed, 56 insertions(+), 25 deletions(-) diff --git a/doc/Doxyfile.in b/doc/Doxyfile.in index 9a678d5b..b0fc778e 100644 --- a/doc/Doxyfile.in +++ b/doc/Doxyfile.in @@ -1,4 +1,4 @@ -# Doxyfile 1.8.17 +# Doxyfile 1.8.20 # This file describes the settings to be used by the documentation system # doxygen (www.doxygen.org) for a project. @@ -227,6 +227,14 @@ QT_AUTOBRIEF = NO MULTILINE_CPP_IS_BRIEF = NO +# By default Python docstrings are displayed as preformatted text and doxygen's +# special commands cannot be used. By setting PYTHON_DOCSTRING to NO the +# doxygen's special commands can be used and the contents of the docstring +# documentation blocks is shown as doxygen documentation. +# The default value is: YES. + +PYTHON_DOCSTRING = YES + # If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the # documentation from any documented member that it re-implements. # The default value is: YES. @@ -263,12 +271,6 @@ TAB_SIZE = 4 ALIASES = -# This tag can be used to specify a number of word-keyword mappings (TCL only). -# A mapping has the form "name=value". For example adding "class=itcl::class" -# will allow you to use the command class in the itcl::class meaning. - -TCL_SUBST = - # Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources # only. Doxygen will then generate output that is more tailored for C. For # instance, some of the names that are used will be different. The list of all @@ -310,13 +312,13 @@ OPTIMIZE_OUTPUT_SLICE = NO # extension. Doxygen has a built-in mapping, but you can override or extend it # using this tag. The format is ext=language, where ext is a file extension, and # language is one of the parsers supported by doxygen: IDL, Java, JavaScript, -# Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice, +# Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice, VHDL, # Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: # FortranFree, unknown formatted Fortran: Fortran. In the later case the parser # tries to guess whether the code is fixed or free formatted code, this is the -# default for Fortran type files), VHDL, tcl. For instance to make doxygen treat -# .inc files as Fortran files (default is PHP), and .f files as C (default is -# Fortran), use: inc=Fortran f=C. +# default for Fortran type files). For instance to make doxygen treat .inc files +# as Fortran files (default is PHP), and .f files as C (default is Fortran), +# use: inc=Fortran f=C. # # Note: For files without extension you can use no_extension as a placeholder. # @@ -455,6 +457,19 @@ TYPEDEF_HIDES_STRUCT = NO LOOKUP_CACHE_SIZE = 0 +# The NUM_PROC_THREADS specifies the number threads doxygen is allowed to use +# during processing. When set to 0 doxygen will based this on the number of +# cores available in the system. You can set it explicitly to a value larger +# than 0 to get more control over the balance between CPU load and processing +# speed. At this moment only the input processing can be done using multiple +# threads. Since this is still an experimental feature the default is set to 1, +# which efficively disables parallel processing. Please report any issues you +# encounter. Generating dot graphs in parallel is controlled by the +# DOT_NUM_THREADS setting. +# Minimum value: 0, maximum value: 32, default value: 1. + +NUM_PROC_THREADS = 1 + #--------------------------------------------------------------------------- # Build related configuration options #--------------------------------------------------------------------------- @@ -559,7 +574,7 @@ INTERNAL_DOCS = NO # names in lower-case letters. If set to YES, upper-case letters are also # allowed. This is useful if you have classes or files whose names only differ # in case and if your file system supports case sensitive file names. Windows -# (including Cygwin) ands Mac users are advised to set this option to NO. +# (including Cygwin) and Mac users are advised to set this option to NO. # The default value is: system dependent. CASE_SENSE_NAMES = NO @@ -853,7 +868,7 @@ INPUT_ENCODING = UTF-8 # *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, # *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C comment), # *.doc (to be provided as doxygen C comment), *.txt (to be provided as doxygen -# C comment), *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f, *.for, *.tcl, *.vhd, +# C comment), *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f18, *.f, *.for, *.vhd, # *.vhdl, *.ucf, *.qsf and *.ice. FILE_PATTERNS = *.c \ @@ -895,9 +910,9 @@ FILE_PATTERNS = *.c \ *.f95 \ *.f03 \ *.f08 \ + *.f18 \ *.f \ *.for \ - *.tcl \ *.vhd \ *.vhdl \ *.ucf \ @@ -1134,10 +1149,13 @@ CLANG_ASSISTED_PARSING = NO CLANG_OPTIONS = # If clang assisted parsing is enabled you can provide the clang parser with the -# path to the compilation database (see: -# http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html) used when the files -# were built. This is equivalent to specifying the "-p" option to a clang tool, -# such as clang-check. These options will then be passed to the parser. +# path to the directory containing a file called compile_commands.json. This +# file is the compilation database (see: +# http://clang.llvm.org/docs/HowToSetupToolingForLLVM.html) containing the +# options used when the source files were built. This is equivalent to +# specifying the "-p" option to a clang tool, such as clang-check. These options +# will then be passed to the parser. Any options specified with CLANG_OPTIONS +# will be added as well. # Note: The availability of this option depends on whether or not doxygen was # generated with the -Duse_libclang=ON option for CMake. @@ -1407,7 +1425,7 @@ CHM_FILE = HHC_LOCATION = # The GENERATE_CHI flag controls if a separate .chi index file is generated -# (YES) or that it should be included in the master .chm file (NO). +# (YES) or that it should be included in the main .chm file (NO). # The default value is: NO. # This tag requires that the tag GENERATE_HTMLHELP is set to YES. @@ -1569,6 +1587,17 @@ TREEVIEW_WIDTH = 250 EXT_LINKS_IN_WINDOW = NO +# If the HTML_FORMULA_FORMAT option is set to svg, doxygen will use the pdf2svg +# tool (see https://github.com/dawbarton/pdf2svg) or inkscape (see +# https://inkscape.org) to generate formulas as SVG images instead of PNGs for +# the HTML output. These images will generally look nicer at scaled resolutions. +# Possible values are: png (the default) and svg (looks nicer but requires the +# pdf2svg or inkscape tool). +# The default value is: png. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FORMULA_FORMAT = png + # Use this tag to change the font size of LaTeX formulas included as images in # the HTML documentation. When you change the font size after a successful # doxygen run you need to manually remove any form_*.png images from the HTML @@ -1624,10 +1653,10 @@ MATHJAX_FORMAT = HTML-CSS # Content Delivery Network so you can quickly see the result without installing # MathJax. However, it is strongly recommended to install a local copy of # MathJax from https://www.mathjax.org before deployment. -# The default value is: https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/. +# The default value is: https://cdn.jsdelivr.net/npm/mathjax@2. # This tag requires that the tag USE_MATHJAX is set to YES. -MATHJAX_RELPATH = https://cdnjs.cloudflare.com/ajax/libs/mathjax/2.7.5/ +MATHJAX_RELPATH = https://cdn.jsdelivr.net/npm/mathjax@2 # The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax # extension names that should be enabled during MathJax rendering. For example @@ -1777,7 +1806,7 @@ MAKEINDEX_CMD_NAME = "${MAKEINDEX_COMPILER}" # The default value is: makeindex. # This tag requires that the tag GENERATE_LATEX is set to YES. -LATEX_MAKEINDEX_CMD = makeindex +LATEX_MAKEINDEX_CMD = "${MAKEINDEX_COMPILER}" # If the COMPACT_LATEX tag is set to YES, doxygen generates more compact LaTeX # documents. This may be useful for small projects and may help to save some @@ -1865,9 +1894,11 @@ LATEX_EXTRA_FILES = PDF_HYPERLINKS = YES -# If the USE_PDFLATEX tag is set to YES, doxygen will use pdflatex to generate -# the PDF file directly from the LaTeX files. Set this option to YES, to get a -# higher quality PDF documentation. +# If the USE_PDFLATEX tag is set to YES, doxygen will use the engine as +# specified with LATEX_CMD_NAME to generate the PDF file directly from the LaTeX +# files. Set this option to YES, to get a higher quality PDF documentation. +# +# See also section LATEX_CMD_NAME for selecting the engine. # The default value is: YES. # This tag requires that the tag GENERATE_LATEX is set to YES. From eb6f35703e7ef5ca2c2aa4b7f1bda4f7b68abcbe Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 Jan 2021 18:57:40 +0100 Subject: [PATCH 431/546] Add missing includes --- src/rl/util/rtai/thread.h | 1 + src/rl/util/xenomai/thread.h | 1 + 2 files changed, 2 insertions(+) diff --git a/src/rl/util/rtai/thread.h b/src/rl/util/rtai/thread.h index a75991b4..91c81f77 100644 --- a/src/rl/util/rtai/thread.h +++ b/src/rl/util/rtai/thread.h @@ -28,6 +28,7 @@ #define RL_UTIL_RTAI_THREAD #include +#include #include #include #include diff --git a/src/rl/util/xenomai/thread.h b/src/rl/util/xenomai/thread.h index ab8f2a4a..6d60cb22 100644 --- a/src/rl/util/xenomai/thread.h +++ b/src/rl/util/xenomai/thread.h @@ -28,6 +28,7 @@ #define RL_UTIL_XENOMAI_THREAD #include +#include #include #include #include From 5cd4ec7a69d449b29dfb19e97554d307307ac9a0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 Jan 2021 18:58:51 +0100 Subject: [PATCH 432/546] Fix whitespace --- src/rl/std/memory.h | 6 +++--- src/rl/util/xenomai/mutex.h | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/rl/std/memory.h b/src/rl/std/memory.h index b275c1e4..38e57422 100644 --- a/src/rl/std/memory.h +++ b/src/rl/std/memory.h @@ -40,21 +40,21 @@ namespace rl #ifdef __cpp_lib_make_unique using ::std::make_unique; #else - template + template typename ::std::enable_if<::std::is_array::value, ::std::unique_ptr>::type make_unique(::std::size_t n) { return ::std::unique_ptr(new typename ::std::remove_extent::type[n]()); } - template + template typename ::std::enable_if::value, ::std::unique_ptr>::type make_unique(Args&&... args) { return ::std::unique_ptr(new T(::std::forward(args)...)); } - template + template typename ::std::enable_if<::std::extent::value != 0, ::std::unique_ptr>::type make_unique(Args&&...) = delete; #endif diff --git a/src/rl/util/xenomai/mutex.h b/src/rl/util/xenomai/mutex.h index f1341e21..29c1f381 100644 --- a/src/rl/util/xenomai/mutex.h +++ b/src/rl/util/xenomai/mutex.h @@ -251,13 +251,13 @@ namespace rl } } - template + template bool try_lock_for(const ::std::chrono::duration& rtime) { return this->M_try_lock_for(rtime); } - template + template bool try_lock_until(const ::std::chrono::time_point& atime) { return this->M_try_lock_until(atime); From 2c1d4b9cae30da0b81972c6b07efda0af17801db Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 Jan 2021 19:00:26 +0100 Subject: [PATCH 433/546] Use GL headers from Open Inventor --- demos/rlCoachKin/SoGradientBackground.cpp | 11 +---------- demos/rlCoachMdl/SoGradientBackground.cpp | 11 +---------- demos/rlCollisionDemo/SoGradientBackground.cpp | 11 +---------- demos/rlPlanDemo/SoGradientBackground.cpp | 11 +---------- demos/rlSimulator/SoGradientBackground.cpp | 11 +---------- 5 files changed, 5 insertions(+), 50 deletions(-) diff --git a/demos/rlCoachKin/SoGradientBackground.cpp b/demos/rlCoachKin/SoGradientBackground.cpp index b50675d2..566e0fb9 100644 --- a/demos/rlCoachKin/SoGradientBackground.cpp +++ b/demos/rlCoachKin/SoGradientBackground.cpp @@ -24,17 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#ifdef WIN32 -#include -#endif // WIN32 - -#ifdef __APPLE__ -#include -#else // __APPLE__ -#include -#endif // __APPLE__ - #include +#include #include "SoGradientBackground.h" diff --git a/demos/rlCoachMdl/SoGradientBackground.cpp b/demos/rlCoachMdl/SoGradientBackground.cpp index b50675d2..566e0fb9 100644 --- a/demos/rlCoachMdl/SoGradientBackground.cpp +++ b/demos/rlCoachMdl/SoGradientBackground.cpp @@ -24,17 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#ifdef WIN32 -#include -#endif // WIN32 - -#ifdef __APPLE__ -#include -#else // __APPLE__ -#include -#endif // __APPLE__ - #include +#include #include "SoGradientBackground.h" diff --git a/demos/rlCollisionDemo/SoGradientBackground.cpp b/demos/rlCollisionDemo/SoGradientBackground.cpp index b50675d2..566e0fb9 100644 --- a/demos/rlCollisionDemo/SoGradientBackground.cpp +++ b/demos/rlCollisionDemo/SoGradientBackground.cpp @@ -24,17 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#ifdef WIN32 -#include -#endif // WIN32 - -#ifdef __APPLE__ -#include -#else // __APPLE__ -#include -#endif // __APPLE__ - #include +#include #include "SoGradientBackground.h" diff --git a/demos/rlPlanDemo/SoGradientBackground.cpp b/demos/rlPlanDemo/SoGradientBackground.cpp index b50675d2..566e0fb9 100644 --- a/demos/rlPlanDemo/SoGradientBackground.cpp +++ b/demos/rlPlanDemo/SoGradientBackground.cpp @@ -24,17 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#ifdef WIN32 -#include -#endif // WIN32 - -#ifdef __APPLE__ -#include -#else // __APPLE__ -#include -#endif // __APPLE__ - #include +#include #include "SoGradientBackground.h" diff --git a/demos/rlSimulator/SoGradientBackground.cpp b/demos/rlSimulator/SoGradientBackground.cpp index b50675d2..566e0fb9 100644 --- a/demos/rlSimulator/SoGradientBackground.cpp +++ b/demos/rlSimulator/SoGradientBackground.cpp @@ -24,17 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#ifdef WIN32 -#include -#endif // WIN32 - -#ifdef __APPLE__ -#include -#else // __APPLE__ -#include -#endif // __APPLE__ - #include +#include #include "SoGradientBackground.h" From 9689cd4c0b6770a336650e9dc099aadd10a306ef Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 Jan 2021 19:02:27 +0100 Subject: [PATCH 434/546] Update CMake syntax --- CMakeLists.txt | 4 ++-- cmake/CPackConfig.cmake | 2 +- cmake/CPackProjectConfig.cmake | 2 +- tests/rlSpatialTest/CMakeLists.txt | 2 +- tests/rlSplineTest/CMakeLists.txt | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 1c55ac52..cee3cbac 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -99,9 +99,9 @@ endif() add_subdirectory(doc) -foreach(TARGET ${TARGETS}) +foreach(TARGET IN LISTS TARGETS) list(APPEND RL_LIBRARIES "rl::${TARGET}") -endforeach(TARGET) +endforeach() export( TARGETS ${TARGETS} diff --git a/cmake/CPackConfig.cmake b/cmake/CPackConfig.cmake index 112354b3..10cd7b75 100644 --- a/cmake/CPackConfig.cmake +++ b/cmake/CPackConfig.cmake @@ -222,7 +222,7 @@ if(ZLIB_INCLUDE_DIRS AND ZLIB_LIBRARY_RELEASE) list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "zlib-devel") endif() -foreach(COMPONENT ${COMPONENTS}) +foreach(COMPONENT IN LISTS COMPONENTS) string(TOUPPER ${COMPONENT} COMPONENT_UPPER) if(DEFINED CPACK_DEBIAN_${COMPONENT_UPPER}_PACKAGE_DEPENDS) string(REPLACE ";" ", " CPACK_DEBIAN_${COMPONENT_UPPER}_PACKAGE_DEPENDS "${CPACK_DEBIAN_${COMPONENT_UPPER}_PACKAGE_DEPENDS}") diff --git a/cmake/CPackProjectConfig.cmake b/cmake/CPackProjectConfig.cmake index 6da8f7c7..05f36951 100644 --- a/cmake/CPackProjectConfig.cmake +++ b/cmake/CPackProjectConfig.cmake @@ -1,3 +1,3 @@ -if("${CPACK_GENERATOR}" STREQUAL "WIX") +if(CPACK_GENERATOR STREQUAL "WIX") set(CPACK_MONOLITHIC_INSTALL ON) endif() diff --git a/tests/rlSpatialTest/CMakeLists.txt b/tests/rlSpatialTest/CMakeLists.txt index 30644128..9ba30203 100644 --- a/tests/rlSpatialTest/CMakeLists.txt +++ b/tests/rlSpatialTest/CMakeLists.txt @@ -10,7 +10,7 @@ set( rlSpatialRigidBodyInertiaTest ) -foreach(TEST ${TESTS}) +foreach(TEST IN LISTS TESTS) add_executable( ${TEST} ${TEST}.cpp diff --git a/tests/rlSplineTest/CMakeLists.txt b/tests/rlSplineTest/CMakeLists.txt index 194ff4a1..49cd0c42 100644 --- a/tests/rlSplineTest/CMakeLists.txt +++ b/tests/rlSplineTest/CMakeLists.txt @@ -10,7 +10,7 @@ set( rlTrapezoidalAccelerationTest ) -foreach(TEST ${TESTS}) +foreach(TEST IN LISTS TESTS) add_executable( ${TEST} ${TEST}.cpp From f948d626e98f7ddb1df6f9788bb0aded634a2a2d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 Jan 2021 19:57:55 +0100 Subject: [PATCH 435/546] Update minimum required CMake version --- CMakeLists.txt | 42 +++++------------- cmake/CPackConfig.cmake | 46 ++++++++++---------- demos/rlCoachKin/CMakeLists.txt | 10 ++--- demos/rlCoachMdl/CMakeLists.txt | 10 ++--- demos/rlCollisionDemo/CMakeLists.txt | 8 ++-- demos/rlPlanDemo/CMakeLists.txt | 8 ++-- demos/rlRotationConverterDemo/CMakeLists.txt | 4 +- demos/rlSimulator/CMakeLists.txt | 10 ++--- demos/rlViewDemo/CMakeLists.txt | 8 ++-- doc/CMakeLists.txt | 2 +- doc/Doxyfile.in | 2 +- examples/CMakeLists.txt | 10 ++--- extras/wrlview/CMakeLists.txt | 12 +++-- extras/wrlview/wrlview.rc.in | 8 ++-- rl-config.cmake.in | 8 ++-- robotics-library.rc.in | 8 ++-- src/CMakeLists.txt | 2 +- src/rl/hal/CMakeLists.txt | 10 ++--- src/rl/kin/CMakeLists.txt | 10 ++--- src/rl/math/CMakeLists.txt | 26 +++-------- src/rl/math/dummy.cpp | 0 src/rl/mdl/CMakeLists.txt | 10 ++--- src/rl/plan/CMakeLists.txt | 10 ++--- src/rl/sg/CMakeLists.txt | 22 +++++----- src/rl/std/CMakeLists.txt | 22 +++------- src/rl/std/dummy.cpp | 0 src/rl/util/CMakeLists.txt | 46 +++++--------------- src/rl/util/dummy.cpp | 0 src/rl/version.h.in | 8 ++-- src/rl/xml/CMakeLists.txt | 46 ++++---------------- src/rl/xml/dummy.cpp | 0 31 files changed, 156 insertions(+), 252 deletions(-) delete mode 100644 src/rl/math/dummy.cpp delete mode 100644 src/rl/std/dummy.cpp delete mode 100644 src/rl/util/dummy.cpp delete mode 100644 src/rl/xml/dummy.cpp diff --git a/CMakeLists.txt b/CMakeLists.txt index cee3cbac..913422ed 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,8 +1,4 @@ -cmake_minimum_required(VERSION 2.8.12) - -if(POLICY CMP0042) - cmake_policy(SET CMP0042 NEW) -endif() +cmake_minimum_required(VERSION 3.1) if(POLICY CMP0072) cmake_policy(SET CMP0072 NEW) @@ -12,13 +8,11 @@ if(POLICY CMP0075) cmake_policy(SET CMP0075 NEW) endif() -project(rl) +project(rl VERSION 0.7.0) -set(VERSION_MAJOR 0) -set(VERSION_MINOR 7) -set(VERSION_PATCH 0) -set(VERSION_TWEAK 0) -set(VERSION ${VERSION_MAJOR}.${VERSION_MINOR}.${VERSION_PATCH}) +if(NOT PROJECT_VERSION_TWEAK) + set(PROJECT_VERSION_TWEAK 0) +endif() list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake) @@ -31,23 +25,11 @@ include(Qt4AutomocMocOptionsBoost) set(Boost_ADDITIONAL_VERSIONS "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) -if(NOT CMAKE_VERSION VERSION_LESS 3.1) - set(CMAKE_CXX_STANDARD 11) - set(CMAKE_CXX_STANDARD_REQUIRED ON) -else() - check_cxx_compiler_flag("-std=c++0x" HAS_CXX_COMPILER_FLAG_STDCXX0X) - if(HAS_CXX_COMPILER_FLAG_STDCXX0X) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++0x") - endif() - check_cxx_compiler_flag("-std=c++11" HAS_CXX_COMPILER_FLAG_STDCXX11) - if(HAS_CXX_COMPILER_FLAG_STDCXX11) - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11") - endif() -endif() - if(MSVC) add_definitions( -D_ENABLE_EXTENDED_ALIGNED_STORAGE @@ -111,31 +93,31 @@ export( configure_package_config_file( rl-config.cmake.in rl-config.cmake - INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${VERSION} + INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${PROJECT_VERSION} ) install( FILES ${CMAKE_CURRENT_BINARY_DIR}/rl-config.cmake - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${VERSION} + DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${PROJECT_VERSION} COMPONENT development ) write_basic_package_version_file( ${CMAKE_CURRENT_BINARY_DIR}/rl-config-version.cmake - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} COMPATIBILITY ExactVersion ) install( FILES ${CMAKE_CURRENT_BINARY_DIR}/rl-config-version.cmake - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${VERSION} + DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${PROJECT_VERSION} COMPONENT development ) if(DEFINED TARGETS) install( EXPORT rl - DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${VERSION} + DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${PROJECT_VERSION} NAMESPACE rl:: FILE rl-export.cmake COMPONENT development diff --git a/cmake/CPackConfig.cmake b/cmake/CPackConfig.cmake index 10cd7b75..c4949c03 100644 --- a/cmake/CPackConfig.cmake +++ b/cmake/CPackConfig.cmake @@ -12,18 +12,18 @@ if(MSVC) set(LINKER_VERSION "${LINKER_VERSION_MAJOR}.${CMAKE_MATCH_2}${CMAKE_MATCH_3}.${CMAKE_MATCH_4}") endif() if(CMAKE_CL_64) - set(CPACK_PACKAGE_FILE_NAME "rl-${VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-x64") - set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\x64") - set(CPACK_PACKAGE_NAME "Robotics Library ${VERSION} - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (x64)") + set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-x64") + set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${PROJECT_VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\x64") + set(CPACK_PACKAGE_NAME "Robotics Library ${PROJECT_VERSION} - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (x64)") else() - set(CPACK_PACKAGE_FILE_NAME "rl-${VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-x86") - set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\x86") - set(CPACK_PACKAGE_NAME "Robotics Library ${VERSION} - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (x86)") + set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-x86") + set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${PROJECT_VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\x86") + set(CPACK_PACKAGE_NAME "Robotics Library ${PROJECT_VERSION} - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (x86)") endif() else() - set(CPACK_PACKAGE_FILE_NAME "rl-${VERSION}-${CMAKE_SYSTEM_NAME}") - set(CPACK_PACKAGE_INSTALL_DIRECTORY "rl-${VERSION}") - set(CPACK_PACKAGE_NAME "Robotics Library ${VERSION}") + set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-${CMAKE_SYSTEM_NAME}") + set(CPACK_PACKAGE_INSTALL_DIRECTORY "rl-${PROJECT_VERSION}") + set(CPACK_PACKAGE_NAME "Robotics Library ${PROJECT_VERSION}") endif() set(CPACK_COMPONENT_DEMOS_DEPENDS examples) @@ -43,7 +43,7 @@ set(CPACK_COMPONENT_SYSTEM_DESCRIPTION "Required system files for the Robotics L set(CPACK_COMPONENT_SYSTEM_DISPLAY_NAME "Required System Files") set(CPACK_DEB_COMPONENT_INSTALL ON) set(CPACK_DEBIAN_DEMOS_FILE_NAME "DEB-DEFAULT") -set(CPACK_DEBIAN_DEMOS_PACKAGE_DEPENDS "librl-examples (= ${VERSION})") +set(CPACK_DEBIAN_DEMOS_PACKAGE_DEPENDS "librl-examples (= ${PROJECT_VERSION})") set(CPACK_DEBIAN_DEMOS_PACKAGE_SHLIBDEPS ON) set(CPACK_DEBIAN_DEVELOPMENT_FILE_NAME "DEB-DEFAULT") set(CPACK_DEBIAN_DEVELOPMENT_PACKAGE_NAME "librl-dev") @@ -62,7 +62,7 @@ set(CPACK_DEBIAN_PACKAGE_SECTION "devel") set(CPACK_DEBIAN_PACKAGE_SOURCE "librl") set(CPACK_DEBIAN_RUNTIME_FILE_NAME "DEB-DEFAULT") set(CPACK_DEBIAN_RUNTIME_PACKAGE_NAME "librl") -set(CPACK_DEBIAN_RUNTIME_PACKAGE_RECOMMENDS "librl-examples (= ${VERSION})") +set(CPACK_DEBIAN_RUNTIME_PACKAGE_RECOMMENDS "librl-examples (= ${PROJECT_VERSION})") set(CPACK_DEBIAN_RUNTIME_PACKAGE_SECTION "libs") set(CPACK_DEBIAN_RUNTIME_PACKAGE_SHLIBDEPS ON) set(CPACK_NSIS_DISPLAY_NAME ${CPACK_PACKAGE_NAME}) @@ -84,15 +84,15 @@ set(CPACK_NSIS_PACKAGE_NAME ${CPACK_PACKAGE_NAME}) set(CPACK_NSIS_URL_INFO_ABOUT "https://www.roboticslibrary.org/") set(CPACK_PACKAGE_CONTACT "Robotics Library Team ") set(CPACK_PACKAGE_VENDOR "Robotics Library") -set(CPACK_PACKAGE_VERSION ${VERSION}) -set(CPACK_PACKAGE_VERSION_MAJOR ${VERSION_MAJOR}) -set(CPACK_PACKAGE_VERSION_MINOR ${VERSION_MINOR}) -set(CPACK_PACKAGE_VERSION_PATCH ${VERSION_PATCH}) +set(CPACK_PACKAGE_VERSION ${PROJECT_VERSION}) +set(CPACK_PACKAGE_VERSION_MAJOR ${PROJECT_VERSION_MAJOR}) +set(CPACK_PACKAGE_VERSION_MINOR ${PROJECT_VERSION_MINOR}) +set(CPACK_PACKAGE_VERSION_PATCH ${PROJECT_VERSION_PATCH}) set(CPACK_PROJECT_CONFIG_FILE ${CMAKE_CURRENT_SOURCE_DIR}/cmake/CPackProjectConfig.cmake) set(CPACK_RESOURCE_FILE_LICENSE ${CMAKE_CURRENT_SOURCE_DIR}/LICENSE.md) set(CPACK_RPM_COMPONENT_INSTALL ON) set(CPACK_RPM_DEMOS_FILE_NAME "RPM-DEFAULT") -set(CPACK_RPM_demos_PACKAGE_REQUIRES "rl-examples = ${VERSION}") +set(CPACK_RPM_demos_PACKAGE_REQUIRES "rl-examples = ${PROJECT_VERSION}") set(CPACK_RPM_DEVELOPMENT_FILE_NAME "RPM-DEFAULT") set(CPACK_RPM_development_PACKAGE_NAME "rl-devel") set(CPACK_RPM_DOCUMENTATION_FILE_NAME "RPM-DEFAULT") @@ -119,7 +119,7 @@ set(CPACK_RPM_PACKAGE_SUMMARY "Robotics Library") set(CPACK_RPM_PACKAGE_URL "https://www.roboticslibrary.org/contact") set(CPACK_RPM_RUNTIME_FILE_NAME "RPM-DEFAULT") set(CPACK_RPM_runtime_PACKAGE_NAME "rl") -set(CPACK_RPM_runtime_PACKAGE_SUGGESTS "rl-examples = ${VERSION}") +set(CPACK_RPM_runtime_PACKAGE_SUGGESTS "rl-examples = ${PROJECT_VERSION}") set(CPACK_WIX_COMPONENT_INSTALL OFF) set(CPACK_WIX_EXTENSIONS "WiXUtilExtension") set( @@ -145,17 +145,17 @@ list(FIND COMPONENTS runtime RUNTIME_COMPONENT_INDEX) list(FIND COMPONENTS system SYSTEM_COMPONENT_INDEX) if(DEMOS_COMPONENT_INDEX GREATER -1) - list(APPEND CPACK_DEBIAN_RUNTIME_PACKAGE_RECOMMENDS "librl-demos (= ${VERSION})") - list(APPEND CPACK_RPM_runtime_PACKAGE_SUGGESTS "rl-demos = ${VERSION}") + list(APPEND CPACK_DEBIAN_RUNTIME_PACKAGE_RECOMMENDS "librl-demos (= ${PROJECT_VERSION})") + list(APPEND CPACK_RPM_runtime_PACKAGE_SUGGESTS "rl-demos = ${PROJECT_VERSION}") endif() if(RUNTIME_COMPONENT_INDEX GREATER -1) list(APPEND CPACK_COMPONENT_DEMOS_DEPENDS runtime) list(APPEND CPACK_COMPONENT_DEVELOPMENT_DEPENDS runtime) - list(APPEND CPACK_DEBIAN_DEMOS_PACKAGE_DEPENDS "librl (= ${VERSION})") - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "librl (= ${VERSION})") - list(APPEND CPACK_RPM_demos_PACKAGE_REQUIRES "rl = ${VERSION}") - list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "rl = ${VERSION}") + list(APPEND CPACK_DEBIAN_DEMOS_PACKAGE_DEPENDS "librl (= ${PROJECT_VERSION})") + list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "librl (= ${PROJECT_VERSION})") + list(APPEND CPACK_RPM_demos_PACKAGE_REQUIRES "rl = ${PROJECT_VERSION}") + list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "rl = ${PROJECT_VERSION}") endif() if(SYSTEM_COMPONENT_INDEX GREATER -1) diff --git a/demos/rlCoachKin/CMakeLists.txt b/demos/rlCoachKin/CMakeLists.txt index 88842bb8..10cc2b42 100644 --- a/demos/rlCoachKin/CMakeLists.txt +++ b/demos/rlCoachKin/CMakeLists.txt @@ -78,7 +78,7 @@ if(QT_FOUND AND SoQt_FOUND) set_target_properties( rlCoachKin PROPERTIES - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) if(MSVC) @@ -97,7 +97,7 @@ if(QT_FOUND AND SoQt_FOUND) RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} ) - if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) + if(MSVC AND BUILD_SHARED_LIBS) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) endif() @@ -113,8 +113,8 @@ if(QT_FOUND AND SoQt_FOUND) \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlCoachKin.lnk\\\" \\\\ \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlCoachKin.exe\\\" \\\\ \\\"\\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlsg\\\\unimation-puma560_boxes.xml\\\$\\\\\\\" \\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlkin\\\\unimation-puma560.xml\\\$\\\\\\\"\\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlsg\\\\unimation-puma560_boxes.xml\\\$\\\\\\\" \\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlkin\\\\unimation-puma560.xml\\\$\\\\\\\"\\\\ \\\" \\\\ \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ \\\"Visualization and kinematics demo with Unimation Puma 560\\\"" @@ -126,7 +126,7 @@ if(QT_FOUND AND SoQt_FOUND) WIX_SHORTCUTS ${WIX_SHORTCUTS} " DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) endif() @@ -113,8 +113,8 @@ if(QT_FOUND AND SoQt_FOUND) \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlCoachMdl.lnk\\\" \\\\ \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlCoachMdl.exe\\\" \\\\ \\\"\\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlsg\\\\unimation-puma560_boxes.xml\\\$\\\\\\\" \\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlmdl\\\\unimation-puma560.xml\\\$\\\\\\\"\\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlsg\\\\unimation-puma560_boxes.xml\\\$\\\\\\\" \\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlmdl\\\\unimation-puma560.xml\\\$\\\\\\\"\\\\ \\\" \\\\ \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ \\\"Visualization and kinematics demo with Unimation Puma 560\\\"" @@ -126,7 +126,7 @@ if(QT_FOUND AND SoQt_FOUND) WIX_SHORTCUTS ${WIX_SHORTCUTS} " DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) endif() @@ -111,7 +111,7 @@ if(QT_FOUND AND SoQt_FOUND) \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlCollisionDemo.lnk\\\" \\\\ \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlCollisionDemo.exe\\\" \\\\ \\\"\\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlsg\\\\scene.xml\\\$\\\\\\\"\\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlsg\\\\scene.xml\\\$\\\\\\\"\\\\ \\\" \\\\ \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ \\\"Collision detection and distance computation demo with basic scene\\\"" @@ -123,7 +123,7 @@ if(QT_FOUND AND SoQt_FOUND) WIX_SHORTCUTS ${WIX_SHORTCUTS} " DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) endif() @@ -128,7 +128,7 @@ if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlPlanDemo.lnk\\\" \\\\ \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlPlanDemo.exe\\\" \\\\ \\\"\\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlplan\\\\unimation-puma560_boxes_rrtConCon.mdl.xml\\\$\\\\\\\"\\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlplan\\\\unimation-puma560_boxes_rrtConCon.mdl.xml\\\$\\\\\\\"\\\\ \\\" \\\\ \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ \\\"Path planning demo with Unimation Puma 560 and RRT algorithm\\\"" @@ -140,7 +140,7 @@ if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE WIX_SHORTCUTS ${WIX_SHORTCUTS} " DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) endif() diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index e7ed9fb3..45189c06 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -81,7 +81,7 @@ if(QT_FOUND AND SoQt_FOUND) set_target_properties( rlSimulator PROPERTIES - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) if(MSVC) @@ -100,7 +100,7 @@ if(QT_FOUND AND SoQt_FOUND) RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} ) - if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) + if(MSVC AND BUILD_SHARED_LIBS) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) endif() @@ -116,8 +116,8 @@ if(QT_FOUND AND SoQt_FOUND) \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlSimulator.lnk\\\" \\\\ \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlSimulator.exe\\\" \\\\ \\\"\\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlsg\\\\unimation-puma560_boxes.xml\\\$\\\\\\\" \\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlmdl\\\\unimation-puma560.xml\\\$\\\\\\\"\\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlsg\\\\unimation-puma560_boxes.xml\\\$\\\\\\\" \\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlmdl\\\\unimation-puma560.xml\\\$\\\\\\\"\\\\ \\\" \\\\ \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ \\\"Simulation demo with Unimation Puma 560\\\"" @@ -129,7 +129,7 @@ if(QT_FOUND AND SoQt_FOUND) WIX_SHORTCUTS ${WIX_SHORTCUTS} " DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) endif() @@ -82,7 +82,7 @@ if(QT_FOUND AND SoQt_FOUND) \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlViewDemo.lnk\\\" \\\\ \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlViewDemo.exe\\\" \\\\ \\\"\\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${VERSION}\\\\examples\\\\rlsg\\\\unimation-puma560_boxes.xml\\\$\\\\\\\"\\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlsg\\\\unimation-puma560_boxes.xml\\\$\\\\\\\"\\\\ \\\" \\\\ \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ \\\"Visualization demo with Unimation Puma 560\\\"" @@ -94,7 +94,7 @@ if(QT_FOUND AND SoQt_FOUND) WIX_SHORTCUTS ${WIX_SHORTCUTS} " $ - $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ${Boost_INCLUDE_DIRS} ) @@ -233,7 +233,7 @@ set_target_properties( PROPERTIES OUTPUT_NAME rlhal POSITION_INDEPENDENT_CODE ON - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) set_target_properties( @@ -263,7 +263,7 @@ if(MSVC) endif() endif() -install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/hal COMPONENT development) +install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/hal COMPONENT development) if(NOT CMAKE_VERSION VERSION_LESS 3.12) install( @@ -290,7 +290,7 @@ else() endif() endif() -if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) +if(MSVC AND BUILD_SHARED_LIBS) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() @@ -300,4 +300,4 @@ generate_export_header( PREFIX_NAME RL_ ) -install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/hal COMPONENT development) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/hal COMPONENT development) diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index 611944cf..25a34b4b 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -46,7 +46,7 @@ target_include_directories( PUBLIC $ $ - $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ${Boost_INCLUDE_DIRS} ) @@ -62,7 +62,7 @@ set_target_properties( PROPERTIES OUTPUT_NAME rlkin POSITION_INDEPENDENT_CODE ON - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) set_target_properties( @@ -92,7 +92,7 @@ if(MSVC) endif() endif() -install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/kin COMPONENT development) +install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/kin COMPONENT development) if(NOT CMAKE_VERSION VERSION_LESS 3.12) install( @@ -119,7 +119,7 @@ else() endif() endif() -if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) +if(MSVC AND BUILD_SHARED_LIBS) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() @@ -129,4 +129,4 @@ generate_export_header( PREFIX_NAME RL_ ) -install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/kin COMPONENT development) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/kin COMPONENT development) diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index b95d4599..c6257c62 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -64,11 +64,9 @@ list(APPEND HDRS ${SPATIAL_HDRS}) if(NOT CMAKE_VERSION VERSION_LESS 3.19) add_library(math INTERFACE ${HDRS}) -elseif(NOT CMAKE_VERSION VERSION_LESS 3.0) +else() add_library(math INTERFACE) add_custom_target(math_sources SOURCES ${HDRS}) -else() - add_library(math STATIC ${HDRS} dummy.cpp) endif() if(CMAKE_SIZEOF_VOID_P EQUAL 4) @@ -84,7 +82,7 @@ target_include_directories( INTERFACE $ $ - $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ${Boost_INCLUDE_DIRS} ${EIGEN3_INCLUDE_DIRS} ) @@ -95,27 +93,17 @@ target_link_libraries( std ) -if(CMAKE_VERSION VERSION_LESS 3.0) +if(NOT CMAKE_VERSION VERSION_LESS 3.19) set_target_properties( math PROPERTIES - OUTPUT_NAME rlmath - POSITION_INDEPENDENT_CODE ON - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) - - if(MSVC) - set_target_properties( - math - PROPERTIES - DEBUG_POSTFIX d - ) - endif() endif() -install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/math COMPONENT development) -install(FILES ${METRICS_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/math/metrics COMPONENT development) -install(FILES ${SPATIAL_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/math/spatial COMPONENT development) +install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/math COMPONENT development) +install(FILES ${METRICS_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/math/metrics COMPONENT development) +install(FILES ${SPATIAL_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/math/spatial COMPONENT development) install( TARGETS math diff --git a/src/rl/math/dummy.cpp b/src/rl/math/dummy.cpp deleted file mode 100644 index e69de29b..00000000 diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 37b234c6..8e2a425e 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -90,7 +90,7 @@ target_include_directories( PUBLIC $ $ - $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ${Boost_INCLUDE_DIRS} ) @@ -112,7 +112,7 @@ set_target_properties( PROPERTIES OUTPUT_NAME rlmdl POSITION_INDEPENDENT_CODE ON - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) set_target_properties( @@ -142,7 +142,7 @@ if(MSVC) endif() endif() -install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/mdl COMPONENT development) +install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/mdl COMPONENT development) if(NOT CMAKE_VERSION VERSION_LESS 3.12) install( @@ -169,7 +169,7 @@ else() endif() endif() -if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) +if(MSVC AND BUILD_SHARED_LIBS) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() @@ -179,4 +179,4 @@ generate_export_header( PREFIX_NAME RL_ ) -install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/mdl COMPONENT development) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/mdl COMPONENT development) diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index 5e4bac91..ab8fe006 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -104,7 +104,7 @@ target_include_directories( PUBLIC $ $ - $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ${Boost_INCLUDE_DIRS} ) @@ -123,7 +123,7 @@ set_target_properties( PROPERTIES OUTPUT_NAME rlplan POSITION_INDEPENDENT_CODE ON - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) set_target_properties( @@ -153,7 +153,7 @@ if(MSVC) endif() endif() -install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/plan COMPONENT development) +install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/plan COMPONENT development) if(NOT CMAKE_VERSION VERSION_LESS 3.12) install( @@ -180,7 +180,7 @@ else() endif() endif() -if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) +if(MSVC AND BUILD_SHARED_LIBS) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() @@ -190,4 +190,4 @@ generate_export_header( PREFIX_NAME RL_ ) -install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/plan COMPONENT development) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/plan COMPONENT development) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 8dad22cc..e093f279 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -186,14 +186,14 @@ target_link_libraries( xml ) -install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg COMPONENT development) +install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg COMPONENT development) target_include_directories( sg PUBLIC $ $ - $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ) if(RL_BUILD_SG_BULLET) @@ -201,7 +201,7 @@ if(RL_BUILD_SG_BULLET) target_compile_definitions(sg PUBLIC ${BULLET_DEFINITIONS}) target_include_directories(sg PUBLIC ${BULLET_INCLUDE_DIRS}) target_link_libraries(sg ${BULLET_LIBRARIES}) - install(FILES ${BULLET_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/bullet COMPONENT development) + install(FILES ${BULLET_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/bullet COMPONENT development) endif() if(CCD_FOUND AND (RL_BUILD_SG_FCL OR RL_BUILD_SG_ODE)) @@ -229,7 +229,7 @@ if(Coin_FOUND) target_compile_definitions(sg PUBLIC ${Coin_DEFINITIONS}) target_include_directories(sg PUBLIC ${Coin_INCLUDE_DIRS}) target_link_libraries(sg ${Coin_LIBRARIES}) - install(FILES ${COIN_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/so COMPONENT development) + install(FILES ${COIN_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/so COMPONENT development) endif() if(RL_BUILD_SG_FCL) @@ -237,7 +237,7 @@ if(RL_BUILD_SG_FCL) target_compile_definitions(sg PUBLIC ${FCL_DEFINITIONS}) target_include_directories(sg PUBLIC ${FCL_INCLUDE_DIRS}) target_link_libraries(sg ${FCL_LIBRARIES}) - install(FILES ${FCL_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/fcl COMPONENT development) + install(FILES ${FCL_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/fcl COMPONENT development) endif() if(RL_BUILD_SG_ODE) @@ -245,7 +245,7 @@ if(RL_BUILD_SG_ODE) target_compile_definitions(sg PUBLIC ${ODE_DEFINITIONS}) target_include_directories(sg PUBLIC ${ODE_INCLUDE_DIRS}) target_link_libraries(sg ${ODE_LIBRARIES}) - install(FILES ${ODE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/ode COMPONENT development) + install(FILES ${ODE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/ode COMPONENT development) endif() if(OCTOMAP_FOUND AND RL_BUILD_SG_FCL) @@ -257,14 +257,14 @@ if(RL_BUILD_SG_PQP) target_compile_definitions(sg INTERFACE RL_SG_PQP) target_include_directories(sg PUBLIC ${PQP_INCLUDE_DIRS}) target_link_libraries(sg ${PQP_LIBRARIES}) - install(FILES ${PQP_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/pqp COMPONENT development) + install(FILES ${PQP_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/pqp COMPONENT development) endif() if(RL_BUILD_SG_SOLID) target_compile_definitions(sg INTERFACE RL_SG_SOLID) target_include_directories(sg PUBLIC ${SOLID3_INCLUDE_DIRS}) target_link_libraries(sg ${SOLID3_LIBRARIES}) - install(FILES ${SOLID_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg/solid COMPONENT development) + install(FILES ${SOLID_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/solid COMPONENT development) endif() set_target_properties( @@ -272,7 +272,7 @@ set_target_properties( PROPERTIES OUTPUT_NAME rlsg POSITION_INDEPENDENT_CODE ON - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) set_target_properties( @@ -327,7 +327,7 @@ else() endif() endif() -if(MSVC AND BUILD_SHARED_LIBS AND NOT CMAKE_VERSION VERSION_LESS 3.1) +if(MSVC AND BUILD_SHARED_LIBS) install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT debug) endif() @@ -337,4 +337,4 @@ generate_export_header( PREFIX_NAME RL_ ) -install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/sg COMPONENT development) +install(FILES ${CMAKE_CURRENT_BINARY_DIR}/export.h DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg COMPONENT development) diff --git a/src/rl/std/CMakeLists.txt b/src/rl/std/CMakeLists.txt index b4140d5a..118690ef 100644 --- a/src/rl/std/CMakeLists.txt +++ b/src/rl/std/CMakeLists.txt @@ -7,11 +7,9 @@ set( if(NOT CMAKE_VERSION VERSION_LESS 3.19) add_library(std INTERFACE ${HDRS}) -elseif(NOT CMAKE_VERSION VERSION_LESS 3.0) +else() add_library(std INTERFACE) add_custom_target(std_sources SOURCES ${HDRS}) -else() - add_library(std STATIC ${HDRS} dummy.cpp) endif() if(NOT CMAKE_VERSION VERSION_LESS 3.8) @@ -23,27 +21,17 @@ target_include_directories( INTERFACE $ $ - $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ) -install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/std COMPONENT development) +install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/std COMPONENT development) -if(CMAKE_VERSION VERSION_LESS 3.0) +if(NOT CMAKE_VERSION VERSION_LESS 3.19) set_target_properties( std PROPERTIES - OUTPUT_NAME rlstd - POSITION_INDEPENDENT_CODE ON - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) - - if(MSVC) - set_target_properties( - std - PROPERTIES - DEBUG_POSTFIX d - ) - endif() endif() install( diff --git a/src/rl/std/dummy.cpp b/src/rl/std/dummy.cpp deleted file mode 100644 index e69de29b..00000000 diff --git a/src/rl/util/CMakeLists.txt b/src/rl/util/CMakeLists.txt index b48b5dcb..2edc807d 100644 --- a/src/rl/util/CMakeLists.txt +++ b/src/rl/util/CMakeLists.txt @@ -41,71 +41,47 @@ endif() if(NOT CMAKE_VERSION VERSION_LESS 3.19) add_library(util INTERFACE ${HDRS}) -elseif(NOT CMAKE_VERSION VERSION_LESS 3.0) +else() add_library(util INTERFACE) add_custom_target(util_sources SOURCES ${HDRS}) -else() - add_library(util STATIC ${HDRS} dummy.cpp) endif() if(NOT CMAKE_VERSION VERSION_LESS 3.8) target_compile_features(util INTERFACE cxx_std_11) endif() -if(NOT CMAKE_VERSION VERSION_LESS 3.0) - target_link_libraries(util INTERFACE ${CMAKE_THREAD_LIBS_INIT}) -else() - target_link_libraries(util ${CMAKE_THREAD_LIBS_INIT}) -endif() +target_link_libraries(util INTERFACE ${CMAKE_THREAD_LIBS_INIT}) target_include_directories( util INTERFACE $ $ - $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ) -install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/util COMPONENT development) -install(FILES ${IO_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/util/io COMPONENT development) +install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util COMPONENT development) +install(FILES ${IO_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util/io COMPONENT development) if(RL_BUILD_UTIL_RTAI) target_include_directories(util INTERFACE ${RTAI_INCLUDE_DIRS}) - if(NOT CMAKE_VERSION VERSION_LESS 3.0) - target_link_libraries(util INTERFACE ${RTAI_LIBRARIES}) - else() - target_link_libraries(util ${RTAI_LIBRARIES}) - endif() - install(FILES ${RTAI_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/util/rtai COMPONENT development) + target_link_libraries(util INTERFACE ${RTAI_LIBRARIES}) + install(FILES ${RTAI_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util/rtai COMPONENT development) endif() if(RL_BUILD_UTIL_XENOMAI) target_compile_definitions(util INTERFACE ${Xenomai_DEFINITIONS}) target_include_directories(util INTERFACE ${Xenomai_INCLUDE_DIRS}) - if(NOT CMAKE_VERSION VERSION_LESS 3.0) - target_link_libraries(util INTERFACE ${Xenomai_LIBRARIES}) - else() - target_link_libraries(util ${Xenomai_LIBRARIES}) - endif() - install(FILES ${XENOMAI_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/util/xenomai COMPONENT development) + target_link_libraries(util INTERFACE ${Xenomai_LIBRARIES}) + install(FILES ${XENOMAI_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util/xenomai COMPONENT development) endif() -if(CMAKE_VERSION VERSION_LESS 3.0) +if(NOT CMAKE_VERSION VERSION_LESS 3.19) set_target_properties( util PROPERTIES - OUTPUT_NAME rlutil - POSITION_INDEPENDENT_CODE ON - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) - - if(MSVC) - set_target_properties( - util - PROPERTIES - DEBUG_POSTFIX d - ) - endif() endif() install( diff --git a/src/rl/util/dummy.cpp b/src/rl/util/dummy.cpp deleted file mode 100644 index e69de29b..00000000 diff --git a/src/rl/version.h.in b/src/rl/version.h.in index 990adf3c..97343f50 100644 --- a/src/rl/version.h.in +++ b/src/rl/version.h.in @@ -29,9 +29,9 @@ #define RL_VERSION RL_VERSION_MACRO(RL_VERSION_MAJOR, RL_VERSION_MINOR, RL_VERSION_PATCH) #define RL_VERSION_MACRO(major, minor, patch) ((major << 16) | (minor << 8) | patch) -#define RL_VERSION_MAJOR @VERSION_MAJOR@ -#define RL_VERSION_MINOR @VERSION_MINOR@ -#define RL_VERSION_PATCH @VERSION_PATCH@ -#define RL_VERSION_STRING "@VERSION@" +#define RL_VERSION_MAJOR @PROJECT_VERSION_MAJOR@ +#define RL_VERSION_MINOR @PROJECT_VERSION_MINOR@ +#define RL_VERSION_PATCH @PROJECT_VERSION_PATCH@ +#define RL_VERSION_STRING "@PROJECT_VERSION@" #endif // RL_VERSION_H diff --git a/src/rl/xml/CMakeLists.txt b/src/rl/xml/CMakeLists.txt index accb1634..52cb7f55 100644 --- a/src/rl/xml/CMakeLists.txt +++ b/src/rl/xml/CMakeLists.txt @@ -23,11 +23,9 @@ set( if(NOT CMAKE_VERSION VERSION_LESS 3.19) add_library(xml INTERFACE ${HDRS}) -elseif(NOT CMAKE_VERSION VERSION_LESS 3.0) +else() add_library(xml INTERFACE) add_custom_target(xml_sources SOURCES ${HDRS}) -else() - add_library(xml STATIC ${HDRS} dummy.cpp) endif() if(NOT CMAKE_VERSION VERSION_LESS 3.8) @@ -39,64 +37,38 @@ target_include_directories( INTERFACE $ $ - $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}> + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ${Boost_INCLUDE_DIRS} ${LIBXML2_INCLUDE_DIRS} ${LIBXSLT_INCLUDE_DIRS} ) -if(NOT CMAKE_VERSION VERSION_LESS 3.0) - target_link_libraries(xml INTERFACE ${LIBXML2_LIBRARIES} ${LIBXSLT_LIBRARIES}) -else() - target_link_libraries(xml ${LIBXML2_LIBRARIES} ${LIBXSLT_LIBRARIES}) -endif() +target_link_libraries(xml INTERFACE ${LIBXML2_LIBRARIES} ${LIBXSLT_LIBRARIES}) if(Iconv_FOUND) target_include_directories(xml INTERFACE ${Iconv_INCLUDE_DIRS}) - if(NOT CMAKE_VERSION VERSION_LESS 3.0) - target_link_libraries(xml INTERFACE ${Iconv_LIBRARIES}) - else() - target_link_libraries(xml ${Iconv_LIBRARIES}) - endif() + target_link_libraries(xml INTERFACE ${Iconv_LIBRARIES}) endif() if(LIBLZMA_FOUND) target_include_directories(xml INTERFACE ${LIBLZMA_INCLUDE_DIRS}) - if(NOT CMAKE_VERSION VERSION_LESS 3.0) - target_link_libraries(xml INTERFACE ${LIBLZMA_LIBRARIES}) - else() - target_link_libraries(xml ${LIBLZMA_LIBRARIES}) - endif() + target_link_libraries(xml INTERFACE ${LIBLZMA_LIBRARIES}) endif() if(ZLIB_FOUND) target_include_directories(xml INTERFACE ${ZLIB_INCLUDE_DIRS}) - if(NOT CMAKE_VERSION VERSION_LESS 3.0) - target_link_libraries(xml INTERFACE ${ZLIB_LIBRARIES}) - else() - target_link_libraries(xml ${ZLIB_LIBRARIES}) - endif() + target_link_libraries(xml INTERFACE ${ZLIB_LIBRARIES}) endif() -if(CMAKE_VERSION VERSION_LESS 3.0) +if(NOT CMAKE_VERSION VERSION_LESS 3.19) set_target_properties( xml PROPERTIES - OUTPUT_NAME rlxml - POSITION_INDEPENDENT_CODE ON - VERSION ${VERSION} + VERSION ${PROJECT_VERSION} ) - - if(MSVC) - set_target_properties( - xml - PROPERTIES - DEBUG_POSTFIX d - ) - endif() endif() -install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${VERSION}/rl/xml COMPONENT development) +install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/xml COMPONENT development) install( TARGETS xml diff --git a/src/rl/xml/dummy.cpp b/src/rl/xml/dummy.cpp deleted file mode 100644 index e69de29b..00000000 From 61db2f6a491bb07bd5b898f5a611f381e29229a1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 Jan 2021 20:11:33 +0100 Subject: [PATCH 436/546] Update CMake find modules --- cmake/CPackConfig.cmake | 34 +-- cmake/FindATIDAQ.cmake | 31 +-- cmake/FindBoost.cmake | 16 ++ cmake/FindBullet.cmake | 278 +++++-------------- cmake/FindCoin.cmake | 70 ++--- cmake/FindComedi.cmake | 58 ++-- cmake/FindEigen3.cmake | 44 ++- cmake/FindFCL.cmake | 62 ----- cmake/FindICU.cmake | 100 +++++++ cmake/FindIconv.cmake | 109 ++++---- cmake/FindLibLZMA.cmake | 50 ++-- cmake/FindLibXml2.cmake | 109 ++++++-- cmake/FindLibXslt.cmake | 60 ++-- cmake/FindNLopt.cmake | 34 +-- cmake/FindODE.cmake | 74 ++--- cmake/FindOctoMap.cmake | 84 ------ cmake/FindPQP.cmake | 31 +-- cmake/FindRTAI.cmake | 54 ++-- cmake/FindSoQt.cmake | 58 ++-- cmake/FindXenomai.cmake | 143 ++++------ cmake/FindZLIB.cmake | 37 +-- cmake/Findccd.cmake | 31 +-- cmake/FindcifX.cmake | 53 ++-- cmake/Findfcl.cmake | 99 +++++++ cmake/Findlibdc1394.cmake | 35 +-- cmake/Findoctomap.cmake | 58 ++++ cmake/{FindSOLID3.cmake => Findsolid3.cmake} | 37 +-- demos/rlCoachKin/CMakeLists.txt | 2 +- demos/rlCoachMdl/CMakeLists.txt | 2 +- demos/rlCollisionDemo/CMakeLists.txt | 9 +- demos/rlPlanDemo/CMakeLists.txt | 9 +- demos/rlPrmDemo/CMakeLists.txt | 4 +- demos/rlRrtDemo/CMakeLists.txt | 4 +- demos/rlSimulator/CMakeLists.txt | 2 +- demos/rlViewDemo/CMakeLists.txt | 2 +- extras/csv2wrl/CMakeLists.txt | 2 +- extras/wrlview/CMakeLists.txt | 2 +- src/rl/hal/CMakeLists.txt | 12 +- src/rl/mdl/CMakeLists.txt | 2 +- src/rl/sg/CMakeLists.txt | 22 +- src/rl/xml/CMakeLists.txt | 19 -- tests/rlCollisionTest/CMakeLists.txt | 7 +- tests/rlEetTest/CMakeLists.txt | 13 +- tests/rlPrmTest/CMakeLists.txt | 13 +- 44 files changed, 900 insertions(+), 1075 deletions(-) create mode 100644 cmake/FindBoost.cmake delete mode 100644 cmake/FindFCL.cmake create mode 100644 cmake/FindICU.cmake delete mode 100644 cmake/FindOctoMap.cmake create mode 100644 cmake/Findfcl.cmake create mode 100644 cmake/Findoctomap.cmake rename cmake/{FindSOLID3.cmake => Findsolid3.cmake} (61%) diff --git a/cmake/CPackConfig.cmake b/cmake/CPackConfig.cmake index c4949c03..b62c5bbf 100644 --- a/cmake/CPackConfig.cmake +++ b/cmake/CPackConfig.cmake @@ -169,58 +169,46 @@ if(Boost_INCLUDE_DIRS) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libboost-dev (>= 1.46)") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "boost-devel >= 1.46") endif() -if(BULLET_INCLUDE_DIRS AND BULLET_BULLETCOLLISION_LIBRARY_RELEASE AND BULLET_BULLETDYNAMICS_LIBRARY_RELEASE AND BULLET_BULLETSOFTBODY_LIBRARY_RELEASE AND BULLET_LINEARMATH_LIBRARY_RELEASE) +if(BULLET_INCLUDE_DIR AND BULLET_BULLETCOLLISION_LIBRARY_RELEASE AND BULLET_BULLETDYNAMICS_LIBRARY_RELEASE AND BULLET_BULLETSOFTBODY_LIBRARY_RELEASE AND BULLET_LINEARMATH_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libbullet-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "bullet-devel") endif() -if(CCD_INCLUDE_DIRS AND CCD_LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libccd-dev") - list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libccd-devel") -endif() -if(Coin_INCLUDE_DIRS AND Coin_LIBRARY_RELEASE) +if(Coin_INCLUDE_DIR AND Coin_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libcoin-dev | libcoin80-dev | libcoin60-dev") - list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "Coin3-devel") + list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "Coin4-devel or Coin3-devel or Coin2-devel") endif() -if(Comedi_INCLUDE_DIRS AND Comedi_LIBRARY_RELEASE) +if(COMEDI_INCLUDE_DIR AND COMEDI_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libcomedi-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "comedilib-devel") endif() -if(EIGEN3_INCLUDE_DIRS) +if(EIGEN3_INCLUDE_DIR) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libeigen3-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "eigen3-devel") endif() -if(FCL_INCLUDE_DIRS AND FCL_LIBRARY_RELEASE) +if(FCL_INCLUDE_DIR AND FCL_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libfcl-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "fcl-devel") endif() -if(libdc1394_INCLUDE_DIRS AND libdc1394_LIBRARY_RELEASE) +if(LIBDC1394_INCLUDE_DIR AND LIBDC1394_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libdc1394-dev | libdc1394-22-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libdc1394-devel") endif() -if(LIBLZMA_INCLUDE_DIRS AND LIBLZMA_LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "liblzma-dev") - list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "lzma-devel") -endif() -if(LIBXML2_INCLUDE_DIRS AND LIBXML2_LIBRARY_RELEASE) +if(LIBXML2_INCLUDE_DIR AND LIBXML2_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libxml2-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libxml2-devel") endif() -if(LIBXSLT_INCLUDE_DIRS AND LIBXSLT_LIBRARY_RELEASE) +if(LIBXSLT_INCLUDE_DIR AND LIBXSLT_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libxslt1-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "libxslt-devel") endif() -if(NLOPT_INCLUDE_DIRS AND NLOPT_LIBRARY_RELEASE) +if(NLOPT_INCLUDE_DIR AND NLOPT_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libnlopt-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "NLopt-devel") endif() -if(ODE_INCLUDE_DIRS AND ODE_LIBRARY_RELEASE) +if(ODE_INCLUDE_DIR AND ODE_LIBRARY_RELEASE) list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "libode-dev") list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "ode-devel") endif() -if(ZLIB_INCLUDE_DIRS AND ZLIB_LIBRARY_RELEASE) - list(APPEND CPACK_DEBIAN_DEVELOPMENT_PACKAGE_DEPENDS "zlib1g-dev") - list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "zlib-devel") -endif() foreach(COMPONENT IN LISTS COMPONENTS) string(TOUPPER ${COMPONENT} COMPONENT_UPPER) diff --git a/cmake/FindATIDAQ.cmake b/cmake/FindATIDAQ.cmake index 9bc3ef08..98371cc3 100644 --- a/cmake/FindATIDAQ.cmake +++ b/cmake/FindATIDAQ.cmake @@ -2,48 +2,39 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - ATIDAQ_INCLUDE_DIRS - NAMES - atidaq/ftconfig.h + ATIDAQ_INCLUDE_DIR + NAMES atidaq/ftconfig.h ) - -mark_as_advanced(ATIDAQ_INCLUDE_DIRS) - find_library( ATIDAQ_LIBRARY_DEBUG - NAMES - atidaqd + NAMES atidaqd ) - find_library( ATIDAQ_LIBRARY_RELEASE - NAMES - atidaq + NAMES atidaq ) - select_library_configurations(ATIDAQ) +set(ATIDAQ_INCLUDE_DIRS ${ATIDAQ_INCLUDE_DIR}) +set(ATIDAQ_LIBRARIES ${ATIDAQ_LIBRARY}) + find_package_handle_standard_args( ATIDAQ FOUND_VAR ATIDAQ_FOUND - REQUIRED_VARS ATIDAQ_INCLUDE_DIRS ATIDAQ_LIBRARIES + REQUIRED_VARS ATIDAQ_INCLUDE_DIR ATIDAQ_LIBRARY ) if(ATIDAQ_FOUND AND NOT TARGET ATIDAQ::ATIDAQ) add_library(ATIDAQ::ATIDAQ UNKNOWN IMPORTED) - if(ATIDAQ_LIBRARY_RELEASE) set_property(TARGET ATIDAQ::ATIDAQ APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(ATIDAQ::ATIDAQ PROPERTIES IMPORTED_LOCATION_RELEASE "${ATIDAQ_LIBRARY_RELEASE}") endif() - if(ATIDAQ_LIBRARY_DEBUG) set_property(TARGET ATIDAQ::ATIDAQ APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(ATIDAQ::ATIDAQ PROPERTIES IMPORTED_LOCATION_DEBUG "${ATIDAQ_LIBRARY_DEBUG}") endif() - - set_target_properties( - ATIDAQ::ATIDAQ PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${ATIDAQ_INCLUDE_DIRS}" - ) + set_target_properties(ATIDAQ::ATIDAQ PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${ATIDAQ_INCLUDE_DIRS}") endif() + +mark_as_advanced(ATIDAQ_INCLUDE_DIR) diff --git a/cmake/FindBoost.cmake b/cmake/FindBoost.cmake new file mode 100644 index 00000000..a3287956 --- /dev/null +++ b/cmake/FindBoost.cmake @@ -0,0 +1,16 @@ +set(_CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH}) +list(REMOVE_ITEM CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}) + +find_package(Boost) + +if(Boost_FOUND AND NOT TARGET Boost::headers) + add_library(Boost::headers INTERFACE IMPORTED) + set_target_properties(Boost::headers PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${Boost_INCLUDE_DIRS}") +endif() +if(TARGET Boost::headers AND NOT TARGET Boost::boost) + add_library(Boost::boost INTERFACE IMPORTED) + set_target_properties(Boost::boost PROPERTIES INTERFACE_LINK_LIBRARIES "Boost::headers") +endif() + +set(CMAKE_MODULE_PATH ${_CMAKE_MODULE_PATH}) +unset(_CMAKE_MODULE_PATH) diff --git a/cmake/FindBullet.cmake b/cmake/FindBullet.cmake index c54a2b7e..f7183b4c 100644 --- a/cmake/FindBullet.cmake +++ b/cmake/FindBullet.cmake @@ -3,99 +3,37 @@ include(CMakePushCheckState) include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) -find_path( - BULLET_INCLUDE_DIRS - NAMES - btBulletCollisionCommon.h - PATH_SUFFIXES - bullet -) - -mark_as_advanced(BULLET_INCLUDE_DIRS) - -find_library( - BULLET_BULLETCOLLISION_LIBRARY_DEBUG - NAMES - BulletCollision-float64_Debug BulletCollision_Debug -) - -find_library( - BULLET_BULLETCOLLISION_LIBRARY_RELEASE - NAMES - BulletCollision-float64 BulletCollision -) - -select_library_configurations(BULLET_BULLETCOLLISION) - -find_library( - BULLET_BULLETDYNAMICS_LIBRARY_DEBUG - NAMES - BulletDynamics-float64_Debug BulletDynamics_Debug -) - -find_library( - BULLET_BULLETDYNAMICS_LIBRARY_RELEASE - NAMES - BulletDynamics-float64 BulletDynamics -) - -select_library_configurations(BULLET_BULLETDYNAMICS) - -find_library( - BULLET_BULLETSOFTBODY_LIBRARY_DEBUG - NAMES - BulletSoftBody-float64_Debug BulletSoftBody_Debug -) - -find_library( - BULLET_BULLETSOFTBODY_LIBRARY_RELEASE - NAMES - BulletSoftBody-float64 BulletSoftBody -) - -select_library_configurations(BULLET_BULLETSOFTBODY) - -find_library( - BULLET_CONVEXDECOMPOSITION_LIBRARY_DEBUG - NAMES - ConvexDecomposition-float64_Debug ConvexDecomposition_Debug -) - -find_library( - BULLET_CONVEXDECOMPOSITION_LIBRARY_RELEASE - NAMES - ConvexDecomposition-float64 ConvexDecomposition -) - -select_library_configurations(BULLET_CONVEXDECOMPOSITION) - -find_library( - BULLET_LINEARMATH_LIBRARY_DEBUG - NAMES - LinearMath-float64_Debug LinearMath_Debug -) +if(NOT Bullet_FIND_COMPONENTS) + set(Bullet_FIND_COMPONENTS BulletCollision BulletDynamics BulletSoftBody LinearMath) + foreach(component IN LISTS Bullet_FIND_COMPONENTS) + set(Bullet_FIND_REQUIRED_${component} ON) + endforeach() +endif() -find_library( - BULLET_LINEARMATH_LIBRARY_RELEASE - NAMES - LinearMath-float64 LinearMath +find_path( + BULLET_INCLUDE_DIR + NAMES btBulletCollisionCommon.h + PATH_SUFFIXES bullet ) -select_library_configurations(BULLET_LINEARMATH) - -set( - BULLET_LIBRARIES - ${BULLET_BULLETCOLLISION_LIBRARIES} - ${BULLET_BULLETDYNAMICS_LIBRARIES} - ${BULLET_BULLETSOFTBODY_LIBRARIES} - ${BULLET_LINEARMATH_LIBRARIES} -) +foreach(component IN LISTS Bullet_FIND_COMPONENTS) + string(TOUPPER ${component} COMPONENT) + find_library( + BULLET_${COMPONENT}_LIBRARY_DEBUG + NAMES ${component}-float64_Debug ${component}_Debug + ) + find_library( + BULLET_${COMPONENT}_LIBRARY_RELEASE + NAMES ${component}-float64 ${component} + ) + select_library_configurations(BULLET_${COMPONENT}) +endforeach() -if(BULLET_INCLUDE_DIRS AND BULLET_LIBRARIES) +if(BULLET_INCLUDE_DIR AND BULLET_BULLETCOLLISION_LIBRARY AND BULLET_LINEARMATH_LIBRARY) cmake_push_check_state(RESET) set(CMAKE_REQUIRED_DEFINITIONS -DBT_USE_DOUBLE_PRECISION) - set(CMAKE_REQUIRED_INCLUDES ${BULLET_INCLUDE_DIRS}) - set(CMAKE_REQUIRED_LIBRARIES ${BULLET_LIBRARIES}) + set(CMAKE_REQUIRED_INCLUDES ${BULLET_INCLUDE_DIR}) + set(CMAKE_REQUIRED_LIBRARIES ${BULLET_BULLETCOLLISION_LIBRARY} ${BULLET_LINEARMATH_LIBRARY}) check_cxx_source_runs(" #include int main() @@ -106,152 +44,60 @@ if(BULLET_INCLUDE_DIRS AND BULLET_LIBRARIES) return !btFuzzyZero(boxHalfExtents.distance(boxHalfExtentsWithMargin)); } " _BULLET_DOUBLE_PRECISION) - if(_BULLET_DOUBLE_PRECISION) set(BULLET_DEFINITIONS -DBT_USE_DOUBLE_PRECISION) + set(_BULLET_INTERFACE_COMPILE_DEFINITIONS "BT_USE_DOUBLE_PRECISION") endif() - unset(_BULLET_DOUBLE_PRECISION) cmake_pop_check_state() endif() -mark_as_advanced(BULLET_DEFINITIONS) - -if(BULLET_INCLUDE_DIRS AND EXISTS "${BULLET_INCLUDE_DIRS}/LinearMath/btScalar.h") - file(STRINGS "${BULLET_INCLUDE_DIRS}/LinearMath/btScalar.h" _BULLET_VERSION_DEFINE REGEX "#define[\t ]+BT_BULLET_VERSION[\t ]+[0-9]+.*") - string(REGEX REPLACE "#define[\t ]+BT_BULLET_VERSION[\t ]+([0-9])[0-9][0-9].*" "\\1" BULLET_VERSION_MAJOR "${_BULLET_VERSION_DEFINE}") - string(REGEX REPLACE "#define[\t ]+BT_BULLET_VERSION[\t ]+[0-9]([0-9][0-9]).*" "\\1" BULLET_VERSION_MINOR "${_BULLET_VERSION_DEFINE}") - +if(BULLET_INCLUDE_DIR AND EXISTS "${BULLET_INCLUDE_DIR}/LinearMath/btScalar.h") + file(STRINGS "${BULLET_INCLUDE_DIR}/LinearMath/btScalar.h" _BULLET_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+BT_BULLET_VERSION[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+BT_BULLET_VERSION[\t ]+([0-9])[0-9][0-9].*" "\\1" BULLET_VERSION_MAJOR "${_BULLET_VERSION_DEFINE}") + string(REGEX REPLACE "[\t ]*#define[\t ]+BT_BULLET_VERSION[\t ]+[0-9]([0-9][0-9]).*" "\\1" BULLET_VERSION_MINOR "${_BULLET_VERSION_DEFINE}") if(NOT BULLET_VERSION_MAJOR STREQUAL "" AND NOT BULLET_VERSION_MINOR STREQUAL "") set(BULLET_VERSION "${BULLET_VERSION_MAJOR}.${BULLET_VERSION_MINOR}") endif() - unset(_BULLET_VERSION_DEFINE) endif() +set(BULLET_INCLUDE_DIRS ${BULLET_INCLUDE_DIR}) +unset(BULLET_LIBRARIES) + +foreach(component IN LISTS Bullet_FIND_COMPONENTS) + string(TOUPPER ${component} COMPONENT) + if(BULLET_${COMPONENT}_LIBRARY) + set(Bullet_${component}_FOUND ON) + list(APPEND BULLET_LIBRARIES ${BULLET_${COMPONENT}_LIBRARY}) + endif() +endforeach() + find_package_handle_standard_args( Bullet - FOUND_VAR BULLET_FOUND - REQUIRED_VARS BULLET_INCLUDE_DIRS BULLET_LIBRARIES + FOUND_VAR Bullet_FOUND + REQUIRED_VARS BULLET_INCLUDE_DIR VERSION_VAR BULLET_VERSION + HANDLE_COMPONENTS ) -if((BULLET_BULLETCOLLISION_LIBRARY_RELEASE OR BULLET_BULLETCOLLISION_LIBRARY_DEBUG) AND BULLET_INCLUDE_DIRS) - set(BULLET_BULLETCOLLISION_LIBRARY_FOUND ON) -endif() - -if((BULLET_BULLETDYNAMICS_LIBRARY_RELEASE OR BULLET_BULLETDYNAMICS_LIBRARY_DEBUG) AND BULLET_INCLUDE_DIRS) - set(BULLET_BULLETDYNAMICS_LIBRARY_FOUND ON) -endif() - -if((BULLET_BULLETSOFTBODY_LIBRARY_RELEASE OR BULLET_BULLETSOFTBODY_LIBRARY_DEBUG) AND BULLET_INCLUDE_DIRS) - set(BULLET_BULLETSOFTBODY_LIBRARY_FOUND ON) -endif() - -if((BULLET_CONVEXDECOMPOSITION_LIBRARY_RELEASE OR BULLET_CONVEXDECOMPOSITION_LIBRARY_DEBUG) AND BULLET_INCLUDE_DIRS) - set(BULLET_CONVEXDECOMPOSITION_LIBRARY_FOUND ON) -endif() - -if((BULLET_LINEARMATH_LIBRARY_RELEASE OR BULLET_LINEARMATH_LIBRARY_DEBUG) AND BULLET_INCLUDE_DIRS) - set(BULLET_LINEARMATH_LIBRARY_FOUND ON) -endif() - -if(BULLET_BULLETCOLLISION_LIBRARY_FOUND AND NOT TARGET Bullet::BulletCollision) - add_library(Bullet::BulletCollision UNKNOWN IMPORTED) - - if(BULLET_BULLETCOLLISION_LIBRARY_RELEASE) - set_property(TARGET Bullet::BulletCollision APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(Bullet::BulletCollision PROPERTIES IMPORTED_LOCATION_RELEASE "${BULLET_BULLETCOLLISION_LIBRARY_RELEASE}") - endif() - - if(BULLET_BULLETCOLLISION_LIBRARY_DEBUG) - set_property(TARGET Bullet::BulletCollision APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(Bullet::BulletCollision PROPERTIES IMPORTED_LOCATION_DEBUG "${BULLET_BULLETCOLLISION_LIBRARY_DEBUG}") - endif() - - set_target_properties( - Bullet::BulletCollision PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" - ) -endif() - -if(BULLET_BULLETDYNAMICS_LIBRARY_FOUND AND NOT TARGET Bullet::BulletDynamics) - add_library(Bullet::BulletDynamics UNKNOWN IMPORTED) - - if(BULLET_BULLETDYNAMICS_LIBRARY_RELEASE) - set_property(TARGET Bullet::BulletDynamics APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(Bullet::BulletDynamics PROPERTIES IMPORTED_LOCATION_RELEASE "${BULLET_BULLETDYNAMICS_LIBRARY_RELEASE}") - endif() - - if(BULLET_BULLETDYNAMICS_LIBRARY_DEBUG) - set_property(TARGET Bullet::BulletDynamics APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(Bullet::BulletDynamics PROPERTIES IMPORTED_LOCATION_DEBUG "${BULLET_BULLETDYNAMICS_LIBRARY_DEBUG}") - endif() - - set_target_properties( - Bullet::BulletDynamics PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" - ) -endif() - -if(BULLET_BULLETSOFTBODY_LIBRARY_FOUND AND NOT TARGET Bullet::BulletSoftBody) - add_library(Bullet::BulletSoftBody UNKNOWN IMPORTED) - - if(BULLET_BULLETSOFTBODY_LIBRARY_RELEASE) - set_property(TARGET Bullet::BulletSoftBody APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(Bullet::BulletSoftBody PROPERTIES IMPORTED_LOCATION_RELEASE "${BULLET_BULLETSOFTBODY_LIBRARY_RELEASE}") - endif() - - if(BULLET_BULLETSOFTBODY_LIBRARY_DEBUG) - set_property(TARGET Bullet::BulletSoftBody APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(Bullet::BulletSoftBody PROPERTIES IMPORTED_LOCATION_DEBUG "${BULLET_BULLETSOFTBODY_LIBRARY_DEBUG}") +foreach(component IN LISTS Bullet_FIND_COMPONENTS) + string(TOUPPER ${component} COMPONENT) + if(Bullet_${component}_FOUND AND NOT TARGET Bullet::${component}) + add_library(Bullet::${component} UNKNOWN IMPORTED) + if(BULLET_${COMPONENT}_LIBRARY_RELEASE) + set_property(TARGET Bullet::${component} APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(Bullet::${component} PROPERTIES IMPORTED_LOCATION_RELEASE "${BULLET_${COMPONENT}_LIBRARY_RELEASE}") + endif() + if(BULLET_${COMPONENT}_LIBRARY_DEBUG) + set_property(TARGET Bullet::${component} APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(Bullet::${component} PROPERTIES IMPORTED_LOCATION_DEBUG "${BULLET_${COMPONENT}_LIBRARY_DEBUG}") + endif() + set_target_properties(Bullet::${component} PROPERTIES INTERFACE_COMPILE_DEFINITIONS "${_BULLET_INTERFACE_COMPILE_DEFINITIONS}") + set_target_properties(Bullet::${component} PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}") endif() - - set_target_properties( - Bullet::BulletSoftBody PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" - ) -endif() +endforeach() -if(BULLET_CONVEXDECOMPOSITION_LIBRARY_FOUND AND NOT TARGET Bullet::ConvexDecomposition) - add_library(Bullet::ConvexDecomposition UNKNOWN IMPORTED) - - if(BULLET_CONVEXDECOMPOSITION_LIBRARY_RELEASE) - set_property(TARGET Bullet::ConvexDecomposition APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(Bullet::ConvexDecomposition PROPERTIES IMPORTED_LOCATION_RELEASE "${BULLET_CONVEXDECOMPOSITION_LIBRARY_RELEASE}") - endif() - - if(BULLET_CONVEXDECOMPOSITION_LIBRARY_DEBUG) - set_property(TARGET Bullet::ConvexDecomposition APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(Bullet::ConvexDecomposition PROPERTIES IMPORTED_LOCATION_DEBUG "${BULLET_CONVEXDECOMPOSITION_LIBRARY_DEBUG}") - endif() - - set_target_properties( - Bullet::ConvexDecomposition PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" - ) -endif() - -if(BULLET_LINEARMATH_LIBRARY_FOUND AND NOT TARGET Bullet::LinearMath) - add_library(Bullet::LinearMath UNKNOWN IMPORTED) - - if(BULLET_LINEARMATH_LIBRARY_RELEASE) - set_property(TARGET Bullet::LinearMath APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(Bullet::LinearMath PROPERTIES IMPORTED_LOCATION_RELEASE "${BULLET_LINEARMATH_LIBRARY_RELEASE}") - endif() - - if(BULLET_LINEARMATH_LIBRARY_DEBUG) - set_property(TARGET Bullet::LinearMath APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(Bullet::LinearMath PROPERTIES IMPORTED_LOCATION_DEBUG "${BULLET_LINEARMATH_LIBRARY_DEBUG}") - endif() - - set_target_properties( - Bullet::LinearMath PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${BULLET_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${BULLET_INCLUDE_DIRS}" - ) -endif() +mark_as_advanced(BULLET_DEFINITIONS) +mark_as_advanced(BULLET_INCLUDE_DIR) +unset(_BULLET_INTERFACE_COMPILE_DEFINITIONS) diff --git a/cmake/FindCoin.cmake b/cmake/FindCoin.cmake index f2f51f82..6134cfa4 100644 --- a/cmake/FindCoin.cmake +++ b/cmake/FindCoin.cmake @@ -3,82 +3,62 @@ include(SelectLibraryConfigurations) find_path( Coin_INCLUDE_DIR - NAMES - Inventor/So.h - PATH_SUFFIXES - Coin4 - Coin3 - Coin2 + NAMES Inventor/So.h + PATH_SUFFIXES Coin4 Coin3 Coin2 ) - -mark_as_advanced(Coin_INCLUDE_DIR) - -set(Coin_INCLUDE_DIRS ${Coin_INCLUDE_DIR}) - find_path( Coin_FOREIGN_FILES_INCLUDE_DIR - NAMES - ForeignFiles/SoForeignFileKit.h + NAMES ForeignFiles/SoForeignFileKit.h PATH_SUFFIXES - Inventor/annex - Coin4/Inventor/annex - Coin3/Inventor/annex - Coin2/Inventor/annex + Inventor/annex + Coin4/Inventor/annex + Coin3/Inventor/annex + Coin2/Inventor/annex ) - -mark_as_advanced(Coin_FOREIGN_FILES_INCLUDE_DIR) - -if(Coin_FOREIGN_FILES_INCLUDE_DIR) - list(APPEND Coin_INCLUDE_DIRS ${Coin_FOREIGN_FILES_INCLUDE_DIR}) -endif() - find_library( Coin_LIBRARY_DEBUG - NAMES - Coind Coin4d Coin3d Coin2d + NAMES Coind Coin4d Coin3d Coin2d ) - find_library( Coin_LIBRARY_RELEASE - NAMES - Coin Coin4 Coin3 Coin2 + NAMES Coin Coin4 Coin3 Coin2 ) - select_library_configurations(Coin) -set(Coin_DEFINITIONS -DCOIN_DLL) - -mark_as_advanced(Coin_DEFINITIONS) - if(Coin_INCLUDE_DIR AND EXISTS "${Coin_INCLUDE_DIR}/Inventor/C/basic.h") - file(STRINGS "${Coin_INCLUDE_DIR}/Inventor/C/basic.h" _Coin_VERSION_DEFINE REGEX "#define[\t ]+COIN_VERSION[\t ]+\"[^\"]*\".*") - string(REGEX REPLACE "#define[\t ]+COIN_VERSION[\t ]+\"([^\"]*)\".*" "\\1" Coin_VERSION "${_Coin_VERSION_DEFINE}") + file(STRINGS "${Coin_INCLUDE_DIR}/Inventor/C/basic.h" _Coin_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+COIN_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+COIN_VERSION[\t ]+\"([^\"]*)\".*" "\\1" Coin_VERSION "${_Coin_VERSION_DEFINE}") unset(_Coin_VERSION_DEFINE) endif() +set(Coin_DEFINITIONS -DCOIN_DLL) +set(Coin_INCLUDE_DIRS ${Coin_INCLUDE_DIR}) +if(Coin_FOREIGN_FILES_INCLUDE_DIR) + list(APPEND Coin_INCLUDE_DIRS ${Coin_FOREIGN_FILES_INCLUDE_DIR}) +endif() +set(Coin_LIBRARIES ${Coin_LIBRARY}) + find_package_handle_standard_args( Coin FOUND_VAR Coin_FOUND - REQUIRED_VARS Coin_INCLUDE_DIRS Coin_LIBRARIES + REQUIRED_VARS Coin_INCLUDE_DIR Coin_LIBRARY VERSION_VAR Coin_VERSION ) if(Coin_FOUND AND NOT TARGET Coin::Coin) add_library(Coin::Coin UNKNOWN IMPORTED) - if(Coin_LIBRARY_RELEASE) set_property(TARGET Coin::Coin APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(Coin::Coin PROPERTIES IMPORTED_LOCATION_RELEASE "${Coin_LIBRARY_RELEASE}") endif() - if(Coin_LIBRARY_DEBUG) set_property(TARGET Coin::Coin APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(Coin::Coin PROPERTIES IMPORTED_LOCATION_DEBUG "${Coin_LIBRARY_DEBUG}") endif() - - set_target_properties( - Coin::Coin PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${Coin_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${Coin_INCLUDE_DIRS}" - ) + set_target_properties(Coin::Coin PROPERTIES INTERFACE_COMPILE_DEFINITIONS "COIN_DLL") + set_target_properties(Coin::Coin PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${Coin_INCLUDE_DIRS}") endif() + +mark_as_advanced(Coin_DEFINITIONS) +mark_as_advanced(Coin_INCLUDE_DIR) +mark_as_advanced(Coin_FOREIGN_FILES_INCLUDE_DIR) diff --git a/cmake/FindComedi.cmake b/cmake/FindComedi.cmake index 1326e5d0..7661e5e1 100644 --- a/cmake/FindComedi.cmake +++ b/cmake/FindComedi.cmake @@ -2,49 +2,47 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - Comedi_INCLUDE_DIRS - NAMES - comedilib.h + COMEDI_INCLUDE_DIR + NAMES comedilib.h ) - -mark_as_advanced(Comedi_INCLUDE_DIRS) - find_library( - Comedi_LIBRARY_DEBUG - NAMES - comedid + COMEDI_LIBRARY_RELEASE + NAMES comedi ) +select_library_configurations(COMEDI) -find_library( - Comedi_LIBRARY_RELEASE - NAMES - comedi -) +if(COMEDI_INCLUDE_DIR AND EXISTS "${COMEDI_INCLUDE_DIR}/comedilib_version.h") + file(STRINGS "${COMEDI_INCLUDE_DIR}/comedilib_version.h" _COMEDI_VERSION_MAJOR_DEFINE REGEX "[\t ]*#define[\t ]+COMEDILIB_VERSION_MAJOR[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+COMEDILIB_VERSION_MAJOR[\t ]+([0-9]+).*" "\\1" COMEDI_VERSION_MAJOR "${_COMEDI_VERSION_MAJOR_DEFINE}") + file(STRINGS "${COMEDI_INCLUDE_DIR}/comedilib_version.h" _COMEDI_VERSION_MINOR_DEFINE REGEX "[\t ]*#define[\t ]+COMEDILIB_VERSION_MINOR[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+COMEDILIB_VERSION_MINOR[\t ]+([0-9]+).*" "\\1" COMEDI_VERSION_MINOR "${_COMEDI_VERSION_MINOR_DEFINE}") + file(STRINGS "${COMEDI_INCLUDE_DIR}/comedilib_version.h" _COMEDI_VERSION_MICRO_DEFINE REGEX "[\t ]*#define[\t ]+COMEDILIB_VERSION_MICRO[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+COMEDILIB_VERSION_MICRO[\t ]+([0-9]+).*" "\\1" COMEDI_VERSION_MICRO "${_COMEDI_VERSION_MICRO_DEFINE}") + if(NOT COMEDI_VERSION_MAJOR STREQUAL "" AND NOT COMEDI_VERSION_MINOR STREQUAL "" AND NOT COMEDI_VERSION_MICRO STREQUAL "") + set(COMEDI_VERSION "${COMEDI_VERSION_MAJOR}.${COMEDI_VERSION_MINOR}.${COMEDI_VERSION_MICRO}") + endif() + unset(_COMEDI_VERSION_MAJOR_DEFINE) + unset(_COMEDI_VERSION_MINOR_DEFINE) + unset(_COMEDI_VERSION_MICRO_DEFINE) +endif() -select_library_configurations(Comedi) +set(COMEDI_INCLUDE_DIRS ${COMEDI_INCLUDE_DIR}) +set(COMEDI_LIBRARIES ${COMEDI_LIBRARY}) find_package_handle_standard_args( Comedi FOUND_VAR Comedi_FOUND - REQUIRED_VARS Comedi_INCLUDE_DIRS Comedi_LIBRARIES + REQUIRED_VARS COMEDI_INCLUDE_DIR COMEDI_LIBRARY + VERSION_VAR COMEDI_VERSION ) if(Comedi_FOUND AND NOT TARGET Comedi::Comedi) add_library(Comedi::Comedi UNKNOWN IMPORTED) - - if(Comedi_LIBRARY_RELEASE) + if(COMEDI_LIBRARY_RELEASE) set_property(TARGET Comedi::Comedi APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(Comedi::Comedi PROPERTIES IMPORTED_LOCATION_RELEASE "${Comedi_LIBRARY_RELEASE}") + set_target_properties(Comedi::Comedi PROPERTIES IMPORTED_LOCATION_RELEASE "${COMEDI_LIBRARY_RELEASE}") endif() - - if(Comedi_LIBRARY_DEBUG) - set_property(TARGET Comedi::Comedi APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(Comedi::Comedi PROPERTIES IMPORTED_LOCATION_DEBUG "${Comedi_LIBRARY_DEBUG}") - endif() - - set_target_properties( - Comedi::Comedi PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${Comedi_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${Comedi_INCLUDE_DIRS}" - ) + set_target_properties(Comedi::Comedi PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${COMEDI_INCLUDE_DIRS}") endif() + +mark_as_advanced(COMEDI_INCLUDE_DIR) diff --git a/cmake/FindEigen3.cmake b/cmake/FindEigen3.cmake index 738a320c..e453695b 100644 --- a/cmake/FindEigen3.cmake +++ b/cmake/FindEigen3.cmake @@ -2,44 +2,38 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - EIGEN3_INCLUDE_DIRS - NAMES - Eigen/Core - PATH_SUFFIXES - eigen3 + EIGEN3_INCLUDE_DIR + NAMES Eigen/Core + PATH_SUFFIXES eigen3 ) -mark_as_advanced(EIGEN3_INCLUDE_DIRS) - -if(EIGEN3_INCLUDE_DIRS AND EXISTS "${EIGEN3_INCLUDE_DIRS}/Eigen/src/Core/util/Macros.h") - file(STRINGS "${EIGEN3_INCLUDE_DIRS}/Eigen/src/Core/util/Macros.h" _EIGEN3_VERSION_WORLD_DEFINE REGEX "#define[\t ]+EIGEN_WORLD_VERSION[\t ]+[0-9]+.*") - string(REGEX REPLACE "#define[\t ]+EIGEN_WORLD_VERSION[\t ]+([0-9]+).*" "\\1" EIGEN3_VERSION_WORLD "${_EIGEN3_VERSION_WORLD_DEFINE}") - file(STRINGS "${EIGEN3_INCLUDE_DIRS}/Eigen/src/Core/util/Macros.h" _EIGEN3_VERSION_MAJOR_DEFINE REGEX "#define[\t ]+EIGEN_MAJOR_VERSION[\t ]+[0-9]+.*") - string(REGEX REPLACE "#define[\t ]+EIGEN_MAJOR_VERSION[\t ]+([0-9]+).*" "\\1" EIGEN3_VERSION_MAJOR "${_EIGEN3_VERSION_MAJOR_DEFINE}") - file(STRINGS "${EIGEN3_INCLUDE_DIRS}/Eigen/src/Core/util/Macros.h" _EIGEN3_VERSION_MINOR_DEFINE REGEX "#define[\t ]+EIGEN_MINOR_VERSION[\t ]+[0-9]+.*") - string(REGEX REPLACE "#define[\t ]+EIGEN_MINOR_VERSION[\t ]+([0-9]+).*" "\\1" EIGEN3_VERSION_MINOR "${_EIGEN3_VERSION_MINOR_DEFINE}") - +if(EIGEN3_INCLUDE_DIR AND EXISTS "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h") + file(STRINGS "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _EIGEN3_VERSION_WORLD_DEFINE REGEX "[\t ]*#define[\t ]+EIGEN_WORLD_VERSION[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+EIGEN_WORLD_VERSION[\t ]+([0-9]+).*" "\\1" EIGEN3_VERSION_WORLD "${_EIGEN3_VERSION_WORLD_DEFINE}") + file(STRINGS "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _EIGEN3_VERSION_MAJOR_DEFINE REGEX "[\t ]*#define[\t ]+EIGEN_MAJOR_VERSION[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+EIGEN_MAJOR_VERSION[\t ]+([0-9]+).*" "\\1" EIGEN3_VERSION_MAJOR "${_EIGEN3_VERSION_MAJOR_DEFINE}") + file(STRINGS "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _EIGEN3_VERSION_MINOR_DEFINE REGEX "[\t ]*#define[\t ]+EIGEN_MINOR_VERSION[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+EIGEN_MINOR_VERSION[\t ]+([0-9]+).*" "\\1" EIGEN3_VERSION_MINOR "${_EIGEN3_VERSION_MINOR_DEFINE}") if(NOT EIGEN3_VERSION_WORLD STREQUAL "" AND NOT EIGEN3_VERSION_MAJOR STREQUAL "" AND NOT EIGEN3_VERSION_MINOR STREQUAL "") set(EIGEN3_VERSION "${EIGEN3_VERSION_WORLD}.${EIGEN3_VERSION_MAJOR}.${EIGEN3_VERSION_MINOR}") endif() - unset(_EIGEN3_VERSION_WORLD_DEFINE) unset(_EIGEN3_VERSION_MAJOR_DEFINE) unset(_EIGEN3_VERSION_MINOR_DEFINE) endif() +set(EIGEN3_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) + find_package_handle_standard_args( Eigen3 - FOUND_VAR EIGEN3_FOUND - REQUIRED_VARS EIGEN3_INCLUDE_DIRS + FOUND_VAR Eigen3_FOUND + REQUIRED_VARS EIGEN3_INCLUDE_DIR VERSION_VAR EIGEN3_VERSION ) -if(EIGEN3_FOUND AND NOT TARGET Eigen3::Eigen) - add_library(Eigen3::Eigen UNKNOWN IMPORTED) - set_target_properties( - Eigen3::Eigen - PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${EIGEN3_INCLUDE_DIRS}" - ) +if(Eigen3_FOUND AND NOT TARGET Eigen3::Eigen) + add_library(Eigen3::Eigen INTERFACE IMPORTED) + set_target_properties(Eigen3::Eigen PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${EIGEN3_INCLUDE_DIRS}") endif() + +mark_as_advanced(EIGEN3_INCLUDE_DIR) diff --git a/cmake/FindFCL.cmake b/cmake/FindFCL.cmake deleted file mode 100644 index db208963..00000000 --- a/cmake/FindFCL.cmake +++ /dev/null @@ -1,62 +0,0 @@ -include(FindPackageHandleStandardArgs) -include(SelectLibraryConfigurations) - -find_path( - FCL_INCLUDE_DIRS - NAMES - fcl/config.h -) - -mark_as_advanced(FCL_INCLUDE_DIRS) - -find_library( - FCL_LIBRARY_DEBUG - NAMES - fcld -) - -find_library( - FCL_LIBRARY_RELEASE - NAMES - fcl -) - -select_library_configurations(FCL) - -if(FCL_INCLUDE_DIRS AND EXISTS "${FCL_INCLUDE_DIRS}/fcl/config.h") - file(STRINGS "${FCL_INCLUDE_DIRS}/fcl/config.h" _FCL_VERSION_DEFINE REGEX "#define[\t ]+FCL_VERSION[\t ]+\"[^\"]*\".*") - string(REGEX REPLACE "#define[\t ]+FCL_VERSION[\t ]+\"([^\"]*)\".*" "\\1" FCL_VERSION "${_FCL_VERSION_DEFINE}") - unset(_FCL_VERSION_DEFINE) -endif() - -if(FCL_VERSION AND FCL_VERSION VERSION_LESS 0.5) - set(FCL_DEFINITIONS -DBOOST_ALL_NO_LIB -DBOOST_SYSTEM_NO_DEPRECATED) - mark_as_advanced(FCL_DEFINITIONS) -endif() - -find_package_handle_standard_args( - FCL - FOUND_VAR FCL_FOUND - REQUIRED_VARS FCL_INCLUDE_DIRS FCL_LIBRARIES - VERSION_VAR FCL_VERSION -) - -if(FCL_FOUND AND NOT TARGET fcl::fcl) - add_library(fcl::fcl UNKNOWN IMPORTED) - - if(FCL_LIBRARY_RELEASE) - set_property(TARGET fcl::fcl APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(fcl::fcl PROPERTIES IMPORTED_LOCATION_RELEASE "${FCL_LIBRARY_RELEASE}") - endif() - - if(FCL_LIBRARY_DEBUG) - set_property(TARGET fcl::fcl APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(fcl::fcl PROPERTIES IMPORTED_LOCATION_DEBUG "${FCL_LIBRARY_DEBUG}") - endif() - - set_target_properties( - fcl::fcl PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${FCL_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${FCL_INCLUDE_DIRS}" - ) -endif() diff --git a/cmake/FindICU.cmake b/cmake/FindICU.cmake new file mode 100644 index 00000000..c31c54cc --- /dev/null +++ b/cmake/FindICU.cmake @@ -0,0 +1,100 @@ +include(FindPackageHandleStandardArgs) +include(SelectLibraryConfigurations) + +find_path( + ICU_INCLUDE_DIR + NAMES unicode/utypes.h +) + +foreach(component IN LISTS ICU_FIND_COMPONENTS) + string(TOUPPER ${component} COMPONENT) + set(names_debug icu${component}d sicu${component}d) + set(names_release icu${component} sicu${component}) + if(component STREQUAL "data") + list(APPEND names_debug icudtd sicudtd) + list(APPEND names_release icudt sicudt) + endif() + if(component STREQUAL "dt") + list(APPEND names_debug icudatad sicudatad) + list(APPEND names_release icudata sicudata) + endif() + if(component STREQUAL "i18n") + list(APPEND names_debug icuind sicuind) + list(APPEND names_release icuin sicuin) + endif() + if(component STREQUAL "in") + list(APPEND names_debug icui18nd sicui18nd) + list(APPEND names_release icui18n sicui18n) + endif() + if(APPLE) + list(APPEND names_debug icucored) + list(APPEND names_release icucore) + endif() + find_library( + ICU_${COMPONENT}_LIBRARY_DEBUG + NAMES ${names_debug} + ) + find_library( + ICU_${COMPONENT}_LIBRARY_RELEASE + NAMES ${names_release} + ) + select_library_configurations(ICU_${COMPONENT}) +endforeach() + +if(ICU_INCLUDE_DIR AND EXISTS "${ICU_INCLUDE_DIR}/unicode/uvernum.h") + file(STRINGS "${ICU_INCLUDE_DIR}/unicode/uvernum.h" _ICU_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+U_ICU_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+U_ICU_VERSION[\t ]+\"([^\"]*)\".*" "\\1" ICU_VERSION "${_ICU_VERSION_DEFINE}") + unset(_ICU_VERSION_DEFINE) +endif() + +set(ICU_INCLUDE_DIRS ${ICU_INCLUDE_DIR}) +unset(ICU_LIBRARIES) + +foreach(component IN LISTS ICU_FIND_COMPONENTS) + string(TOUPPER ${component} COMPONENT) + if(ICU_${COMPONENT}_LIBRARY) + set(ICU_${component}_FOUND ON) + set(ICU_${COMPONENT}_FOUND ON) + list(APPEND ICU_LIBRARIES ${ICU_${COMPONENT}_LIBRARY}) + endif() +endforeach() + +if(APPLE) + list(REMOVE_DUPLICATES ICU_LIBRARIES) +endif() + +if(APPLE AND NOT ICU_INCLUDE_DIR) + find_package_handle_standard_args( + ICU + FOUND_VAR ICU_FOUND + REQUIRED_VARS ICU_LIBRARIES + ) +else() + find_package_handle_standard_args( + ICU + FOUND_VAR ICU_FOUND + REQUIRED_VARS ICU_INCLUDE_DIR + VERSION_VAR ICU_VERSION + HANDLE_COMPONENTS + ) +endif() + +foreach(component IN LISTS ICU_FIND_COMPONENTS) + string(TOUPPER ${component} COMPONENT) + if(ICU_${component}_FOUND AND NOT TARGET ICU::${component}) + add_library(ICU::${component} UNKNOWN IMPORTED) + if(ICU_${COMPONENT}_LIBRARY_RELEASE) + set_property(TARGET ICU::${component} APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(ICU::${component} PROPERTIES IMPORTED_LOCATION_RELEASE "${ICU_${COMPONENT}_LIBRARY_RELEASE}") + endif() + if(ICU_${COMPONENT}_LIBRARY_DEBUG) + set_property(TARGET ICU::${component} APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(ICU::${component} PROPERTIES IMPORTED_LOCATION_RELEASE "${ICU_${COMPONENT}_LIBRARY_DEBUG}") + endif() + if(ICU_INCLUDE_DIRS) + set_target_properties(ICU::${component} PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${ICU_INCLUDE_DIRS}") + endif() + endif() +endforeach() + +mark_as_advanced(ICU_INCLUDE_DIR) diff --git a/cmake/FindIconv.cmake b/cmake/FindIconv.cmake index 21798458..82e4a041 100644 --- a/cmake/FindIconv.cmake +++ b/cmake/FindIconv.cmake @@ -4,91 +4,88 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - Iconv_INCLUDE_DIRS - NAMES - iconv.h + Iconv_INCLUDE_DIR + NAMES iconv.h ) -mark_as_advanced(Iconv_INCLUDE_DIRS) +check_c_source_runs(" + #include + int main() { iconv_t ic = iconv_open(\"to\", \"from\"); return 0; } +" Iconv_IS_BUILT_IN) -find_library( - Iconv_LIBRARY_DEBUG - NAMES - libiconvd iconvd -) - -find_library( - Iconv_LIBRARY_RELEASE - NAMES - libiconv iconv -) - -select_library_configurations(Iconv) - -if(Iconv_INCLUDE_DIRS AND NOT Iconv_LIBRARIES) - cmake_push_check_state(RESET) - set(CMAKE_REQUIRED_INCLUDES ${Iconv_INCLUDE_DIRS}) - check_c_source_runs(" - #include - int main() { iconv_t ic = iconv_open(\"to\", \"from\"); return 0; } - " Iconv_IS_BUILT_IN) - cmake_pop_check_state() - - if(Iconv_IS_BUILT_IN) - unset(Iconv_LIBRARIES) - endif() +if(NOT Iconv_IS_BUILT_IN) + find_library( + Iconv_LIBRARY_DEBUG + NAMES libiconvd iconvd + ) + find_library( + Iconv_LIBRARY_RELEASE + NAMES libiconv iconv + ) + select_library_configurations(Iconv) endif() -if(NOT CMAKE_VERSION VERSION_LESS 3.13) - if(Iconv_INCLUDE_DIRS AND EXISTS "${Iconv_INCLUDE_DIRS}/iconv.h") - file(STRINGS "${Iconv_INCLUDE_DIRS}/iconv.h" _Iconv_VERSION_DEFINE REGEX "#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F][0-9A-F][0-9A-F].*") - string(REGEX REPLACE "#define[\t ]+_LIBICONV_VERSION[\t ]+0x([0-9A-F][0-9A-F])[0-9A-F][0-9A-F].*" "\\1" _Iconv_VERSION_MAJOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") - string(REGEX REPLACE "#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F]([0-9A-F][0-9A-F]).*" "\\1" _Iconv_VERSION_MINOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") - - if(NOT _Iconv_VERSION_MAJOR_HEXADECIMAL STREQUAL "" AND NOT _Iconv_VERSION_MINOR_HEXADECIMAL STREQUAL "") +if(Iconv_INCLUDE_DIR AND EXISTS "${Iconv_INCLUDE_DIR}/iconv.h") + file(STRINGS "${Iconv_INCLUDE_DIR}/iconv.h" _Iconv_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F][0-9A-F][0-9A-F].*") + string(REGEX REPLACE "[\t ]*#define[\t ]+_LIBICONV_VERSION[\t ]+0x([0-9A-F][0-9A-F])[0-9A-F][0-9A-F].*" "\\1" _Iconv_VERSION_MAJOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") + string(REGEX REPLACE "[\t ]*#define[\t ]+_LIBICONV_VERSION[\t ]+0x[0-9A-F][0-9A-F]([0-9A-F][0-9A-F]).*" "\\1" _Iconv_VERSION_MINOR_HEXADECIMAL "${_Iconv_VERSION_DEFINE}") + if(NOT _Iconv_VERSION_MAJOR_HEXADECIMAL STREQUAL "" AND NOT _Iconv_VERSION_MINOR_HEXADECIMAL STREQUAL "") + if(NOT CMAKE_VERSION VERSION_LESS 3.13) math(EXPR Iconv_VERSION_MAJOR "0x${_Iconv_VERSION_MAJOR_HEXADECIMAL}" OUTPUT_FORMAT DECIMAL) math(EXPR Iconv_VERSION_MINOR "0x${_Iconv_VERSION_MINOR_HEXADECIMAL}" OUTPUT_FORMAT DECIMAL) - set(Iconv_VERSION "${Iconv_VERSION_MAJOR}.${Iconv_VERSION_MINOR}") + else() + function(hex_to_dec hex dec) + set(HEX_VALUES 0 1 2 3 4 5 6 7 8 9 A B C D E F) + string(LENGTH ${hex} HEX_LENGTH) + math(EXPR STOP "${HEX_LENGTH} - 1") + set(DEC 0) + foreach(BEGIN RANGE ${STOP}) + math(EXPR DEC "${DEC} * 16") + string(SUBSTRING ${hex} ${BEGIN} 1 HEX) + list(FIND HEX_VALUES ${HEX} INDEX) + math(EXPR DEC "${DEC} + ${INDEX}") + endforeach() + set(${dec} ${DEC} PARENT_SCOPE) + endfunction() + hex_to_dec(${_Iconv_VERSION_MAJOR_HEXADECIMAL} Iconv_VERSION_MAJOR) + hex_to_dec(${_Iconv_VERSION_MINOR_HEXADECIMAL} Iconv_VERSION_MINOR) endif() - - unset(_Iconv_VERSION_DEFINE) - unset(_Iconv_VERSION_MAJOR_HEXADECIMAL) - unset(_Iconv_VERSION_MINOR_HEXADECIMAL) + set(Iconv_VERSION "${Iconv_VERSION_MAJOR}.${Iconv_VERSION_MINOR}") endif() + unset(_Iconv_VERSION_DEFINE) + unset(_Iconv_VERSION_MAJOR_HEXADECIMAL) + unset(_Iconv_VERSION_MINOR_HEXADECIMAL) endif() +set(Iconv_INCLUDE_DIRS ${Iconv_INCLUDE_DIR}) +set(Iconv_LIBRARIES ${Iconv_LIBRARY}) + if(Iconv_IS_BUILT_IN) find_package_handle_standard_args( Iconv FOUND_VAR Iconv_FOUND - REQUIRED_VARS Iconv_INCLUDE_DIRS - VERSION_VAR Iconv_VERSION + REQUIRED_VARS Iconv_INCLUDE_DIR ) else() find_package_handle_standard_args( Iconv FOUND_VAR Iconv_FOUND - REQUIRED_VARS Iconv_INCLUDE_DIRS Iconv_LIBRARIES + REQUIRED_VARS Iconv_INCLUDE_DIR Iconv_LIBRARY VERSION_VAR Iconv_VERSION ) endif() if(Iconv_FOUND AND NOT TARGET Iconv::Iconv) - add_library(Iconv::Iconv UNKNOWN IMPORTED) - - if(Iconv_LIBRARY_RELEASE) + add_library(Iconv::Iconv INTERFACE IMPORTED) + if(NOT Iconv_IS_BUILT_IN AND Iconv_LIBRARY_RELEASE) set_property(TARGET Iconv::Iconv APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(Iconv::Iconv PROPERTIES IMPORTED_LOCATION_RELEASE "${Iconv_LIBRARY_RELEASE}") endif() - - if(Iconv_LIBRARY_DEBUG) + if(NOT Iconv_IS_BUILT_IN AND Iconv_LIBRARY_DEBUG) set_property(TARGET Iconv::Iconv APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(Iconv::Iconv PROPERTIES IMPORTED_LOCATION_DEBUG "${Iconv_LIBRARY_DEBUG}") endif() - - set_target_properties( - Iconv::Iconv PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${Iconv_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${Iconv_INCLUDE_DIRS}" - ) + set_target_properties(Iconv::Iconv PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${Iconv_INCLUDE_DIRS}") endif() + +mark_as_advanced(Iconv_INCLUDE_DIR) diff --git a/cmake/FindLibLZMA.cmake b/cmake/FindLibLZMA.cmake index 0ce468ea..dac34c7c 100644 --- a/cmake/FindLibLZMA.cmake +++ b/cmake/FindLibLZMA.cmake @@ -2,65 +2,55 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - LIBLZMA_INCLUDE_DIRS - NAMES - lzma.h + LIBLZMA_INCLUDE_DIR + NAMES lzma.h ) - -mark_as_advanced(LIBLZMA_INCLUDE_DIRS) - find_library( LIBLZMA_LIBRARY_DEBUG - NAMES - liblzmad lzmad + NAMES liblzmad lzmad ) find_library( LIBLZMA_LIBRARY_RELEASE - NAMES - liblzma lzma + NAMES liblzma lzma ) - select_library_configurations(LIBLZMA) -if(LIBLZMA_INCLUDE_DIRS AND EXISTS "${LIBLZMA_INCLUDE_DIRS}/lzma/version.h") - file(STRINGS "${LIBLZMA_INCLUDE_DIRS}/lzma/version.h" _LZMA_VERSION_MAJOR_DEFINE REGEX "#define[\t ]+LZMA_VERSION_MAJOR[\t ]+[0-9]+.*") - string(REGEX REPLACE "#define[\t ]+LZMA_VERSION_MAJOR[\t ]+([0-9]+).*" "\\1" LZMA_VERSION_MAJOR "${_LZMA_VERSION_MAJOR_DEFINE}") - file(STRINGS "${LIBLZMA_INCLUDE_DIRS}/lzma/version.h" _LZMA_VERSION_MINOR_DEFINE REGEX "#define[\t ]+LZMA_VERSION_MINOR[\t ]+[0-9]+.*") - string(REGEX REPLACE "#define[\t ]+LZMA_VERSION_MINOR[\t ]+([0-9]+).*" "\\1" LZMA_VERSION_MINOR "${_LZMA_VERSION_MINOR_DEFINE}") - file(STRINGS "${LIBLZMA_INCLUDE_DIRS}/lzma/version.h" _LZMA_VERSION_PATCH_DEFINE REGEX "#define[\t ]+LZMA_VERSION_PATCH[\t ]+[0-9]+.*") - string(REGEX REPLACE "#define[\t ]+LZMA_VERSION_PATCH[\t ]+([0-9]+).*" "\\1" LZMA_VERSION_PATCH "${_LZMA_VERSION_PATCH_DEFINE}") - +if(LIBLZMA_INCLUDE_DIR AND EXISTS "${LIBLZMA_INCLUDE_DIR}/lzma/version.h") + file(STRINGS "${LIBLZMA_INCLUDE_DIR}/lzma/version.h" _LZMA_VERSION_MAJOR_DEFINE REGEX "[\t ]*#define[\t ]+LZMA_VERSION_MAJOR[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+LZMA_VERSION_MAJOR[\t ]+([0-9]+).*" "\\1" LZMA_VERSION_MAJOR "${_LZMA_VERSION_MAJOR_DEFINE}") + file(STRINGS "${LIBLZMA_INCLUDE_DIR}/lzma/version.h" _LZMA_VERSION_MINOR_DEFINE REGEX "[\t ]*#define[\t ]+LZMA_VERSION_MINOR[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+LZMA_VERSION_MINOR[\t ]+([0-9]+).*" "\\1" LZMA_VERSION_MINOR "${_LZMA_VERSION_MINOR_DEFINE}") + file(STRINGS "${LIBLZMA_INCLUDE_DIR}/lzma/version.h" _LZMA_VERSION_PATCH_DEFINE REGEX "[\t ]*#define[\t ]+LZMA_VERSION_PATCH[\t ]+[0-9]+.*") + string(REGEX REPLACE "[\t ]*#define[\t ]+LZMA_VERSION_PATCH[\t ]+([0-9]+).*" "\\1" LZMA_VERSION_PATCH "${_LZMA_VERSION_PATCH_DEFINE}") if(NOT LZMA_VERSION_MAJOR STREQUAL "" AND NOT LZMA_VERSION_MINOR STREQUAL "" AND NOT LZMA_VERSION_PATCH STREQUAL "") set(LZMA_VERSION "${LZMA_VERSION_MAJOR}.${LZMA_VERSION_MINOR}.${LZMA_VERSION_PATCH}") endif() - unset(_LZMA_VERSION_MAJOR_DEFINE) unset(_LZMA_VERSION_MINOR_DEFINE) unset(_LZMA_VERSION_PATCH_DEFINE) endif() +set(LIBLZMA_INCLUDE_DIRS ${LIBLZMA_INCLUDE_DIR}) +set(LIBLZMA_LIBRARIES ${LIBLZMA_LIBRARY}) + find_package_handle_standard_args( LibLZMA - FOUND_VAR LIBLZMA_FOUND - REQUIRED_VARS LIBLZMA_INCLUDE_DIRS LIBLZMA_LIBRARIES + FOUND_VAR LibLZMA_FOUND + REQUIRED_VARS LIBLZMA_INCLUDE_DIR LIBLZMA_LIBRARY VERSION_VAR LZMA_VERSION ) -if(LIBLZMA_FOUND AND NOT TARGET LibLZMA::LibLZMA) +if(LibLZMA_FOUND AND NOT TARGET LibLZMA::LibLZMA) add_library(LibLZMA::LibLZMA UNKNOWN IMPORTED) - if(LIBLZMA_LIBRARY_RELEASE) set_property(TARGET LibLZMA::LibLZMA APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(LibLZMA::LibLZMA PROPERTIES IMPORTED_LOCATION_RELEASE "${LIBLZMA_LIBRARY_RELEASE}") endif() - if(LIBLZMA_LIBRARY_DEBUG) set_property(TARGET LibLZMA::LibLZMA APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(LibLZMA::LibLZMA PROPERTIES IMPORTED_LOCATION_DEBUG "${LIBLZMA_LIBRARY_DEBUG}") endif() - - set_target_properties( - LibLZMA::LibLZMA PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${LIBLZMA_INCLUDE_DIRS}" - ) + set_target_properties(LibLZMA::LibLZMA PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${LIBLZMA_INCLUDE_DIRS}") endif() + +mark_as_advanced(LIBLZMA_INCLUDE_DIR) diff --git a/cmake/FindLibXml2.cmake b/cmake/FindLibXml2.cmake index 3a6f714a..7d353bb9 100644 --- a/cmake/FindLibXml2.cmake +++ b/cmake/FindLibXml2.cmake @@ -1,57 +1,118 @@ +include(CheckSymbolExists) +include(CMakePushCheckState) include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - LIBXML2_INCLUDE_DIRS - NAMES - libxml/parser.h - PATH_SUFFIXES - libxml2 + LIBXML2_INCLUDE_DIR + NAMES libxml/parser.h + PATH_SUFFIXES libxml2 ) - -mark_as_advanced(LIBXML2_INCLUDE_DIRS) - find_library( LIBXML2_LIBRARY_DEBUG - NAMES - libxml2d xml2d + NAMES libxml2d xml2d ) find_library( LIBXML2_LIBRARY_RELEASE - NAMES - libxml2 xml2 + NAMES libxml2 xml2 ) - select_library_configurations(LIBXML2) -if(LIBXML2_INCLUDE_DIRS AND EXISTS "${LIBXML2_INCLUDE_DIRS}/libxml/xmlversion.h") - file(STRINGS "${LIBXML2_INCLUDE_DIRS}/libxml/xmlversion.h" _LIBXML2_VERSION_DEFINE REGEX "#define[\t ]+LIBXML_DOTTED_VERSION[\t ]+\"[^\"]*\".*") - string(REGEX REPLACE "#define[\t ]+LIBXML_DOTTED_VERSION[\t ]+\"([^\"]*)\".*" "\\1" LIBXML2_VERSION "${_LIBXML2_VERSION_DEFINE}") +if(LIBXML2_INCLUDE_DIR AND EXISTS "${LIBXML2_INCLUDE_DIR}/libxml/xmlversion.h") + file(STRINGS "${LIBXML2_INCLUDE_DIR}/libxml/xmlversion.h" _LIBXML2_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+LIBXML_DOTTED_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+LIBXML_DOTTED_VERSION[\t ]+\"([^\"]*)\".*" "\\1" LIBXML2_VERSION "${_LIBXML2_VERSION_DEFINE}") unset(_LIBXML2_VERSION_DEFINE) + cmake_push_check_state(RESET) + set(CMAKE_REQUIRED_INCLUDES ${LIBXML2_INCLUDE_DIR}) + check_symbol_exists(LIBXML_ICONV_ENABLED "libxml/xmlversion.h" LIBXML2_WITH_ICONV) + check_symbol_exists(LIBXML_ICU_ENABLED "libxml/xmlversion.h" LIBXML2_WITH_ICU) + check_symbol_exists(LIBXML_LZMA_ENABLED "libxml/xmlversion.h" LIBXML2_WITH_LZMA) + check_symbol_exists(LIBXML_THREAD_ENABLED "libxml/xmlversion.h" LIBXML2_WITH_THREADS) + check_symbol_exists(LIBXML_ZLIB_ENABLED "libxml/xmlversion.h" LIBXML2_WITH_ZLIB) + cmake_pop_check_state() +endif() + +unset(_LIBXML2_FIND_PACKAGE_ARGS) +set(LIBXML2_INCLUDE_DIRS ${LIBXML2_INCLUDE_DIR}) +unset(_LIBXML2_INTERFACE_LINK_LIBRARIES) +set(LIBXML2_LIBRARIES ${LIBXML2_LIBRARY}) +unset(_LIBXML2_REQUIRED_VARS) + +if(LibXml2_FIND_QUIETLY) + list(APPEND _LIBXML2_FIND_PACKAGE_ARGS QUIET) +endif() +if(LibXml2_FIND_REQUIRED) + list(APPEND _LIBXML2_FIND_PACKAGE_ARGS REQUIRED) +endif() + +if(LIBXML2_WITH_ICONV) + find_package(Iconv ${_LIBXML2_FIND_PACKAGE_ARGS}) + list(APPEND LIBXML2_INCLUDE_DIRS ${Iconv_INCLUDE_DIRS}) + list(APPEND _LIBXML2_INTERFACE_LINK_LIBRARIES "Iconv::Iconv") + list(APPEND LIBXML2_LIBRARIES ${Iconv_LIBRARIES}) + list(APPEND _LIBXML2_REQUIRED_VARS Iconv_FOUND) +endif() + +if(LIBXML2_WITH_ICU) + find_package(ICU ${_LIBXML2_FIND_PACKAGE_ARGS} COMPONENTS data i18n uc) + list(APPEND _LIBXML2_INTERFACE_LINK_LIBRARIES "\$;\$;\$") + list(APPEND LIBXML2_LIBRARIES ${ICU_LIBRARIES}) + list(APPEND _LIBXML2_REQUIRED_VARS ICU_FOUND) +endif() + +if(LIBXML2_WITH_LZMA) + find_package(LibLZMA ${_LIBXML2_FIND_PACKAGE_ARGS}) + list(APPEND _LIBXML2_INTERFACE_LINK_LIBRARIES "\$") + list(APPEND LIBXML2_LIBRARIES ${LIBLZMA_LIBRARIES}) + list(APPEND _LIBXML2_REQUIRED_VARS LibLZMA_FOUND) +endif() + +if(LIBXML2_WITH_THREADS) + find_package(Threads ${_LIBXML2_FIND_PACKAGE_ARGS}) + list(APPEND _LIBXML2_INTERFACE_LINK_LIBRARIES "\$") + list(APPEND LIBXML2_LIBRARIES ${CMAKE_THREAD_LIBS_INIT}) + list(APPEND _LIBXML2_REQUIRED_VARS Threads_FOUND) +endif() + +if(LIBXML2_WITH_ZLIB) + find_package(ZLIB ${_LIBXML2_FIND_PACKAGE_ARGS}) + list(APPEND _LIBXML2_INTERFACE_LINK_LIBRARIES "\$") + list(APPEND LIBXML2_LIBRARIES ${ZLIB_LIBRARIES}) + list(APPEND _LIBXML2_REQUIRED_VARS ZLIB_FOUND) +endif() + +if(UNIX) + list(APPEND _LIBXML2_INTERFACE_LINK_LIBRARIES "\$") + list(APPEND LIBXML2_LIBRARIES m) +endif() + +if(WIN32) + list(APPEND _LIBXML2_INTERFACE_LINK_LIBRARIES "\$") + list(APPEND LIBXML2_LIBRARIES ws2_32) endif() find_package_handle_standard_args( LibXml2 FOUND_VAR LibXml2_FOUND - REQUIRED_VARS LIBXML2_INCLUDE_DIRS LIBXML2_LIBRARIES + REQUIRED_VARS LIBXML2_INCLUDE_DIR LIBXML2_LIBRARY ${_LIBXML2_REQUIRED_VARS} VERSION_VAR LIBXML2_VERSION ) if(LibXml2_FOUND AND NOT TARGET LibXml2::LibXml2) add_library(LibXml2::LibXml2 UNKNOWN IMPORTED) - if(LIBXML2_LIBRARY_RELEASE) set_property(TARGET LibXml2::LibXml2 APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(LibXml2::LibXml2 PROPERTIES IMPORTED_LOCATION_RELEASE "${LIBXML2_LIBRARY_RELEASE}") endif() - if(LIBXML2_LIBRARY_DEBUG) set_property(TARGET LibXml2::LibXml2 APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(LibXml2::LibXml2 PROPERTIES IMPORTED_LOCATION_DEBUG "${LIBXML2_LIBRARY_DEBUG}") endif() - - set_target_properties( - LibXml2::LibXml2 PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${LIBXML2_INCLUDE_DIRS}" - ) + set_target_properties(LibXml2::LibXml2 PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${LIBXML2_INCLUDE_DIRS}") + set_target_properties(LibXml2::LibXml2 PROPERTIES INTERFACE_LINK_LIBRARIES "${_LIBXML2_INTERFACE_LINK_LIBRARIES}") endif() + +mark_as_advanced(LIBXML2_INCLUDE_DIR) +unset(_LIBXML2_FIND_PACKAGE_ARGS) +unset(_LIBXML2_INTERFACE_LINK_LIBRARIES) +unset(_LIBXML2_REQUIRED_VARS) diff --git a/cmake/FindLibXslt.cmake b/cmake/FindLibXslt.cmake index 8bf4ad5c..bf0449b1 100644 --- a/cmake/FindLibXslt.cmake +++ b/cmake/FindLibXslt.cmake @@ -2,54 +2,66 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - LIBXSLT_INCLUDE_DIRS - NAMES - libxslt/xslt.h + LIBXSLT_INCLUDE_DIR + NAMES libxslt/xslt.h ) - -mark_as_advanced(LIBXSLT_INCLUDE_DIRS) - find_library( LIBXSLT_LIBRARY_DEBUG - NAMES - libxsltd xsltd + NAMES libxsltd xsltd ) find_library( LIBXSLT_LIBRARY_RELEASE - NAMES - libxslt xslt + NAMES libxslt xslt ) - select_library_configurations(LIBXSLT) -if(LIBXSLT_INCLUDE_DIRS AND EXISTS "${LIBXSLT_INCLUDE_DIRS}/libxslt/xsltconfig.h") - file(STRINGS "${LIBXSLT_INCLUDE_DIRS}/libxslt/xsltconfig.h" _LIBXSLT_VERSION_DEFINE REGEX "#define[\t ]+LIBXSLT_DOTTED_VERSION[\t ]+\"[^\"]*\".*") - string(REGEX REPLACE "#define[\t ]+LIBXSLT_DOTTED_VERSION[\t ]+\"([^\"]*)\".*" "\\1" LIBXSLT_VERSION "${_LIBXSLT_VERSION_DEFINE}") +if(LIBXSLT_INCLUDE_DIR AND EXISTS "${LIBXSLT_INCLUDE_DIR}/libxslt/xsltconfig.h") + file(STRINGS "${LIBXSLT_INCLUDE_DIR}/libxslt/xsltconfig.h" _LIBXSLT_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+LIBXSLT_DOTTED_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+LIBXSLT_DOTTED_VERSION[\t ]+\"([^\"]*)\".*" "\\1" LIBXSLT_VERSION "${_LIBXSLT_VERSION_DEFINE}") unset(_LIBXSLT_VERSION_DEFINE) endif() +unset(_LIBXSLT_FIND_PACKAGE_ARGS) +set(LIBXSLT_INCLUDE_DIRS ${LIBXSLT_INCLUDE_DIR}) +unset(_LIBXSLT_INTERFACE_LINK_LIBRARIES) +set(LIBXSLT_LIBRARIES ${LIBXSLT_LIBRARY}) +unset(_LIBXSLT_REQUIRED_VARS) + +if(LibXslt_FIND_QUIETLY) + list(APPEND _LIBXSLT_FIND_PACKAGE_ARGS QUIET) +endif() +if(LibXslt_FIND_REQUIRED) + list(APPEND _LIBXSLT_FIND_PACKAGE_ARGS REQUIRED) +endif() + +find_package(LibXml2 ${_LIBXSLT_FIND_PACKAGE_ARGS}) +list(APPEND LIBXSLT_INCLUDE_DIRS ${LIBXML2_INCLUDE_DIRS}) +list(APPEND LIBXSLT_LIBRARIES ${LIBXML2_LIBRARIES}) +list(APPEND _LIBXSLT_INTERFACE_LINK_LIBRARIES "LibXml2::LibXml2") +list(APPEND _LIBXSLT_REQUIRED_VARS LibXml2_FOUND) + find_package_handle_standard_args( LibXslt - FOUND_VAR LIBXSLT_FOUND - REQUIRED_VARS LIBXSLT_INCLUDE_DIRS LIBXSLT_LIBRARIES + FOUND_VAR LibXslt_FOUND + REQUIRED_VARS LIBXSLT_INCLUDE_DIR LIBXSLT_LIBRARY ${_LIBXSLT_REQUIRED_VARS} VERSION_VAR LIBXSLT_VERSION ) -if(LIBXSLT_FOUND AND NOT TARGET LibXslt::LibXslt) +if(LibXslt_FOUND AND NOT TARGET LibXslt::LibXslt) add_library(LibXslt::LibXslt UNKNOWN IMPORTED) - if(LIBXSLT_LIBRARY_RELEASE) set_property(TARGET LibXslt::LibXslt APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(LibXslt::LibXslt PROPERTIES IMPORTED_LOCATION_RELEASE "${LIBXSLT_LIBRARY_RELEASE}") endif() - if(LIBXSLT_LIBRARY_DEBUG) set_property(TARGET LibXslt::LibXslt APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(LibXslt::LibXslt PROPERTIES IMPORTED_LOCATION_DEBUG "${LIBXSLT_LIBRARY_DEBUG}") endif() - - set_target_properties( - LibXslt::LibXslt PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${LIBXSLT_INCLUDE_DIRS}" - ) + set_target_properties(LibXslt::LibXslt PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${LIBXSLT_INCLUDE_DIRS}") + set_target_properties(LibXslt::LibXslt PROPERTIES INTERFACE_LINK_LIBRARIES "${_LIBXSLT_INTERFACE_LINK_LIBRARIES}") endif() + +mark_as_advanced(LIBXSLT_INCLUDE_DIR) +unset(_LIBXSLT_FIND_PACKAGE_ARGS) +unset(_LIBXSLT_INTERFACE_LINK_LIBRARIES) +unset(_LIBXSLT_REQUIRED_VARS) diff --git a/cmake/FindNLopt.cmake b/cmake/FindNLopt.cmake index 79c784be..dbc32ab6 100644 --- a/cmake/FindNLopt.cmake +++ b/cmake/FindNLopt.cmake @@ -2,47 +2,39 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - NLOPT_INCLUDE_DIRS - NAMES - nlopt.h + NLOPT_INCLUDE_DIR + NAMES nlopt.h ) - -mark_as_advanced(NLOPT_INCLUDE_DIRS) - find_library( NLOPT_LIBRARY_DEBUG - NAMES - nloptd + NAMES nloptd ) find_library( NLOPT_LIBRARY_RELEASE - NAMES - nlopt + NAMES nlopt ) - select_library_configurations(NLOPT) +set(NLOPT_INCLUDE_DIRS ${NLOPT_INCLUDE_DIR}) +set(NLOPT_LIBRARIES ${NLOPT_LIBRARY}) + find_package_handle_standard_args( NLopt - FOUND_VAR NLOPT_FOUND - REQUIRED_VARS NLOPT_INCLUDE_DIRS NLOPT_LIBRARIES + FOUND_VAR NLopt_FOUND + REQUIRED_VARS NLOPT_INCLUDE_DIR NLOPT_LIBRARY ) -if(NLOPT_FOUND AND NOT TARGET NLopt::nlopt) +if(NLopt_FOUND AND NOT TARGET NLopt::nlopt) add_library(NLopt::nlopt UNKNOWN IMPORTED) - if(NLOPT_LIBRARY_RELEASE) set_property(TARGET NLopt::nlopt APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(NLopt::nlopt PROPERTIES IMPORTED_LOCATION_RELEASE "${NLOPT_LIBRARY_RELEASE}") endif() - if(NLOPT_LIBRARY_DEBUG) set_property(TARGET NLopt::nlopt APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(NLopt::nlopt PROPERTIES IMPORTED_LOCATION_DEBUG "${NLOPT_LIBRARY_DEBUG}") endif() - - set_target_properties( - NLopt::nlopt PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${NLOPT_INCLUDE_DIRS}" - ) + set_target_properties(NLopt::nlopt PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${NLOPT_INCLUDE_DIRS}") endif() + +mark_as_advanced(NLOPT_INCLUDE_DIR) diff --git a/cmake/FindODE.cmake b/cmake/FindODE.cmake index f9cc82b3..6eccde8d 100644 --- a/cmake/FindODE.cmake +++ b/cmake/FindODE.cmake @@ -5,100 +5,100 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - ODE_INCLUDE_DIRS - NAMES - ode/ode.h + ODE_INCLUDE_DIR + NAMES ode/ode.h ) - -mark_as_advanced(ODE_INCLUDE_DIRS) - find_library( ODE_LIBRARY_DEBUG - NAMES - ode_doubled ode_singled oded + NAMES ode_doubled ode_singled oded ode_doublesd ode_singlesd odesd ) - find_library( ODE_LIBRARY_RELEASE - NAMES - ode_double ode_single ode + NAMES ode_double ode_single ode ode_doubles ode_singles odes ) - select_library_configurations(ODE) -if(ODE_INCLUDE_DIRS AND ODE_LIBRARIES) +if(ODE_INCLUDE_DIR AND ODE_LIBRARY) cmake_push_check_state(RESET) - set(CMAKE_REQUIRED_INCLUDES ${ODE_INCLUDE_DIRS}) + set(CMAKE_REQUIRED_INCLUDES ${ODE_INCLUDE_DIR}) check_symbol_exists(dDOUBLE "ode/precision.h" _ODE_HAVE_dDOUBLE) - if(NOT _ODE_HAVE_dDOUBLE) check_symbol_exists(dSINGLE "ode/precision.h" _ODE_HAVE_dSINGLE) - if(NOT _ODE_HAVE_dSINGLE) set(CMAKE_REQUIRED_DEFINITIONS -DdDOUBLE) - set(CMAKE_REQUIRED_LIBRARIES ${ODE_LIBRARIES}) + set(CMAKE_REQUIRED_LIBRARIES ${ODE_LIBRARY}) check_c_source_runs(" #include int main() { return 1 == dCheckConfiguration(\"ODE_double_precision\") ? 0 : 1; } " _ODE_DOUBLE_PRECISION) - if(_ODE_DOUBLE_PRECISION) set(ODE_DEFINITIONS -DdDOUBLE) + set(_ODE_INTERFACE_COMPILE_DEFINITIONS "dDOUBLE") else() set(CMAKE_REQUIRED_DEFINITIONS -DdSINGLE) check_c_source_runs(" #include int main() { return 1 == dCheckConfiguration(\"ODE_single_precision\") ? 0 : 1; } " _ODE_SINGLE_PRECISION) - if(_ODE_SINGLE_PRECISION) set(ODE_DEFINITIONS -DdSINGLE) + set(_ODE_INTERFACE_COMPILE_DEFINITIONS "dSINGLE") endif() - unset(_ODE_SINGLE_PRECISION) endif() - unset(_ODE_DOUBLE_PRECISION) endif() - unset(_ODE_HAVE_dSINGLE) endif() - unset(_ODE_HAVE_dDOUBLE) cmake_pop_check_state() endif() -mark_as_advanced(ODE_DEFINITIONS) - -if(ODE_INCLUDE_DIRS AND EXISTS "${ODE_INCLUDE_DIRS}/ode/version.h") - file(STRINGS "${ODE_INCLUDE_DIRS}/ode/version.h" _ODE_VERSION_DEFINE REGEX "#define[\t ]+dODE_VERSION[\t ]+\"[^\"]*\".*") - string(REGEX REPLACE "#define[\t ]+dODE_VERSION[\t ]+\"([^\"]*)\".*" "\\1" ODE_VERSION "${_ODE_VERSION_DEFINE}") +if(ODE_INCLUDE_DIR AND EXISTS "${ODE_INCLUDE_DIR}/ode/version.h") + file(STRINGS "${ODE_INCLUDE_DIR}/ode/version.h" _ODE_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+dODE_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+dODE_VERSION[\t ]+\"([^\"]*)\".*" "\\1" ODE_VERSION "${_ODE_VERSION_DEFINE}") unset(_ODE_VERSION_DEFINE) endif() +set(ODE_INCLUDE_DIRS ${ODE_INCLUDE_DIR}) +unset(_ODE_INTERFACE_LINK_LIBRARIES) +set(ODE_LIBRARIES ${ODE_LIBRARY}) + +find_package(ccd QUIET) +if(ccd_FOUND) + list(APPEND _ODE_INTERFACE_LINK_LIBRARIES "\$") + list(APPEND ODE_LIBRARIES ${CCD_LIBRARIES}) +endif() + +find_package(Threads QUIET) +if(Threads_FOUND) + list(APPEND _ODE_INTERFACE_LINK_LIBRARIES "\$") + list(APPEND ODE_LIBRARIES ${CMAKE_THREAD_LIBS_INIT}) +endif() + find_package_handle_standard_args( ODE FOUND_VAR ODE_FOUND - REQUIRED_VARS ODE_INCLUDE_DIRS ODE_LIBRARIES + REQUIRED_VARS ODE_INCLUDE_DIR ODE_LIBRARY VERSION_VAR ODE_VERSION ) if(ODE_FOUND AND NOT TARGET ODE::ODE) add_library(ODE::ODE UNKNOWN IMPORTED) - if(ODE_LIBRARY_RELEASE) set_property(TARGET ODE::ODE APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(ODE::ODE PROPERTIES IMPORTED_LOCATION_RELEASE "${ODE_LIBRARY_RELEASE}") endif() - if(ODE_LIBRARY_DEBUG) set_property(TARGET ODE::ODE APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(ODE::ODE PROPERTIES IMPORTED_LOCATION_DEBUG "${ODE_LIBRARY_DEBUG}") endif() - - set_target_properties( - ODE::ODE PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${ODE_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${ODE_INCLUDE_DIRS}" - ) + set_target_properties(ODE::ODE PROPERTIES INTERFACE_COMPILE_DEFINITIONS "${_ODE_INTERFACE_COMPILE_DEFINITIONS}") + set_target_properties(ODE::ODE PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${ODE_INCLUDE_DIRS}") + set_target_properties(ODE::ODE PROPERTIES INTERFACE_LINK_LIBRARIES "${_ODE_INTERFACE_LINK_LIBRARIES}") endif() + +mark_as_advanced(ODE_DEFINITIONS) +mark_as_advanced(ODE_INCLUDE_DIR) +unset(_ODE_INTERFACE_COMPILE_DEFINITIONS) +unset(_ODE_INTERFACE_LINK_LIBRARIES) diff --git a/cmake/FindOctoMap.cmake b/cmake/FindOctoMap.cmake deleted file mode 100644 index 322d02fd..00000000 --- a/cmake/FindOctoMap.cmake +++ /dev/null @@ -1,84 +0,0 @@ -include(FindPackageHandleStandardArgs) -include(SelectLibraryConfigurations) - -find_path( - OCTOMAP_INCLUDE_DIRS - NAMES - octomap/octomap.h -) - -mark_as_advanced(OCTOMAP_INCLUDE_DIRS) - -find_library( - OCTOMAP_OCTOMAP_LIBRARY_DEBUG - NAMES - octomapd -) - -find_library( - OCTOMAP_OCTOMAP_LIBRARY_RELEASE - NAMES - octomap -) - -select_library_configurations(OCTOMAP_OCTOMAP) - -find_library( - OCTOMAP_OCTOMATH_LIBRARY_DEBUG - NAMES - octomathd -) - -find_library( - OCTOMAP_OCTOMATH_LIBRARY_RELEASE - NAMES - octomath -) - -select_library_configurations(OCTOMAP_OCTOMATH) - -set(OCTOMAP_LIBRARIES ${OCTOMAP_OCTOMAP_LIBRARIES} ${OCTOMAP_OCTOMATH_LIBRARIES}) - -find_package_handle_standard_args( - OctoMap - FOUND_VAR OCTOMAP_FOUND - REQUIRED_VARS OCTOMAP_INCLUDE_DIRS OCTOMAP_LIBRARIES -) - -if(OCTOMAP_FOUND AND NOT TARGET octomap::octomap) - add_library(octomap::octomap UNKNOWN IMPORTED) - - if(OCTOMAP_OCTOMAP_LIBRARY_RELEASE) - set_property(TARGET octomap::octomap APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(octomap::octomap PROPERTIES IMPORTED_LOCATION_RELEASE "${OCTOMAP_OCTOMAP_LIBRARY_RELEASE}") - endif() - - if(OCTOMAP_OCTOMAP_LIBRARY_DEBUG) - set_property(TARGET octomap::octomap APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(octomap::octomap PROPERTIES IMPORTED_LOCATION_DEBUG "${OCTOMAP_OCTOMAP_LIBRARY_DEBUG}") - endif() - - set_target_properties( - octomap::octomap PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${OCTOMAP_INCLUDE_DIRS}" - ) -endif() - -if(OCTOMAP_FOUND AND NOT TARGET octomap::octomath) - add_library(octomap::octomath UNKNOWN IMPORTED) - - if(OCTOMAP_OCTOMATH_LIBRARY_RELEASE) - set_property(TARGET octomap::octomath APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(octomap::octomath PROPERTIES IMPORTED_LOCATION_RELEASE "${OCTOMAP_OCTOMATH_LIBRARY_RELEASE}") - endif() - - if(OCTOMAP_OCTOMATH_LIBRARY_DEBUG) - set_property(TARGET octomap::octomath APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(octomap::octomath PROPERTIES IMPORTED_LOCATION_DEBUG "${OCTOMAP_OCTOMATH_LIBRARY_DEBUG}") - endif() - - set_target_properties( - octomap::octomath PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${OCTOMAP_INCLUDE_DIRS}" - ) -endif() diff --git a/cmake/FindPQP.cmake b/cmake/FindPQP.cmake index 2adbc9d8..943bd9d7 100644 --- a/cmake/FindPQP.cmake +++ b/cmake/FindPQP.cmake @@ -2,48 +2,39 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - PQP_INCLUDE_DIRS - NAMES - PQP.h + PQP_INCLUDE_DIR + NAMES PQP.h ) - -mark_as_advanced(PQP_INCLUDE_DIRS) - find_library( PQP_LIBRARY_DEBUG - NAMES - PQPd + NAMES PQPd ) - find_library( PQP_LIBRARY_RELEASE - NAMES - PQP + NAMES PQP ) - select_library_configurations(PQP) +set(PQP_INCLUDE_DIRS ${PQP_INCLUDE_DIR}) +set(PQP_LIBRARIES ${PQP_LIBRARY}) + find_package_handle_standard_args( PQP FOUND_VAR PQP_FOUND - REQUIRED_VARS PQP_INCLUDE_DIRS PQP_LIBRARIES + REQUIRED_VARS PQP_INCLUDE_DIR PQP_LIBRARY ) if(PQP_FOUND AND NOT TARGET PQP::PQP) add_library(PQP::PQP UNKNOWN IMPORTED) - if(PQP_LIBRARY_RELEASE) set_property(TARGET PQP::PQP APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(PQP::PQP PROPERTIES IMPORTED_LOCATION_RELEASE "${PQP_LIBRARY_RELEASE}") endif() - if(PQP_LIBRARY_DEBUG) set_property(TARGET PQP::PQP APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(PQP::PQP PROPERTIES IMPORTED_LOCATION_DEBUG "${PQP_LIBRARY_DEBUG}") endif() - - set_target_properties( - PQP::PQP PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${PQP_INCLUDE_DIRS}" - ) + set_target_properties(PQP::PQP PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${PQP_INCLUDE_DIRS}") endif() + +mark_as_advanced(PQP_INCLUDE_DIR) diff --git a/cmake/FindRTAI.cmake b/cmake/FindRTAI.cmake index 2bfde086..b6c83c7c 100644 --- a/cmake/FindRTAI.cmake +++ b/cmake/FindRTAI.cmake @@ -2,58 +2,42 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - RTAI_INCLUDE_DIRS - NAMES - rtai_lxrt.h - PATHS - /usr/realtime/include - PATH_SUFFIXES - rtai + RTAI_INCLUDE_DIR + NAMES rtai_lxrt.h + PATHS /usr/realtime/include + PATH_SUFFIXES rtai ) - -mark_as_advanced(RTAI_INCLUDE_DIRS) - -find_library( - RTAI_LIBRARY_DEBUG - NAMES - lxrtd - PATHS - /usr/realtime/lib -) - find_library( RTAI_LIBRARY_RELEASE - NAMES - lxrt - PATHS - /usr/realtime/lib + NAMES lxrt + PATHS /usr/realtime/lib ) - select_library_configurations(RTAI) +if(RTAI_INCLUDE_DIR AND EXISTS "${RTAI_INCLUDE_DIR}/rtai_config.h") + file(STRINGS "${RTAI_INCLUDE_DIR}/rtai_config.h" _RTAI_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+VERSION[\t ]+\"([^\"]*)\".*" "\\1" RTAI_VERSION "${_RTAI_VERSION_DEFINE}") + unset(_RTAI_VERSION_DEFINE) +endif() + +set(RTAI_INCLUDE_DIRS ${RTAI_INCLUDE_DIR}) set(RTAI_LIBRARIES ${RTAI_LIBRARIES} rt) find_package_handle_standard_args( RTAI FOUND_VAR RTAI_FOUND - REQUIRED_VARS RTAI_INCLUDE_DIRS RTAI_LIBRARIES + REQUIRED_VARS RTAI_INCLUDE_DIR RTAI_LIBRARY + VERSION_VAR RTAI_VERSION ) if(RTAI_FOUND AND NOT TARGET RTAI::lxrt) add_library(RTAI::lxrt UNKNOWN IMPORTED) - if(RTAI_LIBRARY_RELEASE) set_property(TARGET RTAI::lxrt APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(RTAI::lxrt PROPERTIES IMPORTED_LOCATION_RELEASE "${RTAI_LIBRARY_RELEASE}") endif() - - if(RTAI_LIBRARY_DEBUG) - set_property(TARGET RTAI::lxrt APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(RTAI::lxrt PROPERTIES IMPORTED_LOCATION_DEBUG "${RTAI_LIBRARY_DEBUG}") - endif() - - set_target_properties( - RTAI::lxrt PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${RTAI_INCLUDE_DIRS}" - ) + set_target_properties(RTAI::lxrt PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${RTAI_INCLUDE_DIRS}") + set_target_properties(RTAI::lxrt PROPERTIES INTERFACE_LINK_LIBRARIES "rt") endif() + +mark_as_advanced(RTAI_INCLUDE_DIR) diff --git a/cmake/FindSoQt.cmake b/cmake/FindSoQt.cmake index f5217452..63f5a4fd 100644 --- a/cmake/FindSoQt.cmake +++ b/cmake/FindSoQt.cmake @@ -2,72 +2,56 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - SoQt_INCLUDE_DIRS - NAMES - Inventor/Qt/SoQt.h - PATH_SUFFIXES - Coin4 - Coin3 - Coin2 + SoQt_INCLUDE_DIR + NAMES Inventor/Qt/SoQt.h + PATH_SUFFIXES Coin4 Coin3 Coin2 ) - -mark_as_advanced(SoQt_INCLUDE_DIRS) - find_library( SoQt_LIBRARY_DEBUG - NAMES - SoQtd SoQt1d + NAMES SoQtd SoQt1d ) - find_library( SoQt_LIBRARY_RELEASE - NAMES - SoQt SoQt1 + NAMES SoQt SoQt1 ) - select_library_configurations(SoQt) -set(SoQt_DEFINITIONS -DSOQT_DLL) - -mark_as_advanced(SoQt_DEFINITIONS) - -if(SoQt_INCLUDE_DIRS AND EXISTS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h") - file(STRINGS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h" _SoQt_VERSION_DEFINE REGEX "#define[\t ]+SOQT_VERSION[\t ]+\"[^\"]*\".*") - string(REGEX REPLACE "#define[\t ]+SOQT_VERSION[\t ]+\"([^\"]*)\".*" "\\1" SoQt_VERSION "${_SoQt_VERSION_DEFINE}") - file(STRINGS "${SoQt_INCLUDE_DIRS}/Inventor/Qt/SoQtBasic.h" _SoQt_GUI_TOOLKIT_VERSION_DEFINE REGEX "#define[\t ]+GUI_TOOLKIT_VERSION[\t ]+\"[0-9][0-9][0-9]\".*") - string(REGEX REPLACE "#define[\t ]+GUI_TOOLKIT_VERSION[\t ]+\"([0-9])[0-9][0-9]\".*" "\\1" SoQt_GUI_TOOLKIT_VERSION_MAJOR "${_SoQt_GUI_TOOLKIT_VERSION_DEFINE}") - +if(SoQt_INCLUDE_DIR AND EXISTS "${SoQt_INCLUDE_DIR}/Inventor/Qt/SoQtBasic.h") + file(STRINGS "${SoQt_INCLUDE_DIR}/Inventor/Qt/SoQtBasic.h" _SoQt_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+SOQT_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+SOQT_VERSION[\t ]+\"([^\"]*)\".*" "\\1" SoQt_VERSION "${_SoQt_VERSION_DEFINE}") + file(STRINGS "${SoQt_INCLUDE_DIR}/Inventor/Qt/SoQtBasic.h" _SoQt_GUI_TOOLKIT_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+GUI_TOOLKIT_VERSION[\t ]+\"[0-9][0-9]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+GUI_TOOLKIT_VERSION[\t ]+\"([0-9])[0-9]*\".*" "\\1" SoQt_GUI_TOOLKIT_VERSION_MAJOR "${_SoQt_GUI_TOOLKIT_VERSION_DEFINE}") if(NOT SoQt_GUI_TOOLKIT_VERSION_MAJOR STREQUAL "") - set(SoQt${SoQt_GUI_TOOLKIT_VERSION_MAJOR}_FOUND ON) + set(SoQt_HAVE_QT${SoQt_GUI_TOOLKIT_VERSION_MAJOR} ON) endif() - unset(_SoQt_VERSION_DEFINE) unset(_SoQt_GUI_TOOLKIT_VERSION_DEFINE) endif() +set(SoQt_DEFINITIONS -DSOQT_DLL) +set(SoQt_INCLUDE_DIRS ${SoQt_INCLUDE_DIR}) +set(SoQt_LIBRARIES ${SoQt_LIBRARY}) + find_package_handle_standard_args( SoQt FOUND_VAR SoQt_FOUND - REQUIRED_VARS SoQt_INCLUDE_DIRS SoQt_LIBRARIES + REQUIRED_VARS SoQt_INCLUDE_DIR SoQt_LIBRARY VERSION_VAR SoQt_VERSION ) if(SoQt_FOUND AND NOT TARGET SoQt::SoQt) add_library(SoQt::SoQt UNKNOWN IMPORTED) - if(SoQt_LIBRARY_RELEASE) set_property(TARGET SoQt::SoQt APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(SoQt::SoQt PROPERTIES IMPORTED_LOCATION_RELEASE "${SoQt_LIBRARY_RELEASE}") endif() - if(SoQt_LIBRARY_DEBUG) set_property(TARGET SoQt::SoQt APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(SoQt::SoQt PROPERTIES IMPORTED_LOCATION_DEBUG "${SoQt_LIBRARY_DEBUG}") endif() - - set_target_properties( - SoQt::SoQt PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${SoQt_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${SoQt_INCLUDE_DIRS}" - ) + set_target_properties(SoQt::SoQt PROPERTIES INTERFACE_COMPILE_DEFINITIONS "SOQT_DLL") + set_target_properties(SoQt::SoQt PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${SoQt_INCLUDE_DIRS}") endif() + +mark_as_advanced(SoQt_DEFINITIONS) +mark_as_advanced(SoQt_INCLUDE_DIR) diff --git a/cmake/FindXenomai.cmake b/cmake/FindXenomai.cmake index fb8f0d4e..68e0460d 100644 --- a/cmake/FindXenomai.cmake +++ b/cmake/FindXenomai.cmake @@ -1,104 +1,73 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) -find_path( - Xenomai_INCLUDE_DIRS - NAMES - native/task.h - PATHS - /usr/xenomai/include - PATH_SUFFIXES - xenomai -) - -mark_as_advanced(Xenomai_INCLUDE_DIRS) - -find_library( - Xenomai_NATIVE_LIBRARY_DEBUG - NAMES - natived - PATHS - /usr/xenomai/lib -) - -find_library( - Xenomai_NATIVE_LIBRARY_RELEASE - NAMES - native - PATHS - /usr/xenomai/lib -) - -select_library_configurations(Xenomai_NATIVE) - -find_library( - Xenomai_XENOMAI_LIBRARY_DEBUG - NAMES - xenomaid - PATHS - /usr/xenomai/lib -) +if(NOT Xenomai_FIND_COMPONENTS) + set(Xenomai_FIND_COMPONENTS native xenomai) + foreach(component IN LISTS Xenomai_FIND_COMPONENTS) + set(Xenomai_FIND_REQUIRED_${component} ON) + endforeach() +endif() -find_library( - Xenomai_XENOMAI_LIBRARY_RELEASE - NAMES - xenomai - PATHS - /usr/xenomai/lib +find_path( + XENOMAI_INCLUDE_DIR + NAMES xeno_config.h + PATHS /usr/xenomai/include + PATH_SUFFIXES xenomai ) -select_library_configurations(Xenomai_XENOMAI) +foreach(component IN LISTS Xenomai_FIND_COMPONENTS) + string(TOUPPER ${component} COMPONENT) + find_library( + XENOMAI_${COMPONENT}_LIBRARY_RELEASE + NAMES ${component} + PATHS /usr/xenomai/lib + ) + select_library_configurations(XENOMAI_${COMPONENT}) +endforeach() -set(Xenomai_LIBRARIES ${Xenomai_NATIVE_LIBRARIES} ${Xenomai_XENOMAI_LIBRARIES} pthread rt) +if(XENOMAI_INCLUDE_DIR AND EXISTS "${XENOMAI_INCLUDE_DIR}/xeno_config.h") + file(STRINGS "${XENOMAI_INCLUDE_DIR}/xeno_config.h" _XENOMAI_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+VERSION[\t ]+\"([^\"]*)\".*" "\\1" XENOMAI_VERSION "${_XENOMAI_VERSION_DEFINE}") + unset(_XENOMAI_VERSION_DEFINE) +endif() -set(Xenomai_DEFINITIONS -D__XENO__ -D_GNU_SOURCE -D_REENTRANT) +set(XENOMAI_DEFINITIONS -D__XENO__ -D_GNU_SOURCE -D_REENTRANT) +set(XENOMAI_INCLUDE_DIRS ${XENOMAI_INCLUDE_DIR}) +set(XENOMAI_LIBRARIES pthread rt) -mark_as_advanced(Xenomai_DEFINITIONS) +foreach(component IN LISTS Xenomai_FIND_COMPONENTS) + string(TOUPPER ${component} COMPONENT) + if(XENOMAI_${COMPONENT}_LIBRARY) + set(Xenomai_${component}_FOUND ON) + list(APPEND XENOMAI_LIBRARIES ${XENOMAI_${COMPONENT}_LIBRARY}) + endif() +endforeach() find_package_handle_standard_args( Xenomai FOUND_VAR Xenomai_FOUND - REQUIRED_VARS Xenomai_INCLUDE_DIRS Xenomai_NATIVE_LIBRARY Xenomai_XENOMAI_LIBRARY + REQUIRED_VARS XENOMAI_INCLUDE_DIR + VERSION_VAR XENOMAI_VERSION + HANDLE_COMPONENTS ) -if(Xenomai_FOUND AND NOT TARGET Xenomai::native) - add_library(Xenomai::native UNKNOWN IMPORTED) - - if(Xenomai_NATIVE_LIBRARY_RELEASE) - set_property(TARGET Xenomai::native APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(Xenomai::native PROPERTIES IMPORTED_LOCATION_RELEASE "${Xenomai_NATIVE_LIBRARY_RELEASE}") - endif() - - if(Xenomai_LIBRARY_DEBUG) - set_property(TARGET Xenomai::native APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(Xenomai::native PROPERTIES IMPORTED_LOCATION_RELEASE "${Xenomai_NATIVE_LIBRARY_DEBUG}") +foreach(component IN LISTS Xenomai_FIND_COMPONENTS) + string(TOUPPER ${component} COMPONENT) + if(Xenomai_${component}_FOUND AND NOT TARGET Xenomai::${component}) + add_library(Xenomai::${component} UNKNOWN IMPORTED) + if(XENOMAI_${COMPONENT}_LIBRARY_RELEASE) + set_property(TARGET Xenomai::${component} APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(Xenomai::${component} PROPERTIES IMPORTED_LOCATION_RELEASE "${XENOMAI_${COMPONENT}_LIBRARY_RELEASE}") + endif() + if(component STREQUAL "xenomai") + set_target_properties(Xenomai::${component} PROPERTIES INTERFACE_COMPILE_DEFINITIONS "__XENO__;_GNU_SOURCE;_REENTRANT") + endif() + set_target_properties(Xenomai::${component} PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${XENOMAI_INCLUDE_DIRS}") + if(component STREQUAL "xenomai") + set_target_properties(Xenomai::${component} PROPERTIES INTERFACE_LINK_LIBRARIES "pthread;rt") + endif() endif() - - set_target_properties( - Xenomai::native PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${Xenomai_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${Xenomai_INCLUDE_DIRS}" - ) -endif() +endforeach() -if(Xenomai_FOUND AND NOT TARGET Xenomai::xenomai) - add_library(Xenomai::xenomai UNKNOWN IMPORTED) - - if(Xenomai_LIBRARY_RELEASE) - set_property(TARGET Xenomai::xenomai APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(Xenomai::xenomai PROPERTIES IMPORTED_LOCATION_RELEASE "${Xenomai_XENOMAI_LIBRARY_RELEASE}") - set_target_properties(Xenomai::xenomai PROPERTIES IMPORTED_LINK_INTERFACE_LIBRARIES_RELEASE "Xenomai::native") - endif() - - if(Xenomai_LIBRARY_DEBUG) - set_property(TARGET Xenomai::xenomai APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) - set_target_properties(Xenomai::xenomai PROPERTIES IMPORTED_LOCATION_DEBUG "${Xenomai_XENOMAI_LIBRARY_DEBUG}") - set_target_properties(Xenomai::xenomai PROPERTIES IMPORTED_LINK_INTERFACE_LIBRARIES_DEBUG "Xenomai::native") - endif() - - set_target_properties( - Xenomai::xenomai PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${Xenomai_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${Xenomai_INCLUDE_DIRS}" - ) -endif() +mark_as_advanced(XENOMAI_DEFINITIONS) +mark_as_advanced(XENOMAI_INCLUDE_DIR) diff --git a/cmake/FindZLIB.cmake b/cmake/FindZLIB.cmake index ec1e0bb5..6779c8d6 100644 --- a/cmake/FindZLIB.cmake +++ b/cmake/FindZLIB.cmake @@ -2,55 +2,46 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - ZLIB_INCLUDE_DIRS - NAMES - zlib.h + ZLIB_INCLUDE_DIR + NAMES zlib.h ) - -mark_as_advanced(ZLIB_INCLUDE_DIRS) - find_library( ZLIB_LIBRARY_DEBUG - NAMES - zd zlibd zlib_ad zlibstaticd zlibwapid zdlld + NAMES zd zlibd zdlld zlib1d zlib_ad zlibstaticd zlibwapid ) - find_library( ZLIB_LIBRARY_RELEASE - NAMES - z zlib zlib_a zlibstatic zlibwapi zdll + NAMES z zlib zdll zlib1 zlib_a zlibstatic zlibwapi ) - select_library_configurations(ZLIB) -if(ZLIB_INCLUDE_DIRS AND EXISTS "${ZLIB_INCLUDE_DIRS}/zlib.h") - file(STRINGS "${ZLIB_INCLUDE_DIRS}/zlib.h" _ZLIB_VERSION_DEFINE REGEX "#define[\t ]+ZLIB_VERSION[\t ]+\"[^\"]*\".*") - string(REGEX REPLACE "#define[\t ]+ZLIB_VERSION[\t ]+\"([^\"]*)\".*" "\\1" ZLIB_VERSION "${_ZLIB_VERSION_DEFINE}") +if(ZLIB_INCLUDE_DIR AND EXISTS "${ZLIB_INCLUDE_DIR}/zlib.h") + file(STRINGS "${ZLIB_INCLUDE_DIR}/zlib.h" _ZLIB_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+ZLIB_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+ZLIB_VERSION[\t ]+\"([^\"]*)\".*" "\\1" ZLIB_VERSION "${_ZLIB_VERSION_DEFINE}") unset(_ZLIB_VERSION_DEFINE) endif() +set(ZLIB_INCLUDE_DIRS ${ZLIB_INCLUDE_DIR}) +set(ZLIB_LIBRARIES ${ZLIB_LIBRARY}) + find_package_handle_standard_args( ZLIB FOUND_VAR ZLIB_FOUND - REQUIRED_VARS ZLIB_INCLUDE_DIRS ZLIB_LIBRARIES + REQUIRED_VARS ZLIB_INCLUDE_DIR ZLIB_LIBRARY VERSION_VAR ZLIB_VERSION ) if(ZLIB_FOUND AND NOT TARGET ZLIB::ZLIB) add_library(ZLIB::ZLIB UNKNOWN IMPORTED) - if(ZLIB_LIBRARY_RELEASE) set_property(TARGET ZLIB::ZLIB APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(ZLIB::ZLIB PROPERTIES IMPORTED_LOCATION_RELEASE "${ZLIB_LIBRARY_RELEASE}") endif() - if(ZLIB_LIBRARY_DEBUG) set_property(TARGET ZLIB::ZLIB APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(ZLIB::ZLIB PROPERTIES IMPORTED_LOCATION_DEBUG "${ZLIB_LIBRARY_DEBUG}") endif() - - set_target_properties( - ZLIB::ZLIB PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${ZLIB_INCLUDE_DIRS}" - ) + set_target_properties(ZLIB::ZLIB PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${ZLIB_INCLUDE_DIRS}") endif() + +mark_as_advanced(ZLIB_INCLUDE_DIR) diff --git a/cmake/Findccd.cmake b/cmake/Findccd.cmake index 14d29f6c..b6ad5cb7 100644 --- a/cmake/Findccd.cmake +++ b/cmake/Findccd.cmake @@ -2,48 +2,39 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - CCD_INCLUDE_DIRS - NAMES - ccd/ccd.h + CCD_INCLUDE_DIR + NAMES ccd/ccd.h ) - -mark_as_advanced(CCD_INCLUDE_DIRS) - find_library( CCD_LIBRARY_DEBUG - NAMES - ccdd + NAMES ccdd ) - find_library( CCD_LIBRARY_RELEASE - NAMES - ccd + NAMES ccd ) - select_library_configurations(CCD) +set(CCD_INCLUDE_DIRS ${CCD_INCLUDE_DIR}) +set(CCD_LIBRARIES ${CCD_LIBRARY}) + find_package_handle_standard_args( ccd FOUND_VAR ccd_FOUND - REQUIRED_VARS CCD_INCLUDE_DIRS CCD_LIBRARIES + REQUIRED_VARS CCD_INCLUDE_DIR CCD_LIBRARY ) if(ccd_FOUND AND NOT TARGET ccd::ccd) add_library(ccd::ccd UNKNOWN IMPORTED) - if(CCD_LIBRARY_RELEASE) set_property(TARGET ccd::ccd APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(ccd::ccd PROPERTIES IMPORTED_LOCATION_RELEASE "${CCD_LIBRARY_RELEASE}") endif() - if(CCD_LIBRARY_DEBUG) set_property(TARGET ccd::ccd APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(ccd::ccd PROPERTIES IMPORTED_LOCATION_DEBUG "${CCD_LIBRARY_DEBUG}") endif() - - set_target_properties( - ccd::ccd PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${CCD_INCLUDE_DIRS}" - ) + set_target_properties(ccd::ccd PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${CCD_INCLUDE_DIRS}") endif() + +mark_as_advanced(CCD_INCLUDE_DIR) diff --git a/cmake/FindcifX.cmake b/cmake/FindcifX.cmake index f22b9e9b..876940d1 100644 --- a/cmake/FindcifX.cmake +++ b/cmake/FindcifX.cmake @@ -1,52 +1,45 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) -find_path( - cifX_INCLUDE_DIRS - NAMES - cifXUser.h - PATHS - "$ENV{ProgramW6432}/cifX Device Driver/SDK/includes" - "$ENV{ProgramFiles}/cifX Device Driver/SDK/includes" - PATH_SUFFIXES - cifx -) - -mark_as_advanced(cifX_INCLUDE_DIRS) - if(CMAKE_SIZEOF_VOID_P EQUAL 8) - set(cifX_ARCHITECTURE "x64") + set(CIFX_ARCHITECTURE "x64") else() - set(cifX_ARCHITECTURE "x86") + set(CIFX_ARCHITECTURE "x86") endif() +find_path( + CIFX_INCLUDE_DIR + NAMES cifXUser.h + PATHS + "$ENV{ProgramW6432}/cifX Device Driver/SDK/includes" + "$ENV{ProgramFiles}/cifX Device Driver/SDK/includes" + PATH_SUFFIXES cifx +) find_library( - cifX_LIBRARY_RELEASE - NAMES - cifx cifx32dll + CIFX_LIBRARY_RELEASE + NAMES cifx cifx32dll PATHS - "$ENV{ProgramW6432}/cifX Device Driver/SDK/libs/${cifX_ARCHITECTURE}" - "$ENV{ProgramFiles}/cifX Device Driver/SDK/libs/${cifX_ARCHITECTURE}" + "$ENV{ProgramW6432}/cifX Device Driver/SDK/libs/${CIFX_ARCHITECTURE}" + "$ENV{ProgramFiles}/cifX Device Driver/SDK/libs/${CIFX_ARCHITECTURE}" ) +select_library_configurations(CIFX) -select_library_configurations(cifX) +set(CIFX_INCLUDE_DIRS ${CIFX_INCLUDE_DIR}) +set(CIFX_LIBRARIES ${CIFX_LIBRARY}) find_package_handle_standard_args( cifX FOUND_VAR cifX_FOUND - REQUIRED_VARS cifX_INCLUDE_DIRS cifX_LIBRARIES + REQUIRED_VARS CIFX_INCLUDE_DIR CIFX_LIBRARY ) if(cifX_FOUND AND NOT TARGET cifX::cifX) add_library(cifX::cifX UNKNOWN IMPORTED) - - if(cifX_LIBRARY_RELEASE) + if(CIFX_LIBRARY_RELEASE) set_property(TARGET cifX::cifX APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(cifX::cifX PROPERTIES IMPORTED_LOCATION_RELEASE "${cifX_LIBRARY_RELEASE}") + set_target_properties(cifX::cifX PROPERTIES IMPORTED_LOCATION_RELEASE "${CIFX_LIBRARY_RELEASE}") endif() - - set_target_properties( - cifX::cifX PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${cifX_INCLUDE_DIRS}" - ) + set_target_properties(cifX::cifX PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${CIFX_INCLUDE_DIRS}") endif() + +mark_as_advanced(CIFX_INCLUDE_DIR) diff --git a/cmake/Findfcl.cmake b/cmake/Findfcl.cmake new file mode 100644 index 00000000..76db71c0 --- /dev/null +++ b/cmake/Findfcl.cmake @@ -0,0 +1,99 @@ +include(FindPackageHandleStandardArgs) +include(SelectLibraryConfigurations) + +find_path( + FCL_INCLUDE_DIR + NAMES fcl/config.h +) +find_library( + FCL_LIBRARY_DEBUG + NAMES fcld +) +find_library( + FCL_LIBRARY_RELEASE + NAMES fcl +) +select_library_configurations(FCL) + +if(FCL_INCLUDE_DIR AND EXISTS "${FCL_INCLUDE_DIR}/fcl/config.h") + file(STRINGS "${FCL_INCLUDE_DIR}/fcl/config.h" _FCL_VERSION_DEFINE REGEX "[\t ]*#define[\t ]+FCL_VERSION[\t ]+\"[^\"]*\".*") + string(REGEX REPLACE "[\t ]*#define[\t ]+FCL_VERSION[\t ]+\"([^\"]*)\".*" "\\1" FCL_VERSION "${_FCL_VERSION_DEFINE}") + unset(_FCL_VERSION_DEFINE) + file(STRINGS "${FCL_INCLUDE_DIR}/fcl/config.h" _FCL_OCTOMAP_DEFINE REGEX "[\t ]*#define[\t ]+FCL_HAVE_OCTOMAP[\t ]+[01]") + string(REGEX REPLACE "[\t ]*#define[\t ]+FCL_HAVE_OCTOMAP[\t ]+([01])" "\\1" FCL_HAVE_OCTOMAP "${_FCL_OCTOMAP_DEFINE}") + unset(_FCL_OCTOMAP_DEFINE) +endif() + +unset(FCL_DEFINITIONS) +unset(_FCL_FIND_PACKAGE_ARGS) +set(FCL_INCLUDE_DIRS ${FCL_INCLUDE_DIR}) +unset(_FCL_INTERFACE_COMPILE_DEFINITIONS) +unset(_FCL_INTERFACE_LINK_LIBRARIES) +set(FCL_LIBRARIES ${FCL_LIBRARY}) +unset(_FCL_REQUIRED_VARS) + +if(fcl_FIND_QUIETLY) + list(APPEND _FCL_FIND_PACKAGE_ARGS QUIET) +endif() +if(fcl_FIND_REQUIRED) + list(APPEND _FCL_FIND_PACKAGE_ARGS REQUIRED) +endif() + +if(FCL_VERSION AND FCL_VERSION VERSION_LESS 0.5) + find_package(Boost ${_FCL_FIND_PACKAGE_ARGS}) + list(APPEND FCL_DEFINITIONS -DBOOST_ALL_NO_LIB -DBOOST_SYSTEM_NO_DEPRECATED) + list(APPEND FCL_INCLUDE_DIRS ${Boost_INCLUDE_DIRS}) + list(APPEND _FCL_INTERFACE_COMPILE_DEFINITIONS BOOST_ALL_NO_LIB BOOST_SYSTEM_NO_DEPRECATED) + list(APPEND _FCL_INTERFACE_LINK_LIBRARIES Boost::headers) + list(APPEND _FCL_REQUIRED_VARS Boost_FOUND) +endif() + +find_package(ccd ${_FCL_FIND_PACKAGE_ARGS}) +list(APPEND FCL_INCLUDE_DIRS ${CCD_INCLUDE_DIRS}) +list(APPEND _FCL_INTERFACE_LINK_LIBRARIES ccd::ccd) +list(APPEND FCL_LIBRARIES ${CCD_LIBRARIES}) +list(APPEND _FCL_REQUIRED_VARS ccd_FOUND) + +if(FCL_VERSION AND NOT FCL_VERSION VERSION_LESS 0.6) + find_package(Eigen3 ${_FCL_FIND_PACKAGE_ARGS}) + list(APPEND FCL_INCLUDE_DIRS ${EIGEN3_INCLUDE_DIRS}) + list(APPEND _FCL_INTERFACE_LINK_LIBRARIES Eigen3::Eigen) + list(APPEND _FCL_REQUIRED_VARS Eigen3_FOUND) +endif() + +if(FCL_HAVE_OCTOMAP) + find_package(octomap ${_FCL_FIND_PACKAGE_ARGS}) + list(APPEND FCL_INCLUDE_DIRS ${OCTOMAP_INCLUDE_DIRS}) + list(APPEND _FCL_INTERFACE_LINK_LIBRARIES octomap::octomap) + list(APPEND FCL_LIBRARIES ${OCTOMAP_LIBRARIES}) + list(APPEND _FCL_REQUIRED_VARS octomap_FOUND) +endif() + +find_package_handle_standard_args( + fcl + FOUND_VAR fcl_FOUND + REQUIRED_VARS FCL_INCLUDE_DIR FCL_LIBRARY ${_FCL_REQUIRED_VARS} + VERSION_VAR FCL_VERSION +) + +if(fcl_FOUND AND NOT TARGET fcl::fcl) + add_library(fcl::fcl UNKNOWN IMPORTED) + if(FCL_LIBRARY_RELEASE) + set_property(TARGET fcl::fcl APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(fcl::fcl PROPERTIES IMPORTED_LOCATION_RELEASE "${FCL_LIBRARY_RELEASE}") + endif() + if(FCL_LIBRARY_DEBUG) + set_property(TARGET fcl::fcl APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(fcl::fcl PROPERTIES IMPORTED_LOCATION_DEBUG "${FCL_LIBRARY_DEBUG}") + endif() + set_target_properties(fcl::fcl PROPERTIES INTERFACE_COMPILE_DEFINITIONS "${_FCL_INTERFACE_COMPILE_DEFINITIONS}") + set_target_properties(fcl::fcl PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${FCL_INCLUDE_DIRS}") + set_target_properties(fcl::fcl PROPERTIES INTERFACE_LINK_LIBRARIES "${_FCL_INTERFACE_LINK_LIBRARIES}") +endif() + +mark_as_advanced(FCL_DEFINITIONS) +mark_as_advanced(FCL_INCLUDE_DIR) +unset(_FCL_FIND_PACKAGE_ARGS) +unset(_FCL_INTERFACE_COMPILE_DEFINITIONS) +unset(_FCL_INTERFACE_LINK_LIBRARIES) +unset(_FCL_REQUIRED_VARS) diff --git a/cmake/Findlibdc1394.cmake b/cmake/Findlibdc1394.cmake index 345f426c..99f0dbe2 100644 --- a/cmake/Findlibdc1394.cmake +++ b/cmake/Findlibdc1394.cmake @@ -2,40 +2,31 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - libdc1394_INCLUDE_DIRS - NAMES - dc1394/dc1394.h + LIBDC1394_INCLUDE_DIR + NAMES dc1394/dc1394.h ) - -mark_as_advanced(libdc1394_INCLUDE_DIRS) - find_library( - libdc1394_LIBRARY_RELEASE - NAMES - dc1394 + LIBDC1394_LIBRARY_RELEASE + NAMES dc1394 ) +select_library_configurations(LIBDC1394) -mark_as_advanced(libdc1394_LIBRARY_RELEASE) - -select_library_configurations(libdc1394) +set(LIBDC1394_INCLUDE_DIRS ${LIBDC1394_INCLUDE_DIR}) +set(LIBDC1394_LIBRARIES ${LIBDC1394_LIBRARY}) find_package_handle_standard_args( libdc1394 FOUND_VAR libdc1394_FOUND - REQUIRED_VARS libdc1394_INCLUDE_DIRS libdc1394_LIBRARIES + REQUIRED_VARS LIBDC1394_INCLUDE_DIR LIBDC1394_LIBRARY ) if(libdc1394_FOUND AND NOT TARGET libdc1394::libdc1394) add_library(libdc1394::libdc1394 UNKNOWN IMPORTED) - - if(libdc1394_LIBRARY_RELEASE) + if(LIBDC1394_LIBRARY_RELEASE) set_property(TARGET libdc1394::libdc1394 APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) - set_target_properties(libdc1394::libdc1394 PROPERTIES IMPORTED_LOCATION_RELEASE "${libdc1394_LIBRARY_RELEASE}") + set_target_properties(libdc1394::libdc1394 PROPERTIES IMPORTED_LOCATION_RELEASE "${LIBDC1394_LIBRARY_RELEASE}") endif() - - set_target_properties( - libdc1394::libdc1394 PROPERTIES - INTERFACE_COMPILE_DEFINITIONS "${libdc1394_DEFINITIONS}" - INTERFACE_INCLUDE_DIRECTORIES "${libdc1394_INCLUDE_DIRS}" - ) + set_target_properties(libdc1394::libdc1394 PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${LIBDC1394_INCLUDE_DIRS}") endif() + +mark_as_advanced(LIBDC1394_INCLUDE_DIR) diff --git a/cmake/Findoctomap.cmake b/cmake/Findoctomap.cmake new file mode 100644 index 00000000..4d1eb754 --- /dev/null +++ b/cmake/Findoctomap.cmake @@ -0,0 +1,58 @@ +include(FindPackageHandleStandardArgs) +include(SelectLibraryConfigurations) + +find_path( + OCTOMAP_INCLUDE_DIR + NAMES octomap/octomap.h +) + +foreach(component IN ITEMS octomath octomap) + string(TOUPPER ${component} COMPONENT) + find_library( + OCTOMAP_${COMPONENT}_LIBRARY_DEBUG + NAMES ${component}d + ) + find_library( + OCTOMAP_${COMPONENT}_LIBRARY_RELEASE + NAMES ${component} + ) + select_library_configurations(OCTOMAP_${COMPONENT}) +endforeach() + +set(OCTOMAP_INCLUDE_DIRS ${OCTOMAP_INCLUDE_DIR}) +set(OCTOMAP_LIBRARIES ${OCTOMAP_OCTOMATH_LIBRARY} ${OCTOMAP_OCTOMAP_LIBRARY}) + +foreach(component IN ITEMS octomath octomap) + string(TOUPPER ${component} COMPONENT) + if(OCTOMAP_${COMPONENT}_LIBRARY) + set(octomap_${component}_FOUND ON) + endif() +endforeach() + +find_package_handle_standard_args( + octomap + FOUND_VAR octomap_FOUND + REQUIRED_VARS OCTOMAP_INCLUDE_DIR OCTOMAP_OCTOMATH_LIBRARY OCTOMAP_OCTOMAP_LIBRARY + VERSION_VAR OCTOMAP_VERSION +) + +foreach(component IN ITEMS octomath octomap) + string(TOUPPER ${component} COMPONENT) + if(octomap_${component}_FOUND AND NOT TARGET octomap::${component}) + add_library(octomap::${component} UNKNOWN IMPORTED) + if(OCTOMAP_${COMPONENT}_LIBRARY_RELEASE) + set_property(TARGET octomap::${component} APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) + set_target_properties(octomap::${component} PROPERTIES IMPORTED_LOCATION_RELEASE "${OCTOMAP_${COMPONENT}_LIBRARY_RELEASE}") + endif() + if(OCTOMAP_${COMPONENT}_LIBRARY_DEBUG) + set_property(TARGET octomap::${component} APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) + set_target_properties(octomap::${component} PROPERTIES IMPORTED_LOCATION_DEBUG "${OCTOMAP_${COMPONENT}_LIBRARY_DEBUG}") + endif() + set_target_properties(octomap::${component} PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${OCTOMAP_INCLUDE_DIRS}") + if(component STREQUAL "octomap" AND TARGET octomap::octomath) + set_target_properties(octomap::${component} PROPERTIES INTERFACE_LINK_LIBRARIES "octomap::octomath") + endif() + endif() +endforeach() + +mark_as_advanced(OCTOMAP_INCLUDE_DIR) diff --git a/cmake/FindSOLID3.cmake b/cmake/Findsolid3.cmake similarity index 61% rename from cmake/FindSOLID3.cmake rename to cmake/Findsolid3.cmake index 3f608418..fb56031e 100644 --- a/cmake/FindSOLID3.cmake +++ b/cmake/Findsolid3.cmake @@ -2,48 +2,39 @@ include(FindPackageHandleStandardArgs) include(SelectLibraryConfigurations) find_path( - SOLID3_INCLUDE_DIRS - NAMES - SOLID/SOLID.h + SOLID3_INCLUDE_DIR + NAMES SOLID/SOLID.h ) - -mark_as_advanced(SOLID3_INCLUDE_DIRS) - find_library( SOLID3_LIBRARY_DEBUG - NAMES - solid3d_d solid3_d solidd solidsd + NAMES solid3d_d solid3_d solidd solidsd ) - find_library( SOLID3_LIBRARY_RELEASE - NAMES - solid3d solid3 solid solids + NAMES solid3d solid3 solid solids ) - select_library_configurations(SOLID3) +set(SOLID3_INCLUDE_DIRS ${SOLID3_INCLUDE_DIR}) +set(SOLID3_LIBRARIES ${SOLID3_LIBRARY}) + find_package_handle_standard_args( - SOLID3 - FOUND_VAR SOLID3_FOUND - REQUIRED_VARS SOLID3_INCLUDE_DIRS SOLID3_LIBRARIES + solid3 + FOUND_VAR solid3_FOUND + REQUIRED_VARS SOLID3_INCLUDE_DIR SOLID3_LIBRARY ) -if(SOLID3_FOUND AND NOT TARGET solid3::solid3) +if(solid3_FOUND AND NOT TARGET solid3::solid3) add_library(solid3::solid3 UNKNOWN IMPORTED) - if(SOLID3_LIBRARY_RELEASE) set_property(TARGET solid3::solid3 APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(solid3::solid3 PROPERTIES IMPORTED_LOCATION_RELEASE "${SOLID3_LIBRARY_RELEASE}") endif() - if(SOLID3_LIBRARY_DEBUG) set_property(TARGET solid3::solid3 APPEND PROPERTY IMPORTED_CONFIGURATIONS DEBUG) set_target_properties(solid3::solid3 PROPERTIES IMPORTED_LOCATION_DEBUG "${SOLID3_LIBRARY_DEBUG}") endif() - - set_target_properties( - solid3::solid3 PROPERTIES - INTERFACE_INCLUDE_DIRECTORIES "${SOLID3_INCLUDE_DIRS}" - ) + set_target_properties(solid3::solid3 PROPERTIES INTERFACE_INCLUDE_DIRECTORIES "${SOLID3_INCLUDE_DIRS}") endif() + +mark_as_advanced(SOLID3_INCLUDE_DIR) diff --git a/demos/rlCoachKin/CMakeLists.txt b/demos/rlCoachKin/CMakeLists.txt index 10cc2b42..7211c1c8 100644 --- a/demos/rlCoachKin/CMakeLists.txt +++ b/demos/rlCoachKin/CMakeLists.txt @@ -1,7 +1,7 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) endif() diff --git a/demos/rlCoachMdl/CMakeLists.txt b/demos/rlCoachMdl/CMakeLists.txt index 08d3e9d0..299cff0d 100644 --- a/demos/rlCoachMdl/CMakeLists.txt +++ b/demos/rlCoachMdl/CMakeLists.txt @@ -1,7 +1,7 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) endif() diff --git a/demos/rlCollisionDemo/CMakeLists.txt b/demos/rlCollisionDemo/CMakeLists.txt index 0a10b1ab..c3ad2433 100644 --- a/demos/rlCollisionDemo/CMakeLists.txt +++ b/demos/rlCollisionDemo/CMakeLists.txt @@ -1,7 +1,7 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui OpenGL Widgets QUIET) endif() @@ -19,14 +19,13 @@ set(CMAKE_AUTOMOC ON) set(CMAKE_INCLUDE_CURRENT_DIR ON) find_package(Bullet) -find_package(ccd) -find_package(FCL) +find_package(fcl) find_package(ODE) find_package(PQP) -find_package(SOLID3) +find_package(solid3) if(QT_FOUND AND SoQt_FOUND) - if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3_FOUND) + if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) set( HDRS BodyDelegate.h diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index fc079c18..c6598d6d 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -2,7 +2,7 @@ find_package(Boost REQUIRED) find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui OpenGL PrintSupport Widgets QUIET) endif() @@ -20,13 +20,12 @@ set(CMAKE_AUTOMOC ON) set(CMAKE_INCLUDE_CURRENT_DIR ON) find_package(Bullet) -find_package(ccd) -find_package(FCL) +find_package(fcl) find_package(ODE) find_package(PQP) -find_package(SOLID3) +find_package(solid3) -if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3_FOUND)) +if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND)) set( HDRS ConfigurationDelegate.h diff --git a/demos/rlPrmDemo/CMakeLists.txt b/demos/rlPrmDemo/CMakeLists.txt index 8e94e089..d32afd76 100644 --- a/demos/rlPrmDemo/CMakeLists.txt +++ b/demos/rlPrmDemo/CMakeLists.txt @@ -2,9 +2,9 @@ find_package(Boost REQUIRED) find_package(Bullet) find_package(ODE) -find_package(SOLID3) +find_package(solid3) -if(Bullet_FOUND OR ODE_FOUND OR SOLID3_FOUND) +if(Bullet_FOUND OR ODE_FOUND OR solid3_FOUND) add_executable( rlPrmDemo rlPrmDemo.cpp diff --git a/demos/rlRrtDemo/CMakeLists.txt b/demos/rlRrtDemo/CMakeLists.txt index f061682a..f40e9219 100644 --- a/demos/rlRrtDemo/CMakeLists.txt +++ b/demos/rlRrtDemo/CMakeLists.txt @@ -2,9 +2,9 @@ find_package(Boost REQUIRED) find_package(Bullet) find_package(ODE) -find_package(SOLID3) +find_package(solid3) -if(Bullet_FOUND OR ODE_FOUND OR SOLID3_FOUND) +if(Bullet_FOUND OR ODE_FOUND OR solid3_FOUND) add_executable( rlRrtDemo rlRrtDemo.cpp diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index 45189c06..97c3203e 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -1,7 +1,7 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) endif() diff --git a/demos/rlViewDemo/CMakeLists.txt b/demos/rlViewDemo/CMakeLists.txt index f9823bf3..c551b4c1 100644 --- a/demos/rlViewDemo/CMakeLists.txt +++ b/demos/rlViewDemo/CMakeLists.txt @@ -1,6 +1,6 @@ find_package(SoQt) -if(RL_USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui OpenGL Widgets QUIET) endif() diff --git a/extras/csv2wrl/CMakeLists.txt b/extras/csv2wrl/CMakeLists.txt index 7fb2503b..03f5de74 100644 --- a/extras/csv2wrl/CMakeLists.txt +++ b/extras/csv2wrl/CMakeLists.txt @@ -3,7 +3,7 @@ project(csv2wrl) find_package(Coin) find_package(Eigen3) -if(Coin_FOUND AND EIGEN3_FOUND) +if(Coin_FOUND AND Eigen3_FOUND) add_executable( csv2wrl csv2wrl.cpp diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 50c52f68..77f3669c 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -8,7 +8,7 @@ include(CMakePushCheckState) find_package(SoQt) -if(RL_USE_QT5 AND SoQt5_FOUND) +if(RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) endif() diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 85e7b783..7998007c 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -206,18 +206,18 @@ if(RL_BUILD_HAL_ATIDAQ) endif() if(RL_BUILD_HAL_CIFX) - target_include_directories(hal PUBLIC ${cifX_INCLUDE_DIRS}) - target_link_libraries(hal ${cifX_LIBRARIES}) + target_include_directories(hal PUBLIC ${CIFX_INCLUDE_DIRS}) + target_link_libraries(hal ${CIFX_LIBRARIES}) endif() if(RL_BUILD_HAL_COMEDI) - target_include_directories(hal PUBLIC ${Comedi_INCLUDE_DIRS}) - target_link_libraries(hal ${Comedi_LIBRARIES}) + target_include_directories(hal PUBLIC ${COMEDI_INCLUDE_DIRS}) + target_link_libraries(hal ${COMEDI_LIBRARIES}) endif() if(RL_BUILD_HAL_LIBDC1394) - target_include_directories(hal PUBLIC ${libdc1394_INCLUDE_DIRS}) - target_link_libraries(hal ${libdc1394_LIBRARIES}) + target_include_directories(hal PUBLIC ${LIBDC1394_INCLUDE_DIRS}) + target_link_libraries(hal ${LIBDC1394_LIBRARIES}) endif() if(QNXNTO) diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 8e2a425e..cbb9f17b 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -1,7 +1,7 @@ find_package(Boost REQUIRED) find_package(NLopt) -cmake_dependent_option(RL_BUILD_MDL_NLOPT "Build NLopt support" ON "RL_BUILD_MDL;NLOPT_FOUND" OFF) +cmake_dependent_option(RL_BUILD_MDL_NLOPT "Build NLopt support" ON "RL_BUILD_MDL;NLopt_FOUND" OFF) set( HDRS diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index e093f279..56e27981 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -3,19 +3,17 @@ include(CheckIncludeFileCXX) include(CMakePushCheckState) find_package(Bullet) -find_package(ccd) find_package(Coin REQUIRED) -find_package(FCL) -find_package(OctoMap) +find_package(fcl) find_package(ODE) find_package(PQP) -find_package(SOLID3) +find_package(solid3) -cmake_dependent_option(RL_BUILD_SG_BULLET "Build Bullet support" ON "RL_BUILD_SG;BULLET_FOUND" OFF) -cmake_dependent_option(RL_BUILD_SG_FCL "Build FCL support" ON "RL_BUILD_SG;CCD_FOUND;FCL_FOUND" OFF) +cmake_dependent_option(RL_BUILD_SG_BULLET "Build Bullet support" ON "RL_BUILD_SG;Bullet_FOUND" OFF) +cmake_dependent_option(RL_BUILD_SG_FCL "Build FCL support" ON "RL_BUILD_SG;fcl_FOUND" OFF) cmake_dependent_option(RL_BUILD_SG_ODE "Build ODE support" ON "RL_BUILD_SG;ODE_FOUND" OFF) cmake_dependent_option(RL_BUILD_SG_PQP "Build PQP support" ON "RL_BUILD_SG;PQP_FOUND" OFF) -cmake_dependent_option(RL_BUILD_SG_SOLID "Build SOLID support" ON "RL_BUILD_SG;SOLID3_FOUND" OFF) +cmake_dependent_option(RL_BUILD_SG_SOLID "Build SOLID support" ON "RL_BUILD_SG;solid3_FOUND" OFF) set( BASE_HDRS @@ -204,11 +202,6 @@ if(RL_BUILD_SG_BULLET) install(FILES ${BULLET_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/bullet COMPONENT development) endif() -if(CCD_FOUND AND (RL_BUILD_SG_FCL OR RL_BUILD_SG_ODE)) - target_include_directories(sg PUBLIC ${CCD_INCLUDE_DIRS}) - target_link_libraries(sg ${CCD_LIBRARIES}) -endif() - if(Coin_FOUND) cmake_push_check_state(RESET) set(CMAKE_REQUIRED_DEFINITIONS ${Coin_DEFINITIONS}) @@ -248,11 +241,6 @@ if(RL_BUILD_SG_ODE) install(FILES ${ODE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/ode COMPONENT development) endif() -if(OCTOMAP_FOUND AND RL_BUILD_SG_FCL) - target_include_directories(sg PUBLIC ${OCTOMAP_INCLUDE_DIRS}) - target_link_libraries(sg ${OCTOMAP_LIBRARIES}) -endif() - if(RL_BUILD_SG_PQP) target_compile_definitions(sg INTERFACE RL_SG_PQP) target_include_directories(sg PUBLIC ${PQP_INCLUDE_DIRS}) diff --git a/src/rl/xml/CMakeLists.txt b/src/rl/xml/CMakeLists.txt index 52cb7f55..32095951 100644 --- a/src/rl/xml/CMakeLists.txt +++ b/src/rl/xml/CMakeLists.txt @@ -1,10 +1,6 @@ find_package(Boost REQUIRED) - -find_package(Iconv) -find_package(LibLZMA) find_package(LibXml2 REQUIRED) find_package(LibXslt REQUIRED) -find_package(ZLIB) set( HDRS @@ -45,21 +41,6 @@ target_include_directories( target_link_libraries(xml INTERFACE ${LIBXML2_LIBRARIES} ${LIBXSLT_LIBRARIES}) -if(Iconv_FOUND) - target_include_directories(xml INTERFACE ${Iconv_INCLUDE_DIRS}) - target_link_libraries(xml INTERFACE ${Iconv_LIBRARIES}) -endif() - -if(LIBLZMA_FOUND) - target_include_directories(xml INTERFACE ${LIBLZMA_INCLUDE_DIRS}) - target_link_libraries(xml INTERFACE ${LIBLZMA_LIBRARIES}) -endif() - -if(ZLIB_FOUND) - target_include_directories(xml INTERFACE ${ZLIB_INCLUDE_DIRS}) - target_link_libraries(xml INTERFACE ${ZLIB_LIBRARIES}) -endif() - if(NOT CMAKE_VERSION VERSION_LESS 3.19) set_target_properties( xml diff --git a/tests/rlCollisionTest/CMakeLists.txt b/tests/rlCollisionTest/CMakeLists.txt index cf8a530e..e8f0183e 100644 --- a/tests/rlCollisionTest/CMakeLists.txt +++ b/tests/rlCollisionTest/CMakeLists.txt @@ -1,13 +1,12 @@ find_package(Boost REQUIRED) find_package(Bullet) -find_package(ccd) -find_package(FCL) +find_package(fcl) find_package(ODE) find_package(PQP) -find_package(SOLID3) +find_package(solid3) -if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3_FOUND) +if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) add_executable( rlCollisionTest rlCollisionTest.cpp diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index a80fc2ef..86269e99 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -1,12 +1,11 @@ find_package(Boost REQUIRED) find_package(Bullet) -find_package(ccd) -find_package(FCL) +find_package(fcl) find_package(PQP) -find_package(SOLID3) +find_package(solid3) -if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) +if(Bullet_FOUND OR fcl_FOUND OR PQP_FOUND OR solid3_FOUND) add_executable( rlEetTest rlEetTest.cpp @@ -26,7 +25,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) sg ) - if(BULLET_FOUND) + if(Bullet_FOUND) add_test( NAME rlEetTestBulletBox6d300505Maze COMMAND rlEetTest @@ -39,7 +38,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) ) endif() - if(CCD_FOUND AND FCL_FOUND) + if(fcl_FOUND) add_test( NAME rlEetTestFclBox6d300505Maze COMMAND rlEetTest @@ -65,7 +64,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR PQP_FOUND OR SOLID3_FOUND) ) endif() - if(SOLID3_FOUND) + if(solid3_FOUND) add_test( NAME rlEetTestSolidBox6d300505Maze COMMAND rlEetTest diff --git a/tests/rlPrmTest/CMakeLists.txt b/tests/rlPrmTest/CMakeLists.txt index e3577f0c..89b27bb4 100644 --- a/tests/rlPrmTest/CMakeLists.txt +++ b/tests/rlPrmTest/CMakeLists.txt @@ -1,13 +1,12 @@ find_package(Boost REQUIRED) find_package(Bullet) -find_package(ccd) -find_package(FCL) +find_package(fcl) find_package(ODE) find_package(PQP) -find_package(SOLID3) +find_package(solid3) -if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3_FOUND) +if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) add_executable( rlPrmTest rlPrmTest.cpp @@ -27,7 +26,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 sg ) - if(BULLET_FOUND) + if(Bullet_FOUND) add_test( NAME rlPrmTestBulletUnimationPuma560Boxes1 COMMAND rlPrmTest @@ -53,7 +52,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 ) endif() - if(CCD_FOUND AND FCL_FOUND) + if(fcl_FOUND) add_test( NAME rlPrmTestFclUnimationPuma560Boxes1 COMMAND rlPrmTest @@ -131,7 +130,7 @@ if(BULLET_FOUND OR (CCD_FOUND AND FCL_FOUND) OR ODE_FOUND OR PQP_FOUND OR SOLID3 ) endif() - if(SOLID3_FOUND) + if(solid3_FOUND) add_test( NAME rlPrmTestSolidUnimationPuma560Boxes1 COMMAND rlPrmTest From 30c9918880b5a84923f0666c4dfe5d3b90e90b5d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 10 Jan 2021 18:57:01 +0100 Subject: [PATCH 437/546] Update CMake files --- CMakeLists.txt | 26 ++-- cmake/CPackConfig.cmake | 39 +++-- demos/rlCollisionDemo/CMakeLists.txt | 210 +++++++++++++-------------- demos/rlPlanDemo/CMakeLists.txt | 8 +- demos/rlPrmDemo/CMakeLists.txt | 6 +- demos/rlRrtDemo/CMakeLists.txt | 6 +- demos/rlSimulator/CMakeLists.txt | 3 - demos/rlThreadsDemo/CMakeLists.txt | 4 +- demos/rlTimerDemo/CMakeLists.txt | 2 - rl-config.cmake.in | 2 + src/CMakeLists.txt | 10 ++ src/rl/hal/CMakeLists.txt | 32 ++-- src/rl/kin/CMakeLists.txt | 9 +- src/rl/mdl/CMakeLists.txt | 9 +- src/rl/plan/CMakeLists.txt | 9 +- src/rl/sg/CMakeLists.txt | 62 +++++--- src/rl/util/CMakeLists.txt | 48 +----- src/rl/util/rtai/CMakeLists.txt | 47 ++++++ src/rl/util/xenomai/CMakeLists.txt | 51 +++++++ tests/rlCollisionTest/CMakeLists.txt | 8 +- tests/rlEetTest/CMakeLists.txt | 15 +- tests/rlPrmTest/CMakeLists.txt | 18 +-- tests/rlSpatialTest/CMakeLists.txt | 10 +- tests/rlSplineTest/CMakeLists.txt | 10 +- 24 files changed, 330 insertions(+), 314 deletions(-) create mode 100644 src/rl/util/rtai/CMakeLists.txt create mode 100644 src/rl/util/xenomai/CMakeLists.txt diff --git a/CMakeLists.txt b/CMakeLists.txt index 913422ed..576406e4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -14,22 +14,23 @@ if(NOT PROJECT_VERSION_TWEAK) set(PROJECT_VERSION_TWEAK 0) endif() +set(Boost_ADDITIONAL_VERSIONS "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") +set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/lib) +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_STANDARD_REQUIRED ON) +set(CMAKE_INSTALL_SYSTEM_RUNTIME_COMPONENT system) +set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/lib) list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/cmake) +set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/bin) include(CheckCXXCompilerFlag) include(CMakeDependentOption) include(CMakePackageConfigHelpers) include(GenerateExportHeader) include(GNUInstallDirs) +include(InstallRequiredSystemLibraries) include(Qt4AutomocMocOptionsBoost) -set(Boost_ADDITIONAL_VERSIONS "1.73.0" "1.73" "1.72.0" "1.72" "1.71.0" "1.71" "1.70.0" "1.70" "1.69.0" "1.69" "1.68.0" "1.68" "1.67.0" "1.67" "1.66.0" "1.66" "1.65.1" "1.65.0" "1.65" "1.64.0" "1.64" "1.63.0" "1.63" "1.62.0" "1.62" "1.61.0" "1.61" "1.60.0" "1.60" "1.59.0" "1.59" "1.58.0" "1.58" "1.57.0" "1.57") -set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) -set(CMAKE_CXX_STANDARD 11) -set(CMAKE_CXX_STANDARD_REQUIRED ON) -set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib) -set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin) - if(MSVC) add_definitions( -D_ENABLE_EXTENDED_ALIGNED_STORAGE @@ -62,6 +63,8 @@ cmake_dependent_option(RL_BUILD_HAL "Build hardware abstraction layer component" cmake_dependent_option(RL_BUILD_KIN "Build Denavit-Hartenberg kinematics component" ON "RL_BUILD_MATH;RL_BUILD_XML" OFF) cmake_dependent_option(RL_BUILD_MDL "Build rigid body kinematics and dynamics component" ON "RL_BUILD_MATH;RL_BUILD_XML" OFF) cmake_dependent_option(RL_BUILD_SG "Build scene graph abstraction component" ON "RL_BUILD_MATH;RL_BUILD_UTIL;RL_BUILD_XML" OFF) +cmake_dependent_option(RL_BUILD_UTIL_RTAI "Build RTAI support" OFF "RL_BUILD_UTIL" OFF) +cmake_dependent_option(RL_BUILD_UTIL_XENOMAI "Build Xenomai support" OFF "RL_BUILD_UTIL" OFF) cmake_dependent_option(RL_BUILD_PLAN "Build path planning component" ON "RL_BUILD_KIN;RL_BUILD_MATH;RL_BUILD_MDL;RL_BUILD_SG;RL_BUILD_UTIL;RL_BUILD_XML" OFF) @@ -81,8 +84,10 @@ endif() add_subdirectory(doc) -foreach(TARGET IN LISTS TARGETS) - list(APPEND RL_LIBRARIES "rl::${TARGET}") +foreach(target IN LISTS TARGETS) + if(NOT target STREQUAL "util_rtai" AND NOT target STREQUAL "util_xenomai") + list(APPEND RL_LIBRARIES "rl::${target}") + endif() endforeach() export( @@ -128,8 +133,5 @@ if(RL_BUILD_EXTRAS) add_subdirectory(extras) endif() -set(CMAKE_INSTALL_SYSTEM_RUNTIME_COMPONENT system) -include(InstallRequiredSystemLibraries) - include(CPackConfig) include(CPack) diff --git a/cmake/CPackConfig.cmake b/cmake/CPackConfig.cmake index b62c5bbf..708e108a 100644 --- a/cmake/CPackConfig.cmake +++ b/cmake/CPackConfig.cmake @@ -11,15 +11,14 @@ if(MSVC) set(PLATFORM_TOOLSET_MINOR ${CMAKE_MATCH_2}) set(LINKER_VERSION "${LINKER_VERSION_MAJOR}.${CMAKE_MATCH_2}${CMAKE_MATCH_3}.${CMAKE_MATCH_4}") endif() - if(CMAKE_CL_64) - set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-x64") - set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${PROJECT_VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\x64") - set(CPACK_PACKAGE_NAME "Robotics Library ${PROJECT_VERSION} - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (x64)") + if(CMAKE_SIZEOF_VOID_P EQUAL 4) + set(ARCHITECTURE "x86") else() - set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-x86") - set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${PROJECT_VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\x86") - set(CPACK_PACKAGE_NAME "Robotics Library ${PROJECT_VERSION} - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (x86)") + set(ARCHITECTURE "x64") endif() + set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-${ARCHITECTURE}") + set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${PROJECT_VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\${ARCHITECTURE}") + set(CPACK_PACKAGE_NAME "Robotics Library ${PROJECT_VERSION} - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (${ARCHITECTURE})") else() set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-${CMAKE_SYSTEM_NAME}") set(CPACK_PACKAGE_INSTALL_DIRECTORY "rl-${PROJECT_VERSION}") @@ -210,25 +209,25 @@ if(ODE_INCLUDE_DIR AND ODE_LIBRARY_RELEASE) list(APPEND CPACK_RPM_development_PACKAGE_REQUIRES "ode-devel") endif() -foreach(COMPONENT IN LISTS COMPONENTS) - string(TOUPPER ${COMPONENT} COMPONENT_UPPER) - if(DEFINED CPACK_DEBIAN_${COMPONENT_UPPER}_PACKAGE_DEPENDS) - string(REPLACE ";" ", " CPACK_DEBIAN_${COMPONENT_UPPER}_PACKAGE_DEPENDS "${CPACK_DEBIAN_${COMPONENT_UPPER}_PACKAGE_DEPENDS}") +foreach(component IN LISTS COMPONENTS) + string(TOUPPER ${component} COMPONENT) + if(DEFINED CPACK_DEBIAN_${COMPONENT}_PACKAGE_DEPENDS) + string(REPLACE ";" ", " CPACK_DEBIAN_${COMPONENT}_PACKAGE_DEPENDS "${CPACK_DEBIAN_${COMPONENT}_PACKAGE_DEPENDS}") endif() - if(DEFINED CPACK_DEBIAN_${COMPONENT_UPPER}_PACKAGE_RECOMMENDS) - string(REPLACE ";" ", " CPACK_DEBIAN_${COMPONENT_UPPER}_PACKAGE_RECOMMENDS "${CPACK_DEBIAN_${COMPONENT_UPPER}_PACKAGE_RECOMMENDS}") + if(DEFINED CPACK_DEBIAN_${COMPONENT}_PACKAGE_RECOMMENDS) + string(REPLACE ";" ", " CPACK_DEBIAN_${COMPONENT}_PACKAGE_RECOMMENDS "${CPACK_DEBIAN_${COMPONENT}_PACKAGE_RECOMMENDS}") endif() - if(DEFINED CPACK_RPM_${COMPONENT}_PACKAGE_REQUIRES) - string(REPLACE ";" ", " CPACK_RPM_${COMPONENT}_PACKAGE_REQUIRES "${CPACK_RPM_${COMPONENT}_PACKAGE_REQUIRES}") + if(DEFINED CPACK_RPM_${component}_PACKAGE_REQUIRES) + string(REPLACE ";" ", " CPACK_RPM_${component}_PACKAGE_REQUIRES "${CPACK_RPM_${component}_PACKAGE_REQUIRES}") endif() - if(DEFINED CPACK_RPM_${COMPONENT}_PACKAGE_SUGGESTS) - string(REPLACE ";" ", " CPACK_RPM_${COMPONENT}_PACKAGE_SUGGESTS "${CPACK_RPM_${COMPONENT}_PACKAGE_SUGGESTS}") + if(DEFINED CPACK_RPM_${component}_PACKAGE_SUGGESTS) + string(REPLACE ";" ", " CPACK_RPM_${component}_PACKAGE_SUGGESTS "${CPACK_RPM_${component}_PACKAGE_SUGGESTS}") endif() endforeach() -string(REPLACE ";" "\r\n" CPACK_NSIS_CREATE_ICONS_EXTRA "${CPACK_NSIS_CREATE_ICONS_EXTRA}") -string(REPLACE ";" "\r\n" CPACK_NSIS_DELETE_ICONS_EXTRA "${CPACK_NSIS_DELETE_ICONS_EXTRA}") -string(REPLACE "/>;\r\n;\n DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) - endif() - - if(UNIX) - configure_file(rlCollisionDemo.desktop.in rlCollisionDemo.desktop @ONLY) - install(FILES ${CMAKE_CURRENT_BINARY_DIR}/rlCollisionDemo.desktop DESTINATION ${CMAKE_INSTALL_DATADIR}/applications COMPONENT demos) - endif() - - set( - CPACK_NSIS_CREATE_ICONS_EXTRA - ${CPACK_NSIS_CREATE_ICONS_EXTRA} - "CreateShortCut \\\\ - \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlCollisionDemo.lnk\\\" \\\\ - \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlCollisionDemo.exe\\\" \\\\ - \\\"\\\\ - \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlsg\\\\scene.xml\\\$\\\\\\\"\\\\ - \\\" \\\\ - \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ - \\\"Collision detection and distance computation demo with basic scene\\\"" - PARENT_SCOPE - ) - set(CPACK_NSIS_DELETE_ICONS_EXTRA ${CPACK_NSIS_DELETE_ICONS_EXTRA} "Delete \\\"$SMPROGRAMS\\\\$START_MENU\\\\rlCollisionDemo.lnk\\\"" PARENT_SCOPE) - - set( - WIX_SHORTCUTS - ${WIX_SHORTCUTS} - "" - PARENT_SCOPE + DEBUG_POSTFIX d ) endif() + + install( + TARGETS rlCollisionDemo + COMPONENT demos + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} + ) + + if(MSVC AND BUILD_SHARED_LIBS) + install(FILES $ DESTINATION ${CMAKE_INSTALL_BINDIR} CONFIGURATIONS Debug RelWithDebInfo COMPONENT demos) + endif() + + if(UNIX) + configure_file(rlCollisionDemo.desktop.in rlCollisionDemo.desktop @ONLY) + install(FILES ${CMAKE_CURRENT_BINARY_DIR}/rlCollisionDemo.desktop DESTINATION ${CMAKE_INSTALL_DATADIR}/applications COMPONENT demos) + endif() + + set( + CPACK_NSIS_CREATE_ICONS_EXTRA + ${CPACK_NSIS_CREATE_ICONS_EXTRA} + "CreateShortCut \\\\ + \\\"$SMPROGRAMS\\\\$STARTMENU_FOLDER\\\\rlCollisionDemo.lnk\\\" \\\\ + \\\"$INSTDIR\\\\${CMAKE_INSTALL_BINDIR}\\\\rlCollisionDemo.exe\\\" \\\\ + \\\"\\\\ + \\\$\\\\\\\"$INSTDIR\\\\${CMAKE_INSTALL_DATADIR}\\\\rl-${PROJECT_VERSION}\\\\examples\\\\rlsg\\\\scene.xml\\\$\\\\\\\"\\\\ + \\\" \\\\ + \\\"\\\" \\\"\\\" \\\"\\\" \\\"\\\" \\\\ + \\\"Collision detection and distance computation demo with basic scene\\\"" + PARENT_SCOPE + ) + set(CPACK_NSIS_DELETE_ICONS_EXTRA ${CPACK_NSIS_DELETE_ICONS_EXTRA} "Delete \\\"$SMPROGRAMS\\\\$START_MENU\\\\rlCollisionDemo.lnk\\\"" PARENT_SCOPE) + + set( + WIX_SHORTCUTS + ${WIX_SHORTCUTS} + "" + PARENT_SCOPE + ) endif() diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index c6598d6d..424cc249 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -19,13 +19,7 @@ endif() set(CMAKE_AUTOMOC ON) set(CMAKE_INCLUDE_CURRENT_DIR ON) -find_package(Bullet) -find_package(fcl) -find_package(ODE) -find_package(PQP) -find_package(solid3) - -if(QT_FOUND AND SoQt_FOUND AND (Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND)) +if(QT_FOUND AND SoQt_FOUND AND (RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUILD_SG_ODE OR RL_BUILD_SG_PQP OR RL_BUILD_SG_SOLID)) set( HDRS ConfigurationDelegate.h diff --git a/demos/rlPrmDemo/CMakeLists.txt b/demos/rlPrmDemo/CMakeLists.txt index d32afd76..d67a99dd 100644 --- a/demos/rlPrmDemo/CMakeLists.txt +++ b/demos/rlPrmDemo/CMakeLists.txt @@ -1,10 +1,6 @@ find_package(Boost REQUIRED) -find_package(Bullet) -find_package(ODE) -find_package(solid3) - -if(Bullet_FOUND OR ODE_FOUND OR solid3_FOUND) +if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_ODE OR RL_BUILD_SG_SOLID) add_executable( rlPrmDemo rlPrmDemo.cpp diff --git a/demos/rlRrtDemo/CMakeLists.txt b/demos/rlRrtDemo/CMakeLists.txt index f40e9219..2019b70f 100644 --- a/demos/rlRrtDemo/CMakeLists.txt +++ b/demos/rlRrtDemo/CMakeLists.txt @@ -1,10 +1,6 @@ find_package(Boost REQUIRED) -find_package(Bullet) -find_package(ODE) -find_package(solid3) - -if(Bullet_FOUND OR ODE_FOUND OR solid3_FOUND) +if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_ODE OR RL_BUILD_SG_SOLID) add_executable( rlRrtDemo rlRrtDemo.cpp diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index 97c3203e..47dee10c 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -61,8 +61,6 @@ if(QT_FOUND AND SoQt_FOUND) target_include_directories( rlSimulator PUBLIC - ${Boost_INCLUDE_DIRS} - ${Coin_INCLUDE_DIRS} ${OPENGL_INCLUDE_DIR} ${SoQt_INCLUDE_DIRS} ) @@ -72,7 +70,6 @@ if(QT_FOUND AND SoQt_FOUND) math mdl sg - ${Coin_LIBRARIES} ${OPENGL_LIBRARIES} ${QT_LIBRARIES} ${SoQt_LIBRARIES} diff --git a/demos/rlThreadsDemo/CMakeLists.txt b/demos/rlThreadsDemo/CMakeLists.txt index b4ee3206..101f2dc1 100644 --- a/demos/rlThreadsDemo/CMakeLists.txt +++ b/demos/rlThreadsDemo/CMakeLists.txt @@ -1,3 +1,5 @@ +find_package(Threads REQUIRED) + add_executable( rlThreadsDemo rlThreadsDemo.cpp @@ -6,5 +8,5 @@ add_executable( target_link_libraries( rlThreadsDemo - util + ${CMAKE_THREAD_LIBS_INIT} ) diff --git a/demos/rlTimerDemo/CMakeLists.txt b/demos/rlTimerDemo/CMakeLists.txt index cd61dde4..902aefa9 100644 --- a/demos/rlTimerDemo/CMakeLists.txt +++ b/demos/rlTimerDemo/CMakeLists.txt @@ -1,5 +1,3 @@ -project(rlTimerDemo) - add_executable( rlTimerDemo rlTimerDemo.cpp diff --git a/rl-config.cmake.in b/rl-config.cmake.in index 73784cbd..7ee2d514 100644 --- a/rl-config.cmake.in +++ b/rl-config.cmake.in @@ -10,6 +10,8 @@ set(RL_MDL_FOUND @RL_BUILD_MDL@) set(RL_PLAN_FOUND @RL_BUILD_PLAN@) set(RL_SG_FOUND @RL_BUILD_SG@) set(RL_UTIL_FOUND @RL_BUILD_UTIL@) +set(RL_UTIL_RTAI_FOUND @RL_BUILD_UTIL_RTAI@) +set(RL_UTIL_XENOMAI_FOUND @RL_BUILD_UTIL_XENOMAI@) set(RL_XML_FOUND @RL_BUILD_XML@) @PACKAGE_INIT@ diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index d41e6cce..e391bbe9 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -14,6 +14,16 @@ if(RL_BUILD_UTIL) list(APPEND TARGETS util) endif() +if(RL_BUILD_UTIL_RTAI) + add_subdirectory(rl/util/rtai) + list(APPEND TARGETS util_rtai) +endif() + +if(RL_BUILD_UTIL_XENOMAI) + add_subdirectory(rl/util/xenomai) + list(APPEND TARGETS util_xenomai) +endif() + if(RL_BUILD_XML) add_subdirectory(rl/xml) list(APPEND TARGETS xml) diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 7998007c..4b0ccb6d 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -1,6 +1,7 @@ -find_package(Boost REQUIRED) +include(TestBigEndian) find_package(ATIDAQ) +find_package(Boost REQUIRED) find_package(cifX) find_package(Comedi) find_package(libdc1394) @@ -10,8 +11,6 @@ cmake_dependent_option(RL_BUILD_HAL_CIFX "Build cifX support" ON "RL_BUILD_HAL;c cmake_dependent_option(RL_BUILD_HAL_COMEDI "Build Comedi support" ON "RL_BUILD_HAL;Comedi_FOUND" OFF) cmake_dependent_option(RL_BUILD_HAL_LIBDC1394 "Build libdc1394 support" ON "RL_BUILD_HAL;libdc1394_FOUND" OFF) -include(TestBigEndian) - test_big_endian(BIG_ENDIAN) set( @@ -169,12 +168,6 @@ add_library( ${rl_BINARY_DIR}/robotics-library.rc ) -target_compile_definitions( - hal - PUBLIC - BOOST_ALL_NO_LIB -) - if(BIG_ENDIAN) target_compile_definitions(hal PRIVATE HAVE_BIG_ENDIAN) else() @@ -185,12 +178,6 @@ if(NOT CMAKE_VERSION VERSION_LESS 3.8) target_compile_features(hal PUBLIC cxx_std_11) endif() -target_link_libraries( - hal - math - util -) - target_include_directories( hal PUBLIC @@ -200,6 +187,12 @@ target_include_directories( ${Boost_INCLUDE_DIRS} ) +target_link_libraries( + hal + math + util +) + if(RL_BUILD_HAL_ATIDAQ) target_include_directories(hal PUBLIC ${ATIDAQ_INCLUDE_DIRS}) target_link_libraries(hal ${ATIDAQ_LIBRARIES}) @@ -231,16 +224,11 @@ endif() set_target_properties( hal PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden OUTPUT_NAME rlhal POSITION_INDEPENDENT_CODE ON VERSION ${PROJECT_VERSION} -) - -set_target_properties( - hal - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden VISIBILITY_INLINES_HIDDEN ON ) diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index 25a34b4b..01a826ad 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -60,16 +60,11 @@ target_link_libraries( set_target_properties( kin PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden OUTPUT_NAME rlkin POSITION_INDEPENDENT_CODE ON VERSION ${PROJECT_VERSION} -) - -set_target_properties( - kin - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden VISIBILITY_INLINES_HIDDEN ON ) diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index cbb9f17b..8f2fc9df 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -110,16 +110,11 @@ endif() set_target_properties( mdl PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden OUTPUT_NAME rlmdl POSITION_INDEPENDENT_CODE ON VERSION ${PROJECT_VERSION} -) - -set_target_properties( - mdl - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden VISIBILITY_INLINES_HIDDEN ON ) diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index ab8fe006..06e4ca79 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -121,16 +121,11 @@ target_link_libraries( set_target_properties( plan PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden OUTPUT_NAME rlplan POSITION_INDEPENDENT_CODE ON VERSION ${PROJECT_VERSION} -) - -set_target_properties( - plan - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden VISIBILITY_INLINES_HIDDEN ON ) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index 56e27981..dc7033d0 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -2,6 +2,7 @@ include(CheckCXXSourceCompiles) include(CheckIncludeFileCXX) include(CMakePushCheckState) +find_package(Boost REQUIRED) find_package(Bullet) find_package(Coin REQUIRED) find_package(fcl) @@ -176,22 +177,22 @@ if(NOT CMAKE_VERSION VERSION_LESS 3.8) target_compile_features(sg PUBLIC cxx_std_11) endif() -target_link_libraries( - sg - math - std - util - xml -) - -install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg COMPONENT development) - target_include_directories( sg PUBLIC $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> + PRIVATE + ${Boost_INCLUDE_DIRS} +) + +target_link_libraries( + sg + math + std + util + xml ) if(RL_BUILD_SG_BULLET) @@ -199,7 +200,6 @@ if(RL_BUILD_SG_BULLET) target_compile_definitions(sg PUBLIC ${BULLET_DEFINITIONS}) target_include_directories(sg PUBLIC ${BULLET_INCLUDE_DIRS}) target_link_libraries(sg ${BULLET_LIBRARIES}) - install(FILES ${BULLET_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/bullet COMPONENT development) endif() if(Coin_FOUND) @@ -222,7 +222,6 @@ if(Coin_FOUND) target_compile_definitions(sg PUBLIC ${Coin_DEFINITIONS}) target_include_directories(sg PUBLIC ${Coin_INCLUDE_DIRS}) target_link_libraries(sg ${Coin_LIBRARIES}) - install(FILES ${COIN_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/so COMPONENT development) endif() if(RL_BUILD_SG_FCL) @@ -230,7 +229,6 @@ if(RL_BUILD_SG_FCL) target_compile_definitions(sg PUBLIC ${FCL_DEFINITIONS}) target_include_directories(sg PUBLIC ${FCL_INCLUDE_DIRS}) target_link_libraries(sg ${FCL_LIBRARIES}) - install(FILES ${FCL_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/fcl COMPONENT development) endif() if(RL_BUILD_SG_ODE) @@ -238,36 +236,28 @@ if(RL_BUILD_SG_ODE) target_compile_definitions(sg PUBLIC ${ODE_DEFINITIONS}) target_include_directories(sg PUBLIC ${ODE_INCLUDE_DIRS}) target_link_libraries(sg ${ODE_LIBRARIES}) - install(FILES ${ODE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/ode COMPONENT development) endif() if(RL_BUILD_SG_PQP) target_compile_definitions(sg INTERFACE RL_SG_PQP) target_include_directories(sg PUBLIC ${PQP_INCLUDE_DIRS}) target_link_libraries(sg ${PQP_LIBRARIES}) - install(FILES ${PQP_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/pqp COMPONENT development) endif() if(RL_BUILD_SG_SOLID) target_compile_definitions(sg INTERFACE RL_SG_SOLID) target_include_directories(sg PUBLIC ${SOLID3_INCLUDE_DIRS}) target_link_libraries(sg ${SOLID3_LIBRARIES}) - install(FILES ${SOLID_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/solid COMPONENT development) endif() set_target_properties( sg PROPERTIES + C_VISIBILITY_PRESET hidden + CXX_VISIBILITY_PRESET hidden OUTPUT_NAME rlsg POSITION_INDEPENDENT_CODE ON VERSION ${PROJECT_VERSION} -) - -set_target_properties( - sg - PROPERTIES - C_VISIBILITY_PRESET hidden - CXX_VISIBILITY_PRESET hidden VISIBILITY_INLINES_HIDDEN ON ) @@ -290,6 +280,32 @@ if(MSVC) endif() endif() +install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg COMPONENT development) + +if(RL_BUILD_SG_BULLET) + install(FILES ${BULLET_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/bullet COMPONENT development) +endif() + +if(Coin_FOUND) + install(FILES ${COIN_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/so COMPONENT development) +endif() + +if(RL_BUILD_SG_FCL) + install(FILES ${FCL_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/fcl COMPONENT development) +endif() + +if(RL_BUILD_SG_ODE) + install(FILES ${ODE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/ode COMPONENT development) +endif() + +if(RL_BUILD_SG_PQP) + install(FILES ${PQP_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/pqp COMPONENT development) +endif() + +if(RL_BUILD_SG_SOLID) + install(FILES ${SOLID_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/sg/solid COMPONENT development) +endif() + if(NOT CMAKE_VERSION VERSION_LESS 3.12) install( TARGETS sg diff --git a/src/rl/util/CMakeLists.txt b/src/rl/util/CMakeLists.txt index 2edc807d..e0d60144 100644 --- a/src/rl/util/CMakeLists.txt +++ b/src/rl/util/CMakeLists.txt @@ -1,10 +1,3 @@ -find_package(RTAI) -find_package(Threads REQUIRED) -find_package(Xenomai) - -cmake_dependent_option(RL_BUILD_UTIL_RTAI "Build RTAI support" ON "RL_BUILD_UTIL;RTAI_FOUND" OFF) -cmake_dependent_option(RL_BUILD_UTIL_XENOMAI "Build Xenomai support" ON "RL_BUILD_UTIL;Xenomai_FOUND" OFF) - set( BASE_HDRS process.h @@ -19,26 +12,6 @@ set( ) list(APPEND HDRS ${IO_HDRS}) -if(RL_BUILD_UTIL_RTAI) - set( - RTAI_HDRS - rtai/chrono.h - rtai/thread.h - ) - list(APPEND HDRS ${RTAI_HDRS}) -endif() - -if(RL_BUILD_UTIL_XENOMAI) - set( - XENOMAI_HDRS - xenomai/chrono.h - xenomai/condition_variable.h - xenomai/mutex.h - xenomai/thread.h - ) - list(APPEND HDRS ${XENOMAI_HDRS}) -endif() - if(NOT CMAKE_VERSION VERSION_LESS 3.19) add_library(util INTERFACE ${HDRS}) else() @@ -50,8 +23,6 @@ if(NOT CMAKE_VERSION VERSION_LESS 3.8) target_compile_features(util INTERFACE cxx_std_11) endif() -target_link_libraries(util INTERFACE ${CMAKE_THREAD_LIBS_INIT}) - target_include_directories( util INTERFACE @@ -60,22 +31,6 @@ target_include_directories( $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> ) -install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util COMPONENT development) -install(FILES ${IO_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util/io COMPONENT development) - -if(RL_BUILD_UTIL_RTAI) - target_include_directories(util INTERFACE ${RTAI_INCLUDE_DIRS}) - target_link_libraries(util INTERFACE ${RTAI_LIBRARIES}) - install(FILES ${RTAI_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util/rtai COMPONENT development) -endif() - -if(RL_BUILD_UTIL_XENOMAI) - target_compile_definitions(util INTERFACE ${Xenomai_DEFINITIONS}) - target_include_directories(util INTERFACE ${Xenomai_INCLUDE_DIRS}) - target_link_libraries(util INTERFACE ${Xenomai_LIBRARIES}) - install(FILES ${XENOMAI_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util/xenomai COMPONENT development) -endif() - if(NOT CMAKE_VERSION VERSION_LESS 3.19) set_target_properties( util @@ -84,6 +39,9 @@ if(NOT CMAKE_VERSION VERSION_LESS 3.19) ) endif() +install(FILES ${BASE_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util COMPONENT development) +install(FILES ${IO_HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util/io COMPONENT development) + install( TARGETS util EXPORT rl diff --git a/src/rl/util/rtai/CMakeLists.txt b/src/rl/util/rtai/CMakeLists.txt new file mode 100644 index 00000000..174f8e07 --- /dev/null +++ b/src/rl/util/rtai/CMakeLists.txt @@ -0,0 +1,47 @@ +find_package(RTAI REQUIRED) + +set( + HDRS + chrono.h + thread.h +) + +if(NOT CMAKE_VERSION VERSION_LESS 3.19) + add_library(util_rtai INTERFACE ${HDRS}) +else() + add_library(util_rtai INTERFACE) + add_custom_target(util_rtai_sources SOURCES ${HDRS}) +endif() + +if(NOT CMAKE_VERSION VERSION_LESS 3.8) + target_compile_features(util_rtai INTERFACE cxx_std_11) +endif() + +target_include_directories( + util_rtai + INTERFACE + $ + $ + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> + ${RTAI_INCLUDE_DIRS} +) + +target_link_libraries(util_rtai INTERFACE ${RTAI_LIBRARIES}) + +if(NOT CMAKE_VERSION VERSION_LESS 3.19) + set_target_properties( + util_rtai + PROPERTIES + VERSION ${PROJECT_VERSION} + ) +endif() + +install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util/rtai COMPONENT development) + +install( + TARGETS util_rtai + EXPORT rl + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime +) diff --git a/src/rl/util/xenomai/CMakeLists.txt b/src/rl/util/xenomai/CMakeLists.txt new file mode 100644 index 00000000..7bd021c4 --- /dev/null +++ b/src/rl/util/xenomai/CMakeLists.txt @@ -0,0 +1,51 @@ +find_package(Xenomai REQUIRED) + +set( + HDRS + chrono.h + condition_variable.h + mutex.h + thread.h +) + +if(NOT CMAKE_VERSION VERSION_LESS 3.19) + add_library(util_xenomai INTERFACE ${HDRS}) +else() + add_library(util_xenomai INTERFACE) + add_custom_target(util_xenomai_sources SOURCES ${HDRS}) +endif() + +target_compile_definitions(util_xenomai INTERFACE ${Xenomai_DEFINITIONS}) + +if(NOT CMAKE_VERSION VERSION_LESS 3.8) + target_compile_features(util_xenomai INTERFACE cxx_std_11) +endif() + +target_include_directories( + util_xenomai + INTERFACE + $ + $ + $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> + ${XENOMAI_INCLUDE_DIRS} +) + +target_link_libraries(util_xenomai INTERFACE ${XENOMAI_LIBRARIES}) + +if(NOT CMAKE_VERSION VERSION_LESS 3.19) + set_target_properties( + util_xenomai + PROPERTIES + VERSION ${PROJECT_VERSION} + ) +endif() + +install(FILES ${HDRS} DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}/rl/util/xenomai COMPONENT development) + +install( + TARGETS util_xenomai + EXPORT rl + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT development + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} COMPONENT runtime NAMELINK_SKIP + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} COMPONENT runtime +) diff --git a/tests/rlCollisionTest/CMakeLists.txt b/tests/rlCollisionTest/CMakeLists.txt index e8f0183e..f4b99206 100644 --- a/tests/rlCollisionTest/CMakeLists.txt +++ b/tests/rlCollisionTest/CMakeLists.txt @@ -1,12 +1,6 @@ find_package(Boost REQUIRED) -find_package(Bullet) -find_package(fcl) -find_package(ODE) -find_package(PQP) -find_package(solid3) - -if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) +if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUILD_SG_ODE OR RL_BUILD_SG_PQP OR RL_BUILD_SG_SOLID) add_executable( rlCollisionTest rlCollisionTest.cpp diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index 86269e99..da77d21f 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -1,11 +1,6 @@ find_package(Boost REQUIRED) -find_package(Bullet) -find_package(fcl) -find_package(PQP) -find_package(solid3) - -if(Bullet_FOUND OR fcl_FOUND OR PQP_FOUND OR solid3_FOUND) +if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUILD_SG_PQP OR RL_BUILD_SG_SOLID) add_executable( rlEetTest rlEetTest.cpp @@ -25,7 +20,7 @@ if(Bullet_FOUND OR fcl_FOUND OR PQP_FOUND OR solid3_FOUND) sg ) - if(Bullet_FOUND) + if(RL_BUILD_SG_BULLET) add_test( NAME rlEetTestBulletBox6d300505Maze COMMAND rlEetTest @@ -38,7 +33,7 @@ if(Bullet_FOUND OR fcl_FOUND OR PQP_FOUND OR solid3_FOUND) ) endif() - if(fcl_FOUND) + if(RL_BUILD_SG_FCL) add_test( NAME rlEetTestFclBox6d300505Maze COMMAND rlEetTest @@ -51,7 +46,7 @@ if(Bullet_FOUND OR fcl_FOUND OR PQP_FOUND OR solid3_FOUND) ) endif() - if(PQP_FOUND) + if(RL_BUILD_SG_PQP) add_test( NAME rlEetTestPqpBox6d300505Maze COMMAND rlEetTest @@ -64,7 +59,7 @@ if(Bullet_FOUND OR fcl_FOUND OR PQP_FOUND OR solid3_FOUND) ) endif() - if(solid3_FOUND) + if(RL_BUILD_SG_SOLID) add_test( NAME rlEetTestSolidBox6d300505Maze COMMAND rlEetTest diff --git a/tests/rlPrmTest/CMakeLists.txt b/tests/rlPrmTest/CMakeLists.txt index 89b27bb4..ae3b1790 100644 --- a/tests/rlPrmTest/CMakeLists.txt +++ b/tests/rlPrmTest/CMakeLists.txt @@ -1,12 +1,6 @@ find_package(Boost REQUIRED) -find_package(Bullet) -find_package(fcl) -find_package(ODE) -find_package(PQP) -find_package(solid3) - -if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) +if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUILD_SG_ODE OR RL_BUILD_SG_PQP OR RL_BUILD_SG_SOLID) add_executable( rlPrmTest rlPrmTest.cpp @@ -26,7 +20,7 @@ if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) sg ) - if(Bullet_FOUND) + if(RL_BUILD_SG_BULLET) add_test( NAME rlPrmTestBulletUnimationPuma560Boxes1 COMMAND rlPrmTest @@ -52,7 +46,7 @@ if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) ) endif() - if(fcl_FOUND) + if(RL_BUILD_SG_FCL) add_test( NAME rlPrmTestFclUnimationPuma560Boxes1 COMMAND rlPrmTest @@ -78,7 +72,7 @@ if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) ) endif() - if(ODE_FOUND) + if(RL_BUILD_SG_ODE) add_test( NAME rlPrmTestOdeUnimationPuma560Boxes1 COMMAND rlPrmTest @@ -104,7 +98,7 @@ if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) ) endif() - if(PQP_FOUND) + if(RL_BUILD_SG_PQP) add_test( NAME rlPrmTestPqpUnimationPuma560Boxes1 COMMAND rlPrmTest @@ -130,7 +124,7 @@ if(Bullet_FOUND OR fcl_FOUND OR ODE_FOUND OR PQP_FOUND OR solid3_FOUND) ) endif() - if(solid3_FOUND) + if(RL_BUILD_SG_SOLID) add_test( NAME rlPrmTestSolidUnimationPuma560Boxes1 COMMAND rlPrmTest diff --git a/tests/rlSpatialTest/CMakeLists.txt b/tests/rlSpatialTest/CMakeLists.txt index 9ba30203..80a08382 100644 --- a/tests/rlSpatialTest/CMakeLists.txt +++ b/tests/rlSpatialTest/CMakeLists.txt @@ -10,12 +10,12 @@ set( rlSpatialRigidBodyInertiaTest ) -foreach(TEST IN LISTS TESTS) +foreach(test IN LISTS TESTS) add_executable( - ${TEST} - ${TEST}.cpp + ${test} + ${test}.cpp ${rl_BINARY_DIR}/robotics-library.rc ) - target_link_libraries(${TEST} math) - add_test(NAME ${TEST} COMMAND ${TEST}) + target_link_libraries(${test} math) + add_test(NAME ${test} COMMAND ${test}) endforeach() diff --git a/tests/rlSplineTest/CMakeLists.txt b/tests/rlSplineTest/CMakeLists.txt index 49cd0c42..63693d49 100644 --- a/tests/rlSplineTest/CMakeLists.txt +++ b/tests/rlSplineTest/CMakeLists.txt @@ -10,12 +10,12 @@ set( rlTrapezoidalAccelerationTest ) -foreach(TEST IN LISTS TESTS) +foreach(test IN LISTS TESTS) add_executable( - ${TEST} - ${TEST}.cpp + ${test} + ${test}.cpp ${rl_BINARY_DIR}/robotics-library.rc ) - target_link_libraries(${TEST} math) - add_test(NAME ${TEST} COMMAND ${TEST}) + target_link_libraries(${test} math) + add_test(NAME ${test} COMMAND ${test}) endforeach() From 2c44075c8771e3c7af2948732cb7a3aee7aa6342 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 1 Jan 2021 23:30:45 +0100 Subject: [PATCH 438/546] Use CMake targets for dependencies --- CMakeLists.txt | 54 ++++++++++++++++++-- demos/rlCoachKin/CMakeLists.txt | 33 +++++------- demos/rlCoachMdl/CMakeLists.txt | 33 +++++------- demos/rlCollisionDemo/CMakeLists.txt | 33 +++++------- demos/rlDynamics1Demo/CMakeLists.txt | 7 +-- demos/rlDynamics2Demo/CMakeLists.txt | 7 +-- demos/rlEulerAnglesDemo/CMakeLists.txt | 7 +-- demos/rlInversePositionDemo/CMakeLists.txt | 7 +-- demos/rlJacobianDemo/CMakeLists.txt | 7 +-- demos/rlPlanDemo/CMakeLists.txt | 35 ++++++------- demos/rlPolynomialRootsDemo/CMakeLists.txt | 7 +-- demos/rlPrmDemo/CMakeLists.txt | 7 +-- demos/rlPumaDemo/CMakeLists.txt | 7 +-- demos/rlRotationConverterDemo/CMakeLists.txt | 10 ++-- demos/rlRrtDemo/CMakeLists.txt | 7 +-- demos/rlSimulator/CMakeLists.txt | 33 +++++------- demos/rlSocketDemo/CMakeLists.txt | 14 +---- demos/rlThreadsDemo/CMakeLists.txt | 2 +- demos/rlViewDemo/CMakeLists.txt | 24 +++------ extras/byu2wrl/CMakeLists.txt | 14 +---- extras/csv2wrl/CMakeLists.txt | 16 +----- extras/tris2wrl/CMakeLists.txt | 16 +----- extras/wrlview/CMakeLists.txt | 41 ++++++--------- rl-config.cmake.in | 11 ++-- src/rl/hal/CMakeLists.txt | 14 ++--- src/rl/kin/CMakeLists.txt | 2 +- src/rl/math/CMakeLists.txt | 4 +- src/rl/mdl/CMakeLists.txt | 5 +- src/rl/plan/CMakeLists.txt | 2 +- src/rl/sg/CMakeLists.txt | 26 +++------- src/rl/xml/CMakeLists.txt | 5 +- tests/rlCollisionTest/CMakeLists.txt | 7 +-- tests/rlEetTest/CMakeLists.txt | 7 +-- tests/rlNearestNeighborsTest/CMakeLists.txt | 7 +-- tests/rlPrmTest/CMakeLists.txt | 7 +-- 35 files changed, 196 insertions(+), 322 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 576406e4..c76d141b 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -88,33 +88,77 @@ foreach(target IN LISTS TARGETS) if(NOT target STREQUAL "util_rtai" AND NOT target STREQUAL "util_xenomai") list(APPEND RL_LIBRARIES "rl::${target}") endif() + get_target_property(TARGET_INTERFACE_LINK_LIBRARIES ${target} INTERFACE_LINK_LIBRARIES) + if(TARGET_INTERFACE_LINK_LIBRARIES) + foreach(library IN LISTS TARGET_INTERFACE_LINK_LIBRARIES) + if(library MATCHES "([A-Za-z0-9_.+-]*)::([A-Za-z0-9_.+-]*)") + list(APPEND PACKAGES ${CMAKE_MATCH_1}) + endif() + endforeach() + endif() +endforeach() + +list(REMOVE_DUPLICATES PACKAGES) +list(SORT PACKAGES) + +foreach(package IN LISTS PACKAGES) + list(APPEND FIND_DEPENDENCIES "find_dependency(${package})") + list(APPEND MODULES ${package}) + if(package STREQUAL "fcl") + list(APPEND MODULES Boost ccd Eigen3 octomap) + elseif(package STREQUAL "LibXml2") + list(APPEND MODULES Iconv ICU LibLZMA Threads ZLIB) + elseif(package STREQUAL "LibXslt") + list(APPEND MODULES LibXml2) + elseif(package STREQUAL "ODE") + list(APPEND MODULES ccd Threads) + endif() endforeach() +list(REMOVE_DUPLICATES MODULES) +list(SORT MODULES) + +foreach(module IN LISTS MODULES) + if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Find${module}.cmake) + file( + COPY cmake/Find${module}.cmake + DESTINATION ${CMAKE_CURRENT_BINARY_DIR}/lib/cmake/rl + ) + install( + FILES cmake/Find${module}.cmake + DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${PROJECT_VERSION} + COMPONENT development + ) + endif() +endforeach() + +string(REPLACE ";" "\n" FIND_DEPENDENCIES "${FIND_DEPENDENCIES}") + export( TARGETS ${TARGETS} NAMESPACE rl:: - FILE ${CMAKE_CURRENT_BINARY_DIR}/rl-export.cmake + FILE ${CMAKE_CURRENT_BINARY_DIR}/lib/cmake/rl/rl-export.cmake ) configure_package_config_file( - rl-config.cmake.in rl-config.cmake + rl-config.cmake.in lib/cmake/rl/rl-config.cmake INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${PROJECT_VERSION} ) install( - FILES ${CMAKE_CURRENT_BINARY_DIR}/rl-config.cmake + FILES ${CMAKE_CURRENT_BINARY_DIR}/lib/cmake/rl/rl-config.cmake DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${PROJECT_VERSION} COMPONENT development ) write_basic_package_version_file( - ${CMAKE_CURRENT_BINARY_DIR}/rl-config-version.cmake + ${CMAKE_CURRENT_BINARY_DIR}/lib/cmake/rl/rl-config-version.cmake VERSION ${PROJECT_VERSION} COMPATIBILITY ExactVersion ) install( - FILES ${CMAKE_CURRENT_BINARY_DIR}/rl-config-version.cmake + FILES ${CMAKE_CURRENT_BINARY_DIR}/lib/cmake/rl/rl-config-version.cmake DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/rl-${PROJECT_VERSION} COMPONENT development ) diff --git a/demos/rlCoachKin/CMakeLists.txt b/demos/rlCoachKin/CMakeLists.txt index 7211c1c8..78ca0978 100644 --- a/demos/rlCoachKin/CMakeLists.txt +++ b/demos/rlCoachKin/CMakeLists.txt @@ -6,13 +6,10 @@ if(RL_USE_QT5 AND SoQt_HAVE_QT5) endif() if(Qt5_FOUND) - set(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5OpenGL_LIBRARIES} ${Qt5Network_LIBRARIES} ${Qt5Widgets_LIBRARIES}) set(QT_FOUND Qt5_FOUND) else() set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtNetwork QtOpenGL) - set(QT_USE_QTMAIN ON) - include(${QT_USE_FILE}) endif() set(CMAKE_AUTOMOC ON) @@ -52,29 +49,27 @@ if(QT_FOUND AND SoQt_FOUND) ${rl_BINARY_DIR}/robotics-library.rc ) - target_compile_definitions( - rlCoachKin - PUBLIC - ${SoQt_DEFINITIONS} - ) - - target_include_directories( - rlCoachKin - PUBLIC - ${OPENGL_INCLUDE_DIR} - ${SoQt_INCLUDE_DIRS} - ) - target_link_libraries( rlCoachKin kin math sg - ${OPENGL_LIBRARIES} - ${QT_LIBRARIES} - ${SoQt_LIBRARIES} + SoQt::SoQt ) + if(TARGET OpenGL::GL) + target_link_libraries(rlCoachKin OpenGL::GL) + else() + target_include_directories(rlCoachKin PRIVATE ${OPENGL_INCLUDE_DIRS}) + target_link_libraries(rlCoachKin ${OPENGL_LIBRARIES}) + endif() + + if(Qt5_FOUND) + target_link_libraries(rlCoachKin Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Network Qt5::Widgets) + elseif(Qt4_FOUND) + target_link_libraries(rlCoachKin Qt4::QtCore Qt4::QtGui Qt4::QtNetwork Qt4::QtOpenGL) + endif() + set_target_properties( rlCoachKin PROPERTIES diff --git a/demos/rlCoachMdl/CMakeLists.txt b/demos/rlCoachMdl/CMakeLists.txt index 299cff0d..e0f4b50f 100644 --- a/demos/rlCoachMdl/CMakeLists.txt +++ b/demos/rlCoachMdl/CMakeLists.txt @@ -6,13 +6,10 @@ if(RL_USE_QT5 AND SoQt_HAVE_QT5) endif() if(Qt5_FOUND) - set(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5OpenGL_LIBRARIES} ${Qt5Network_LIBRARIES} ${Qt5Widgets_LIBRARIES}) set(QT_FOUND Qt5_FOUND) else() set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtNetwork QtOpenGL) - set(QT_USE_QTMAIN ON) - include(${QT_USE_FILE}) endif() set(CMAKE_AUTOMOC ON) @@ -52,29 +49,27 @@ if(QT_FOUND AND SoQt_FOUND) ${rl_BINARY_DIR}/robotics-library.rc ) - target_compile_definitions( - rlCoachMdl - PUBLIC - ${SoQt_DEFINITIONS} - ) - - target_include_directories( - rlCoachMdl - PUBLIC - ${OPENGL_INCLUDE_DIR} - ${SoQt_INCLUDE_DIRS} - ) - target_link_libraries( rlCoachMdl math mdl sg - ${OPENGL_LIBRARIES} - ${QT_LIBRARIES} - ${SoQt_LIBRARIES} + SoQt::SoQt ) + if(TARGET OpenGL::GL) + target_link_libraries(rlCoachMdl OpenGL::GL) + else() + target_include_directories(rlCoachMdl PRIVATE ${OPENGL_INCLUDE_DIRS}) + target_link_libraries(rlCoachMdl ${OPENGL_LIBRARIES}) + endif() + + if(Qt5_FOUND) + target_link_libraries(rlCoachMdl Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Network Qt5::Widgets) + elseif(Qt4_FOUND) + target_link_libraries(rlCoachMdl Qt4::QtCore Qt4::QtGui Qt4::QtNetwork Qt4::QtOpenGL) + endif() + set_target_properties( rlCoachMdl PROPERTIES diff --git a/demos/rlCollisionDemo/CMakeLists.txt b/demos/rlCollisionDemo/CMakeLists.txt index c5c6f5a5..3b455184 100644 --- a/demos/rlCollisionDemo/CMakeLists.txt +++ b/demos/rlCollisionDemo/CMakeLists.txt @@ -6,13 +6,10 @@ if(RL_USE_QT5 AND SoQt_HAVE_QT5) endif() if(Qt5_FOUND) - set(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5OpenGL_LIBRARIES} ${Qt5Widgets_LIBRARIES}) set(QT_FOUND Qt5_FOUND) else() set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtOpenGL) - set(QT_USE_QTMAIN ON) - include(${QT_USE_FILE}) endif() set(CMAKE_AUTOMOC ON) @@ -44,27 +41,25 @@ if(QT_FOUND AND SoQt_FOUND AND (RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUIL ${rl_BINARY_DIR}/robotics-library.rc ) - target_compile_definitions( - rlCollisionDemo - PUBLIC - ${SoQt_DEFINITIONS} - ) - - target_include_directories( - rlCollisionDemo - PUBLIC - ${OPENGL_INCLUDE_DIR} - ${SoQt_INCLUDE_DIRS} - ) - target_link_libraries( rlCollisionDemo sg - ${OPENGL_LIBRARIES} - ${QT_LIBRARIES} - ${SoQt_LIBRARIES} + SoQt::SoQt ) + if(TARGET OpenGL::GL) + target_link_libraries(rlCollisionDemo OpenGL::GL) + else() + target_include_directories(rlCollisionDemo PRIVATE ${OPENGL_INCLUDE_DIRS}) + target_link_libraries(rlCollisionDemo ${OPENGL_LIBRARIES}) + endif() + + if(Qt5_FOUND) + target_link_libraries(rlCollisionDemo Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Widgets) + elseif(Qt4_FOUND) + target_link_libraries(rlCollisionDemo Qt4::QtCore Qt4::QtGui Qt4::QtOpenGL) + endif() + set_target_properties( rlCollisionDemo PROPERTIES diff --git a/demos/rlDynamics1Demo/CMakeLists.txt b/demos/rlDynamics1Demo/CMakeLists.txt index 8c23e974..00b80d89 100644 --- a/demos/rlDynamics1Demo/CMakeLists.txt +++ b/demos/rlDynamics1Demo/CMakeLists.txt @@ -6,13 +6,8 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlDynamics1Demo - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlDynamics1Demo mdl + Boost::headers ) diff --git a/demos/rlDynamics2Demo/CMakeLists.txt b/demos/rlDynamics2Demo/CMakeLists.txt index 8b6eb1ee..bceb83c7 100644 --- a/demos/rlDynamics2Demo/CMakeLists.txt +++ b/demos/rlDynamics2Demo/CMakeLists.txt @@ -6,13 +6,8 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlDynamics2Demo - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlDynamics2Demo mdl + Boost::headers ) diff --git a/demos/rlEulerAnglesDemo/CMakeLists.txt b/demos/rlEulerAnglesDemo/CMakeLists.txt index 47fc2607..d8816662 100644 --- a/demos/rlEulerAnglesDemo/CMakeLists.txt +++ b/demos/rlEulerAnglesDemo/CMakeLists.txt @@ -6,13 +6,8 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlEulerAnglesDemo - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlEulerAnglesDemo math + Boost::headers ) diff --git a/demos/rlInversePositionDemo/CMakeLists.txt b/demos/rlInversePositionDemo/CMakeLists.txt index 66229c44..bfbe02eb 100644 --- a/demos/rlInversePositionDemo/CMakeLists.txt +++ b/demos/rlInversePositionDemo/CMakeLists.txt @@ -6,15 +6,10 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlInversePositionDemo - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlInversePositionDemo hal mdl util + Boost::headers ) diff --git a/demos/rlJacobianDemo/CMakeLists.txt b/demos/rlJacobianDemo/CMakeLists.txt index 815553b3..415c04fa 100644 --- a/demos/rlJacobianDemo/CMakeLists.txt +++ b/demos/rlJacobianDemo/CMakeLists.txt @@ -6,13 +6,8 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlJacobianDemo - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlJacobianDemo mdl + Boost::headers ) diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index 424cc249..6488d1c0 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -7,13 +7,10 @@ if(RL_USE_QT5 AND SoQt_HAVE_QT5) endif() if(Qt5_FOUND) - set(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5OpenGL_LIBRARIES} ${Qt5PrintSupport_LIBRARIES} ${Qt5Widgets_LIBRARIES}) set(QT_FOUND Qt5_FOUND) else() set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtOpenGL) - set(QT_USE_QTMAIN ON) - include(${QT_USE_FILE}) endif() set(CMAKE_AUTOMOC ON) @@ -59,29 +56,27 @@ if(QT_FOUND AND SoQt_FOUND AND (RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUIL ${rl_BINARY_DIR}/robotics-library.rc ) - target_compile_definitions( - rlPlanDemo - PUBLIC - ${SoQt_DEFINITIONS} - ) - - target_include_directories( - rlPlanDemo - PUBLIC - ${Boost_INCLUDE_DIRS} - ${OPENGL_INCLUDE_DIR} - ${SoQt_INCLUDE_DIRS} - ) - target_link_libraries( rlPlanDemo plan kin sg - ${OPENGL_LIBRARIES} - ${QT_LIBRARIES} - ${SoQt_LIBRARIES} + Boost::headers + SoQt::SoQt ) + + if(TARGET OpenGL::GL) + target_link_libraries(rlPlanDemo OpenGL::GL) + else() + target_include_directories(rlPlanDemo PRIVATE ${OPENGL_INCLUDE_DIRS}) + target_link_libraries(rlPlanDemo ${OPENGL_LIBRARIES}) + endif() + + if(Qt5_FOUND) + target_link_libraries(rlPlanDemo Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::PrintSupport Qt5::Widgets) + elseif(Qt4_FOUND) + target_link_libraries(rlPlanDemo Qt4::QtCore Qt4::QtGui Qt4::QtOpenGL) + endif() set_target_properties( rlPlanDemo diff --git a/demos/rlPolynomialRootsDemo/CMakeLists.txt b/demos/rlPolynomialRootsDemo/CMakeLists.txt index 60f14426..fa13d012 100644 --- a/demos/rlPolynomialRootsDemo/CMakeLists.txt +++ b/demos/rlPolynomialRootsDemo/CMakeLists.txt @@ -6,13 +6,8 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlPolynomialRootsDemo - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlPolynomialRootsDemo math + Boost::headers ) diff --git a/demos/rlPrmDemo/CMakeLists.txt b/demos/rlPrmDemo/CMakeLists.txt index d67a99dd..5382e642 100644 --- a/demos/rlPrmDemo/CMakeLists.txt +++ b/demos/rlPrmDemo/CMakeLists.txt @@ -7,16 +7,11 @@ if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_ODE OR RL_BUILD_SG_SOLID) ${rl_BINARY_DIR}/robotics-library.rc ) - target_include_directories( - rlPrmDemo - PUBLIC - ${Boost_INCLUDE_DIRS} - ) - target_link_libraries( rlPrmDemo mdl plan sg + Boost::headers ) endif() diff --git a/demos/rlPumaDemo/CMakeLists.txt b/demos/rlPumaDemo/CMakeLists.txt index d28e3e71..6db66792 100644 --- a/demos/rlPumaDemo/CMakeLists.txt +++ b/demos/rlPumaDemo/CMakeLists.txt @@ -6,13 +6,8 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlPumaDemo - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlPumaDemo kin + Boost::headers ) diff --git a/demos/rlRotationConverterDemo/CMakeLists.txt b/demos/rlRotationConverterDemo/CMakeLists.txt index 6f828fa6..7533acd7 100644 --- a/demos/rlRotationConverterDemo/CMakeLists.txt +++ b/demos/rlRotationConverterDemo/CMakeLists.txt @@ -3,13 +3,10 @@ if(RL_USE_QT5) endif() if(Qt5_FOUND) - set(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5Widgets_LIBRARIES}) set(QT_FOUND Qt5_FOUND) else() set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui) - set(QT_USE_QTMAIN ON) - include(${QT_USE_FILE}) endif() set(CMAKE_AUTOMOC ON) @@ -51,9 +48,14 @@ if(QT_FOUND) target_link_libraries( rlRotationConverterDemo math - ${QT_LIBRARIES} ) + if(Qt5_FOUND) + target_link_libraries(rlRotationConverterDemo Qt5::Core Qt5::Gui Qt5::Widgets) + elseif(Qt4_FOUND) + target_link_libraries(rlRotationConverterDemo Qt4::QtCore Qt4::QtGui) + endif() + set_target_properties( rlRotationConverterDemo PROPERTIES diff --git a/demos/rlRrtDemo/CMakeLists.txt b/demos/rlRrtDemo/CMakeLists.txt index 2019b70f..1b4a466a 100644 --- a/demos/rlRrtDemo/CMakeLists.txt +++ b/demos/rlRrtDemo/CMakeLists.txt @@ -7,16 +7,11 @@ if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_ODE OR RL_BUILD_SG_SOLID) ${rl_BINARY_DIR}/robotics-library.rc ) - target_include_directories( - rlRrtDemo - PUBLIC - ${Boost_INCLUDE_DIRS} - ) - target_link_libraries( rlRrtDemo mdl plan sg + Boost::headers ) endif() diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index 47dee10c..2578d0e5 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -6,13 +6,10 @@ if(RL_USE_QT5 AND SoQt_HAVE_QT5) endif() if(Qt5_FOUND) - set(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5OpenGL_LIBRARIES} ${Qt5Network_LIBRARIES} ${Qt5Widgets_LIBRARIES}) set(QT_FOUND Qt5_FOUND) else() set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtNetwork QtOpenGL) - set(QT_USE_QTMAIN ON) - include(${QT_USE_FILE}) endif() set(CMAKE_AUTOMOC ON) @@ -52,29 +49,27 @@ if(QT_FOUND AND SoQt_FOUND) ${rl_BINARY_DIR}/robotics-library.rc ) - target_compile_definitions( - rlSimulator - PUBLIC - ${SoQt_DEFINITIONS} - ) - - target_include_directories( - rlSimulator - PUBLIC - ${OPENGL_INCLUDE_DIR} - ${SoQt_INCLUDE_DIRS} - ) - target_link_libraries( rlSimulator math mdl sg - ${OPENGL_LIBRARIES} - ${QT_LIBRARIES} - ${SoQt_LIBRARIES} + SoQt::SoQt ) + if(TARGET OpenGL::GL) + target_link_libraries(rlSimulator OpenGL::GL) + else() + target_include_directories(rlSimulator PRIVATE ${OPENGL_INCLUDE_DIRS}) + target_link_libraries(rlSimulator ${OPENGL_LIBRARIES}) + endif() + + if(Qt5_FOUND) + target_link_libraries(rlSimulator Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Network Qt5::Widgets) + elseif(Qt4_FOUND) + target_link_libraries(rlSimulator Qt4::QtCore Qt4::QtGui Qt4::QtNetwork Qt4::QtOpenGL) + endif() + set_target_properties( rlSimulator PROPERTIES diff --git a/demos/rlSocketDemo/CMakeLists.txt b/demos/rlSocketDemo/CMakeLists.txt index 947c3f2c..c4939fb2 100644 --- a/demos/rlSocketDemo/CMakeLists.txt +++ b/demos/rlSocketDemo/CMakeLists.txt @@ -6,15 +6,10 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlSocketDemoClient - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlSocketDemoClient hal + Boost::headers ) add_executable( @@ -23,13 +18,8 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlSocketDemoServer - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlSocketDemoServer hal + Boost::headers ) diff --git a/demos/rlThreadsDemo/CMakeLists.txt b/demos/rlThreadsDemo/CMakeLists.txt index 101f2dc1..e7dda6b6 100644 --- a/demos/rlThreadsDemo/CMakeLists.txt +++ b/demos/rlThreadsDemo/CMakeLists.txt @@ -8,5 +8,5 @@ add_executable( target_link_libraries( rlThreadsDemo - ${CMAKE_THREAD_LIBS_INIT} + Threads::Threads ) diff --git a/demos/rlViewDemo/CMakeLists.txt b/demos/rlViewDemo/CMakeLists.txt index c551b4c1..6eca29ab 100644 --- a/demos/rlViewDemo/CMakeLists.txt +++ b/demos/rlViewDemo/CMakeLists.txt @@ -5,13 +5,10 @@ if(RL_USE_QT5 AND SoQt_HAVE_QT5) endif() if(Qt5_FOUND) - set(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5OpenGL_LIBRARIES} ${Qt5Widgets_LIBRARIES}) set(QT_FOUND Qt5_FOUND) else() set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtOpenGL) - set(QT_USE_QTMAIN ON) - include(${QT_USE_FILE}) endif() set(CMAKE_AUTOMOC ON) @@ -25,25 +22,18 @@ if(QT_FOUND AND SoQt_FOUND) ${rl_BINARY_DIR}/robotics-library.rc ) - target_compile_definitions( - rlViewDemo - PUBLIC - ${SoQt_DEFINITIONS} - ) - - target_include_directories( - rlViewDemo - PUBLIC - ${SoQt_INCLUDE_DIRS} - ) - target_link_libraries( rlViewDemo sg - ${QT_LIBRARIES} - ${SoQt_LIBRARIES} + SoQt::SoQt ) + if(Qt5_FOUND) + target_link_libraries(rlViewDemo Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Widgets) + elseif(Qt4_FOUND) + target_link_libraries(rlViewDemo Qt4::QtCore Qt4::QtGui Qt4::QtOpenGL) + endif() + set_target_properties( rlViewDemo PROPERTIES diff --git a/extras/byu2wrl/CMakeLists.txt b/extras/byu2wrl/CMakeLists.txt index 727c20cb..b949cb3d 100644 --- a/extras/byu2wrl/CMakeLists.txt +++ b/extras/byu2wrl/CMakeLists.txt @@ -8,20 +8,8 @@ if(Coin_FOUND) byu2wrl.cpp ) - target_compile_definitions( - byu2wrl - PUBLIC - ${Coin_DEFINITIONS} - ) - - target_include_directories( - byu2wrl - PUBLIC - ${Coin_INCLUDE_DIRS} - ) - target_link_libraries( byu2wrl - ${Coin_LIBRARIES} + Coin::Coin ) endif() diff --git a/extras/csv2wrl/CMakeLists.txt b/extras/csv2wrl/CMakeLists.txt index 03f5de74..f929f26f 100644 --- a/extras/csv2wrl/CMakeLists.txt +++ b/extras/csv2wrl/CMakeLists.txt @@ -9,21 +9,9 @@ if(Coin_FOUND AND Eigen3_FOUND) csv2wrl.cpp ) - target_compile_definitions( - csv2wrl - PUBLIC - ${Coin_DEFINITIONS} - ) - - target_include_directories( - csv2wrl - PUBLIC - ${Coin_INCLUDE_DIRS} - ${EIGEN3_INCLUDE_DIRS} - ) - target_link_libraries( csv2wrl - ${Coin_LIBRARIES} + Coin::Coin + Eigen3::Eigen ) endif() diff --git a/extras/tris2wrl/CMakeLists.txt b/extras/tris2wrl/CMakeLists.txt index d20269d6..6c0c669c 100644 --- a/extras/tris2wrl/CMakeLists.txt +++ b/extras/tris2wrl/CMakeLists.txt @@ -9,21 +9,9 @@ if(Coin_FOUND) tris2wrl.cpp ) - target_compile_definitions( - tris2wrl - PUBLIC - ${Coin_DEFINITIONS} - ) - - target_include_directories( - tris2wrl - PUBLIC - ${Boost_INCLUDE_DIRS} - ${Coin_INCLUDE_DIRS} - ) - target_link_libraries( tris2wrl - ${Coin_LIBRARIES} + Boost::headers + Coin::Coin ) endif() diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 77f3669c..5713a73a 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -13,13 +13,10 @@ if(RL_USE_QT5 AND SoQt_HAVE_QT5) endif() if(Qt5_FOUND) - set(QT_LIBRARIES ${Qt5Core_LIBRARIES} ${Qt5Gui_LIBRARIES} ${Qt5OpenGL_LIBRARIES} ${Qt5Network_LIBRARIES} ${Qt5Widgets_LIBRARIES}) set(QT_FOUND Qt5_FOUND) else() set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtNetwork QtOpenGL) - set(QT_USE_QTMAIN ON) - include(${QT_USE_FILE}) endif() set(CMAKE_AUTOMOC ON) @@ -42,17 +39,8 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) ${CMAKE_CURRENT_BINARY_DIR}/wrlview.rc ) - target_compile_definitions( - wrlview - PRIVATE - ${Coin_DEFINITIONS} - ${SoQt_DEFINITIONS} - ) - cmake_push_check_state(RESET) - set(CMAKE_REQUIRED_DEFINITIONS ${Coin_DEFINITIONS}) - set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) - set(CMAKE_REQUIRED_LIBRARIES ${Coin_LIBRARIES}) + set(CMAKE_REQUIRED_LIBRARIES Coin::Coin) check_include_file_cxx(ForeignFiles/SoSTLFileKit.h HAVE_SOSTLFILEKIT_H) if(HAVE_SOSTLFILEKIT_H) target_compile_definitions(wrlview PRIVATE HAVE_SOSTLFILEKIT_H) @@ -66,22 +54,25 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) endif() cmake_pop_check_state() - target_include_directories( - wrlview - PRIVATE - ${Coin_INCLUDE_DIRS} - ${OPENGL_INCLUDE_DIR} - ${SoQt_INCLUDE_DIRS} - ) - target_link_libraries( wrlview - ${Coin_LIBRARIES} - ${OPENGL_LIBRARIES} - ${QT_LIBRARIES} - ${SoQt_LIBRARIES} + Coin::Coin + SoQt::SoQt ) + if(TARGET OpenGL::GL) + target_link_libraries(wrlview OpenGL::GL) + else() + target_include_directories(wrlview PRIVATE ${OPENGL_INCLUDE_DIRS}) + target_link_libraries(wrlview ${OPENGL_LIBRARIES}) + endif() + + if(Qt5_FOUND) + target_link_libraries(wrlview Qt5::Core Qt5::Gui Qt5::Network Qt5::OpenGL Qt5::Widgets) + elseif(Qt4_FOUND) + target_link_libraries(wrlview Qt4::QtCore Qt4::QtGui Qt4::QtNetwork Qt4::QtOpenGL) + endif() + set_target_properties( wrlview PROPERTIES diff --git a/rl-config.cmake.in b/rl-config.cmake.in index 7ee2d514..d6079559 100644 --- a/rl-config.cmake.in +++ b/rl-config.cmake.in @@ -18,9 +18,12 @@ set(RL_XML_FOUND @RL_BUILD_XML@) include("${CMAKE_CURRENT_LIST_DIR}/rl-export.cmake") -set(RL_DEFINITIONS "@RL_DEFINITIONS@") -set(RL_INCLUDE_DIRS "@RL_INCLUDE_DIRS@") -set(RL_LIBRARY_DIRS "@RL_LIBRARY_DIRS@") +check_required_components(RL) + set(RL_LIBRARIES "@RL_LIBRARIES@") -check_required_components(RL) +list(APPEND CMAKE_MODULE_PATH ${CMAKE_CURRENT_LIST_DIR}) + +include(CMakeFindDependencyMacro) + +@FIND_DEPENDENCIES@ diff --git a/src/rl/hal/CMakeLists.txt b/src/rl/hal/CMakeLists.txt index 4b0ccb6d..49f91e55 100644 --- a/src/rl/hal/CMakeLists.txt +++ b/src/rl/hal/CMakeLists.txt @@ -184,33 +184,29 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> - ${Boost_INCLUDE_DIRS} ) target_link_libraries( hal math util + Boost::headers ) if(RL_BUILD_HAL_ATIDAQ) - target_include_directories(hal PUBLIC ${ATIDAQ_INCLUDE_DIRS}) - target_link_libraries(hal ${ATIDAQ_LIBRARIES}) + target_link_libraries(hal ATIDAQ::ATIDAQ) endif() if(RL_BUILD_HAL_CIFX) - target_include_directories(hal PUBLIC ${CIFX_INCLUDE_DIRS}) - target_link_libraries(hal ${CIFX_LIBRARIES}) + target_link_libraries(hal cifX::cifX) endif() if(RL_BUILD_HAL_COMEDI) - target_include_directories(hal PUBLIC ${COMEDI_INCLUDE_DIRS}) - target_link_libraries(hal ${COMEDI_LIBRARIES}) + target_link_libraries(hal Comedi::Comedi) endif() if(RL_BUILD_HAL_LIBDC1394) - target_include_directories(hal PUBLIC ${LIBDC1394_INCLUDE_DIRS}) - target_link_libraries(hal ${LIBDC1394_LIBRARIES}) + target_link_libraries(hal libdc1394::libdc1394) endif() if(QNXNTO) diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index 01a826ad..997a7555 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -47,7 +47,6 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> - ${Boost_INCLUDE_DIRS} ) target_link_libraries( @@ -55,6 +54,7 @@ target_link_libraries( math std xml + Boost::headers ) set_target_properties( diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index c6257c62..bd9737fc 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -83,14 +83,14 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> - ${Boost_INCLUDE_DIRS} - ${EIGEN3_INCLUDE_DIRS} ) target_link_libraries( math INTERFACE std + Boost::headers + Eigen3::Eigen ) if(NOT CMAKE_VERSION VERSION_LESS 3.19) diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index 8f2fc9df..cf5b801b 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -91,7 +91,6 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> - ${Boost_INCLUDE_DIRS} ) target_link_libraries( @@ -99,12 +98,12 @@ target_link_libraries( math std xml + Boost::headers ) if(RL_BUILD_MDL_NLOPT) target_compile_definitions(mdl INTERFACE RL_MDL_NLOPT) - target_include_directories(mdl PUBLIC ${NLOPT_INCLUDE_DIRS}) - target_link_libraries(mdl ${NLOPT_LIBRARY}) + target_link_libraries(mdl NLopt::nlopt) endif() set_target_properties( diff --git a/src/rl/plan/CMakeLists.txt b/src/rl/plan/CMakeLists.txt index 06e4ca79..2c30fcd3 100644 --- a/src/rl/plan/CMakeLists.txt +++ b/src/rl/plan/CMakeLists.txt @@ -105,7 +105,6 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> - ${Boost_INCLUDE_DIRS} ) target_link_libraries( @@ -116,6 +115,7 @@ target_link_libraries( sg util xml + Boost::headers ) set_target_properties( diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index dc7033d0..f47a00bb 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -197,16 +197,12 @@ target_link_libraries( if(RL_BUILD_SG_BULLET) target_compile_definitions(sg INTERFACE RL_SG_BULLET) - target_compile_definitions(sg PUBLIC ${BULLET_DEFINITIONS}) - target_include_directories(sg PUBLIC ${BULLET_INCLUDE_DIRS}) - target_link_libraries(sg ${BULLET_LIBRARIES}) + target_link_libraries(sg Bullet::BulletCollision Bullet::BulletDynamics Bullet::BulletSoftBody Bullet::LinearMath) endif() if(Coin_FOUND) cmake_push_check_state(RESET) - set(CMAKE_REQUIRED_DEFINITIONS ${Coin_DEFINITIONS}) - set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) - set(CMAKE_REQUIRED_LIBRARIES ${Coin_LIBRARIES}) + set(CMAKE_REQUIRED_LIBRARIES Coin::Coin) check_include_file_cxx(ForeignFiles/SoSTLFileKit.h HAVE_SOSTLFILEKIT_H) if(HAVE_SOSTLFILEKIT_H) target_compile_definitions(sg PRIVATE HAVE_SOSTLFILEKIT_H) @@ -219,35 +215,27 @@ if(Coin_FOUND) endif() endif() cmake_pop_check_state() - target_compile_definitions(sg PUBLIC ${Coin_DEFINITIONS}) - target_include_directories(sg PUBLIC ${Coin_INCLUDE_DIRS}) - target_link_libraries(sg ${Coin_LIBRARIES}) + target_link_libraries(sg Coin::Coin) endif() if(RL_BUILD_SG_FCL) target_compile_definitions(sg INTERFACE RL_SG_FCL) - target_compile_definitions(sg PUBLIC ${FCL_DEFINITIONS}) - target_include_directories(sg PUBLIC ${FCL_INCLUDE_DIRS}) - target_link_libraries(sg ${FCL_LIBRARIES}) + target_link_libraries(sg fcl::fcl) endif() if(RL_BUILD_SG_ODE) target_compile_definitions(sg INTERFACE RL_SG_ODE) - target_compile_definitions(sg PUBLIC ${ODE_DEFINITIONS}) - target_include_directories(sg PUBLIC ${ODE_INCLUDE_DIRS}) - target_link_libraries(sg ${ODE_LIBRARIES}) + target_link_libraries(sg ODE::ODE) endif() if(RL_BUILD_SG_PQP) target_compile_definitions(sg INTERFACE RL_SG_PQP) - target_include_directories(sg PUBLIC ${PQP_INCLUDE_DIRS}) - target_link_libraries(sg ${PQP_LIBRARIES}) + target_link_libraries(sg PQP::PQP) endif() if(RL_BUILD_SG_SOLID) target_compile_definitions(sg INTERFACE RL_SG_SOLID) - target_include_directories(sg PUBLIC ${SOLID3_INCLUDE_DIRS}) - target_link_libraries(sg ${SOLID3_LIBRARIES}) + target_link_libraries(sg solid3::solid3) endif() set_target_properties( diff --git a/src/rl/xml/CMakeLists.txt b/src/rl/xml/CMakeLists.txt index 32095951..a7ecd3c3 100644 --- a/src/rl/xml/CMakeLists.txt +++ b/src/rl/xml/CMakeLists.txt @@ -34,12 +34,9 @@ target_include_directories( $ $ $/${CMAKE_INSTALL_INCLUDEDIR}/rl-${PROJECT_VERSION}> - ${Boost_INCLUDE_DIRS} - ${LIBXML2_INCLUDE_DIRS} - ${LIBXSLT_INCLUDE_DIRS} ) -target_link_libraries(xml INTERFACE ${LIBXML2_LIBRARIES} ${LIBXSLT_LIBRARIES}) +target_link_libraries(xml INTERFACE Boost::headers LibXml2::LibXml2 LibXslt::LibXslt) if(NOT CMAKE_VERSION VERSION_LESS 3.19) set_target_properties( diff --git a/tests/rlCollisionTest/CMakeLists.txt b/tests/rlCollisionTest/CMakeLists.txt index f4b99206..f4ebbc7d 100644 --- a/tests/rlCollisionTest/CMakeLists.txt +++ b/tests/rlCollisionTest/CMakeLists.txt @@ -7,16 +7,11 @@ if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUILD_SG_ODE OR RL_BUILD_SG_PQP O ${rl_BINARY_DIR}/robotics-library.rc ) - target_include_directories( - rlCollisionTest - PUBLIC - ${Boost_INCLUDE_DIRS} - ) - target_link_libraries( rlCollisionTest mdl sg + Boost::headers ) add_test( diff --git a/tests/rlEetTest/CMakeLists.txt b/tests/rlEetTest/CMakeLists.txt index da77d21f..6bbfab0b 100644 --- a/tests/rlEetTest/CMakeLists.txt +++ b/tests/rlEetTest/CMakeLists.txt @@ -7,17 +7,12 @@ if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUILD_SG_PQP OR RL_BUILD_SG_SOLID ${rl_BINARY_DIR}/robotics-library.rc ) - target_include_directories( - rlEetTest - PUBLIC - ${Boost_INCLUDE_DIRS} - ) - target_link_libraries( rlEetTest plan kin sg + Boost::headers ) if(RL_BUILD_SG_BULLET) diff --git a/tests/rlNearestNeighborsTest/CMakeLists.txt b/tests/rlNearestNeighborsTest/CMakeLists.txt index 7d809dea..a5ec4303 100644 --- a/tests/rlNearestNeighborsTest/CMakeLists.txt +++ b/tests/rlNearestNeighborsTest/CMakeLists.txt @@ -7,15 +7,10 @@ add_executable( ${rl_BINARY_DIR}/robotics-library.rc ) -target_include_directories( - rlNearestNeighborsTest - PUBLIC - ${Boost_INCLUDE_DIRS} -) - target_link_libraries( rlNearestNeighborsTest math + Boost::headers ) add_test( diff --git a/tests/rlPrmTest/CMakeLists.txt b/tests/rlPrmTest/CMakeLists.txt index ae3b1790..fd94bdc8 100644 --- a/tests/rlPrmTest/CMakeLists.txt +++ b/tests/rlPrmTest/CMakeLists.txt @@ -7,17 +7,12 @@ if(RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUILD_SG_ODE OR RL_BUILD_SG_PQP O ${rl_BINARY_DIR}/robotics-library.rc ) - target_include_directories( - rlPrmTest - PUBLIC - ${Boost_INCLUDE_DIRS} - ) - target_link_libraries( rlPrmTest plan kin sg + Boost::headers ) if(RL_BUILD_SG_BULLET) From 86895cb24871a1957887e9374d727895110bf2a4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 25 Jan 2021 19:54:39 +0100 Subject: [PATCH 439/546] Add visualization option for path vertices --- demos/rlPlanDemo/MainWindow.cpp | 22 +++-- demos/rlPlanDemo/MainWindow.h | 4 +- demos/rlPlanDemo/Viewer.cpp | 151 ++++++++++++++++++++++++-------- demos/rlPlanDemo/Viewer.h | 36 ++++++-- 4 files changed, 161 insertions(+), 52 deletions(-) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index fe1b7ac7..eb1e2ece 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -180,7 +180,8 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : toggleConfigurationSpaceSceneAction(new QAction(this)), toggleConfigurationVerticesAction(new QAction(this)), toggleLinesAction(new QAction(this)), - togglePathAction(new QAction(this)), + togglePathEdgesAction(new QAction(this)), + togglePathVerticesAction(new QAction(this)), togglePlannerAction(new QAction(this)), togglePointsAction(new QAction(this)), toggleSpheresAction(new QAction(this)), @@ -701,12 +702,19 @@ MainWindow::init() viewMenu->addSeparator(); - this->togglePathAction->setCheckable(true); - this->togglePathAction->setChecked(true); - this->togglePathAction->setText("Path"); - QObject::connect(this->togglePathAction, SIGNAL(toggled(bool)), this->viewer, SLOT(togglePath(bool))); - this->addAction(this->togglePathAction); - viewMenu->addAction(this->togglePathAction); + this->togglePathEdgesAction->setCheckable(true); + this->togglePathEdgesAction->setChecked(true); + this->togglePathEdgesAction->setText("Path Edges"); + QObject::connect(this->togglePathEdgesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(togglePathEdges(bool))); + this->addAction(this->togglePathEdgesAction); + viewMenu->addAction(this->togglePathEdgesAction); + + this->togglePathVerticesAction->setCheckable(true); + this->togglePathVerticesAction->setChecked(false); + this->togglePathVerticesAction->setText("Path Vertices"); + QObject::connect(this->togglePathVerticesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(togglePathVertices(bool))); + this->addAction(this->togglePathVerticesAction); + viewMenu->addAction(this->togglePathVerticesAction); this->toggleAnimationAction->setCheckable(true); this->toggleAnimationAction->setChecked(true); diff --git a/demos/rlPlanDemo/MainWindow.h b/demos/rlPlanDemo/MainWindow.h index 4d2ded7b..73d58ee4 100644 --- a/demos/rlPlanDemo/MainWindow.h +++ b/demos/rlPlanDemo/MainWindow.h @@ -267,7 +267,9 @@ public slots: QAction* toggleLinesAction; - QAction* togglePathAction; + QAction* togglePathEdgesAction; + + QAction* togglePathVerticesAction; QAction* togglePlannerAction; diff --git a/demos/rlPlanDemo/Viewer.cpp b/demos/rlPlanDemo/Viewer.cpp index 3d00c762..c48a6c77 100644 --- a/demos/rlPlanDemo/Viewer.cpp +++ b/demos/rlPlanDemo/Viewer.cpp @@ -80,12 +80,20 @@ Viewer::Viewer(QWidget* parent, Qt::WindowFlags f) : linesMaterial(new SoVRMLMaterial()), linesShape(new SoVRMLShape()), path(new SoVRMLSwitch()), - pathAppearance(new SoVRMLAppearance()), - pathCoordinate(new SoVRMLCoordinate()), - pathDrawStyle(new SoDrawStyle()), - pathIndexedLineSet(new SoVRMLIndexedLineSet()), - pathMaterial(new SoVRMLMaterial()), - pathShape(new SoVRMLShape()), + pathEdges(new SoVRMLSwitch()), + pathEdgesAppearance(new SoVRMLAppearance()), + pathEdgesCoordinate(new SoVRMLCoordinate()), + pathEdgesDrawStyle(new SoDrawStyle()), + pathEdgesIndexedLineSet(new SoVRMLIndexedLineSet()), + pathEdgesMaterial(new SoVRMLMaterial()), + pathEdgesShape(new SoVRMLShape()), + pathVertices(new SoVRMLSwitch()), + pathVerticesAppearance(new SoVRMLAppearance()), + pathVerticesCoordinate(new SoVRMLCoordinate()), + pathVerticesDrawStyle(new SoDrawStyle()), + pathVerticesPointSet(new SoVRMLPointSet()), + pathVerticesMaterial(new SoVRMLMaterial()), + pathVerticesShape(new SoVRMLShape()), path3(new SoVRMLSwitch()), path3Appearance(new SoVRMLAppearance()), path3Coordinate(new SoVRMLCoordinate()), @@ -270,20 +278,47 @@ Viewer::Viewer(QWidget* parent, Qt::WindowFlags f) : this->path->setName("path"); this->path->whichChoice = SO_SWITCH_ALL; - this->pathDrawStyle->lineWidth = 3.0f; - this->pathDrawStyle->pointSize = 0.0f; - this->path->addChild(this->pathDrawStyle); + this->root->addChild(this->path); - this->pathMaterial->diffuseColor.setValue(55.0f / 255.0f, 176.0f / 255.0f, 55.0f / 255.0f); - this->pathAppearance->material = this->pathMaterial; - this->pathShape->appearance = this->pathAppearance; + // path edges - this->pathIndexedLineSet->coord = this->pathCoordinate; - this->pathShape->geometry = this->pathIndexedLineSet; + this->pathEdges->setName("pathEdges"); + this->pathEdges->whichChoice = SO_SWITCH_ALL; - this->path->addChild(this->pathShape); + this->pathEdgesDrawStyle->lineWidth = 3.0f; + this->pathEdgesDrawStyle->pointSize = 0.0f; + this->pathEdges->addChild(this->pathEdgesDrawStyle); - this->root->addChild(this->path); + this->pathEdgesMaterial->diffuseColor.setValue(55.0f / 255.0f, 176.0f / 255.0f, 55.0f / 255.0f); + this->pathEdgesAppearance->material = this->pathEdgesMaterial; + this->pathEdgesShape->appearance = this->pathEdgesAppearance; + + this->pathEdgesIndexedLineSet->coord = this->pathEdgesCoordinate; + this->pathEdgesShape->geometry = this->pathEdgesIndexedLineSet; + + this->pathEdges->addChild(this->pathEdgesShape); + + this->path->addChild(this->pathEdges); + + // path vertices + + this->pathVertices->setName("pathVertices"); + this->pathVertices->whichChoice = SO_SWITCH_NONE; + + this->pathVerticesDrawStyle->lineWidth = 0.0f; + this->pathVerticesDrawStyle->pointSize = 8.0f; + this->pathVertices->addChild(this->pathVerticesDrawStyle); + + this->pathVerticesMaterial->emissiveColor.setValue(55.0f / 255.0f, 176.0f / 255.0f, 55.0f / 255.0f); + this->pathVerticesAppearance->material = this->pathVerticesMaterial; + this->pathVerticesShape->appearance = this->pathVerticesAppearance; + + this->pathVerticesPointSet->coord = this->pathVerticesCoordinate; + this->pathVerticesShape->geometry = this->pathVerticesPointSet; + + this->pathVertices->addChild(this->pathVerticesShape); + + this->path->addChild(this->pathVertices); // path3 @@ -505,8 +540,10 @@ Viewer::drawConfigurationPath(const rl::plan::VectorList& path) { this->path->enableNotify(false); - this->pathCoordinate->point.setNum(0); - this->pathIndexedLineSet->coordIndex.setNum(0); + this->pathEdgesCoordinate->point.setNum(0); + this->pathEdgesIndexedLineSet->coordIndex.setNum(0); + + this->pathVerticesCoordinate->point.setNum(0); rl::math::Vector inter(this->model->getDofPosition()); @@ -520,16 +557,23 @@ Viewer::drawConfigurationPath(const rl::plan::VectorList& path) this->model->setPosition(*i); this->model->updateFrames(); - this->pathCoordinate->point.set1Value( - this->pathCoordinate->point.getNum(), + this->pathEdgesCoordinate->point.set1Value( + this->pathEdgesCoordinate->point.getNum(), this->model->forwardPosition(l)(0, 3), this->model->forwardPosition(l)(1, 3), this->model->forwardPosition(l)(2, 3) ); - this->pathIndexedLineSet->coordIndex.set1Value( - this->pathIndexedLineSet->coordIndex.getNum(), - this->pathCoordinate->point.getNum() - 1 + this->pathEdgesIndexedLineSet->coordIndex.set1Value( + this->pathEdgesIndexedLineSet->coordIndex.getNum(), + this->pathEdgesCoordinate->point.getNum() - 1 + ); + + this->pathVerticesCoordinate->point.set1Value( + this->pathVerticesCoordinate->point.getNum(), + this->model->forwardPosition(l)(0, 3), + this->model->forwardPosition(l)(1, 3), + this->model->forwardPosition(l)(2, 3) ); } @@ -544,22 +588,29 @@ Viewer::drawConfigurationPath(const rl::plan::VectorList& path) this->model->setPosition(inter); this->model->updateFrames(false); - this->pathCoordinate->point.set1Value( - this->pathCoordinate->point.getNum(), + this->pathEdgesCoordinate->point.set1Value( + this->pathEdgesCoordinate->point.getNum(), this->model->forwardPosition(l)(0, 3), this->model->forwardPosition(l)(1, 3), this->model->forwardPosition(l)(2, 3) ); - this->pathIndexedLineSet->coordIndex.set1Value( - this->pathIndexedLineSet->coordIndex.getNum(), - this->pathCoordinate->point.getNum() - 1 + this->pathEdgesIndexedLineSet->coordIndex.set1Value( + this->pathEdgesIndexedLineSet->coordIndex.getNum(), + this->pathEdgesCoordinate->point.getNum() - 1 ); } + + this->pathVerticesCoordinate->point.set1Value( + this->pathVerticesCoordinate->point.getNum(), + this->model->forwardPosition(l)(0, 3), + this->model->forwardPosition(l)(1, 3), + this->model->forwardPosition(l)(2, 3) + ); } - this->pathIndexedLineSet->coordIndex.set1Value( - this->pathIndexedLineSet->coordIndex.getNum(), + this->pathEdgesIndexedLineSet->coordIndex.set1Value( + this->pathEdgesIndexedLineSet->coordIndex.getNum(), SO_END_FACE_INDEX ); } @@ -855,13 +906,11 @@ Viewer::reset() { this->resetEdges(); this->resetLines(); + this->resetPath(); + this->resetPath3(); this->resetPoints(); this->resetSpheres(); this->resetVertices(); - this->pathCoordinate->point.setNum(0); - this->pathIndexedLineSet->coordIndex.setNum(0); - this->path3Coordinate->point.setNum(0); - this->path3IndexedLineSet->coordIndex.setNum(0); this->sweptGroup->removeAllChildren(); this->workTransform->setMatrix(SbMatrix::identity()); } @@ -884,6 +933,21 @@ Viewer::resetLines() this->linesIndexedLineSet->coordIndex.setNum(0); } +void +Viewer::resetPath() +{ + this->pathEdgesCoordinate->point.setNum(0); + this->pathEdgesIndexedLineSet->coordIndex.setNum(0); + this->pathVerticesCoordinate->point.setNum(0); +} + +void +Viewer::resetPath3() +{ + this->path3Coordinate->point.setNum(0); + this->path3IndexedLineSet->coordIndex.setNum(0); +} + void Viewer::resetPoints() { @@ -1015,15 +1079,28 @@ Viewer::toggleLines(const bool& doOn) } void -Viewer::togglePath(const bool& doOn) +Viewer::togglePathEdges(const bool& doOn) +{ + if (doOn) + { + this->pathEdges->whichChoice = SO_SWITCH_ALL; + } + else + { + this->pathEdges->whichChoice = SO_SWITCH_NONE; + } +} + +void +Viewer::togglePathVertices(const bool& doOn) { if (doOn) { - this->path->whichChoice = SO_SWITCH_ALL; + this->pathVertices->whichChoice = SO_SWITCH_ALL; } else { - this->path->whichChoice = SO_SWITCH_NONE; + this->pathVertices->whichChoice = SO_SWITCH_NONE; } } diff --git a/demos/rlPlanDemo/Viewer.h b/demos/rlPlanDemo/Viewer.h index 439797d0..366c729f 100644 --- a/demos/rlPlanDemo/Viewer.h +++ b/demos/rlPlanDemo/Viewer.h @@ -98,6 +98,10 @@ public slots: void resetLines(); + void resetPath(); + + void resetPath3(); + void resetPoints(); void resetSpheres(); @@ -116,7 +120,9 @@ public slots: void toggleLines(const bool& doOn); - void togglePath(const bool& doOn); + void togglePathEdges(const bool& doOn); + + void togglePathVertices(const bool& doOn); void togglePoints(const bool& doOn); @@ -195,17 +201,33 @@ public slots: SoVRMLSwitch* path; - SoVRMLAppearance* pathAppearance; + SoVRMLSwitch* pathEdges; + + SoVRMLAppearance* pathEdgesAppearance; + + SoVRMLCoordinate* pathEdgesCoordinate; + + SoDrawStyle* pathEdgesDrawStyle; + + SoVRMLIndexedLineSet* pathEdgesIndexedLineSet; + + SoVRMLMaterial* pathEdgesMaterial; + + SoVRMLShape* pathEdgesShape; + + SoVRMLSwitch* pathVertices; + + SoVRMLAppearance* pathVerticesAppearance; - SoVRMLCoordinate* pathCoordinate; + SoVRMLCoordinate* pathVerticesCoordinate; - SoDrawStyle* pathDrawStyle; + SoDrawStyle* pathVerticesDrawStyle; - SoVRMLIndexedLineSet* pathIndexedLineSet; + SoVRMLPointSet* pathVerticesPointSet; - SoVRMLMaterial* pathMaterial; + SoVRMLMaterial* pathVerticesMaterial; - SoVRMLShape* pathShape; + SoVRMLShape* pathVerticesShape; SoVRMLSwitch* path3; From 18024513ce88c0d2c79fe97d767a4b77b3b6444b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 19 Dec 2020 23:23:40 +0100 Subject: [PATCH 440/546] Add support for Qt6 --- CMakeLists.txt | 1 + demos/rlCoachKin/CMakeLists.txt | 16 +++++++---- demos/rlCoachKin/MainWindow.cpp | 18 ++++++++++++- demos/rlCoachMdl/CMakeLists.txt | 16 +++++++---- demos/rlCoachMdl/MainWindow.cpp | 27 ++++++++++++++++++- demos/rlCollisionDemo/CMakeLists.txt | 16 +++++++---- demos/rlPlanDemo/CMakeLists.txt | 16 +++++++---- demos/rlPlanDemo/MainWindow.cpp | 13 ++++++++- demos/rlPlanDemo/Viewer.cpp | 21 ++++++++++++++- demos/rlRotationConverterDemo/CMakeLists.txt | 16 +++++++---- demos/rlSimulator/CMakeLists.txt | 16 +++++++---- demos/rlSimulator/MainWindow.cpp | 18 ++++++++++++- demos/rlViewDemo/CMakeLists.txt | 16 +++++++---- extras/wrlview/CMakeLists.txt | 16 +++++++---- extras/wrlview/MainWindow.cpp | 28 +++++++++++++++++++- 15 files changed, 208 insertions(+), 46 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index c76d141b..ce6c6d1f 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -58,6 +58,7 @@ option(RL_BUILD_TESTS "Build tests" ON) option(RL_BUILD_UTIL "Build utility component" ON) option(RL_BUILD_XML "Build XML abstraction layer component" ON) option(RL_USE_QT5 "Prefer Qt5 over Qt4 if available" ON) +option(RL_USE_QT6 "Prefer Qt6 over Qt6 if available" ON) cmake_dependent_option(RL_BUILD_HAL "Build hardware abstraction layer component" ON "RL_BUILD_MATH;RL_BUILD_UTIL" OFF) cmake_dependent_option(RL_BUILD_KIN "Build Denavit-Hartenberg kinematics component" ON "RL_BUILD_MATH;RL_BUILD_XML" OFF) diff --git a/demos/rlCoachKin/CMakeLists.txt b/demos/rlCoachKin/CMakeLists.txt index 78ca0978..9257c5b3 100644 --- a/demos/rlCoachKin/CMakeLists.txt +++ b/demos/rlCoachKin/CMakeLists.txt @@ -1,13 +1,17 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt_HAVE_QT5) +if(RL_USE_QT6 AND SoQt_HAVE_QT6) + find_package(Qt6 COMPONENTS Core Gui Network OpenGL Widgets QUIET) + set(QT_FOUND ${Qt6_FOUND}) +endif() + +if(NOT Qt6_FOUND AND RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) + set(QT_FOUND ${Qt5_FOUND}) endif() -if(Qt5_FOUND) - set(QT_FOUND Qt5_FOUND) -else() +if(NOT Qt6_FOUND AND NOT Qt5_FOUND) set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtNetwork QtOpenGL) endif() @@ -64,7 +68,9 @@ if(QT_FOUND AND SoQt_FOUND) target_link_libraries(rlCoachKin ${OPENGL_LIBRARIES}) endif() - if(Qt5_FOUND) + if(Qt6_FOUND) + target_link_libraries(rlCoachKin Qt6::Core Qt6::Gui Qt6::OpenGL Qt6::Network Qt6::Widgets) + elseif(Qt5_FOUND) target_link_libraries(rlCoachKin Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Network Qt5::Widgets) elseif(Qt4_FOUND) target_link_libraries(rlCoachKin Qt4::QtCore Qt4::QtGui Qt4::QtNetwork Qt4::QtOpenGL) diff --git a/demos/rlCoachKin/MainWindow.cpp b/demos/rlCoachKin/MainWindow.cpp index c9723706..d7b339b6 100644 --- a/demos/rlCoachKin/MainWindow.cpp +++ b/demos/rlCoachKin/MainWindow.cpp @@ -26,12 +26,17 @@ #include #include -#include #include #include #include #include +#if QT_VERSION >= 0x060000 +#include +#else +#include +#endif + #include "ConfigurationDelegate.h" #include "ConfigurationModel.h" #include "MainWindow.h" @@ -65,10 +70,16 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoDB::init(); SoGradientBackground::initClass(); +#if QT_VERSION >= 0x060000 + QSurfaceFormat format; + format.setSamples(8); + QSurfaceFormat::setDefaultFormat(format); +#else QGLFormat format; format.setAlpha(true); format.setSampleBuffers(true); QGLFormat::setDefaultFormat(format); +#endif this->scene = std::make_shared(); rl::sg::XmlFactory geometryFactory; @@ -229,7 +240,12 @@ MainWindow::saveImage(bool withAlpha) } glReadBuffer(GL_FRONT); + +#if QT_VERSION >= 0x060000 + QImage image = this->viewer->getGLWidget()->property("SoQtGLArea").value()->grabFramebuffer(); +#else QImage image = static_cast(this->viewer->getGLWidget())->grabFrameBuffer(withAlpha); +#endif if (withAlpha) { diff --git a/demos/rlCoachMdl/CMakeLists.txt b/demos/rlCoachMdl/CMakeLists.txt index e0f4b50f..59502160 100644 --- a/demos/rlCoachMdl/CMakeLists.txt +++ b/demos/rlCoachMdl/CMakeLists.txt @@ -1,13 +1,17 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt_HAVE_QT5) +if(RL_USE_QT6 AND SoQt_HAVE_QT6) + find_package(Qt6 COMPONENTS Core Gui Network OpenGL Widgets QUIET) + set(QT_FOUND ${Qt6_FOUND}) +endif() + +if(NOT Qt6_FOUND AND RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) + set(QT_FOUND ${Qt5_FOUND}) endif() -if(Qt5_FOUND) - set(QT_FOUND Qt5_FOUND) -else() +if(NOT Qt6_FOUND AND NOT Qt5_FOUND) set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtNetwork QtOpenGL) endif() @@ -64,7 +68,9 @@ if(QT_FOUND AND SoQt_FOUND) target_link_libraries(rlCoachMdl ${OPENGL_LIBRARIES}) endif() - if(Qt5_FOUND) + if(Qt6_FOUND) + target_link_libraries(rlCoachMdl Qt6::Core Qt6::Gui Qt6::OpenGL Qt6::Network Qt6::Widgets) + elseif(Qt5_FOUND) target_link_libraries(rlCoachMdl Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Network Qt5::Widgets) elseif(Qt4_FOUND) target_link_libraries(rlCoachMdl Qt4::QtCore Qt4::QtGui Qt4::QtNetwork Qt4::QtOpenGL) diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index 33555520..e24293f9 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -26,7 +26,6 @@ #include #include -#include #include #include #include @@ -36,6 +35,12 @@ #include #include +#if QT_VERSION >= 0x060000 +#include +#else +#include +#endif + #include "ConfigurationDelegate.h" #include "ConfigurationModel.h" #include "MainWindow.h" @@ -77,10 +82,16 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoDB::init(); SoGradientBackground::initClass(); +#if QT_VERSION >= 0x060000 + QSurfaceFormat format; + format.setSamples(8); + QSurfaceFormat::setDefaultFormat(format); +#else QGLFormat format; format.setAlpha(true); format.setSampleBuffers(true); QGLFormat::setDefaultFormat(format); +#endif std::shared_ptr geometryFactory; std::string geometryFilename = QApplication::arguments()[1].toStdString(); @@ -317,7 +328,21 @@ MainWindow::saveImage(bool withAlpha) } glReadBuffer(GL_FRONT); + +#if QT_VERSION >= 0x060000 + QOpenGLWindow* window = this->viewer->getGLWidget()->property("SoQtGLArea").value(); + QSurfaceFormat surfaceFormat = window->format(); + + if (withAlpha != surfaceFormat.hasAlpha()) + { + surfaceFormat.setAlphaBufferSize(withAlpha ? 8 : 0); + window->setFormat(surfaceFormat); + } + + QImage image = window->grabFramebuffer(); +#else QImage image = static_cast(this->viewer->getGLWidget())->grabFrameBuffer(withAlpha); +#endif if (withAlpha) { diff --git a/demos/rlCollisionDemo/CMakeLists.txt b/demos/rlCollisionDemo/CMakeLists.txt index 3b455184..d791d02c 100644 --- a/demos/rlCollisionDemo/CMakeLists.txt +++ b/demos/rlCollisionDemo/CMakeLists.txt @@ -1,13 +1,17 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt_HAVE_QT5) +if(RL_USE_QT6 AND SoQt_HAVE_QT6) + find_package(Qt6 COMPONENTS Core Gui OpenGL Widgets QUIET) + set(QT_FOUND ${Qt6_FOUND}) +endif() + +if(NOT Qt6_FOUND AND RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui OpenGL Widgets QUIET) + set(QT_FOUND ${Qt5_FOUND}) endif() -if(Qt5_FOUND) - set(QT_FOUND Qt5_FOUND) -else() +if(NOT Qt6_FOUND AND NOT Qt5_FOUND) set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtOpenGL) endif() @@ -54,7 +58,9 @@ if(QT_FOUND AND SoQt_FOUND AND (RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUIL target_link_libraries(rlCollisionDemo ${OPENGL_LIBRARIES}) endif() - if(Qt5_FOUND) + if(Qt6_FOUND) + target_link_libraries(rlCollisionDemo Qt6::Core Qt6::Gui Qt6::OpenGL Qt6::Widgets) + elseif(Qt5_FOUND) target_link_libraries(rlCollisionDemo Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Widgets) elseif(Qt4_FOUND) target_link_libraries(rlCollisionDemo Qt4::QtCore Qt4::QtGui Qt4::QtOpenGL) diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index 6488d1c0..b3f33d81 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -2,13 +2,17 @@ find_package(Boost REQUIRED) find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt_HAVE_QT5) +if(RL_USE_QT6 AND SoQt_HAVE_QT6) + find_package(Qt6 COMPONENTS Core Gui OpenGL PrintSupport Widgets QUIET) + set(QT_FOUND ${Qt6_FOUND}) +endif() + +if(NOT Qt6_FOUND AND RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui OpenGL PrintSupport Widgets QUIET) + set(QT_FOUND ${Qt5_FOUND}) endif() -if(Qt5_FOUND) - set(QT_FOUND Qt5_FOUND) -else() +if(NOT Qt6_FOUND AND NOT Qt5_FOUND) set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtOpenGL) endif() @@ -72,7 +76,9 @@ if(QT_FOUND AND SoQt_FOUND AND (RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUIL target_link_libraries(rlPlanDemo ${OPENGL_LIBRARIES}) endif() - if(Qt5_FOUND) + if(Qt6_FOUND) + target_link_libraries(rlPlanDemo Qt6::Core Qt6::Gui Qt6::OpenGL Qt6::PrintSupport Qt6::Widgets) + elseif(Qt5_FOUND) target_link_libraries(rlPlanDemo Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::PrintSupport Qt5::Widgets) elseif(Qt4_FOUND) target_link_libraries(rlPlanDemo Qt4::QtCore Qt4::QtGui Qt4::QtOpenGL) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index eb1e2ece..3d78f4df 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -29,7 +29,6 @@ #include #include #include -#include #include #include #include @@ -85,6 +84,12 @@ #include #endif +#if QT_VERSION >= 0x060000 +#include +#else +#include +#endif + #ifdef RL_SG_BULLET #include #endif // RL_SG_BULLET @@ -196,10 +201,16 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoDB::init(); SoGradientBackground::initClass(); +#if QT_VERSION >= 0x060000 + QSurfaceFormat format; + format.setSamples(8); + QSurfaceFormat::setDefaultFormat(format); +#else QGLFormat format; format.setAlpha(true); format.setSampleBuffers(true); QGLFormat::setDefaultFormat(format); +#endif this->viewer = new Viewer(this); this->setCentralWidget(this->viewer); diff --git a/demos/rlPlanDemo/Viewer.cpp b/demos/rlPlanDemo/Viewer.cpp index c48a6c77..f6b21c99 100644 --- a/demos/rlPlanDemo/Viewer.cpp +++ b/demos/rlPlanDemo/Viewer.cpp @@ -25,7 +25,6 @@ // #include -#include #include #include #include @@ -36,6 +35,12 @@ #include #include +#if QT_VERSION >= 0x060000 +#include +#else +#include +#endif + #include "SoGradientBackground.h" #include "MainWindow.h" #include "Viewer.h" @@ -981,7 +986,21 @@ Viewer::saveImage(bool withAlpha) } glReadBuffer(GL_FRONT); + +#if QT_VERSION >= 0x060000 + QOpenGLWindow* window = this->viewer->getGLWidget()->property("SoQtGLArea").value(); + QSurfaceFormat surfaceFormat = window->format(); + + if (withAlpha != surfaceFormat.hasAlpha()) + { + surfaceFormat.setAlphaBufferSize(withAlpha ? 8 : 0); + window->setFormat(surfaceFormat); + } + + QImage image = window->grabFramebuffer(); +#else QImage image = static_cast(this->viewer->getGLWidget())->grabFrameBuffer(withAlpha); +#endif if (withAlpha) { diff --git a/demos/rlRotationConverterDemo/CMakeLists.txt b/demos/rlRotationConverterDemo/CMakeLists.txt index 7533acd7..502af1a0 100644 --- a/demos/rlRotationConverterDemo/CMakeLists.txt +++ b/demos/rlRotationConverterDemo/CMakeLists.txt @@ -1,10 +1,14 @@ -if(RL_USE_QT5) +if(RL_USE_QT6) + find_package(Qt6 COMPONENTS Core Gui Widgets QUIET) + set(QT_FOUND ${Qt6_FOUND}) +endif() + +if(NOT Qt6_FOUND AND RL_USE_QT5) find_package(Qt5 COMPONENTS Core Gui Widgets QUIET) + set(QT_FOUND ${Qt5_FOUND}) endif() -if(Qt5_FOUND) - set(QT_FOUND Qt5_FOUND) -else() +if(NOT Qt6_FOUND AND NOT Qt5_FOUND) set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui) endif() @@ -50,7 +54,9 @@ if(QT_FOUND) math ) - if(Qt5_FOUND) + if(Qt6_FOUND) + target_link_libraries(rlRotationConverterDemo Qt6::Core Qt6::Gui Qt6::Widgets) + elseif(Qt5_FOUND) target_link_libraries(rlRotationConverterDemo Qt5::Core Qt5::Gui Qt5::Widgets) elseif(Qt4_FOUND) target_link_libraries(rlRotationConverterDemo Qt4::QtCore Qt4::QtGui) diff --git a/demos/rlSimulator/CMakeLists.txt b/demos/rlSimulator/CMakeLists.txt index 2578d0e5..b27cf134 100644 --- a/demos/rlSimulator/CMakeLists.txt +++ b/demos/rlSimulator/CMakeLists.txt @@ -1,13 +1,17 @@ find_package(OpenGL REQUIRED) find_package(SoQt) -if(RL_USE_QT5 AND SoQt_HAVE_QT5) +if(RL_USE_QT6 AND SoQt_HAVE_QT6) + find_package(Qt6 COMPONENTS Core Gui Network OpenGL Widgets QUIET) + set(QT_FOUND ${Qt6_FOUND}) +endif() + +if(NOT Qt6_FOUND AND RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) + set(QT_FOUND ${Qt5_FOUND}) endif() -if(Qt5_FOUND) - set(QT_FOUND Qt5_FOUND) -else() +if(NOT Qt6_FOUND AND NOT Qt5_FOUND) set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtNetwork QtOpenGL) endif() @@ -64,7 +68,9 @@ if(QT_FOUND AND SoQt_FOUND) target_link_libraries(rlSimulator ${OPENGL_LIBRARIES}) endif() - if(Qt5_FOUND) + if(Qt6_FOUND) + target_link_libraries(rlSimulator Qt6::Core Qt6::Gui Qt6::OpenGL Qt6::Network Qt6::Widgets) + elseif(Qt5_FOUND) target_link_libraries(rlSimulator Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Network Qt5::Widgets) elseif(Qt4_FOUND) target_link_libraries(rlSimulator Qt4::QtCore Qt4::QtGui Qt4::QtNetwork Qt4::QtOpenGL) diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index 41b20536..01bee4ba 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -27,7 +27,6 @@ #include #include #include -#include #include #include #include @@ -47,6 +46,12 @@ #include #include +#if QT_VERSION >= 0x060000 +#include +#else +#include +#endif + #include "ConfigurationDelegate.h" #include "ConfigurationModel.h" #include "MainWindow.h" @@ -112,10 +117,17 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoDB::init(); SoGradientBackground::initClass(); +#if QT_VERSION >= 0x060000 + QSurfaceFormat format; + format.setAlphaBufferSize(8); + format.setSamples(8); + QSurfaceFormat::setDefaultFormat(format); +#else QGLFormat format; format.setAlpha(true); format.setSampleBuffers(true); QGLFormat::setDefaultFormat(format); +#endif this->scene = std::make_shared(); rl::sg::XmlFactory geometryFactory; @@ -540,7 +552,11 @@ MainWindow::timerEvent(QTimerEvent *event) void MainWindow::saveImage() { +#if QT_VERSION >= 0x060000 + QImage image = this->viewer->getGLWidget()->property("SoQtGLArea").value()->grabFramebuffer(); +#else QImage image = static_cast(this->viewer->getGLWidget())->grabFrameBuffer(true); +#endif image.save("rlSimulator-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".png", "PNG"); } diff --git a/demos/rlViewDemo/CMakeLists.txt b/demos/rlViewDemo/CMakeLists.txt index 6eca29ab..8b2ae60b 100644 --- a/demos/rlViewDemo/CMakeLists.txt +++ b/demos/rlViewDemo/CMakeLists.txt @@ -1,12 +1,16 @@ find_package(SoQt) -if(RL_USE_QT5 AND SoQt_HAVE_QT5) +if(RL_USE_QT6 AND SoQt_HAVE_QT6) + find_package(Qt6 COMPONENTS Core Gui OpenGL Widgets QUIET) + set(QT_FOUND ${Qt6_FOUND}) +endif() + +if(NOT Qt6_FOUND AND RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui OpenGL Widgets QUIET) + set(QT_FOUND ${Qt5_FOUND}) endif() -if(Qt5_FOUND) - set(QT_FOUND Qt5_FOUND) -else() +if(NOT Qt6_FOUND AND NOT Qt5_FOUND) set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtOpenGL) endif() @@ -28,7 +32,9 @@ if(QT_FOUND AND SoQt_FOUND) SoQt::SoQt ) - if(Qt5_FOUND) + if(Qt6_FOUND) + target_link_libraries(rlViewDemo Qt6::Core Qt6::Gui Qt6::OpenGL Qt6::Widgets) + elseif(Qt5_FOUND) target_link_libraries(rlViewDemo Qt5::Core Qt5::Gui Qt5::OpenGL Qt5::Widgets) elseif(Qt4_FOUND) target_link_libraries(rlViewDemo Qt4::QtCore Qt4::QtGui Qt4::QtOpenGL) diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 5713a73a..0f4afba9 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -8,13 +8,17 @@ include(CMakePushCheckState) find_package(SoQt) -if(RL_USE_QT5 AND SoQt_HAVE_QT5) +if(RL_USE_QT6 AND SoQt_HAVE_QT6) + find_package(Qt6 COMPONENTS Core Gui Network OpenGL Widgets QUIET) + set(QT_FOUND ${Qt6_FOUND}) +endif() + +if(NOT Qt6_FOUND AND RL_USE_QT5 AND SoQt_HAVE_QT5) find_package(Qt5 COMPONENTS Core Gui Network OpenGL Widgets QUIET) + set(QT_FOUND ${Qt5_FOUND}) endif() -if(Qt5_FOUND) - set(QT_FOUND Qt5_FOUND) -else() +if(NOT Qt6_FOUND AND NOT Qt5_FOUND) set(QT_USE_IMPORTED_TARGETS ON) find_package(Qt4 COMPONENTS QtCore QtGui QtNetwork QtOpenGL) endif() @@ -67,7 +71,9 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) target_link_libraries(wrlview ${OPENGL_LIBRARIES}) endif() - if(Qt5_FOUND) + if(Qt6_FOUND) + target_link_libraries(wrlview Qt6::Core Qt6::Gui Qt6::Network Qt6::OpenGL Qt6::Widgets) + elseif(Qt5_FOUND) target_link_libraries(wrlview Qt5::Core Qt5::Gui Qt5::Network Qt5::OpenGL Qt5::Widgets) elseif(Qt4_FOUND) target_link_libraries(wrlview Qt4::QtCore Qt4::QtGui Qt4::QtNetwork Qt4::QtOpenGL) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 16e79b0f..75c45dd3 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -24,6 +24,7 @@ // POSSIBILITY OF SUCH DAMAGE. // +#include #include #include #include @@ -34,7 +35,6 @@ #include #include #include -#include #include #include #include @@ -53,6 +53,12 @@ #include #include +#if QT_VERSION >= 0x060000 +#include +#else +#include +#endif + #include "MainWindow.h" #include "SoGradientBackground.h" @@ -83,10 +89,16 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QObject::connect(this->manager, SIGNAL(finished(QNetworkReply*)), this, SLOT(replyFinished(QNetworkReply*))); +#if QT_VERSION >= 0x060000 + QSurfaceFormat format; + format.setSamples(8); + QSurfaceFormat::setDefaultFormat(format); +#else QGLFormat format; format.setAlpha(true); format.setSampleBuffers(true); QGLFormat::setDefaultFormat(format); +#endif this->setAcceptDrops(true); @@ -662,7 +674,21 @@ MainWindow::saveImage(bool withAlpha) QString filename = "wrlview-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".png"; glReadBuffer(GL_FRONT); + +#if QT_VERSION >= 0x060000 + QOpenGLWindow* window = this->viewer->getGLWidget()->property("SoQtGLArea").value(); + QSurfaceFormat surfaceFormat = window->format(); + + if (withAlpha != surfaceFormat.hasAlpha()) + { + surfaceFormat.setAlphaBufferSize(withAlpha ? 8 : 0); + window->setFormat(surfaceFormat); + } + + QImage image = window->grabFramebuffer(); +#else QImage image = static_cast(this->viewer->getGLWidget())->grabFrameBuffer(withAlpha); +#endif QString format = filename.right(filename.length() - filename.lastIndexOf('.') - 1).toUpper(); From fd1ff93820c7b360e9bf01541d548de7a5df94df Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 3 Feb 2021 18:00:10 +0100 Subject: [PATCH 441/546] Fix typo --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index ce6c6d1f..13ea685a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -58,7 +58,7 @@ option(RL_BUILD_TESTS "Build tests" ON) option(RL_BUILD_UTIL "Build utility component" ON) option(RL_BUILD_XML "Build XML abstraction layer component" ON) option(RL_USE_QT5 "Prefer Qt5 over Qt4 if available" ON) -option(RL_USE_QT6 "Prefer Qt6 over Qt6 if available" ON) +option(RL_USE_QT6 "Prefer Qt6 over Qt5 if available" ON) cmake_dependent_option(RL_BUILD_HAL "Build hardware abstraction layer component" ON "RL_BUILD_MATH;RL_BUILD_UTIL" OFF) cmake_dependent_option(RL_BUILD_KIN "Build Denavit-Hartenberg kinematics component" ON "RL_BUILD_MATH;RL_BUILD_XML" OFF) From 0d3fa8e47326d28be3aa3ad07d58a1de9095525a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 31 Jul 2020 22:01:04 +0200 Subject: [PATCH 442/546] Add getters and setters for parameters --- demos/rlPlanDemo/MainWindow.cpp | 314 ++++++++++++++---------- demos/rlPlanDemo/PlannerModel.cpp | 76 +++--- demos/rlPlanDemo/Thread.cpp | 16 +- demos/rlPrmDemo/rlPrmDemo.cpp | 14 +- demos/rlRrtDemo/rlRrtDemo.cpp | 10 +- src/rl/plan/AddRrtConCon.cpp | 48 +++- src/rl/plan/AddRrtConCon.h | 12 + src/rl/plan/AdvancedOptimizer.cpp | 50 +++- src/rl/plan/AdvancedOptimizer.h | 8 + src/rl/plan/BridgeSampler.cpp | 28 ++- src/rl/plan/BridgeSampler.h | 4 + src/rl/plan/Eet.cpp | 244 ++++++++++++++---- src/rl/plan/Eet.h | 52 ++++ src/rl/plan/GaussianSampler.cpp | 24 +- src/rl/plan/GaussianSampler.h | 4 + src/rl/plan/Optimizer.cpp | 36 +++ src/rl/plan/Optimizer.h | 12 + src/rl/plan/Planner.cpp | 64 ++++- src/rl/plan/Planner.h | 20 ++ src/rl/plan/Prm.cpp | 92 ++++++- src/rl/plan/Prm.h | 30 +++ src/rl/plan/PrmUtilityGuided.cpp | 16 +- src/rl/plan/RecursiveVerifier.cpp | 8 +- src/rl/plan/Rrt.cpp | 79 ++++-- src/rl/plan/Rrt.h | 12 + src/rl/plan/RrtCon.cpp | 6 +- src/rl/plan/RrtConCon.cpp | 6 +- src/rl/plan/RrtDual.cpp | 6 +- src/rl/plan/RrtExtCon.cpp | 6 +- src/rl/plan/RrtExtExt.cpp | 6 +- src/rl/plan/RrtGoalBias.cpp | 14 +- src/rl/plan/RrtGoalBias.h | 4 + src/rl/plan/Sampler.cpp | 12 + src/rl/plan/Sampler.h | 4 + src/rl/plan/SequentialVerifier.cpp | 8 +- src/rl/plan/SimpleOptimizer.cpp | 8 +- src/rl/plan/UniformSampler.cpp | 6 +- src/rl/plan/Verifier.cpp | 24 ++ src/rl/plan/Verifier.h | 8 + src/rl/plan/WorkspaceSphereExplorer.cpp | 108 ++++++++ src/rl/plan/WorkspaceSphereExplorer.h | 36 +++ tests/rlEetTest/rlEetTest.cpp | 54 ++-- tests/rlPrmTest/rlPrmTest.cpp | 18 +- 43 files changed, 1230 insertions(+), 377 deletions(-) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 3d78f4df..257f3096 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -1113,13 +1113,13 @@ MainWindow::load(const QString& filename) gaussianSampler->seed(*this->seed); } - gaussianSampler->sigma = this->sigma.get(); + gaussianSampler->setSigma(this->sigma.get()); } else if (path.eval("count((/rl/plan|/rlplan)//bridgeSampler) > 0").getValue()) { this->sampler = std::make_shared(); rl::plan::BridgeSampler* bridgeSampler = static_cast(this->sampler.get()); - bridgeSampler->ratio = path.eval("number((/rl/plan|/rlplan)//bridgeSampler/ratio)").getValue(static_cast(5) / static_cast(6)); + bridgeSampler->setRatio(path.eval("number((/rl/plan|/rlplan)//bridgeSampler/ratio)").getValue(static_cast(5) / static_cast(6))); if (path.eval("count((/rl/plan|/rlplan)//bridgeSampler/seed) > 0").getValue()) { @@ -1132,67 +1132,75 @@ MainWindow::load(const QString& filename) bridgeSampler->seed(*this->seed); } - bridgeSampler->sigma = this->sigma.get(); + bridgeSampler->setSigma(this->sigma.get()); } if (nullptr != this->sampler) { - this->sampler->model = this->model.get(); + this->sampler->setModel(this->model.get()); } this->sampler2 = std::make_shared(); - this->sampler2->model = this->model.get(); + this->sampler2->setModel(this->model.get()); if (path.eval("count((/rl/plan|/rlplan)//recursiveVerifier) > 0").getValue()) { this->verifier = std::make_shared(); - this->verifier->delta = path.eval("number((/rl/plan|/rlplan)//recursiveVerifier/delta)").getValue(1); + rl::math::Real delta = path.eval("number((/rl/plan|/rlplan)//recursiveVerifier/delta)").getValue(1); if ("deg" == path.eval("string((/rl/plan|/rlplan)//recursiveVerifier/delta/@unit)").getValue()) { - this->verifier->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } + + this->verifier->setDelta(delta); } else if (path.eval("count((/rl/plan|/rlplan)//sequentialVerifier) > 0").getValue()) { this->verifier = std::make_shared(); - this->verifier->delta = path.eval("number((/rl/plan|/rlplan)//sequentialVerifier/delta)").getValue(1); + rl::math::Real delta = path.eval("number((/rl/plan|/rlplan)//sequentialVerifier/delta)").getValue(1); if ("deg" == path.eval("string((/rl/plan|/rlplan)//sequentialVerifier/delta/@unit)").getValue()) { - this->verifier->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } + + this->verifier->setDelta(delta); } if (nullptr != this->verifier) { - this->verifier->model = this->model.get(); + this->verifier->setModel(this->model.get()); } if (path.eval("count((/rl/plan|/rlplan)//simpleOptimizer/recursiveVerifier) > 0").getValue()) { this->verifier2 = std::make_shared(); - this->verifier2->delta = path.eval("number((/rl/plan|/rlplan)//simpleOptimizer/recursiveVerifier/delta)").getValue(1); + rl::math::Real delta = path.eval("number((/rl/plan|/rlplan)//simpleOptimizer/recursiveVerifier/delta)").getValue(1); if ("deg" == path.eval("string((/rl/plan|/rlplan)//simpleOptimizer/recursiveVerifier/delta/@unit)").getValue()) { - this->verifier2->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } + + this->verifier2->setDelta(delta); } else if (path.eval("count((/rl/plan|/rlplan)//advancedOptimizer/recursiveVerifier) > 0").getValue()) { this->verifier2 = std::make_shared(); - this->verifier2->delta = path.eval("number((/rl/plan|/rlplan)//advancedOptimizer/recursiveVerifier/delta)").getValue(1); + rl::math::Real delta = path.eval("number((/rl/plan|/rlplan)//advancedOptimizer/recursiveVerifier/delta)").getValue(1); if ("deg" == path.eval("string((/rl/plan|/rlplan)//advancedOptimizer/recursiveVerifier/delta/@unit)").getValue()) { - this->verifier2->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } + + this->verifier2->setDelta(delta); } if (nullptr != this->verifier2) { - this->verifier2->model = this->model.get(); + this->verifier2->setModel(this->model.get()); } this->optimizer.reset(); @@ -1205,20 +1213,21 @@ MainWindow::load(const QString& filename) { this->optimizer = std::make_shared(); rl::plan::AdvancedOptimizer* advancedOptimizer = static_cast(this->optimizer.get()); - advancedOptimizer->length = path.eval("number((/rl/plan|/rlplan)//advancedOptimizer/length)").getValue(1); + rl::math::Real length = path.eval("number((/rl/plan|/rlplan)//advancedOptimizer/length)").getValue(1); if ("deg" == path.eval("string((/rl/plan|/rlplan)//advancedOptimizer/length/@unit)").getValue()) { - advancedOptimizer->length *= rl::math::constants::deg2rad; + length *= rl::math::constants::deg2rad; } - advancedOptimizer->ratio = path.eval("number((/rl/plan|/rlplan)//advancedOptimizer/ratio)").getValue(static_cast(0.1)); + advancedOptimizer->setLength(length); + advancedOptimizer->setRatio(path.eval("number((/rl/plan|/rlplan)//advancedOptimizer/ratio)").getValue(static_cast(0.1))); } if (nullptr != this->optimizer) { - this->optimizer->model = this->model.get(); - this->optimizer->verifier = this->verifier2.get(); + this->optimizer->setModel(this->model.get()); + this->optimizer->setVerifier(this->verifier2.get()); } rl::xml::NodeSet planners = path.eval("(/rl/plan|/rlplan)//addRrtConCon|(/rl/plan|/rlplan)//eet|(/rl/plan|/rlplan)//prm|(/rl/plan|/rlplan)//prmUtilityGuided|(/rl/plan|/rlplan)//rrt|(/rl/plan|/rlplan)//rrtCon|(/rl/plan|/rlplan)//rrtConCon|(/rl/plan|/rlplan)//rrtConExt|(/rl/plan|/rlplan)//rrtDual|(/rl/plan|/rlplan)//rrtGoalBias|(/rl/plan|/rlplan)//rrtExtCon|(/rl/plan|/rlplan)//rrtExtExt").getValue(); @@ -1231,78 +1240,92 @@ MainWindow::load(const QString& filename) { this->planner = std::make_shared(); rl::plan::AddRrtConCon* addRrtConCon = static_cast(this->planner.get()); - addRrtConCon->alpha = path.eval("number(alpha)").getValue(static_cast(0.05)); - addRrtConCon->delta = path.eval("number(delta)").getValue(1); + addRrtConCon->setAlpha(path.eval("number(alpha)").getValue(static_cast(0.05))); + rl::math::Real delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) { - addRrtConCon->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } - addRrtConCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); + addRrtConCon->setDelta(delta); + rl::math::Real epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - addRrtConCon->epsilon *= rl::math::constants::deg2rad; + epsilon *= rl::math::constants::deg2rad; } - addRrtConCon->lower = path.eval("number(lower)").getValue(2); + addRrtConCon->setEpsilon(epsilon); + rl::math::Real lower = path.eval("number(lower)").getValue(2); if ("deg" == path.eval("string(lower/@unit)").getValue()) { - addRrtConCon->lower *= rl::math::constants::deg2rad; + lower *= rl::math::constants::deg2rad; } - addRrtConCon->radius = path.eval("number(radius)").getValue(20); + addRrtConCon->setLower(lower); + rl::math::Real radius = path.eval("number(radius)").getValue(20); if ("deg" == path.eval("string(radius/@unit)").getValue()) { - addRrtConCon->radius *= rl::math::constants::deg2rad; + radius *= rl::math::constants::deg2rad; } - addRrtConCon->sampler = this->sampler.get(); + addRrtConCon->setRadius(radius); + addRrtConCon->setSampler(this->sampler.get()); } else if ("eet" == planners[i].getName()) { this->planner = std::make_shared(); rl::plan::Eet* eet = static_cast(this->planner.get()); - eet->alpha = path.eval("number(alpha)").getValue(static_cast(0.01)); - eet->alternativeDistanceComputation = path.eval("count(alternativeDistanceComputation) > 0").getValue() ? true : false; - eet->beta = path.eval("number(beta)").getValue(0); - eet->delta = path.eval("number(delta)").getValue(1); + eet->setAlpha(path.eval("number(alpha)").getValue(static_cast(0.01))); + eet->setAlternativeDistanceComputation(path.eval("count(alternativeDistanceComputation) > 0").getValue() ? true : false); + eet->setBeta(path.eval("number(beta)").getValue(0)); + rl::math::Real delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) { - eet->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } - eet->distanceWeight = path.eval("number(distanceWeight)").getValue(static_cast(0.1)); - eet->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); + eet->setDelta(delta); + eet->setDistanceWeight(path.eval("number(distanceWeight)").getValue(static_cast(0.1))); + rl::math::Real epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - eet->epsilon *= rl::math::constants::deg2rad; + epsilon *= rl::math::constants::deg2rad; } - eet->gamma = path.eval("number(gamma)").getValue(static_cast(1) / static_cast(3)); - eet->goalEpsilon = path.eval("number(goalEpsilon)").getValue(static_cast(0.1)); + eet->setEpsilon(epsilon); + eet->setGamma(path.eval("number(gamma)").getValue(static_cast(1) / static_cast(3))); + eet->setGoalEpsilon(path.eval("number(goalEpsilon)").getValue(static_cast(0.1))); if (path.eval("translate(string(goalEpsilon/@orientation), 'TRUE', 'true') = 'true' or string(goalEpsilon/@orientation) = '1'").getValue()) { - eet->goalEpsilonUseOrientation = true; + eet->setGoalEpsilonUseOrientation(true); } else { - eet->goalEpsilonUseOrientation = false; + eet->setGoalEpsilonUseOrientation(false); } - eet->max.x() = path.eval("number(max/x)").getValue(0); - eet->max.y() = path.eval("number(max/y)").getValue(0); - eet->max.z() = path.eval("number(max/z)").getValue(0); - eet->min.x() = path.eval("number(min/x)").getValue(0); - eet->min.y() = path.eval("number(min/y)").getValue(0); - eet->min.z() = path.eval("number(min/z)").getValue(0); - eet->sampler = this->sampler.get(); + eet->setMax( + rl::math::Vector3( + path.eval("number(max/x)").getValue(0), + path.eval("number(max/y)").getValue(0), + path.eval("number(max/z)").getValue(0) + ) + ); + eet->setMin( + rl::math::Vector3( + path.eval("number(min/x)").getValue(0), + path.eval("number(min/y)").getValue(0), + path.eval("number(min/z)").getValue(0) + ) + ); + eet->setSampler(this->sampler.get()); if (path.eval("count(seed) > 0").getValue()) { @@ -1323,13 +1346,13 @@ MainWindow::load(const QString& filename) std::shared_ptr explorer = std::make_shared(); this->explorers.push_back(explorer); - eet->explorers.push_back(explorer.get()); + eet->addExplorer(explorer.get()); rl::plan::Eet::ExplorerSetup explorerSetup; std::shared_ptr explorerStart = std::make_shared(); this->explorerStarts.push_back(explorerStart); - explorer->start = explorerStart.get(); + explorer->setStart(explorerStart.get()); (*explorerStart).x() = path.eval("number(start/x)").getValue(0); (*explorerStart).y() = path.eval("number(start/y)").getValue(0); @@ -1359,7 +1382,7 @@ MainWindow::load(const QString& filename) std::shared_ptr explorerGoal = std::make_shared(); this->explorerGoals.push_back(explorerGoal); - explorer->goal = explorerGoal.get(); + explorer->setGoal(explorerGoal.get()); (*explorerGoal).x() = path.eval("number(goal/x)").getValue(0); (*explorerGoal).y() = path.eval("number(goal/y)").getValue(0); @@ -1387,38 +1410,46 @@ MainWindow::load(const QString& filename) explorerSetup.goalFrame = -1; } - explorer->boundingBox.max().x() = path.eval("number(boundingBox/max/x)").getValue(std::numeric_limits::max()); - explorer->boundingBox.max().y() = path.eval("number(boundingBox/max/y)").getValue(std::numeric_limits::max()); - explorer->boundingBox.max().z() = path.eval("number(boundingBox/max/z)").getValue(std::numeric_limits::max()); - explorer->boundingBox.min().x() = path.eval("number(boundingBox/min/x)").getValue(-std::numeric_limits::max()); - explorer->boundingBox.min().y() = path.eval("number(boundingBox/min/y)").getValue(-std::numeric_limits::max()); - explorer->boundingBox.min().z() = path.eval("number(boundingBox/min/z)").getValue(-std::numeric_limits::max()); + explorer->setBoundingBox( + rl::math::AlignedBox3( + rl::math::Vector3( + path.eval("number(boundingBox/min/x)").getValue(-std::numeric_limits::max()), + path.eval("number(boundingBox/min/y)").getValue(-std::numeric_limits::max()), + path.eval("number(boundingBox/min/z)").getValue(-std::numeric_limits::max()) + ), + rl::math::Vector3( + path.eval("number(boundingBox/max/x)").getValue(std::numeric_limits::max()), + path.eval("number(boundingBox/max/y)").getValue(std::numeric_limits::max()), + path.eval("number(boundingBox/max/z)").getValue(std::numeric_limits::max()) + ) + ) + ); if (path.eval("count(distance) > 0").getValue()) { - explorer->greedy = rl::plan::WorkspaceSphereExplorer::Greedy::distance; + explorer->setGreedy(rl::plan::WorkspaceSphereExplorer::Greedy::distance); } else if (path.eval("count(sourceDistance) > 0").getValue()) { - explorer->greedy = rl::plan::WorkspaceSphereExplorer::Greedy::sourceDistance; + explorer->setGreedy(rl::plan::WorkspaceSphereExplorer::Greedy::sourceDistance); } else if (path.eval("count(space) > 0").getValue()) { - explorer->greedy = rl::plan::WorkspaceSphereExplorer::Greedy::space; + explorer->setGreedy(rl::plan::WorkspaceSphereExplorer::Greedy::space); } if (rl::plan::DistanceModel* model = dynamic_cast(this->model.get())) { - explorer->model = model; + explorer->setModel(model); } else { throw std::runtime_error("selected engine does not support distance queries"); } - explorer->radius = path.eval("number(radius)").getValue(0); - explorer->range = path.eval("number(range)").getValue(std::numeric_limits::max()); - explorer->samples = path.eval("number(samples)").getValue(10); + explorer->setRadius(path.eval("number(radius)").getValue(0)); + explorer->setRange(path.eval("number(range)").getValue(std::numeric_limits::max())); + explorer->setSamples(path.eval("number(samples)").getValue(10)); if (path.eval("count(seed) > 0").getValue()) { @@ -1431,50 +1462,53 @@ MainWindow::load(const QString& filename) explorer->seed(*this->seed); } - eet->explorersSetup.push_back(explorerSetup); + eet->addExplorerSetup(explorerSetup); } } else if ("prm" == planners[i].getName()) { this->planner = std::make_shared(); rl::plan::Prm* prm = static_cast(this->planner.get()); - prm->degree = path.eval("number(degree)").getValue(std::numeric_limits::max()); + prm->setMaxDegree(path.eval("number(degree)").getValue(std::numeric_limits::max())); if (path.eval("count(dijkstra) > 0").getValue()) { - prm->astar = false; + prm->setSearch(rl::plan::Prm::Search::dijkstra); } - prm->k = path.eval("number(k)").getValue(30); - prm->radius = path.eval("number(radius)").getValue(std::numeric_limits::max()); + prm->setMaxNeighbors(path.eval("number(k)").getValue(30)); + rl::math::Real radius = path.eval("number(radius)").getValue(std::numeric_limits::max()); if ("deg" == path.eval("string(radius/@unit)").getValue()) { - prm->radius *= rl::math::constants::deg2rad; + radius *= rl::math::constants::deg2rad; } - prm->sampler = this->sampler.get(); - prm->verifier = this->verifier.get(); + prm->setMaxRadius(radius); + prm->setSampler(this->sampler.get()); + prm->setVerifier(this->verifier.get()); } else if ("prmUtilityGuided" == planners[i].getName()) { this->planner = std::make_shared(); rl::plan::PrmUtilityGuided* prmUtilityGuided = static_cast(this->planner.get()); - prmUtilityGuided->degree = path.eval("number(degree)").getValue(std::numeric_limits::max()); + prmUtilityGuided->setMaxDegree(path.eval("number(degree)").getValue(std::numeric_limits::max())); if (path.eval("count(dijkstra) > 0").getValue()) { - prmUtilityGuided->astar = false; + prmUtilityGuided->setSearch(rl::plan::Prm::Search::dijkstra); } - prmUtilityGuided->k = path.eval("number(k)").getValue(30); - prmUtilityGuided->radius = path.eval("number(radius)").getValue(std::numeric_limits::max()); + prmUtilityGuided->setMaxNeighbors(path.eval("number(k)").getValue(30)); + rl::math::Real radius = path.eval("number(radius)").getValue(std::numeric_limits::max()); if ("deg" == path.eval("string(radius/@unit)").getValue()) { - prmUtilityGuided->radius *= rl::math::constants::deg2rad; + radius *= rl::math::constants::deg2rad; } + prmUtilityGuided->setMaxRadius(radius); + if (path.eval("count(seed) > 0").getValue()) { prmUtilityGuided->seed( @@ -1486,49 +1520,53 @@ MainWindow::load(const QString& filename) prmUtilityGuided->seed(*this->seed); } - prmUtilityGuided->sampler = this->sampler.get(); - prmUtilityGuided->verifier = this->verifier.get(); + prmUtilityGuided->setSampler(this->sampler.get()); + prmUtilityGuided->setVerifier(this->verifier.get()); } else if ("rrt" == planners[i].getName()) { this->planner = std::make_shared(); rl::plan::Rrt* rrt = static_cast(this->planner.get()); - rrt->delta = path.eval("number(delta)").getValue(1); + rl::math::Real delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrt->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } - rrt->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); + rrt->setDelta(delta); + rl::math::Real epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrt->epsilon *= rl::math::constants::deg2rad; + epsilon *= rl::math::constants::deg2rad; } - rrt->sampler = this->sampler.get(); + rrt->setEpsilon(epsilon); + rrt->setSampler(this->sampler.get()); } else if ("rrtCon" == planners[i].getName()) { this->planner = std::make_shared(); rl::plan::RrtCon* rrtCon = static_cast(this->planner.get()); - rrtCon->delta = path.eval("number(delta)").getValue(1); + rl::math::Real delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtCon->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } - rrtCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); + rrtCon->setDelta(delta); + rl::math::Real epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtCon->epsilon *= rl::math::constants::deg2rad; + epsilon *= rl::math::constants::deg2rad; } - rrtCon->probability = path.eval("number(probability)").getValue(static_cast(0.05)); - rrtCon->sampler = this->sampler.get(); + rrtCon->setEpsilon(epsilon); + rrtCon->setProbability(path.eval("number(probability)").getValue(static_cast(0.05))); + rrtCon->setSampler(this->sampler.get()); if (path.eval("count(seed) > 0").getValue()) { @@ -1545,102 +1583,112 @@ MainWindow::load(const QString& filename) { this->planner = std::make_shared(); rl::plan::RrtConCon* rrtConCon = static_cast(this->planner.get()); - rrtConCon->delta = path.eval("number(delta)").getValue(1); + rl::math::Real delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtConCon->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } - rrtConCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); + rrtConCon->setDelta(delta); + rl::math::Real epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtConCon->epsilon *= rl::math::constants::deg2rad; + epsilon *= rl::math::constants::deg2rad; } - rrtConCon->sampler = this->sampler.get(); + rrtConCon->setEpsilon(epsilon); + rrtConCon->setSampler(this->sampler.get()); } else if ("rrtDual" == planners[i].getName()) { this->planner = std::make_shared(); rl::plan::RrtDual* rrtDual = static_cast(this->planner.get()); - rrtDual->delta = path.eval("number(delta)").getValue(1); + rl::math::Real delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtDual->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } - rrtDual->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); + rrtDual->setDelta(delta); + rl::math::Real epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtDual->epsilon *= rl::math::constants::deg2rad; + epsilon *= rl::math::constants::deg2rad; } - rrtDual->sampler = this->sampler.get(); + rrtDual->setEpsilon(epsilon); + rrtDual->setSampler(this->sampler.get()); } else if ("rrtExtCon" == planners[i].getName()) { this->planner = std::make_shared(); rl::plan::RrtExtCon* rrtExtCon = static_cast(this->planner.get()); - rrtExtCon->delta = path.eval("number(delta)").getValue(1); + rl::math::Real delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtExtCon->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } - rrtExtCon->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); + rrtExtCon->setDelta(delta); + rl::math::Real epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtExtCon->epsilon *= rl::math::constants::deg2rad; + epsilon *= rl::math::constants::deg2rad; } - rrtExtCon->sampler = this->sampler.get(); + rrtExtCon->setEpsilon(epsilon); + rrtExtCon->setSampler(this->sampler.get()); } else if ("rrtExtExt" == planners[i].getName()) { this->planner = std::make_shared(); rl::plan::RrtExtExt* rrtExtExt = static_cast(this->planner.get()); - rrtExtExt->delta = path.eval("number(delta)").getValue(1); + rl::math::Real delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtExtExt->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } - rrtExtExt->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); + rrtExtExt->setDelta(delta); + rl::math::Real epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtExtExt->epsilon *= rl::math::constants::deg2rad; + epsilon *= rl::math::constants::deg2rad; } - rrtExtExt->sampler = this->sampler.get(); + rrtExtExt->setEpsilon(epsilon); + rrtExtExt->setSampler(this->sampler.get()); } else if ("rrtGoalBias" == planners[i].getName()) { this->planner = std::make_shared(); rl::plan::RrtGoalBias* rrtGoalBias = static_cast(this->planner.get()); - rrtGoalBias->delta = path.eval("number(delta)").getValue(1); + rl::math::Real delta = path.eval("number(delta)").getValue(1); if ("deg" == path.eval("string(delta/@unit)").getValue()) { - rrtGoalBias->delta *= rl::math::constants::deg2rad; + delta *= rl::math::constants::deg2rad; } - rrtGoalBias->epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); + rrtGoalBias->setDelta(delta); + rl::math::Real epsilon = path.eval("number(epsilon)").getValue(static_cast(1.0e-3)); if ("deg" == path.eval("string(epsilon/@unit)").getValue()) { - rrtGoalBias->epsilon *= rl::math::constants::deg2rad; + epsilon *= rl::math::constants::deg2rad; } - rrtGoalBias->probability = path.eval("number(probability)").getValue(static_cast(0.05)); - rrtGoalBias->sampler = this->sampler.get(); + rrtGoalBias->setEpsilon(epsilon); + rrtGoalBias->setProbability(path.eval("number(probability)").getValue(static_cast(0.05))); + rrtGoalBias->setSampler(this->sampler.get()); if (path.eval("count(seed) > 0").getValue()) { @@ -1776,15 +1824,17 @@ MainWindow::load(const QString& filename) } } - this->planner->duration = std::chrono::duration_cast( - std::chrono::duration( - path.eval("number((/rl/plan|/rlplan)//duration)").getValue(std::numeric_limits::max()) + this->planner->setDuration( + std::chrono::duration_cast( + std::chrono::duration( + path.eval("number((/rl/plan|/rlplan)//duration)").getValue(std::numeric_limits::max()) + ) ) ); - this->planner->goal = this->goal.get(); - this->planner->model = this->model.get(); - this->planner->start = this->start.get(); + this->planner->setGoal(this->goal.get()); + this->planner->setModel(this->model.get()); + this->planner->setStart(this->start.get()); this->viewer->delta = path.eval("number((/rl/plan|/rlplan)//viewer/delta)").getValue(); @@ -2111,13 +2161,13 @@ MainWindow::parseCommandLine() void MainWindow::reset() { - std::chrono::steady_clock::duration duration = this->planner->duration; + std::chrono::steady_clock::duration duration = this->planner->getDuration(); this->thread->blockSignals(true); QCoreApplication::processEvents(); - this->planner->duration = std::chrono::steady_clock::duration::zero(); + this->planner->setDuration(std::chrono::steady_clock::duration::zero()); this->thread->stop(); - this->planner->duration = duration; + this->planner->setDuration(duration); this->thread->blockSignals(false); this->planner->reset(); @@ -2342,16 +2392,16 @@ MainWindow::toggleViewActive(const bool& doOn) { if (doOn) { - this->planner->viewer = this->thread; + this->planner->setViewer(this->thread); if (nullptr != this->optimizer) { - this->optimizer->viewer = this->thread; + this->optimizer->setViewer(this->thread); } for (std::vector>::iterator i = this->explorers.begin(); i != this->explorers.end(); ++i) { - (*i)->viewer = this->thread; + (*i)->setViewer(this->thread); } this->connect(this->thread, this->viewer); @@ -2360,16 +2410,16 @@ MainWindow::toggleViewActive(const bool& doOn) { this->disconnect(this->thread, this->viewer); - this->planner->viewer = nullptr; + this->planner->setViewer(nullptr); if (nullptr != this->optimizer) { - this->optimizer->viewer = nullptr; + this->optimizer->setViewer(nullptr); } for (std::vector>::iterator i = this->explorers.begin(); i != this->explorers.end(); ++i) { - (*i)->viewer = nullptr; + (*i)->setViewer(nullptr); } } } diff --git a/demos/rlPlanDemo/PlannerModel.cpp b/demos/rlPlanDemo/PlannerModel.cpp index 5b9a0455..55147796 100644 --- a/demos/rlPlanDemo/PlannerModel.cpp +++ b/demos/rlPlanDemo/PlannerModel.cpp @@ -71,7 +71,7 @@ PlannerModel::data(const QModelIndex& index, int role) const { case 0: return std::chrono::duration_cast>( - MainWindow::instance()->planner->duration + MainWindow::instance()->planner->getDuration() ).count(); break; default: @@ -83,34 +83,34 @@ PlannerModel::data(const QModelIndex& index, int role) const switch (index.row()) { case 4: - return eet->alpha; + return eet->getAlpha(); break; case 5: - return eet->beta; + return eet->getBeta(); break; case 6: - return eet->distanceWeight; + return eet->getDistanceWeight(); break; case 7: - return eet->gamma; + return eet->getGamma(); break; case 8: - return eet->max.x(); + return eet->getMax().x(); break; case 9: - return eet->max.y(); + return eet->getMax().y(); break; case 10: - return eet->max.z(); + return eet->getMax().z(); break; case 11: - return eet->min.x(); + return eet->getMin().x(); break; case 12: - return eet->min.y(); + return eet->getMin().y(); break; case 13: - return eet->min.z(); + return eet->getMin().z(); break; default: break; @@ -122,16 +122,16 @@ PlannerModel::data(const QModelIndex& index, int role) const switch (index.row()) { case 1: - return static_cast(prm->degree); + return static_cast(prm->getMaxDegree()); break; case 2: - return prm->verifier->delta; + return prm->getVerifier()->getDelta(); break; case 3: - return static_cast(prm->k); + return static_cast(prm->getMaxNeighbors()); break; case 4: - return prm->radius; + return prm->getMaxRadius(); break; default: break; @@ -143,10 +143,10 @@ PlannerModel::data(const QModelIndex& index, int role) const switch (index.row()) { case 1: - return rrt->delta; + return rrt->getDelta(); break; case 2: - return rrt->epsilon; + return rrt->getEpsilon(); break; default: break; @@ -158,7 +158,7 @@ PlannerModel::data(const QModelIndex& index, int role) const switch (index.row()) { case 3: - return rrtGoalBias->probability; + return rrtGoalBias->getProbability(); break; default: break; @@ -350,8 +350,10 @@ PlannerModel::setData(const QModelIndex& index, const QVariant& value, int role) switch (index.row()) { case 0: - MainWindow::instance()->planner->duration = std::chrono::duration_cast( - std::chrono::duration(value.value()) + MainWindow::instance()->planner->setDuration( + std::chrono::duration_cast( + std::chrono::duration(value.value()) + ) ); break; default: @@ -363,34 +365,34 @@ PlannerModel::setData(const QModelIndex& index, const QVariant& value, int role) switch (index.row()) { case 4: - eet->alpha = value.value(); + eet->setAlpha(value.value()); break; case 5: - eet->beta = value.value(); + eet->setBeta(value.value()); break; case 6: - eet->distanceWeight = value.value(); + eet->setDistanceWeight(value.value()); break; case 7: - eet->gamma = value.value(); + eet->setGamma(value.value()); break; case 8: - eet->max.x() = value.value(); + eet->setMax(rl::math::Vector3(value.value(), eet->getMax().y(), eet->getMax().z())); break; case 9: - eet->max.y() = value.value(); + eet->setMax(rl::math::Vector3(eet->getMax().x(), value.value(), eet->getMax().z())); break; case 10: - eet->max.z() = value.value(); + eet->setMax(rl::math::Vector3(eet->getMax().x(), eet->getMax().y(), value.value())); break; case 11: - eet->min.x() = value.value(); + eet->setMin(rl::math::Vector3(value.value(), eet->getMin().y(), eet->getMin().z())); break; case 12: - eet->min.y() = value.value(); + eet->setMin(rl::math::Vector3(eet->getMin().x(), value.value(), eet->getMin().z())); break; case 13: - eet->min.z() = value.value(); + eet->setMin(rl::math::Vector3(eet->getMin().x(), eet->getMin().y(), value.value())); break; default: break; @@ -402,16 +404,16 @@ PlannerModel::setData(const QModelIndex& index, const QVariant& value, int role) switch (index.row()) { case 1: - prm->degree = value.value(); + prm->setMaxDegree(value.value()); break; case 2: - prm->verifier->delta = value.value(); + prm->getVerifier()->setDelta(value.value()); break; case 3: - prm->k = value.value(); + prm->setMaxNeighbors(value.value()); break; case 4: - prm->radius = value.value(); + prm->setMaxRadius(value.value()); break; default: break; @@ -423,10 +425,10 @@ PlannerModel::setData(const QModelIndex& index, const QVariant& value, int role) switch (index.row()) { case 1: - rrt->delta = value.value(); + rrt->setDelta(value.value()); break; case 2: - rrt->epsilon = value.value(); + rrt->setEpsilon(value.value()); break; default: break; @@ -438,7 +440,7 @@ PlannerModel::setData(const QModelIndex& index, const QVariant& value, int role) switch (index.row()) { case 3: - rrtGoalBias->probability = value.value(); + rrtGoalBias->setProbability(value.value()); break; default: break; diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index 9131dcd4..0e7d29ca 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -169,19 +169,19 @@ Thread::run() this->running = true; - if (nullptr != MainWindow::instance()->planner->viewer) + if (nullptr != MainWindow::instance()->planner->getViewer()) { emit statusChanged("Showing start configuration."); - this->drawConfiguration(*MainWindow::instance()->planner->start); + this->drawConfiguration(*MainWindow::instance()->planner->getStart()); QThread::usleep(static_cast(2.0 * 1000.0 * 1000.0)); } if (!this->running) return; - if (nullptr != MainWindow::instance()->planner->viewer) + if (nullptr != MainWindow::instance()->planner->getViewer()) { emit statusChanged("Showing goal configuration."); - this->drawConfiguration(*MainWindow::instance()->planner->goal); + this->drawConfiguration(*MainWindow::instance()->planner->getGoal()); QThread::usleep(static_cast(2.0 * 1000.0 * 1000.0)); } @@ -343,7 +343,7 @@ Thread::run() if (solved) { - if (nullptr != MainWindow::instance()->planner->viewer) + if (nullptr != MainWindow::instance()->planner->getViewer()) { this->drawConfigurationPath(path); } @@ -352,7 +352,7 @@ Thread::run() if (nullptr != MainWindow::instance()->optimizer) { - if (nullptr != MainWindow::instance()->planner->viewer) + if (nullptr != MainWindow::instance()->planner->getViewer()) { QThread::usleep(static_cast(2.0 * 1000.0 * 1000.0)); } @@ -367,13 +367,13 @@ Thread::run() emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration) + " ms. Optimizer finished in " + QString::number(optimizerDuration) + " ms."); - if (nullptr != MainWindow::instance()->planner->viewer) + if (nullptr != MainWindow::instance()->planner->getViewer()) { this->drawConfigurationPath(path); } } - if (nullptr == MainWindow::instance()->planner->viewer) return; + if (nullptr == MainWindow::instance()->planner->getViewer()) return; if (this->swept) { diff --git a/demos/rlPrmDemo/rlPrmDemo.cpp b/demos/rlPrmDemo/rlPrmDemo.cpp index 05f10952..701b3d73 100644 --- a/demos/rlPrmDemo/rlPrmDemo.cpp +++ b/demos/rlPrmDemo/rlPrmDemo.cpp @@ -108,13 +108,13 @@ main(int argc, char** argv) planner.model = &model; planner.setNearestNeighbors(&nearestNeighbors); - planner.sampler = &sampler; - planner.verifier = &verifier; + planner.setSampler(&sampler); + planner.setVerifier(&verifier); - sampler.model = &model; + sampler.setModel(&model); - verifier.delta = 1 * rl::math::constants::deg2rad; - verifier.model = &model; + verifier.setDelta(1 * rl::math::constants::deg2rad); + verifier.setModel(&model); rl::math::Vector start(kinematic->getDofPosition()); @@ -123,7 +123,7 @@ main(int argc, char** argv) start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::constants::deg2rad; } - planner.start = &start; + planner.setStart(&start); rl::math::Vector goal(kinematic->getDofPosition()); @@ -132,7 +132,7 @@ main(int argc, char** argv) goal(i) = boost::lexical_cast(argv[start.size() + i + 3]) * rl::math::constants::deg2rad; } - planner.goal = &goal; + planner.setGoal(&goal); std::cout << "start: " << start.transpose() * rl::math::constants::rad2deg << std::endl;; std::cout << "goal: " << goal.transpose() * rl::math::constants::rad2deg << std::endl;; diff --git a/demos/rlRrtDemo/rlRrtDemo.cpp b/demos/rlRrtDemo/rlRrtDemo.cpp index 7bcce277..ed179c6e 100644 --- a/demos/rlRrtDemo/rlRrtDemo.cpp +++ b/demos/rlRrtDemo/rlRrtDemo.cpp @@ -108,11 +108,11 @@ main(int argc, char** argv) planner.model = &model; planner.setNearestNeighbors(&nearestNeighbors0, 0); planner.setNearestNeighbors(&nearestNeighbors1, 1); - planner.sampler = &sampler; + planner.setSampler(&sampler); - sampler.model = &model; + sampler.setModel(&model); - planner.delta = 1 * rl::math::constants::deg2rad; + planner.setDelta(1 * rl::math::constants::deg2rad); rl::math::Vector start(kinematic->getDofPosition()); @@ -121,7 +121,7 @@ main(int argc, char** argv) start(i) = boost::lexical_cast(argv[i + 3]) * rl::math::constants::deg2rad; } - planner.start = &start; + planner.setStart(&start); rl::math::Vector goal(kinematic->getDofPosition()); @@ -130,7 +130,7 @@ main(int argc, char** argv) goal(i) = boost::lexical_cast(argv[start.size() + i + 3]) * rl::math::constants::deg2rad; } - planner.goal = &goal; + planner.setGoal(&goal); std::cout << "start: " << start.transpose() * rl::math::constants::rad2deg << std::endl;; std::cout << "goal: " << goal.transpose() * rl::math::constants::rad2deg << std::endl;; diff --git a/src/rl/plan/AddRrtConCon.cpp b/src/rl/plan/AddRrtConCon.cpp index afdc0b04..ee58b5f6 100644 --- a/src/rl/plan/AddRrtConCon.cpp +++ b/src/rl/plan/AddRrtConCon.cpp @@ -57,9 +57,9 @@ namespace rl tree[::boost::graph_bundle].nn->push(Metric::Value(q.get(), v)); - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationVertex(*get(tree, v)->q); + this->getViewer()->drawConfigurationVertex(*get(tree, v)->q); } return v; @@ -71,26 +71,62 @@ namespace rl return static_cast(tree[v].get()); } + ::rl::math::Real + AddRrtConCon::getAlpha() const + { + return this->alpha; + } + + ::rl::math::Real + AddRrtConCon::getLower() const + { + return this->lower; + } + ::std::string AddRrtConCon::getName() const { return "Adaptive Dynamic Domain RRT Connect Connect"; } + ::rl::math::Real + AddRrtConCon::getRadius() const + { + return this->radius; + } + + void + AddRrtConCon::setAlpha(const ::rl::math::Real& alpha) + { + this->alpha = alpha; + } + + void + AddRrtConCon::setLower(const ::rl::math::Real& lower) + { + this->lower = lower; + } + + void + AddRrtConCon::setRadius(const ::rl::math::Real& radius) + { + this->radius = radius; + } + bool AddRrtConCon::solve() { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->getStart())); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->getGoal())); Tree* a = &this->tree[0]; Tree* b = &this->tree[1]; - ::rl::math::Vector chosen(this->model->getDofPosition()); + ::rl::math::Vector chosen(this->getModel()->getDofPosition()); - while ((::std::chrono::steady_clock::now() - this->time) < this->duration) + while ((::std::chrono::steady_clock::now() - this->time) < this->getDuration()) { for (::std::size_t j = 0; j < 2; ++j) { diff --git a/src/rl/plan/AddRrtConCon.h b/src/rl/plan/AddRrtConCon.h index 1d08f89d..230b9959 100644 --- a/src/rl/plan/AddRrtConCon.h +++ b/src/rl/plan/AddRrtConCon.h @@ -50,8 +50,20 @@ namespace rl virtual ~AddRrtConCon(); + ::rl::math::Real getAlpha() const; + + ::rl::math::Real getLower() const; + virtual ::std::string getName() const; + ::rl::math::Real getRadius() const; + + void setAlpha(const ::rl::math::Real& alpha); + + void setLower(const ::rl::math::Real& lower); + + void setRadius(const ::rl::math::Real& radius); + bool solve(); /** Radius expansion factor. */ diff --git a/src/rl/plan/AdvancedOptimizer.cpp b/src/rl/plan/AdvancedOptimizer.cpp index d79278b0..3e6bdd6b 100644 --- a/src/rl/plan/AdvancedOptimizer.cpp +++ b/src/rl/plan/AdvancedOptimizer.cpp @@ -44,6 +44,18 @@ namespace rl { } + ::rl::math::Real + AdvancedOptimizer::getLength() const + { + return this->length; + } + + ::rl::math::Real + AdvancedOptimizer::getRatio() const + { + return this->ratio; + } + void AdvancedOptimizer::process(VectorList& path) { @@ -53,7 +65,7 @@ namespace rl VectorList::iterator j; VectorList::iterator k; - ::rl::math::Vector inter(this->model->getDofPosition()); + ::rl::math::Vector inter(this->getModel()->getDofPosition()); while (changed && path.size() > 2) { @@ -67,18 +79,18 @@ namespace rl while (i != path.end() && j != path.end() && k != path.end()) { - ::rl::math::Real ik = this->model->distance(*i, *k); + ::rl::math::Real ik = this->getModel()->distance(*i, *k); - if (!this->verifier->isColliding(*i, *k, ik)) + if (!this->getVerifier()->isColliding(*i, *k, ik)) { - ::rl::math::Real ij = this->model->distance(*i, *j); - ::rl::math::Real jk = this->model->distance(*j, *k); + ::rl::math::Real ij = this->getModel()->distance(*i, *j); + ::rl::math::Real jk = this->getModel()->distance(*j, *k); ::rl::math::Real alpha = ij / (ij + jk); - this->model->interpolate(*i, *k, alpha, inter); + this->getModel()->interpolate(*i, *k, alpha, inter); - ::rl::math::Real ratio = this->model->distance(*j, inter) / ik; + ::rl::math::Real ratio = this->getModel()->distance(*j, inter) / ik; if (ratio > this->ratio) { @@ -87,9 +99,9 @@ namespace rl ++k; path.erase(l); - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationPath(path); + this->getViewer()->drawConfigurationPath(path); } changed = true; @@ -115,15 +127,15 @@ namespace rl while (i != path.end() && j != path.end()) { - if (this->model->distance(*i, *j) > this->length) + if (this->getModel()->distance(*i, *j) > this->length) { - this->model->interpolate(*i, *j, static_cast<::rl::math::Real>(0.5), inter); + this->getModel()->interpolate(*i, *j, static_cast<::rl::math::Real>(0.5), inter); j = path.insert(j, inter); - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationPath(path); + this->getViewer()->drawConfigurationPath(path); } changed = true; @@ -136,5 +148,17 @@ namespace rl } } } + + void + AdvancedOptimizer::setLength(const ::rl::math::Real& length) + { + this->length = length; + } + + void + AdvancedOptimizer::setRatio(const ::rl::math::Real& ratio) + { + this->ratio = ratio; + } } } diff --git a/src/rl/plan/AdvancedOptimizer.h b/src/rl/plan/AdvancedOptimizer.h index e91cb2b6..f31c66af 100644 --- a/src/rl/plan/AdvancedOptimizer.h +++ b/src/rl/plan/AdvancedOptimizer.h @@ -40,8 +40,16 @@ namespace rl virtual ~AdvancedOptimizer(); + ::rl::math::Real getLength() const; + + ::rl::math::Real getRatio() const; + void process(VectorList& path); + void setLength(const ::rl::math::Real& length); + + void setRatio(const ::rl::math::Real& ratio); + ::rl::math::Real length; ::rl::math::Real ratio; diff --git a/src/rl/plan/BridgeSampler.cpp b/src/rl/plan/BridgeSampler.cpp index ff74038d..2264737e 100644 --- a/src/rl/plan/BridgeSampler.cpp +++ b/src/rl/plan/BridgeSampler.cpp @@ -50,27 +50,27 @@ namespace rl } else { - ::rl::math::Vector q(this->model->getDof()); - ::rl::math::Vector gauss(this->model->getDof()); + ::rl::math::Vector q(this->getModel()->getDof()); + ::rl::math::Vector gauss(this->getModel()->getDof()); while (true) { ::rl::math::Vector q2 = this->generate(); - if (this->model->isColliding(q2)) + if (this->getModel()->isColliding(q2)) { - for (::std::size_t i = 0; i < this->model->getDof(); ++i) + for (::std::size_t i = 0; i < this->getModel()->getDof(); ++i) { gauss(i) = this->gauss(); } - ::rl::math::Vector q3 = this->model->generatePositionGaussian(gauss, q2, *this->sigma); + ::rl::math::Vector q3 = this->getModel()->generatePositionGaussian(gauss, q2, *this->getSigma()); - if (this->model->isColliding(q3)) + if (this->getModel()->isColliding(q3)) { - this->model->interpolate(q2, q3, static_cast<::rl::math::Real>(0.5), q); + this->getModel()->interpolate(q2, q3, static_cast<::rl::math::Real>(0.5), q); - if (!this->model->isColliding(q)) + if (!this->getModel()->isColliding(q)) { return q; } @@ -79,5 +79,17 @@ namespace rl } } } + + ::rl::math::Real + BridgeSampler::getRatio() const + { + return this->ratio; + } + + void + BridgeSampler::setRatio(const ::rl::math::Real& ratio) + { + this->ratio = ratio; + } } } diff --git a/src/rl/plan/BridgeSampler.h b/src/rl/plan/BridgeSampler.h index f4cc4883..3828dafb 100644 --- a/src/rl/plan/BridgeSampler.h +++ b/src/rl/plan/BridgeSampler.h @@ -52,6 +52,10 @@ namespace rl ::rl::math::Vector generateCollisionFree(); + ::rl::math::Real getRatio() const; + + void setRatio(const ::rl::math::Real& ratio); + /** Probability of choosing bridge sample. */ ::rl::math::Real ratio; diff --git a/src/rl/plan/Eet.cpp b/src/rl/plan/Eet.cpp index 7ef07bc4..f3678522 100644 --- a/src/rl/plan/Eet.cpp +++ b/src/rl/plan/Eet.cpp @@ -81,14 +81,26 @@ namespace rl { Edge e = ::boost::add_edge(u, v, tree).first; - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationEdge(*get(tree, u)->q, *get(tree, v)->q); + this->getViewer()->drawConfigurationEdge(*get(tree, u)->q, *get(tree, v)->q); } return e; } + void + Eet::addExplorer(WorkspaceSphereExplorer* explorer) + { + this->explorers.push_back(explorer); + } + + void + Eet::addExplorerSetup(const ExplorerSetup& explorerSetup) + { + this->explorersSetup.push_back(explorerSetup); + } + Eet::Vertex Eet::addVertex(Tree& tree, const VectorPtr& q) { @@ -99,14 +111,26 @@ namespace rl Vertex v = ::boost::add_vertex(tree); tree[v] = bundle; - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationVertex(*get(tree, v)->q); + this->getViewer()->drawConfigurationVertex(*get(tree, v)->q); } return v; } + void + Eet::clearExplorers() + { + this->explorers.clear(); + } + + void + Eet::clearExplorersSetup() + { + this->explorersSetup.clear(); + } + Rrt::Vertex Eet::connect(Tree& tree, const Neighbor& nearest, const ::rl::math::Transform& chosen) { @@ -119,7 +143,7 @@ namespace rl do { VertexBundle best; - best.q = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); + best.q = ::std::make_shared<::rl::math::Vector>(this->getModel()->getDofPosition()); best.t = ::std::make_shared<::rl::math::Transform>(); state = this->expand(get(tree, n), *get(tree, nearest.second)->t, chosen, distance, best); // TODO @@ -176,53 +200,53 @@ namespace rl ::rl::math::Vector6 tdot = nearest2.toDelta(chosen, true); - this->model->setPosition(*nearest->q); - this->model->updateFrames(); - this->model->updateJacobian(); - this->model->updateJacobianInverse(); + this->getModel()->setPosition(*nearest->q); + this->getModel()->updateFrames(); + this->getModel()->updateJacobian(); + this->getModel()->updateJacobianInverse(); - ::rl::math::Vector qdot(this->model->getDof()); + ::rl::math::Vector qdot(this->getModel()->getDof()); qdot.setZero(); - ::rl::math::Vector qdot2(this->model->getDof()); - this->model->inverseVelocity(tdot, qdot2); + ::rl::math::Vector qdot2(this->getModel()->getDof()); + this->getModel()->inverseVelocity(tdot, qdot2); qdot += qdot2; - if (qdot.norm() <= this->delta) + if (qdot.norm() <= this->getDelta()) { state = 0; } else { qdot.normalize(); - qdot *= this->delta; + qdot *= this->getDelta(); } - this->model->step(*nearest->q, qdot, *expanded.q); + this->getModel()->step(*nearest->q, qdot, *expanded.q); - if (this->model->getManipulabilityMeasure() < static_cast<::rl::math::Real>(1.0e-3)) // within singularity + if (this->getModel()->getManipulabilityMeasure() < static_cast<::rl::math::Real>(1.0e-3)) // within singularity { - *expanded.q = this->sampler->generate(); // uniform sampling for singularities - ::rl::math::Real tmp = this->model->distance(*nearest->q, *expanded.q); - this->model->interpolate(*nearest->q, *expanded.q, this->delta / tmp, *expanded.q); + *expanded.q = this->getSampler()->generate(); // uniform sampling for singularities + ::rl::math::Real tmp = this->getModel()->distance(*nearest->q, *expanded.q); + this->getModel()->interpolate(*nearest->q, *expanded.q, this->getDelta() / tmp, *expanded.q); } - if (!this->model->isValid(*expanded.q)) + if (!this->getModel()->isValid(*expanded.q)) { return -1; } - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfiguration(*expanded.q); + this->getViewer()->drawConfiguration(*expanded.q); } - if (this->model->isColliding(*expanded.q)) + if (this->getModel()->isColliding(*expanded.q)) { return -1; } - *expanded.t = this->model->forwardPosition(); + *expanded.t = this->getModel()->forwardPosition(); return state; } @@ -235,7 +259,7 @@ namespace rl Vertex extended = nullptr; VertexBundle best; - best.q = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); + best.q = ::std::make_shared<::rl::math::Vector>(this->getModel()->getDofPosition()); best.t = ::std::make_shared<::rl::math::Transform>(); if (this->expand(get(tree, nearest.second), *get(tree, nearest.second)->t, chosen, distance, best) >= 0) @@ -260,12 +284,78 @@ namespace rl return static_cast(tree[v].get()); } + ::rl::math::Real + Eet::getAlpha() const + { + return this->alpha; + } + + bool + Eet::getAlternativeDistanceComputation() const + { + return this->alternativeDistanceComputation; + } + + ::rl::math::Real + Eet::getBeta() const + { + return this->beta; + } + + ::rl::math::Real + Eet::getDistanceWeight() const + { + return this->distanceWeight; + } + ::std::chrono::steady_clock::duration Eet::getExplorationDuration() const { return this->explorationTimeStop - this->explorationTimeStart; } + const ::std::vector& + Eet::getExplorers() const + { + return this->explorers; + } + + const ::std::vector& + Eet::getExplorersSetup() const + { + return this->explorersSetup; + } + + ::rl::math::Real + Eet::getGamma() const + { + return this->gamma; + } + + ::rl::math::Real + Eet::getGoalEpsilon() const + { + return this->goalEpsilon; + } + + bool + Eet::getGoalEpsilonUseOrientation() const + { + return this->goalEpsilonUseOrientation; + } + + const ::rl::math::Vector3& + Eet::getMax() const + { + return this->max; + } + + const ::rl::math::Vector3& + Eet::getMin() const + { + return this->min; + } + ::std::string Eet::getName() const { @@ -324,10 +414,76 @@ namespace rl this->randEngine.seed(value); } + void + Eet::setAlpha(const ::rl::math::Real& alpha) + { + this->alpha = alpha; + } + + void + Eet::setAlternativeDistanceComputation(const bool& alternativeDistanceComputation) + { + this->alternativeDistanceComputation = alternativeDistanceComputation; + } + + void + Eet::setBeta(const ::rl::math::Real& beta) + { + this->beta = beta; + } + + void + Eet::setDistanceWeight(const ::rl::math::Real& distanceWeight) + { + this->distanceWeight = distanceWeight; + } + + void + Eet::setExplorers(const ::std::vector& explorers) + { + this->explorers = explorers; + } + + void + Eet::setExplorersSetup(const ::std::vector& explorersSetup) + { + this->explorersSetup = explorersSetup; + } + + void + Eet::setGamma(const ::rl::math::Real& gamma) + { + this->gamma = gamma; + } + + void + Eet::setGoalEpsilon(const ::rl::math::Real& goalEpsilon) + { + this->goalEpsilon = goalEpsilon; + } + + void + Eet::setGoalEpsilonUseOrientation(const bool& goalEpsilonUseOrientation) + { + this->goalEpsilonUseOrientation = goalEpsilonUseOrientation; + } + + void + Eet::setMax(const ::rl::math::Vector3& max) + { + this->max = max; + } + + void + Eet::setMin(const ::rl::math::Vector3& min) + { + this->min = min; + } + bool Eet::solve() { - if (this->model->getOperationalDof() > 1) + if (this->getModel()->getOperationalDof() > 1) { throw("::rl::plan::Eet::solve() - branched kinematics not supported"); } @@ -342,31 +498,31 @@ namespace rl { if (nullptr != this->explorersSetup[i].startConfiguration) { - this->model->setPosition(*this->explorersSetup[i].startConfiguration); - this->model->updateFrames(false); + this->getModel()->setPosition(*this->explorersSetup[i].startConfiguration); + this->getModel()->updateFrames(false); if (-1 == this->explorersSetup[i].startFrame) { - *this->explorers[i]->start = this->model->forwardPosition().translation(); + *this->explorers[i]->getStart() = this->getModel()->forwardPosition().translation(); } else { - *this->explorers[i]->start = this->model->getFrame(this->explorersSetup[i].startFrame).translation(); + *this->explorers[i]->getStart() = this->getModel()->getFrame(this->explorersSetup[i].startFrame).translation(); } } if (nullptr != this->explorersSetup[i].goalConfiguration) { - this->model->setPosition(*this->explorersSetup[i].goalConfiguration); - this->model->updateFrames(false); + this->getModel()->setPosition(*this->explorersSetup[i].goalConfiguration); + this->getModel()->updateFrames(false); if (-1 == this->explorersSetup[i].goalFrame) { - *this->explorers[i]->goal = this->model->forwardPosition().translation(); + *this->explorers[i]->getGoal() = this->getModel()->forwardPosition().translation(); } else { - *this->explorers[i]->goal = this->model->getFrame(this->explorersSetup[i].goalFrame).translation(); + *this->explorers[i]->getGoal() = this->getModel()->getFrame(this->explorersSetup[i].goalFrame).translation(); } } } @@ -390,23 +546,23 @@ namespace rl // tree initialization with start configuration - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); - this->model->setPosition(*this->start); - this->model->updateFrames(); - get(this->tree[0], this->begin[0])->t = ::std::make_shared<::rl::math::Transform>(this->model->forwardPosition()); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->getStart())); + this->getModel()->setPosition(*this->getStart()); + this->getModel()->updateFrames(); + get(this->tree[0], this->begin[0])->t = ::std::make_shared<::rl::math::Transform>(this->getModel()->forwardPosition()); this->nn.push(WorkspaceMetric::Value(get(this->tree[0], this->begin[0])->t.get(), begin[0])); ::rl::math::Transform chosen; chosen.setIdentity(); - this->model->setPosition(*this->goal); - this->model->updateFrames(); - ::rl::math::Transform goal = this->model->forwardPosition(); + this->getModel()->setPosition(*this->getGoal()); + this->getModel()->updateFrames(); + ::rl::math::Transform goal = this->getModel()->forwardPosition(); WorkspaceSphereVector::iterator i = ++path.begin(); ::rl::math::Real sigma = gamma; // initialize exploration/exploitation balance - while ((::std::chrono::steady_clock::now() - this->time) < this->duration) // search until goal reached + while ((::std::chrono::steady_clock::now() - this->time) < this->getDuration()) // search until goal reached { if (sigma < 1) // sample is within current sphere { @@ -449,9 +605,9 @@ namespace rl } } - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawWork(chosen); + this->getViewer()->drawWork(chosen); } Vertex connected = this->connect(this->tree[0], nearest, chosen); diff --git a/src/rl/plan/Eet.h b/src/rl/plan/Eet.h index a2c608e5..158959d5 100644 --- a/src/rl/plan/Eet.h +++ b/src/rl/plan/Eet.h @@ -71,8 +71,38 @@ namespace rl virtual ~Eet(); + void addExplorer(WorkspaceSphereExplorer* explorer); + + void addExplorerSetup(const ExplorerSetup& explorerSetup); + + void clearExplorers(); + + void clearExplorersSetup(); + + ::rl::math::Real getAlpha() const; + + bool getAlternativeDistanceComputation() const; + + ::rl::math::Real getBeta() const; + + ::rl::math::Real getDistanceWeight() const; + ::std::chrono::steady_clock::duration getExplorationDuration() const; + const ::std::vector& getExplorers() const; + + const ::std::vector& getExplorersSetup() const; + + ::rl::math::Real getGamma() const; + + ::rl::math::Real getGoalEpsilon() const; + + bool getGoalEpsilonUseOrientation() const; + + const ::rl::math::Vector3& getMax() const; + + const ::rl::math::Vector3& getMin() const; + virtual ::std::string getName() const; virtual ::std::size_t getNumEdges() const; @@ -85,6 +115,28 @@ namespace rl void reset(); + void setAlpha(const ::rl::math::Real& alpha); + + void setAlternativeDistanceComputation(const bool& alternativeDistanceComputation); + + void setBeta(const ::rl::math::Real& beta); + + void setDistanceWeight(const ::rl::math::Real& distanceWeight); + + void setExplorers(const ::std::vector& explorers); + + void setExplorersSetup(const ::std::vector& explorersSetup); + + void setGamma(const ::rl::math::Real& gamma); + + void setGoalEpsilon(const ::rl::math::Real& goalEpsilon); + + void setGoalEpsilonUseOrientation(const bool& goalEpsilonUseOrientation); + + void setMax(const ::rl::math::Vector3& max); + + void setMin(const ::rl::math::Vector3& min); + bool solve(); /** Control increase/decrease of exploitation. */ diff --git a/src/rl/plan/GaussianSampler.cpp b/src/rl/plan/GaussianSampler.cpp index f15a69c8..4ef63e95 100644 --- a/src/rl/plan/GaussianSampler.cpp +++ b/src/rl/plan/GaussianSampler.cpp @@ -54,29 +54,29 @@ namespace rl ::rl::math::Vector GaussianSampler::generateCollisionFree() { - ::rl::math::Vector gauss(this->model->getDof()); + ::rl::math::Vector gauss(this->getModel()->getDof()); while (true) { ::rl::math::Vector q = this->generate(); - for (::std::size_t i = 0; i < this->model->getDof(); ++i) + for (::std::size_t i = 0; i < this->getModel()->getDof(); ++i) { gauss(i) = this->gauss(); } - ::rl::math::Vector q2 = this->model->generatePositionGaussian(gauss, q, *this->sigma); + ::rl::math::Vector q2 = this->getModel()->generatePositionGaussian(gauss, q, *this->sigma); - if (!this->model->isColliding(q)) + if (!this->getModel()->isColliding(q)) { - if (this->model->isColliding(q2)) + if (this->getModel()->isColliding(q2)) { return q; } } else { - if (!this->model->isColliding(q2)) + if (!this->getModel()->isColliding(q2)) { return q2; } @@ -84,11 +84,23 @@ namespace rl } } + ::rl::math::Vector* + GaussianSampler::getSigma() const + { + return this->sigma; + } + void GaussianSampler::seed(const ::std::mt19937::result_type& value) { this->gaussEngine.seed(value); this->randEngine.seed(value); } + + void + GaussianSampler::setSigma(::rl::math::Vector* sigma) + { + this->sigma = sigma; + } } } diff --git a/src/rl/plan/GaussianSampler.h b/src/rl/plan/GaussianSampler.h index 92f37a4e..64666d0b 100644 --- a/src/rl/plan/GaussianSampler.h +++ b/src/rl/plan/GaussianSampler.h @@ -52,8 +52,12 @@ namespace rl ::rl::math::Vector generateCollisionFree(); + ::rl::math::Vector* getSigma() const; + virtual void seed(const ::std::mt19937::result_type& value); + void setSigma(::rl::math::Vector* sigma); + ::rl::math::Vector* sigma; protected: diff --git a/src/rl/plan/Optimizer.cpp b/src/rl/plan/Optimizer.cpp index 3e1ab063..8482a5d8 100644 --- a/src/rl/plan/Optimizer.cpp +++ b/src/rl/plan/Optimizer.cpp @@ -40,5 +40,41 @@ namespace rl Optimizer::~Optimizer() { } + + SimpleModel* + Optimizer::getModel() const + { + return this->model; + } + + Verifier* + Optimizer::getVerifier() const + { + return this->verifier; + } + + Viewer* + Optimizer::getViewer() const + { + return this->viewer; + } + + void + Optimizer::setModel(SimpleModel* model) + { + this->model = model; + } + + void + Optimizer::setVerifier(Verifier* verifier) + { + this->verifier = verifier; + } + + void + Optimizer::setViewer(Viewer* viewer) + { + this->viewer = viewer; + } } } diff --git a/src/rl/plan/Optimizer.h b/src/rl/plan/Optimizer.h index 7ff2eb87..33f57055 100644 --- a/src/rl/plan/Optimizer.h +++ b/src/rl/plan/Optimizer.h @@ -46,8 +46,20 @@ namespace rl virtual ~Optimizer(); + SimpleModel* getModel() const; + + Verifier* getVerifier() const; + + Viewer* getViewer() const; + virtual void process(VectorList& path) = 0; + void setModel(SimpleModel* model); + + void setVerifier(Verifier* verifier); + + void setViewer(Viewer* viewer); + SimpleModel* model; Verifier* verifier; diff --git a/src/rl/plan/Planner.cpp b/src/rl/plan/Planner.cpp index d3dd99a5..ec49b77f 100644 --- a/src/rl/plan/Planner.cpp +++ b/src/rl/plan/Planner.cpp @@ -33,12 +33,12 @@ namespace rl namespace plan { Planner::Planner() : + time(), duration(::std::chrono::steady_clock::duration::max()), goal(nullptr), model(nullptr), start(nullptr), - viewer(nullptr), - time() + viewer(nullptr) { } @@ -46,6 +46,66 @@ namespace rl { } + ::std::chrono::steady_clock::duration + Planner::getDuration() const + { + return this->duration; + } + + ::rl::math::Vector* + Planner::getGoal() const + { + return this->goal; + } + + SimpleModel* + Planner::getModel() const + { + return this->model; + } + + ::rl::math::Vector* + Planner::getStart() const + { + return this->start; + } + + Viewer* + Planner::getViewer() const + { + return this->viewer; + } + + void + Planner::setDuration(const ::std::chrono::steady_clock::duration& duration) + { + this->duration = duration; + } + + void + Planner::setGoal(::rl::math::Vector* goal) + { + this->goal = goal; + } + + void + Planner::setModel(SimpleModel* model) + { + this->model = model; + } + + void + Planner::setStart(::rl::math::Vector* start) + { + this->start = start; + } + + void + Planner::setViewer(Viewer* viewer) + { + this->viewer = viewer; + } + bool Planner::verify() { diff --git a/src/rl/plan/Planner.h b/src/rl/plan/Planner.h index 246b568c..f4a8b759 100644 --- a/src/rl/plan/Planner.h +++ b/src/rl/plan/Planner.h @@ -51,6 +51,12 @@ namespace rl virtual ~Planner(); + ::std::chrono::steady_clock::duration getDuration() const; + + ::rl::math::Vector* getGoal() const; + + SimpleModel* getModel() const; + virtual ::std::string getName() const = 0; /** @@ -60,11 +66,25 @@ namespace rl */ virtual VectorList getPath() = 0; + ::rl::math::Vector* getStart() const; + + Viewer* getViewer() const; + /** * Reset planner. */ virtual void reset() = 0; + void setDuration(const ::std::chrono::steady_clock::duration& duration); + + void setGoal(::rl::math::Vector* goal); + + void setModel(SimpleModel* model); + + void setStart(::rl::math::Vector* start); + + void setViewer(Viewer* viewer); + /** * Find collision free path. */ diff --git a/src/rl/plan/Prm.cpp b/src/rl/plan/Prm.cpp index 3ae53dba..41a0fe66 100644 --- a/src/rl/plan/Prm.cpp +++ b/src/rl/plan/Prm.cpp @@ -70,9 +70,9 @@ namespace rl this->ds.union_set(u, v); - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationEdge(*this->graph[u].q, *this->graph[v].q); + this->getViewer()->drawConfigurationEdge(*this->graph[u].q, *this->graph[v].q); } return e; @@ -86,9 +86,9 @@ namespace rl this->graph[v].q = q; this->ds.make_set(v); - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationVertex(*this->graph[v].q); + this->getViewer()->drawConfigurationVertex(*this->graph[v].q); } return v; @@ -99,13 +99,31 @@ namespace rl { for (::std::size_t i = 0; i < steps; ++i) { - VectorPtr q = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); + VectorPtr q = ::std::make_shared<::rl::math::Vector>(this->getModel()->getDofPosition()); *q = this->sampler->generateCollisionFree(); Vertex v = this->addVertex(q); this->insert(v); } } + ::std::size_t + Prm::getMaxDegree() const + { + return this->degree; + } + + ::std::size_t + Prm::getMaxNeighbors() const + { + return this->k; + } + + ::rl::math::Real + Prm::getMaxRadius() const + { + return this->radius; + } + ::std::string Prm::getName() const { @@ -160,6 +178,24 @@ namespace rl return path; } + Sampler* + Prm::getSampler() const + { + return this->sampler; + } + + Prm::Search + Prm::getSearch() const + { + return this->astar ? Search::astar : Search::dijkstra; + } + + Verifier* + Prm::getVerifier() const + { + return this->verifier; + } + void Prm::insert(const Vertex& v) { @@ -171,7 +207,7 @@ namespace rl if (::boost::degree(u, this->graph) < this->degree) { - ::rl::math::Real d = this->graph[::boost::graph_bundle].nn->isTransformedDistance() ? this->model->inverseOfTransformedDistance(neighbors[i].first) : neighbors[i].first; + ::rl::math::Real d = this->graph[::boost::graph_bundle].nn->isTransformedDistance() ? this->getModel()->inverseOfTransformedDistance(neighbors[i].first) : neighbors[i].first; if (d < this->radius) { @@ -198,24 +234,60 @@ namespace rl this->end = nullptr; } + void + Prm::setMaxDegree(const ::std::size_t& degree) + { + this->degree = degree; + } + + void + Prm::setMaxNeighbors(const ::std::size_t& k) + { + this->k = k; + } + + void + Prm::setMaxRadius(const ::rl::math::Real& radius) + { + this->radius = radius; + } + void Prm::setNearestNeighbors(NearestNeighbors* nearestNeighbors) { this->graph[::boost::graph_bundle].nn = nearestNeighbors; } + void + Prm::setSampler(Sampler* sampler) + { + this->sampler = sampler; + } + + void + Prm::setSearch(const Search& search) + { + this->astar = search == Search::astar ? true : false; + } + + void + Prm::setVerifier(Verifier* verifier) + { + this->verifier = verifier; + } + bool Prm::solve() { this->time = ::std::chrono::steady_clock::now(); - this->begin = this->addVertex(::std::make_shared<::rl::math::Vector>(*this->start)); + this->begin = this->addVertex(::std::make_shared<::rl::math::Vector>(*this->getStart())); this->insert(this->begin); - this->end = this->addVertex(::std::make_shared<::rl::math::Vector>(*this->goal)); + this->end = this->addVertex(::std::make_shared<::rl::math::Vector>(*this->getGoal())); this->insert(this->end); - while ((::std::chrono::steady_clock::now() - this->time) < this->duration && !::boost::same_component(this->begin, this->end, this->ds)) + while ((::std::chrono::steady_clock::now() - this->time) < this->getDuration() && !::boost::same_component(this->begin, this->end, this->ds)) { this->construct(1); } @@ -230,7 +302,7 @@ namespace rl ::boost::astar_search( this->graph, this->begin, - AStarHeuristic(this->model, this->graph, this->end), + AStarHeuristic(this->getModel(), this->graph, this->end), ::boost::default_astar_visitor(), ::boost::get(&VertexBundle::predecessor, this->graph), ::boost::get(&VertexBundle::cost, this->graph), diff --git a/src/rl/plan/Prm.h b/src/rl/plan/Prm.h index fb1794db..789e0ec3 100644 --- a/src/rl/plan/Prm.h +++ b/src/rl/plan/Prm.h @@ -64,12 +64,24 @@ namespace rl class RL_PLAN_EXPORT Prm : public Planner { public: + enum class Search + { + astar, + dijkstra + }; + Prm(); virtual ~Prm(); virtual void construct(const ::std::size_t& steps); + ::std::size_t getMaxDegree() const; + + ::std::size_t getMaxNeighbors() const; + + ::rl::math::Real getMaxRadius() const; + virtual ::std::string getName() const; NearestNeighbors* getNearestNeighbors() const; @@ -80,10 +92,28 @@ namespace rl VectorList getPath(); + Sampler* getSampler() const; + + Search getSearch() const; + + Verifier* getVerifier() const; + void reset(); + void setMaxDegree(const ::std::size_t& degree); + + void setMaxNeighbors(const ::std::size_t& k); + + void setMaxRadius(const ::rl::math::Real& radius); + void setNearestNeighbors(NearestNeighbors* nearestNeighbors); + void setSampler(Sampler* sampler); + + void setSearch(const Search& search); + + void setVerifier(Verifier* verifier); + bool solve(); bool astar; diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index d6da709c..619c2d34 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -59,8 +59,8 @@ namespace rl { for (::std::size_t i = 0; i < steps; ++i) { - Sample sample(this->model->getDofPosition()); - Sample bestSample(this->model->getDofPosition()); + Sample sample(this->getModel()->getDofPosition()); + Sample bestSample(this->getModel()->getDofPosition()); ::rl::math::Real pBest = -1; // From numSamples samples, get the one with the best probability for being free. @@ -90,7 +90,7 @@ namespace rl } // now do collision check - if (!this->model->isColliding(bestSample.q)) + if (!this->getModel()->isColliding(bestSample.q)) { // store the sample in the graph bestSample.isColliding = false; @@ -160,7 +160,7 @@ namespace rl // TODO use kd tree!!! for (::std::size_t i = 0; i < this->samples.size(); ++i) { - this->samples[i].d = this->model->transformedDistance(sample.q, this->samples[i].q); + this->samples[i].d = this->getModel()->transformedDistance(sample.q, this->samples[i].q); queue.push(&this->samples[i]); } @@ -201,14 +201,14 @@ namespace rl PrmUtilityGuided::solve() { // Add the start and end configurations as samples - Sample first(this->model->getDofPosition()); + Sample first(this->getModel()->getDofPosition()); first.isColliding = false; - first.q = *this->start; + first.q = *this->getStart(); this->samples.push_back(first); - Sample last(this->model->getDofPosition()); + Sample last(this->getModel()->getDofPosition()); last.isColliding = false; - last.q = *this->goal; + last.q = *this->getGoal(); this->samples.push_back(last); return Prm::solve(); diff --git a/src/rl/plan/RecursiveVerifier.cpp b/src/rl/plan/RecursiveVerifier.cpp index 3e4eb95d..b72833fe 100644 --- a/src/rl/plan/RecursiveVerifier.cpp +++ b/src/rl/plan/RecursiveVerifier.cpp @@ -45,8 +45,8 @@ namespace rl bool RecursiveVerifier::isColliding(const ::rl::math::Vector& u, const ::rl::math::Vector& v, const ::rl::math::Real& d) { - assert(u.size() == this->model->getDofPosition()); - assert(v.size() == this->model->getDofPosition()); + assert(u.size() == this->getModel()->getDofPosition()); + assert(v.size() == this->getModel()->getDofPosition()); ::std::size_t steps = this->getSteps(d); @@ -62,9 +62,9 @@ namespace rl { ::std::size_t midpoint = (queue.front().first + queue.front().second) / 2; - this->model->interpolate(u, v, static_cast<::rl::math::Real>(midpoint) / static_cast<::rl::math::Real>(steps), inter); + this->getModel()->interpolate(u, v, static_cast<::rl::math::Real>(midpoint) / static_cast<::rl::math::Real>(steps), inter); - if (this->model->isColliding(inter)) + if (this->getModel()->isColliding(inter)) { return true; } diff --git a/src/rl/plan/Rrt.cpp b/src/rl/plan/Rrt.cpp index 30a6f397..0d10bf25 100644 --- a/src/rl/plan/Rrt.cpp +++ b/src/rl/plan/Rrt.cpp @@ -53,9 +53,9 @@ namespace rl { Edge e = ::boost::add_edge(u, v, tree).first; - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationEdge(*get(tree, u)->q, *get(tree, v)->q); + this->getViewer()->drawConfigurationEdge(*get(tree, u)->q, *get(tree, v)->q); } return e; @@ -73,9 +73,9 @@ namespace rl tree[::boost::graph_bundle].nn->push(Metric::Value(q.get(), v)); - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationVertex(*get(tree, v)->q); + this->getViewer()->drawConfigurationVertex(*get(tree, v)->q); } return v; @@ -84,7 +84,7 @@ namespace rl bool Rrt::areEqual(const ::rl::math::Vector& lhs, const ::rl::math::Vector& rhs) const { - if (this->model->distance(lhs, rhs) > this->epsilon) + if (this->getModel()->distance(lhs, rhs) > this->epsilon) { return false; } @@ -117,21 +117,21 @@ namespace rl step = this->delta; } - VectorPtr last = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); + VectorPtr last = ::std::make_shared<::rl::math::Vector>(this->getModel()->getDofPosition()); - this->model->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, *last); + this->getModel()->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, *last); - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { -// this->viewer->drawConfiguration(*last); +// this->getViewer()->drawConfiguration(*last); } - if (this->model->isColliding(*last)) + if (this->getModel()->isColliding(*last)) { return nullptr; } - ::rl::math::Vector next(this->model->getDofPosition()); + ::rl::math::Vector next(this->getModel()->getDofPosition()); while (!reached) { @@ -143,14 +143,14 @@ namespace rl step = distance; } - this->model->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, next); + this->getModel()->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, next); - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { -// this->viewer->drawConfiguration(next); +// this->getViewer()->drawConfiguration(next); } - if (this->model->isColliding(next)) + if (this->getModel()->isColliding(next)) { break; } @@ -169,11 +169,11 @@ namespace rl ::rl::math::Real distance = nearest.first; ::rl::math::Real step = ::std::min(distance, this->delta); - VectorPtr next = ::std::make_shared<::rl::math::Vector>(this->model->getDofPosition()); + VectorPtr next = ::std::make_shared<::rl::math::Vector>(this->getModel()->getDofPosition()); - this->model->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, *next); + this->getModel()->interpolate(*get(tree, nearest.second)->q, chosen, step / distance, *next); - if (!this->model->isColliding(*next)) + if (!this->getModel()->isColliding(*next)) { Vertex extended = this->addVertex(tree, next); this->addEdge(nearest.second, extended, tree); @@ -189,6 +189,18 @@ namespace rl return tree[v].get(); } + ::rl::math::Real + Rrt::getDelta() const + { + return this->delta; + } + + ::rl::math::Real + Rrt::getEpsilon() const + { + return this->epsilon; + } + ::std::string Rrt::getName() const { @@ -245,12 +257,18 @@ namespace rl return path; } + Sampler* + Rrt::getSampler() const + { + return this->sampler; + } + Rrt::Neighbor Rrt::nearest(const Tree& tree, const ::rl::math::Vector& chosen) { ::std::vector neighbors = tree[::boost::graph_bundle].nn->nearest(Metric::Value(&chosen, Vertex()), 1); return Neighbor( - tree[::boost::graph_bundle].nn->isTransformedDistance() ? this->model->inverseOfTransformedDistance(neighbors.front().first) : neighbors.front().first, + tree[::boost::graph_bundle].nn->isTransformedDistance() ? this->getModel()->inverseOfTransformedDistance(neighbors.front().first) : neighbors.front().first, neighbors.front().second.second ); } @@ -266,6 +284,17 @@ namespace rl this->end[i] = nullptr; } } + void + Rrt::setDelta(const ::rl::math::Real& delta) + { + this->delta = delta; + } + + void + Rrt::setEpsilon(const ::rl::math::Real& epsilon) + { + this->epsilon = epsilon; + } void Rrt::setNearestNeighbors(NearestNeighbors* nearestNeighbors, const ::std::size_t& i) @@ -273,14 +302,20 @@ namespace rl this->tree[i][::boost::graph_bundle].nn = nearestNeighbors; } + void + Rrt::setSampler(Sampler* sampler) + { + this->sampler = sampler; + } + bool Rrt::solve() { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->getStart())); - while ((::std::chrono::steady_clock::now() - this->time) < this->duration) + while ((::std::chrono::steady_clock::now() - this->time) < this->getDuration()) { ::rl::math::Vector chosen = this->choose(); Neighbor nearest = this->nearest(this->tree[0], chosen); @@ -288,7 +323,7 @@ namespace rl if (nullptr != extended) { - if (this->areEqual(*get(this->tree[0], extended)->q, *this->goal)) + if (this->areEqual(*get(this->tree[0], extended)->q, *this->getGoal())) { this->end[0] = extended; return true; diff --git a/src/rl/plan/Rrt.h b/src/rl/plan/Rrt.h index 9fe36479..91bfcbf1 100644 --- a/src/rl/plan/Rrt.h +++ b/src/rl/plan/Rrt.h @@ -58,6 +58,10 @@ namespace rl virtual ~Rrt(); + ::rl::math::Real getDelta() const; + + ::rl::math::Real getEpsilon() const; + virtual ::std::string getName() const; NearestNeighbors* getNearestNeighbors(const ::std::size_t& i) const; @@ -68,10 +72,18 @@ namespace rl virtual VectorList getPath(); + Sampler* getSampler() const; + virtual void reset(); + void setDelta(const ::rl::math::Real& delta); + + void setEpsilon(const ::rl::math::Real& epsilon); + void setNearestNeighbors(NearestNeighbors* nearestNeighbors, const ::std::size_t& i); + void setSampler(Sampler* sampler); + virtual bool solve(); /** Configuration step size. */ diff --git a/src/rl/plan/RrtCon.cpp b/src/rl/plan/RrtCon.cpp index 7633e8fb..725b0a2d 100644 --- a/src/rl/plan/RrtCon.cpp +++ b/src/rl/plan/RrtCon.cpp @@ -51,9 +51,9 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->getStart())); - while ((::std::chrono::steady_clock::now() - this->time) < this->duration) + while ((::std::chrono::steady_clock::now() - this->time) < this->getDuration()) { ::rl::math::Vector chosen = this->choose(); Neighbor nearest = this->nearest(this->tree[0], chosen); @@ -61,7 +61,7 @@ namespace rl if (nullptr != connected) { - if (this->areEqual(*get(this->tree[0], connected)->q, *this->goal)) + if (this->areEqual(*get(this->tree[0], connected)->q, *this->getGoal())) { this->end[0] = connected; return true; diff --git a/src/rl/plan/RrtConCon.cpp b/src/rl/plan/RrtConCon.cpp index 0091d01b..794583a0 100644 --- a/src/rl/plan/RrtConCon.cpp +++ b/src/rl/plan/RrtConCon.cpp @@ -51,13 +51,13 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->getStart())); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->getGoal())); Tree* a = &this->tree[0]; Tree* b = &this->tree[1]; - while ((::std::chrono::steady_clock::now() - this->time) < this->duration) + while ((::std::chrono::steady_clock::now() - this->time) < this->getDuration()) { for (::std::size_t j = 0; j < 2; ++j) { diff --git a/src/rl/plan/RrtDual.cpp b/src/rl/plan/RrtDual.cpp index 13057aca..d62ce73c 100644 --- a/src/rl/plan/RrtDual.cpp +++ b/src/rl/plan/RrtDual.cpp @@ -79,10 +79,10 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->getStart())); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->getGoal())); - while ((::std::chrono::steady_clock::now() - this->time) < this->duration) + while ((::std::chrono::steady_clock::now() - this->time) < this->getDuration()) { ::rl::math::Vector chosen = this->choose(); Neighbor nearest = this->nearest(this->tree[0], chosen); diff --git a/src/rl/plan/RrtExtCon.cpp b/src/rl/plan/RrtExtCon.cpp index aa95b027..8bb39dbf 100644 --- a/src/rl/plan/RrtExtCon.cpp +++ b/src/rl/plan/RrtExtCon.cpp @@ -51,13 +51,13 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->getStart())); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->getGoal())); Tree* a = &this->tree[0]; Tree* b = &this->tree[1]; - while ((::std::chrono::steady_clock::now() - this->time) < this->duration) + while ((::std::chrono::steady_clock::now() - this->time) < this->getDuration()) { for (::std::size_t j = 0; j < 2; ++j) { diff --git a/src/rl/plan/RrtExtExt.cpp b/src/rl/plan/RrtExtExt.cpp index 039e39ce..abb9876f 100644 --- a/src/rl/plan/RrtExtExt.cpp +++ b/src/rl/plan/RrtExtExt.cpp @@ -51,13 +51,13 @@ namespace rl { this->time = ::std::chrono::steady_clock::now(); - this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->start)); - this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->goal)); + this->begin[0] = this->addVertex(this->tree[0], ::std::make_shared<::rl::math::Vector>(*this->getStart())); + this->begin[1] = this->addVertex(this->tree[1], ::std::make_shared<::rl::math::Vector>(*this->getGoal())); Tree* a = &this->tree[0]; Tree* b = &this->tree[1]; - while ((::std::chrono::steady_clock::now() - this->time) < this->duration) + while ((::std::chrono::steady_clock::now() - this->time) < this->getDuration()) { for (::std::size_t j = 0; j < 2; ++j) { diff --git a/src/rl/plan/RrtGoalBias.cpp b/src/rl/plan/RrtGoalBias.cpp index f9680c3e..b9fccd99 100644 --- a/src/rl/plan/RrtGoalBias.cpp +++ b/src/rl/plan/RrtGoalBias.cpp @@ -54,7 +54,7 @@ namespace rl } else { - return *this->goal; + return *this->getGoal(); } } @@ -64,6 +64,12 @@ namespace rl return "RRT Goal Bias"; } + ::rl::math::Real + RrtGoalBias::getProbability() const + { + return this->probability; + } + ::std::uniform_real_distribution<::rl::math::Real>::result_type RrtGoalBias::rand() { @@ -75,5 +81,11 @@ namespace rl { this->randEngine.seed(value); } + + void + RrtGoalBias::setProbability(const ::rl::math::Real& probability) + { + this->probability = probability; + } } } diff --git a/src/rl/plan/RrtGoalBias.h b/src/rl/plan/RrtGoalBias.h index e7027e42..e0b35906 100644 --- a/src/rl/plan/RrtGoalBias.h +++ b/src/rl/plan/RrtGoalBias.h @@ -44,8 +44,12 @@ namespace rl virtual ::std::string getName() const; + ::rl::math::Real getProbability() const; + virtual void seed(const ::std::mt19937::result_type& value); + void setProbability(const ::rl::math::Real& probability); + /** Probability of choosing goal configuration. */ ::rl::math::Real probability; diff --git a/src/rl/plan/Sampler.cpp b/src/rl/plan/Sampler.cpp index aa8f7419..1e8d6bdd 100644 --- a/src/rl/plan/Sampler.cpp +++ b/src/rl/plan/Sampler.cpp @@ -53,5 +53,17 @@ namespace rl return q; } + + SimpleModel* + Sampler::getModel() const + { + return this->model; + } + + void + Sampler::setModel(SimpleModel* model) + { + this->model = model; + } } } diff --git a/src/rl/plan/Sampler.h b/src/rl/plan/Sampler.h index 94696e1a..02d638da 100644 --- a/src/rl/plan/Sampler.h +++ b/src/rl/plan/Sampler.h @@ -47,6 +47,10 @@ namespace rl virtual ::rl::math::Vector generateCollisionFree(); + SimpleModel* getModel() const; + + void setModel(SimpleModel* model); + SimpleModel* model; protected: diff --git a/src/rl/plan/SequentialVerifier.cpp b/src/rl/plan/SequentialVerifier.cpp index 1fcec426..b6e441cc 100644 --- a/src/rl/plan/SequentialVerifier.cpp +++ b/src/rl/plan/SequentialVerifier.cpp @@ -43,8 +43,8 @@ namespace rl bool SequentialVerifier::isColliding(const ::rl::math::Vector& u, const ::rl::math::Vector& v, const ::rl::math::Real& d) { - assert(u.size() == this->model->getDofPosition()); - assert(v.size() == this->model->getDofPosition()); + assert(u.size() == this->getModel()->getDofPosition()); + assert(v.size() == this->getModel()->getDofPosition()); ::std::size_t steps = this->getSteps(d);; @@ -52,9 +52,9 @@ namespace rl for (::std::size_t i = 0; i < steps - 1; ++i) { - this->model->interpolate(u, v, static_cast<::rl::math::Real>(i + 1) / static_cast<::rl::math::Real>(steps), inter); + this->getModel()->interpolate(u, v, static_cast<::rl::math::Real>(i + 1) / static_cast<::rl::math::Real>(steps), inter); - if (this->model->isColliding(inter)) + if (this->getModel()->isColliding(inter)) { return true; } diff --git a/src/rl/plan/SimpleOptimizer.cpp b/src/rl/plan/SimpleOptimizer.cpp index 98d09ee9..ad51c8d9 100644 --- a/src/rl/plan/SimpleOptimizer.cpp +++ b/src/rl/plan/SimpleOptimizer.cpp @@ -57,18 +57,18 @@ namespace rl while (i != path.end() && j != path.end() && k != path.end()) { - ::rl::math::Real ik = this->model->distance(*i, *k); + ::rl::math::Real ik = this->getModel()->distance(*i, *k); - if (!this->verifier->isColliding(*i, *k, ik)) + if (!this->getVerifier()->isColliding(*i, *k, ik)) { VectorList::iterator l = j; ++j; ++k; path.erase(l); - if (nullptr != this->viewer) + if (nullptr != this->getViewer()) { - this->viewer->drawConfigurationPath(path); + this->getViewer()->drawConfigurationPath(path); } changed = true; diff --git a/src/rl/plan/UniformSampler.cpp b/src/rl/plan/UniformSampler.cpp index fec759f4..c5023545 100644 --- a/src/rl/plan/UniformSampler.cpp +++ b/src/rl/plan/UniformSampler.cpp @@ -47,14 +47,14 @@ namespace rl ::rl::math::Vector UniformSampler::generate() { - ::rl::math::Vector rand(this->model->getDof()); + ::rl::math::Vector rand(this->getModel()->getDof()); - for (::std::size_t i = 0; i < this->model->getDof(); ++i) + for (::std::size_t i = 0; i < this->getModel()->getDof(); ++i) { rand(i) = this->rand(); } - return this->model->generatePositionUniform(rand); + return this->getModel()->generatePositionUniform(rand); } ::std::uniform_real_distribution<::rl::math::Real>::result_type diff --git a/src/rl/plan/Verifier.cpp b/src/rl/plan/Verifier.cpp index 9efba6da..23349f89 100644 --- a/src/rl/plan/Verifier.cpp +++ b/src/rl/plan/Verifier.cpp @@ -40,10 +40,34 @@ namespace rl { } + ::rl::math::Real + Verifier::getDelta() const + { + return this->delta; + } + + SimpleModel* + Verifier::getModel() const + { + return this->model; + } + ::std::size_t Verifier::getSteps(const ::rl::math::Real& d) { return static_cast<::std::size_t>(::std::ceil(d / this->delta)); } + + void + Verifier::setDelta(const ::rl::math::Real& delta) + { + this->delta = delta; + } + + void + Verifier::setModel(SimpleModel* model) + { + this->model = model; + } } } diff --git a/src/rl/plan/Verifier.h b/src/rl/plan/Verifier.h index e7d00f09..f34402dd 100644 --- a/src/rl/plan/Verifier.h +++ b/src/rl/plan/Verifier.h @@ -43,10 +43,18 @@ namespace rl virtual ~Verifier(); + ::rl::math::Real getDelta() const; + + SimpleModel* getModel() const; + virtual ::std::size_t getSteps(const ::rl::math::Real& d); virtual bool isColliding(const ::rl::math::Vector& u, const ::rl::math::Vector& v, const ::rl::math::Real& d) = 0; + void setDelta(const ::rl::math::Real& delta); + + void setModel(SimpleModel* model); + ::rl::math::Real delta; SimpleModel* model; diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index 32ef7edf..efcfc3e5 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -217,6 +217,30 @@ namespace rl return false; } + const ::rl::math::AlignedBox3& + WorkspaceSphereExplorer::getBoundingBox() const + { + return this->boundingBox; + } + + ::rl::math::Vector3* + WorkspaceSphereExplorer::getGoal() const + { + return this->goal; + } + + WorkspaceSphereExplorer::Greedy + WorkspaceSphereExplorer::getGreedy() const + { + return this->greedy; + } + + DistanceModel* + WorkspaceSphereExplorer::getModel() const + { + return this->model; + } + WorkspaceSphereList WorkspaceSphereExplorer::getPath() const { @@ -252,6 +276,36 @@ namespace rl return path; } + ::rl::math::Real + WorkspaceSphereExplorer::getRadius() const + { + return this->radius; + } + + ::rl::math::Real + WorkspaceSphereExplorer::getRange() const + { + return this->range; + } + + ::std::size_t + WorkspaceSphereExplorer::getSamples() const + { + return this->samples; + } + + ::rl::math::Vector3* + WorkspaceSphereExplorer::getStart() const + { + return this->start; + } + + Viewer* + WorkspaceSphereExplorer::getViewer() const + { + return this->viewer; + } + bool WorkspaceSphereExplorer::isCovered(const ::rl::math::Vector3& point) const { @@ -303,5 +357,59 @@ namespace rl { this->randEngine.seed(value); } + + void + WorkspaceSphereExplorer::setBoundingBox(const ::rl::math::AlignedBox3& boundingBox) + { + this->boundingBox = boundingBox; + } + + void + WorkspaceSphereExplorer::setGoal(::rl::math::Vector3* goal) + { + this->goal = goal; + } + + void + WorkspaceSphereExplorer::setGreedy(const Greedy& greedy) + { + this->greedy = greedy; + } + + void + WorkspaceSphereExplorer::setModel(DistanceModel* model) + { + this->model = model; + } + + void + WorkspaceSphereExplorer::setRadius(const ::rl::math::Real& radius) + { + this->radius = radius; + } + + void + WorkspaceSphereExplorer::setRange(const ::rl::math::Real& range) + { + this->range = range; + } + + void + WorkspaceSphereExplorer::setSamples(const ::std::size_t& samples) + { + this->samples = samples; + } + + void + WorkspaceSphereExplorer::setStart(::rl::math::Vector3* start) + { + this->start = start; + } + + void + WorkspaceSphereExplorer::setViewer(Viewer* viewer) + { + this->viewer = viewer; + } } } diff --git a/src/rl/plan/WorkspaceSphereExplorer.h b/src/rl/plan/WorkspaceSphereExplorer.h index 2337da96..ff62de70 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.h +++ b/src/rl/plan/WorkspaceSphereExplorer.h @@ -74,14 +74,50 @@ namespace rl bool explore(); + const ::rl::math::AlignedBox3& getBoundingBox() const; + + ::rl::math::Vector3* getGoal() const; + + Greedy getGreedy() const; + + DistanceModel* getModel() const; + WorkspaceSphereList getPath() const; + ::rl::math::Real getRadius() const; + + ::rl::math::Real getRange() const; + + ::std::size_t getSamples() const; + + ::rl::math::Vector3* getStart() const; + + Viewer* getViewer() const; + bool isCovered(const ::rl::math::Vector3& point) const; void reset(); void seed(const ::std::mt19937::result_type& value); + void setBoundingBox(const ::rl::math::AlignedBox3& boundingBox); + + void setGoal(::rl::math::Vector3* goal); + + void setGreedy(const Greedy& greedy); + + void setModel(DistanceModel* model); + + void setRadius(const ::rl::math::Real& radius); + + void setRange(const ::rl::math::Real& range); + + void setSamples(const ::std::size_t& samples); + + void setStart(::rl::math::Vector3* start); + + void setViewer(Viewer* viewer); + ::rl::math::AlignedBox3 boundingBox; ::rl::math::Vector3* goal; diff --git a/tests/rlEetTest/rlEetTest.cpp b/tests/rlEetTest/rlEetTest.cpp index c5208d2d..a62e0324 100644 --- a/tests/rlEetTest/rlEetTest.cpp +++ b/tests/rlEetTest/rlEetTest.cpp @@ -140,43 +140,39 @@ main(int argc, char** argv) planner.seed(0); sampler.seed(0); - explorer.goal = &explorerGoal; - explorer.greedy = rl::plan::WorkspaceSphereExplorer::Greedy::space; - explorer.model = &model; - explorer.radius = 0.025; - explorer.range = 45; - explorer.samples = 100; - explorer.start = &explorerStart; + explorer.setGoal(&explorerGoal); + explorer.setGreedy(rl::plan::WorkspaceSphereExplorer::Greedy::space); + explorer.setModel(&model); + explorer.setRadius(0.025); + explorer.setRange(45); + explorer.setSamples(100); + explorer.setStart(&explorerStart); explorerSetup.goalConfiguration = &goal; explorerSetup.goalFrame = -1; explorerSetup.startConfiguration = &start; explorerSetup.startFrame = -1; - planner.alpha = static_cast(0.01); - planner.alternativeDistanceComputation = false; - planner.beta = 0; - planner.delta = 1 * rl::math::constants::deg2rad; - planner.distanceWeight = static_cast(0.1); - planner.epsilon = static_cast(1.0e-9); - planner.explorers.push_back(&explorer); - planner.explorersSetup.push_back(explorerSetup); - planner.gamma = static_cast(1) / static_cast(3); - planner.goal = &goal; - planner.goalEpsilon = static_cast(0.1); - planner.goalEpsilonUseOrientation = false; - planner.max.x() = 30; - planner.max.y() = 30; - planner.max.z() = 2; - planner.model = &model; - planner.min.x() = 0; - planner.min.y() = 0; - planner.min.z() = 0; + planner.setAlpha(static_cast(0.01)); + planner.setAlternativeDistanceComputation(false); + planner.setBeta(0); + planner.setDelta(1 * rl::math::constants::deg2rad); + planner.setDistanceWeight(static_cast(0.1)); + planner.setEpsilon(static_cast(1.0e-9)); + planner.addExplorer(&explorer); + planner.addExplorerSetup(explorerSetup); + planner.setGamma(static_cast(1) / static_cast(3)); + planner.setGoal(&goal); + planner.setGoalEpsilon(static_cast(0.1)); + planner.setGoalEpsilonUseOrientation(false); + planner.setMax(rl::math::Vector3(30, 30, 2)); + planner.setModel(&model); + planner.setMin(rl::math::Vector3(0, 0, 0)); planner.setNearestNeighbors(&nearestNeighbors, 0); - planner.sampler = &sampler; - planner.start = &start; + planner.setSampler(&sampler); + planner.setStart(&start); - sampler.model = &model; + sampler.setModel(&model); std::cout << "verify() ... " << std::endl;; bool verified = planner.verify(); diff --git a/tests/rlPrmTest/rlPrmTest.cpp b/tests/rlPrmTest/rlPrmTest.cpp index 9d0b6141..ff63717c 100644 --- a/tests/rlPrmTest/rlPrmTest.cpp +++ b/tests/rlPrmTest/rlPrmTest.cpp @@ -137,15 +137,15 @@ main(int argc, char** argv) sampler.seed(0); - planner.model = &model; + planner.setModel(&model); planner.setNearestNeighbors(&nearestNeighbors); - planner.sampler = &sampler; - planner.verifier = &verifier; + planner.setSampler(&sampler); + planner.setVerifier(&verifier); - sampler.model = &model; + sampler.setModel(&model); - verifier.delta = 1 * rl::math::constants::deg2rad; - verifier.model = &model; + verifier.setDelta(1 * rl::math::constants::deg2rad); + verifier.setModel(&model); rl::math::Vector start(kinematic->getDofPosition()); @@ -154,7 +154,7 @@ main(int argc, char** argv) start(i) = boost::lexical_cast(argv[i + 12]) * rl::math::constants::deg2rad; } - planner.start = &start; + planner.setStart(&start); rl::math::Vector goal(kinematic->getDofPosition()); @@ -163,9 +163,9 @@ main(int argc, char** argv) goal(i) = boost::lexical_cast(argv[start.size() + i + 12]) * rl::math::constants::deg2rad; } - planner.goal = &goal; + planner.setGoal(&goal); - planner.duration = std::chrono::seconds(20); + planner.setDuration(std::chrono::seconds(20)); std::cout << "verify() ... " << std::endl;; bool verified = planner.verify(); From 49dcb85288b46198703a8d733df2f44a7cf2994d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 6 Feb 2021 17:44:28 +0100 Subject: [PATCH 443/546] Add additional functions to model --- src/rl/plan/Model.cpp | 12 ++++++++++++ src/rl/plan/Model.h | 4 ++++ 2 files changed, 16 insertions(+) diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index 6f7f54c0..7ce25866 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -167,6 +167,12 @@ namespace rl return this->model->getBody(i); } + void + Model::getBoundingBoxPoints(const ::std::size_t& i, const ::rl::math::Transform& frame, ::std::vector<::rl::math::Vector3>& p) const + { + this->model->getBody(i)->getBoundingBoxPoints(frame, p); + } + ::rl::math::Vector3& Model::getCenter(const ::std::size_t& i) const { @@ -433,6 +439,12 @@ namespace rl { } + void + Model::setFrame(const ::std::size_t& i, const ::rl::math::Transform& frame) + { + this->model->getBody(i)->setFrame(frame); + } + void Model::setPosition(const ::rl::math::Vector& q) { diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 932d3f95..31a3081d 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -66,6 +66,8 @@ namespace rl virtual ::std::size_t getBodies() const; + virtual void getBoundingBoxPoints(const ::std::size_t& i, const ::rl::math::Transform& frame, ::std::vector<::rl::math::Vector3>& p) const; + virtual ::rl::math::Vector3& getCenter(const ::std::size_t& i) const; virtual ::std::size_t getDof() const; @@ -108,6 +110,8 @@ namespace rl virtual void reset(); + virtual void setFrame(const ::std::size_t& i, const ::rl::math::Transform& frame); + virtual void setPosition(const ::rl::math::Vector& q); virtual void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& dq, ::rl::math::Vector& q2) const; From ef7d7cf78b2d71df653eb4ba6a0106c1332ddda1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Feb 2021 17:51:09 +0100 Subject: [PATCH 444/546] Disable CPACK_INCLUDE_TOPLEVEL_DIRECTORY --- cmake/CPackConfig.cmake | 1 + 1 file changed, 1 insertion(+) diff --git a/cmake/CPackConfig.cmake b/cmake/CPackConfig.cmake index 708e108a..1b6eff65 100644 --- a/cmake/CPackConfig.cmake +++ b/cmake/CPackConfig.cmake @@ -64,6 +64,7 @@ set(CPACK_DEBIAN_RUNTIME_PACKAGE_NAME "librl") set(CPACK_DEBIAN_RUNTIME_PACKAGE_RECOMMENDS "librl-examples (= ${PROJECT_VERSION})") set(CPACK_DEBIAN_RUNTIME_PACKAGE_SECTION "libs") set(CPACK_DEBIAN_RUNTIME_PACKAGE_SHLIBDEPS ON) +set(CPACK_INCLUDE_TOPLEVEL_DIRECTORY OFF) set(CPACK_NSIS_DISPLAY_NAME ${CPACK_PACKAGE_NAME}) set(CPACK_NSIS_EXECUTABLES_DIRECTORY ${CMAKE_INSTALL_BINDIR}) set(CPACK_NSIS_HELP_LINK "https://www.roboticslibrary.org/contact") From 85ed38dbfb034b77572e1e7f67ff8fc8ae11f41e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Feb 2021 18:07:35 +0100 Subject: [PATCH 445/546] Update CodeQL workflow --- .github/workflows/codeql.yml | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index bef7cea6..8d7db233 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -32,6 +32,7 @@ jobs: libfcl-dev libnlopt-dev libode-dev + libpqp-dev libsimage-dev libsolid3d-dev libsoqt-dev @@ -45,10 +46,10 @@ jobs: - name: Configure CMake run: > cmake - -G Ninja - -D CMAKE_BUILD_TYPE=Release - -S $GITHUB_WORKSPACE - -B $RUNNER_WORKSPACE/rl-build + -GNinja + -DCMAKE_BUILD_TYPE=Release + -S"${{ github.workspace }}" + -B"${{ runner.workspace }}/rl-build" - name: Build working-directory: ${{ runner.workspace }}/rl-build run: cmake --build . From 18e877ab043df4a8cabdeaa450f906fd501ed0e8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Feb 2021 18:09:22 +0100 Subject: [PATCH 446/546] Add MSVC to CI workflow --- .github/workflows/ci.yml | 54 +++++++++++++++++++++++++++++++++------- 1 file changed, 45 insertions(+), 9 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index cb3985b3..7ab3f16a 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -17,6 +17,7 @@ jobs: - macos-latest - ubuntu-latest-clang - ubuntu-latest-gcc + - windows-latest-msvc - windows-latest-msys2 include: - name: macos-latest @@ -30,10 +31,14 @@ jobs: cc: gcc cxx: g++ os: ubuntu-latest + - name: windows-latest-msvc + os: windows-latest - name: windows-latest-msys2 os: windows-latest env: CC: ${{ matrix.cc }} + CCACHE_COMPRESS: true + CCACHE_MAXSIZE: 500M CMAKE_C_COMPILER_LAUNCHER: ccache CMAKE_CXX_COMPILER_LAUNCHER: ccache CMAKE_PREFIX_PATH: ${{ matrix.cmake_prefix_path }} @@ -83,12 +88,31 @@ jobs: libfcl-dev libnlopt-dev libode-dev + libpqp-dev libsimage-dev libsolid3d-dev libsoqt-dev libxml2-dev libxslt1-dev ninja-build + - if: matrix.name == 'windows-latest-msvc' + name: Enable Developer Command Prompt + uses: ilammy/msvc-dev-cmd@v1.5.0 + - if: matrix.name == 'windows-latest-msvc' + name: Install ccache for MSVC + working-directory: ${{ runner.workspace }} + run: | + curl -L https://github.com/cristianadam/ccache/releases/download/v4.2/Windows.tar.xz -o Windows.tar.xz + 7z x Windows.tar.xz + 7z x Windows.tar -occache + Write-Output "${{ runner.workspace }}\ccache\bin" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append + - if: matrix.name == 'windows-latest-msvc' + name: Install dependencies for MSVC + working-directory: ${{ runner.workspace }} + run: | + curl -L https://github.com/roboticslibrary/rl-3rdparty/releases/download/latest/rl-3rdparty-msvc-14.2-x64.7z -o rl-3rdparty-msvc-14.2-x64.7z + 7z x rl-3rdparty-msvc-14.2-x64.7z -orl-3rdparty-install + Write-Output "${{ runner.workspace }}\rl-3rdparty-install\bin" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append - if: matrix.name == 'windows-latest-msys2' name: Set up MSYS2 uses: msys2/setup-msys2@v2 @@ -111,32 +135,44 @@ jobs: mingw-w64-x86_64-solid3 mingw-w64-x86_64-soqt update: true - - if: matrix.name != 'windows-latest-msys2' + - if: matrix.name == 'windows-latest-msys2' + name: Add MSYS2 to PATH + run: | + Write-Output (msys2 -c "cygpath -w /mingw64/bin") | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append + - if: matrix.os != 'windows-latest' name: Update environment variables run: | echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV - - if: matrix.name == 'windows-latest-msys2' - name: Update environment variables for MSYS2 + - if: matrix.os == 'windows-latest' + name: Update environment variables run: | Write-Output "CCACHE_BASEDIR=${{ runner.workspace }}" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append Write-Output "CCACHE_DIR=${{ runner.workspace }}\.ccache" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append - Write-Output (msys2 -c "cygpath -w /mingw64/bin") | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append - name: Cache compiler uses: actions/cache@v2 with: path: ${{ runner.workspace }}/.ccache - key: ${{ matrix.name }}-ccache + key: ${{ matrix.name }}-ccache-${{ github.sha }} + restore-keys: ${{ matrix.name }}-ccache- - name: Configure CMake run: > cmake - -G Ninja - -D CMAKE_BUILD_TYPE=RelWithDebInfo - -S ${{ github.workspace }} - -B ${{ runner.workspace }}/rl-build + -GNinja + -DCMAKE_BUILD_TYPE=Release + -S"${{ github.workspace }}" + -B"${{ runner.workspace }}/rl-build" - name: Build working-directory: ${{ runner.workspace }}/rl-build run: cmake --build . - name: Test working-directory: ${{ runner.workspace }}/rl-build run: ctest --output-on-failure + - name: Create archive + working-directory: ${{ runner.workspace }}/rl-build + run: cpack -G 7Z + - name: Upload artifacts + uses: actions/upload-artifact@v2 + with: + name: ${{ matrix.name }} + path: ${{ runner.workspace }}/rl-build/rl-*.7z From 831ec0098b13e8cbe49af38df8cf2566f476e748 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Feb 2021 20:46:47 +0100 Subject: [PATCH 447/546] Update CPack variables --- cmake/CPackConfig.cmake | 41 +++++++++++++++++++++++++++++++---------- 1 file changed, 31 insertions(+), 10 deletions(-) diff --git a/cmake/CPackConfig.cmake b/cmake/CPackConfig.cmake index 1b6eff65..7286c190 100644 --- a/cmake/CPackConfig.cmake +++ b/cmake/CPackConfig.cmake @@ -1,7 +1,13 @@ set(CPACK_PACKAGE_DESCRIPTION_SUMMARY "The Robotics Library is a self-contained C++ library for robot kinematics, visualization, motion planning, and control.") +if(CMAKE_SIZEOF_VOID_P EQUAL 4) + set(ARCHITECTURE "x86") +else() + set(ARCHITECTURE "x64") +endif() + if(MSVC) - if(CMAKE_CXX_COMPILER_VERSION MATCHES "^([0-9]+)\\.([0-9])([0-9]*)\\.([0-9]+)\\.") + if(CMAKE_CXX_COMPILER_VERSION MATCHES "^([0-9]+)\\.([0-9])([0-9]*)") if(CMAKE_CXX_COMPILER_VERSION VERSION_GREATER 18) math(EXPR LINKER_VERSION_MAJOR "${CMAKE_MATCH_1} - 5") else() @@ -9,22 +15,37 @@ if(MSVC) endif() set(PLATFORM_TOOLSET_MAJOR ${LINKER_VERSION_MAJOR}) set(PLATFORM_TOOLSET_MINOR ${CMAKE_MATCH_2}) - set(LINKER_VERSION "${LINKER_VERSION_MAJOR}.${CMAKE_MATCH_2}${CMAKE_MATCH_3}.${CMAKE_MATCH_4}") + set(COMPILER_VERSION "${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}") + endif() + set(COMPILER_ID ${CMAKE_CXX_COMPILER_ID}) + set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-${COMPILER_ID}-${COMPILER_VERSION}-${ARCHITECTURE}") +else() + if(CMAKE_CXX_COMPILER_VERSION MATCHES "^([0-9]+)\\.([0-9]+)\\.([0-9]+)") + set(COMPILER_VERSION_MAJOR ${CMAKE_MATCH_1}) + set(COMPILER_VERSION_MINOR ${CMAKE_MATCH_2}) + set(COMPILER_VERSION_PATCH ${CMAKE_MATCH_3}) + set(COMPILER_VERSION "${COMPILER_VERSION_MAJOR}.${COMPILER_VERSION_MINOR}.${COMPILER_VERSION_PATCH}") + else() + set(COMPILER_VERSION ${CMAKE_CXX_COMPILER_VERSION}) endif() - if(CMAKE_SIZEOF_VOID_P EQUAL 4) - set(ARCHITECTURE "x86") + if(CMAKE_CXX_COMPILER_ID STREQUAL "GNU") + set(COMPILER_ID "GCC") else() - set(ARCHITECTURE "x64") + set(COMPILER_ID ${CMAKE_CXX_COMPILER_ID}) endif() - set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-msvc-${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}-${ARCHITECTURE}") - set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${PROJECT_VERSION}\\\\MSVC\\\\${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR}\\\\${ARCHITECTURE}") - set(CPACK_PACKAGE_NAME "Robotics Library ${PROJECT_VERSION} - MSVC ${PLATFORM_TOOLSET_MAJOR}.${PLATFORM_TOOLSET_MINOR} (${ARCHITECTURE})") + set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-${CMAKE_SYSTEM_NAME}-${COMPILER_ID}-${COMPILER_VERSION}-${ARCHITECTURE}") +endif() + +string(TOLOWER ${CPACK_PACKAGE_FILE_NAME} CPACK_PACKAGE_FILE_NAME) + +if(WIN32) + set(CPACK_PACKAGE_INSTALL_DIRECTORY "Robotics Library\\\\${PROJECT_VERSION}\\\\${COMPILER_ID}\\\\${COMPILER_VERSION}\\\\${ARCHITECTURE}") else() - set(CPACK_PACKAGE_FILE_NAME "rl-${PROJECT_VERSION}-${CMAKE_SYSTEM_NAME}") set(CPACK_PACKAGE_INSTALL_DIRECTORY "rl-${PROJECT_VERSION}") - set(CPACK_PACKAGE_NAME "Robotics Library ${PROJECT_VERSION}") endif() +set(CPACK_PACKAGE_NAME "Robotics Library ${PROJECT_VERSION} - ${COMPILER_ID} ${COMPILER_VERSION} (${ARCHITECTURE})") + set(CPACK_COMPONENT_DEMOS_DEPENDS examples) set(CPACK_COMPONENT_DEMOS_DESCRIPTION "Demo programs for the Robotics Library.") set(CPACK_COMPONENT_DEMOS_DISPLAY_NAME "Demo Programs") From 1b0d2ed25d0839ad91df45832168a9e9c3699ff9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 21 Feb 2021 14:22:21 +0100 Subject: [PATCH 448/546] Extract octomap version from package file --- cmake/Findoctomap.cmake | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/cmake/Findoctomap.cmake b/cmake/Findoctomap.cmake index 4d1eb754..d96d294d 100644 --- a/cmake/Findoctomap.cmake +++ b/cmake/Findoctomap.cmake @@ -19,6 +19,18 @@ foreach(component IN ITEMS octomath octomap) select_library_configurations(OCTOMAP_${COMPONENT}) endforeach() +find_file( + OCTOMAP_PACKAGE_FILE + NAMES octomap/package.xml octomap/stack.xml + PATH_SUFFIXES share +) + +if(OCTOMAP_PACKAGE_FILE) + file(STRINGS "${OCTOMAP_PACKAGE_FILE}" _OCTOMAP_VERSION_TAG REGEX ".*[^<]*.*") + string(REGEX REPLACE ".*([^<]*).*" "\\1" OCTOMAP_VERSION "${_OCTOMAP_VERSION_TAG}") + unset(_OCTOMAP_VERSION_TAG) +endif() + set(OCTOMAP_INCLUDE_DIRS ${OCTOMAP_INCLUDE_DIR}) set(OCTOMAP_LIBRARIES ${OCTOMAP_OCTOMATH_LIBRARY} ${OCTOMAP_OCTOMAP_LIBRARY}) @@ -56,3 +68,4 @@ foreach(component IN ITEMS octomath octomap) endforeach() mark_as_advanced(OCTOMAP_INCLUDE_DIR) +mark_as_advanced(OCTOMAP_PACKAGE_FILE) From dfb5be7719f27f16927e7fd55045d242e97e8edd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 24 Feb 2021 11:08:14 +0100 Subject: [PATCH 449/546] Fix command line parsing --- demos/rlCollisionDemo/MainWindow.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/demos/rlCollisionDemo/MainWindow.cpp b/demos/rlCollisionDemo/MainWindow.cpp index 514e714d..0394d8aa 100644 --- a/demos/rlCollisionDemo/MainWindow.cpp +++ b/demos/rlCollisionDemo/MainWindow.cpp @@ -324,6 +324,18 @@ MainWindow::parseCommandLine() } } + if (parser.isSet(engineOption)) + { + QString engine = parser.value(engineOption); + + if (!engines.contains(engine, Qt::CaseInsensitive)) + { + parser.showHelp(); + } + + this->engine = engine; + } + if (parser.isSet(modelOption)) { bool ok; From 012138f7893162c86f2084a14ee2cc267c632f79 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 24 Feb 2021 13:18:19 +0100 Subject: [PATCH 450/546] Remove ccache for MSVC in CI workflow --- .github/workflows/ci.yml | 19 ++++++++----------- 1 file changed, 8 insertions(+), 11 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 7ab3f16a..d521c566 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -21,26 +21,30 @@ jobs: - windows-latest-msys2 include: - name: macos-latest + cmake_compiler_launcher: ccache cmake_prefix_path: /usr/local/opt/qt/lib/cmake os: macos-latest - name: ubuntu-latest-clang cc: clang + cmake_compiler_launcher: ccache cxx: clang++ os: ubuntu-latest - name: ubuntu-latest-gcc cc: gcc + cmake_compiler_launcher: ccache cxx: g++ os: ubuntu-latest - name: windows-latest-msvc os: windows-latest - name: windows-latest-msys2 + cmake_compiler_launcher: ccache os: windows-latest env: CC: ${{ matrix.cc }} CCACHE_COMPRESS: true CCACHE_MAXSIZE: 500M - CMAKE_C_COMPILER_LAUNCHER: ccache - CMAKE_CXX_COMPILER_LAUNCHER: ccache + CMAKE_C_COMPILER_LAUNCHER: ${{ matrix.cmake_compiler_launcher }} + CMAKE_CXX_COMPILER_LAUNCHER: ${{ matrix.cmake_compiler_launcher }} CMAKE_PREFIX_PATH: ${{ matrix.cmake_prefix_path }} CXX: ${{ matrix.cxx }} steps: @@ -98,14 +102,6 @@ jobs: - if: matrix.name == 'windows-latest-msvc' name: Enable Developer Command Prompt uses: ilammy/msvc-dev-cmd@v1.5.0 - - if: matrix.name == 'windows-latest-msvc' - name: Install ccache for MSVC - working-directory: ${{ runner.workspace }} - run: | - curl -L https://github.com/cristianadam/ccache/releases/download/v4.2/Windows.tar.xz -o Windows.tar.xz - 7z x Windows.tar.xz - 7z x Windows.tar -occache - Write-Output "${{ runner.workspace }}\ccache\bin" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append - if: matrix.name == 'windows-latest-msvc' name: Install dependencies for MSVC working-directory: ${{ runner.workspace }} @@ -149,7 +145,8 @@ jobs: run: | Write-Output "CCACHE_BASEDIR=${{ runner.workspace }}" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append Write-Output "CCACHE_DIR=${{ runner.workspace }}\.ccache" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append - - name: Cache compiler + - if: matrix.cmake_compiler_launcher != '' + name: Cache compiler uses: actions/cache@v2 with: path: ${{ runner.workspace }}/.ccache From 3c522c3abc2be819bdb6512cd5805f0a34d851d2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 21 May 2021 20:29:04 +0200 Subject: [PATCH 451/546] Add support for textures in URDF materials --- src/rl/sg/UrdfFactory.cpp | 118 +++++++++++++++++++++++++++----------- 1 file changed, 85 insertions(+), 33 deletions(-) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 4f0e5ecb..19770fc0 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -45,6 +45,7 @@ #include #include #include +#include #include #include #include @@ -110,13 +111,24 @@ ::std::cout << model->getName() << ::std::endl; ::rl::xml::NodeSet materials = path.eval("material").getValue<::rl::xml::NodeSet>(); - ::std::unordered_map<::std::string, ::SoVRMLMaterial*> name2material; + ::std::unordered_map<::std::string, ::SoVRMLAppearance*> name2appearance; for (int j = 0; j < materials.size(); ++j) { ::std::cout << "material: " << j << ::std::endl; ::rl::xml::Path path(document, materials[j]); + ::std::string name = path.eval("string(@name)").getValue<::std::string>(); + + ::SoVRMLAppearance* vrmlAppearance = new ::SoVRMLAppearance(); + vrmlAppearance->ref(); + + vrmlAppearance->setName(name.c_str()); + name2appearance[name] = vrmlAppearance; +::std::cout << "\tname: " << name << ::std::endl; + + ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); + if (path.eval("count(color/@rgba) > 0").getValue()) { ::std::vector<::std::string> rgba; @@ -124,9 +136,6 @@ ::std::cout << "material: " << j << ::std::endl; ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\trgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; - ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); - vrmlMaterial->ref(); - vrmlMaterial->diffuseColor.setValue( ::boost::lexical_cast(rgba[0]), ::boost::lexical_cast(rgba[1]), @@ -135,10 +144,27 @@ ::std::cout << "\trgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " vrmlMaterial->transparency.setValue( 1 - ::boost::lexical_cast(rgba[3]) ); + } + + vrmlAppearance->material = vrmlMaterial; + + SoVRMLImageTexture* vrmlImageTexture = new SoVRMLImageTexture(); + + if (path.eval("count(texture/@filename) > 0").getValue()) + { + ::rl::xml::NodeSet texture = path.eval("texture").getValue<::rl::xml::NodeSet>(); + ::std::string textureFilename = texture[0].getLocalPath(texture[0].getProperty("filename")); +::std::cout << "\tfilename: " << textureFilename << ::std::endl; + + SbImage image; - name2material[path.eval("string(@name)").getValue<::std::string>()] = vrmlMaterial; -::std::cout << "\tname: " << path.eval("string(@name)").getValue<::std::string>() << ::std::endl; + if (image.readFile(textureFilename.c_str())) + { + vrmlImageTexture->setImage(image); + } } + + vrmlAppearance->texture = vrmlImageTexture; } // joints @@ -231,38 +257,64 @@ ::std::cout << "\tname: " << body->getName() << ::std::endl; ::SoVRMLShape* vrmlShape = new ::SoVRMLShape(); vrmlShape->ref(); - ::SoVRMLAppearance* vrmlAppearance = new ::SoVRMLAppearance(); - vrmlShape->appearance = vrmlAppearance; - - if (path.eval("count(material/color/@rgba) > 0").getValue()) - { - ::std::vector<::std::string> rgba; - ::std::string tmp = path.eval("string(material/color/@rgba)").getValue<::std::string>(); - ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); -::std::cout << "\tmaterial rgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; - - ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); - - vrmlMaterial->diffuseColor.setValue( - ::boost::lexical_cast(rgba[0]), - ::boost::lexical_cast(rgba[1]), - ::boost::lexical_cast(rgba[2]) - ); - vrmlMaterial->transparency.setValue( - 1 - ::boost::lexical_cast(rgba[3]) - ); - - vrmlAppearance->material = vrmlMaterial; - } - else if (path.eval("count(material/@name) > 0").getValue()) + if (path.eval("count(material/@name) > 0 and count(material//*) = 0").getValue()) { -::std::cout << "\tmaterial name: " << path.eval("string(material/@name)").getValue<::std::string>() << ::std::endl; - vrmlAppearance->material = name2material[path.eval("string(material/@name)").getValue<::std::string>()]; + ::std::string name = path.eval("string(material/@name)").getValue<::std::string>(); +::std::cout << "\tmaterial: " << name << ::std::endl; + vrmlShape->appearance = name2appearance[name]; } else { + ::std::string name = path.eval("string(material/@name)").getValue<::std::string>(); + + ::SoVRMLAppearance* vrmlAppearance = new ::SoVRMLAppearance(); + + if (!name.empty()) + { + vrmlAppearance->setName(name.c_str()); +::std::cout << "\tmaterial name: " << name << ::std::endl; + } + ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); + + if (path.eval("count(material/color/@rgba) > 0").getValue()) + { + ::std::vector<::std::string> rgba; + ::std::string tmp = path.eval("string(material/color/@rgba)").getValue<::std::string>(); + ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); +::std::cout << "\tmaterial rgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; + + vrmlMaterial->diffuseColor.setValue( + ::boost::lexical_cast(rgba[0]), + ::boost::lexical_cast(rgba[1]), + ::boost::lexical_cast(rgba[2]) + ); + vrmlMaterial->transparency.setValue( + 1 - ::boost::lexical_cast(rgba[3]) + ); + } + vrmlAppearance->material = vrmlMaterial; + + SoVRMLImageTexture* vrmlImageTexture = new SoVRMLImageTexture(); + + if (path.eval("count(material/texture/@filename) > 0").getValue()) + { + ::rl::xml::NodeSet texture = path.eval("material/texture").getValue<::rl::xml::NodeSet>(); + ::std::string textureFilename = texture[0].getLocalPath(texture[0].getProperty("filename")); +::std::cout << "\tmaterial filename: " << textureFilename << ::std::endl; + + SbImage image; + + if (image.readFile(textureFilename.c_str())) + { + vrmlImageTexture->setImage(image); + } + } + + vrmlAppearance->texture = vrmlImageTexture; + + vrmlShape->appearance = vrmlAppearance; } ::rl::xml::NodeSet shapes = path.eval("geometry/box|geometry/cylinder|geometry/mesh|geometry/sphere").getValue<::rl::xml::NodeSet>(); @@ -470,7 +522,7 @@ ::std::cout << "\torigin xyz: " << xyz[0] << " " << xyz[1] << " " << xyz[2] << : } } - for (::std::unordered_map<::std::string, ::SoVRMLMaterial*>::iterator j = name2material.begin(); j != name2material.end(); ++j) + for (::std::unordered_map<::std::string, ::SoVRMLAppearance*>::iterator j = name2appearance.begin(); j != name2appearance.end(); ++j) { j->second->unref(); } From 285a7adab0bca3aa4ce4382bf5385f5b0626f10e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 2 Jun 2021 20:09:22 +0200 Subject: [PATCH 452/546] Fix check for include file on older CMake versions --- extras/wrlview/CMakeLists.txt | 3 +++ src/rl/sg/CMakeLists.txt | 3 +++ 2 files changed, 6 insertions(+) diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 0f4afba9..3715df1b 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -44,6 +44,9 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) ) cmake_push_check_state(RESET) + if(CMAKE_VERSION VERSION_LESS 3.12) + set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) + endif() set(CMAKE_REQUIRED_LIBRARIES Coin::Coin) check_include_file_cxx(ForeignFiles/SoSTLFileKit.h HAVE_SOSTLFILEKIT_H) if(HAVE_SOSTLFILEKIT_H) diff --git a/src/rl/sg/CMakeLists.txt b/src/rl/sg/CMakeLists.txt index f47a00bb..53e29dec 100644 --- a/src/rl/sg/CMakeLists.txt +++ b/src/rl/sg/CMakeLists.txt @@ -202,6 +202,9 @@ endif() if(Coin_FOUND) cmake_push_check_state(RESET) + if(CMAKE_VERSION VERSION_LESS 3.12) + set(CMAKE_REQUIRED_INCLUDES ${Coin_INCLUDE_DIRS}) + endif() set(CMAKE_REQUIRED_LIBRARIES Coin::Coin) check_include_file_cxx(ForeignFiles/SoSTLFileKit.h HAVE_SOSTLFILEKIT_H) if(HAVE_SOSTLFILEKIT_H) From 89703cf70c0d5344d62b703b0e26f48a4c25c55d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 8 Feb 2021 17:39:57 +0100 Subject: [PATCH 453/546] Move exception handling to subclasses --- src/rl/kin/Kinematics.cpp | 51 --------------------------------------- src/rl/kin/Kinematics.h | 2 +- src/rl/kin/Puma.cpp | 27 +++++++++++++++++++++ src/rl/kin/Puma.h | 1 + src/rl/kin/Rhino.cpp | 27 +++++++++++++++++++++ src/rl/kin/Rhino.h | 1 + 6 files changed, 57 insertions(+), 52 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index b70634be..c0e0f05c 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -409,57 +409,6 @@ namespace rl kinematics->update(); - if (::std::dynamic_pointer_cast(kinematics)) - { - if (kinematics->joints.size() != 6 || kinematics->links.size() != 7 || kinematics->transforms.size() != 8 || kinematics->frames.size() != 9) - { - if (kinematics->joints.size() != 6) - { - throw Exception("Puma kinematics with incorrect number of joints"); - } - - if (kinematics->links.size() != 7) - { - throw Exception("Puma kinematics with incorrect number of links"); - } - - if (kinematics->transforms.size() != 8) - { - throw Exception("Puma kinematics with incorrect number of transforms"); - } - - if (kinematics->frames.size() != 9) - { - throw Exception("Puma kinematics with incorrect number of frames"); - } - } - } - else if (::std::dynamic_pointer_cast(kinematics)) - { - if (kinematics->joints.size() != 5 || kinematics->links.size() != 6 || kinematics->transforms.size() != 7 || kinematics->frames.size() != 8) - { - if (kinematics->joints.size() != 5) - { - throw Exception("Rhino kinematics with incorrect number of joints"); - } - - if (kinematics->links.size() != 6) - { - throw Exception("Rhino kinematics with incorrect number of links"); - } - - if (kinematics->transforms.size() != 7) - { - throw Exception("Rhino kinematics with incorrect number of transforms"); - } - - if (kinematics->frames.size() != 8) - { - throw Exception("Rhino kinematics with incorrect number of frames"); - } - } - } - return kinematics; } diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 81e5188f..67cdf015 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -353,7 +353,7 @@ namespace rl typedef ::std::pair VertexIteratorPair; - void update(); + virtual void update(); void update(Vertex& u); diff --git a/src/rl/kin/Puma.cpp b/src/rl/kin/Puma.cpp index cb879046..fa66372a 100644 --- a/src/rl/kin/Puma.cpp +++ b/src/rl/kin/Puma.cpp @@ -28,6 +28,7 @@ #include #include +#include "Exception.h" #include "Frame.h" #include "Joint.h" #include "Puma.h" @@ -359,5 +360,31 @@ namespace rl { this->wrist = wrist; } + + void + Puma::update() + { + Kinematics::update(); + + if (this->joints.size() != 6) + { + throw Exception("Puma kinematics with incorrect number of joints"); + } + + if (this->links.size() != 7) + { + throw Exception("Puma kinematics with incorrect number of links"); + } + + if (this->transforms.size() != 8) + { + throw Exception("Puma kinematics with incorrect number of transforms"); + } + + if (this->frames.size() != 9) + { + throw Exception("Puma kinematics with incorrect number of frames"); + } + } } } diff --git a/src/rl/kin/Puma.h b/src/rl/kin/Puma.h index e65f5ca4..3144eaae 100644 --- a/src/rl/kin/Puma.h +++ b/src/rl/kin/Puma.h @@ -89,6 +89,7 @@ namespace rl void setWrist(const Wrist& wrist); protected: + void update(); private: template T atan2(const T& y, const T& x) const diff --git a/src/rl/kin/Rhino.cpp b/src/rl/kin/Rhino.cpp index f75bc0d1..8a36d63c 100644 --- a/src/rl/kin/Rhino.cpp +++ b/src/rl/kin/Rhino.cpp @@ -28,6 +28,7 @@ #include #include +#include "Exception.h" #include "Frame.h" #include "Joint.h" #include "Rhino.h" @@ -246,5 +247,31 @@ namespace rl { this->elbow = elbow; } + + void + Rhino::update() + { + Kinematics::update(); + + if (this->joints.size() != 5) + { + throw Exception("Rhino kinematics with incorrect number of joints"); + } + + if (this->links.size() != 6) + { + throw Exception("Rhino kinematics with incorrect number of links"); + } + + if (this->transforms.size() != 7) + { + throw Exception("Rhino kinematics with incorrect number of transforms"); + } + + if (this->frames.size() != 8) + { + throw Exception("Rhino kinematics with incorrect number of frames"); + } + } } } diff --git a/src/rl/kin/Rhino.h b/src/rl/kin/Rhino.h index c8badf62..8b951d63 100644 --- a/src/rl/kin/Rhino.h +++ b/src/rl/kin/Rhino.h @@ -74,6 +74,7 @@ namespace rl void setElbow(const Elbow& elbow); protected: + void update(); private: template T atan2(const T& y, const T& x) const From ffb00f2a0a8772e5b0e57271968f1f64f81cf3ba Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Feb 2021 21:11:36 +0100 Subject: [PATCH 454/546] Fix typos --- src/rl/hal/MitsubishiR3.h | 2 +- src/rl/plan/PrmUtilityGuided.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/hal/MitsubishiR3.h b/src/rl/hal/MitsubishiR3.h index c5b1cc77..06f172ae 100644 --- a/src/rl/hal/MitsubishiR3.h +++ b/src/rl/hal/MitsubishiR3.h @@ -325,7 +325,7 @@ namespace rl void doExec(const ::std::string& instruction); /** - * The hand is openend and closed. + * The hand is opened and closed. * * @param[in] doOpen CLOSE / OPEN * @param[in] handNo Hand number (1 - 8) is specified diff --git a/src/rl/plan/PrmUtilityGuided.cpp b/src/rl/plan/PrmUtilityGuided.cpp index 619c2d34..6a5910a2 100644 --- a/src/rl/plan/PrmUtilityGuided.cpp +++ b/src/rl/plan/PrmUtilityGuided.cpp @@ -107,7 +107,7 @@ namespace rl PrmUtilityGuided::generateEntropyGuidedSample(::rl::math::Vector& q) { // indices for two random vertices - // the first sample uses the start ot the end component + // the first sample uses the start or the end component #ifdef ORIGINAL_VERSION ::std::size_t randIndex1 = static_cast<::std::size_t>(::std::floor(this->rand() * this->getNumVertices())); #else From 037d2fe957edc99d0412da88cfcf618a434ede21 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 20 Oct 2021 14:24:13 +0200 Subject: [PATCH 455/546] Add default constructor for rl::xml::NodeSet --- src/rl/xml/NodeSet.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/rl/xml/NodeSet.h b/src/rl/xml/NodeSet.h index 964d8362..89766775 100644 --- a/src/rl/xml/NodeSet.h +++ b/src/rl/xml/NodeSet.h @@ -40,6 +40,11 @@ namespace rl class NodeSet { public: + NodeSet() : + nodeSet(nullptr) + { + } + explicit NodeSet(::xmlNodeSetPtr nodeSet) : nodeSet(nodeSet, ::xmlXPathFreeNodeSet) { From 4ef2bdba6ec7ba441b435427b27881c021d51bad Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 20 Oct 2021 14:24:57 +0200 Subject: [PATCH 456/546] Add support for multiple URDF shapes inside a link --- src/rl/sg/UrdfFactory.cpp | 391 +++++++++++++++++++------------------- 1 file changed, 199 insertions(+), 192 deletions(-) diff --git a/src/rl/sg/UrdfFactory.cpp b/src/rl/sg/UrdfFactory.cpp index 19770fc0..2a2d9985 100644 --- a/src/rl/sg/UrdfFactory.cpp +++ b/src/rl/sg/UrdfFactory.cpp @@ -231,277 +231,284 @@ ::std::cout << "link: " << name << ::std::endl; body->setName(name); ::std::cout << "\tname: " << body->getName() << ::std::endl; + ::rl::xml::NodeSet shapes; + if (SimpleScene* simple = dynamic_cast(scene)) { if (path.eval("count(collision) > 0").getValue()) { - path.setNode(path.eval("collision").getValue<::rl::xml::NodeSet>()[0]); + shapes = path.eval("collision").getValue<::rl::xml::NodeSet>(); } else if (path.eval("count(visual) > 0").getValue()) { - path.setNode(path.eval("visual").getValue<::rl::xml::NodeSet>()[0]); + shapes = path.eval("visual").getValue<::rl::xml::NodeSet>(); } } else { if (path.eval("count(visual) > 0").getValue()) { - path.setNode(path.eval("visual").getValue<::rl::xml::NodeSet>()[0]); + shapes = path.eval("visual").getValue<::rl::xml::NodeSet>(); } else if (path.eval("count(collision) > 0").getValue()) { - path.setNode(path.eval("collision").getValue<::rl::xml::NodeSet>()[0]); + shapes = path.eval("collision").getValue<::rl::xml::NodeSet>(); } } - ::SoVRMLShape* vrmlShape = new ::SoVRMLShape(); - vrmlShape->ref(); - - if (path.eval("count(material/@name) > 0 and count(material//*) = 0").getValue()) - { - ::std::string name = path.eval("string(material/@name)").getValue<::std::string>(); -::std::cout << "\tmaterial: " << name << ::std::endl; - vrmlShape->appearance = name2appearance[name]; - } - else + for (int j = 0; j < shapes.size(); ++j) { - ::std::string name = path.eval("string(material/@name)").getValue<::std::string>(); + ::rl::xml::Path path(document, shapes[j]); - ::SoVRMLAppearance* vrmlAppearance = new ::SoVRMLAppearance(); + ::SoVRMLShape* vrmlShape = new ::SoVRMLShape(); + vrmlShape->ref(); - if (!name.empty()) + if (path.eval("count(material/@name) > 0 and count(material//*) = 0").getValue()) { - vrmlAppearance->setName(name.c_str()); -::std::cout << "\tmaterial name: " << name << ::std::endl; - } - - ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); - - if (path.eval("count(material/color/@rgba) > 0").getValue()) - { - ::std::vector<::std::string> rgba; - ::std::string tmp = path.eval("string(material/color/@rgba)").getValue<::std::string>(); - ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); -::std::cout << "\tmaterial rgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; - - vrmlMaterial->diffuseColor.setValue( - ::boost::lexical_cast(rgba[0]), - ::boost::lexical_cast(rgba[1]), - ::boost::lexical_cast(rgba[2]) - ); - vrmlMaterial->transparency.setValue( - 1 - ::boost::lexical_cast(rgba[3]) - ); + ::std::string name = path.eval("string(material/@name)").getValue<::std::string>(); +::std::cout << "\tmaterial: " << name << ::std::endl; + vrmlShape->appearance = name2appearance[name]; } - - vrmlAppearance->material = vrmlMaterial; - - SoVRMLImageTexture* vrmlImageTexture = new SoVRMLImageTexture(); - - if (path.eval("count(material/texture/@filename) > 0").getValue()) + else { - ::rl::xml::NodeSet texture = path.eval("material/texture").getValue<::rl::xml::NodeSet>(); - ::std::string textureFilename = texture[0].getLocalPath(texture[0].getProperty("filename")); -::std::cout << "\tmaterial filename: " << textureFilename << ::std::endl; + ::std::string name = path.eval("string(material/@name)").getValue<::std::string>(); - SbImage image; + ::SoVRMLAppearance* vrmlAppearance = new ::SoVRMLAppearance(); - if (image.readFile(textureFilename.c_str())) + if (!name.empty()) { - vrmlImageTexture->setImage(image); + vrmlAppearance->setName(name.c_str()); +::std::cout << "\tmaterial name: " << name << ::std::endl; } - } - - vrmlAppearance->texture = vrmlImageTexture; - - vrmlShape->appearance = vrmlAppearance; - } - - ::rl::xml::NodeSet shapes = path.eval("geometry/box|geometry/cylinder|geometry/mesh|geometry/sphere").getValue<::rl::xml::NodeSet>(); - - for (int k = 0; k < shapes.size(); ++k) - { - if ("box" == shapes[k].getName()) - { - ::SoVRMLBox* box = new ::SoVRMLBox(); - if (!shapes[k].getProperty("size").empty()) + ::SoVRMLMaterial* vrmlMaterial = new ::SoVRMLMaterial(); + + if (path.eval("count(material/color/@rgba) > 0").getValue()) { - ::std::vector<::std::string> size; - ::std::string tmp = shapes[k].getProperty("size"); - ::boost::split(size, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); + ::std::vector<::std::string> rgba; + ::std::string tmp = path.eval("string(material/color/@rgba)").getValue<::std::string>(); + ::boost::split(rgba, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); +::std::cout << "\tmaterial rgba: " << rgba[0] << " " << rgba[1] << " " << rgba[2] << " " << rgba[3] << ::std::endl; - box->size.setValue( - ::boost::lexical_cast(size[0]), - ::boost::lexical_cast(size[1]), - ::boost::lexical_cast(size[2]) + vrmlMaterial->diffuseColor.setValue( + ::boost::lexical_cast(rgba[0]), + ::boost::lexical_cast(rgba[1]), + ::boost::lexical_cast(rgba[2]) + ); + vrmlMaterial->transparency.setValue( + 1 - ::boost::lexical_cast(rgba[3]) ); } - vrmlShape->geometry = box; -::std::cout << "\tbox size: " << box->size.getValue()[0] << " " << box->size.getValue()[1] << " " << box->size.getValue()[2] << ::std::endl; - } - else if ("cylinder" == shapes[k].getName()) - { - ::SoVRMLCylinder* cylinder = new ::SoVRMLCylinder(); + vrmlAppearance->material = vrmlMaterial; - if (!shapes[k].getProperty("length").empty()) - { - cylinder->height.setValue( - ::boost::lexical_cast(shapes[k].getProperty("length")) - ); - } + SoVRMLImageTexture* vrmlImageTexture = new SoVRMLImageTexture(); - if (!shapes[k].getProperty("radius").empty()) + if (path.eval("count(material/texture/@filename) > 0").getValue()) { - cylinder->radius.setValue( - ::boost::lexical_cast(shapes[k].getProperty("radius")) - ); + ::rl::xml::NodeSet texture = path.eval("material/texture").getValue<::rl::xml::NodeSet>(); + ::std::string textureFilename = texture[0].getLocalPath(texture[0].getProperty("filename")); +::std::cout << "\tmaterial filename: " << textureFilename << ::std::endl; + + SbImage image; + + if (image.readFile(textureFilename.c_str())) + { + vrmlImageTexture->setImage(image); + } } - vrmlShape->geometry = cylinder; -::std::cout << "\tcylinder height: " << cylinder->height.getValue() << ::std::endl; -::std::cout << "\tcylinder radius: " << cylinder->radius.getValue() << ::std::endl; + vrmlAppearance->texture = vrmlImageTexture; + + vrmlShape->appearance = vrmlAppearance; } - else if ("mesh" == shapes[k].getName()) + + ::rl::xml::NodeSet geometries = path.eval("geometry/box|geometry/cylinder|geometry/mesh|geometry/sphere").getValue<::rl::xml::NodeSet>(); + + for (int k = 0; k < geometries.size(); ++k) { - if (!shapes[k].getProperty("filename").empty()) + if ("box" == geometries[k].getName()) { - ::std::string meshFilename = shapes[k].getLocalPath(shapes[k].getProperty("filename")); -::std::cout << "\tmesh filename: " << meshFilename << ::std::endl; + ::SoVRMLBox* box = new ::SoVRMLBox(); -#if defined(HAVE_SOSTLFILEKIT_H) && defined(HAVE_SOSTLFILEKIT_CONVERT) - if (!boost::iends_with(meshFilename, "stl")) + if (!geometries[k].getProperty("size").empty()) { - throw Exception("rl::sg::UrdfFactory::load() - Only STL meshes currently supported"); + ::std::vector<::std::string> size; + ::std::string tmp = geometries[k].getProperty("size"); + ::boost::split(size, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); + + box->size.setValue( + ::boost::lexical_cast(size[0]), + ::boost::lexical_cast(size[1]), + ::boost::lexical_cast(size[2]) + ); } - ::SoSTLFileKit* stlFileKit = new ::SoSTLFileKit(); - stlFileKit->ref(); + vrmlShape->geometry = box; +::std::cout << "\tbox size: " << box->size.getValue()[0] << " " << box->size.getValue()[1] << " " << box->size.getValue()[2] << ::std::endl; + } + else if ("cylinder" == geometries[k].getName()) + { + ::SoVRMLCylinder* cylinder = new ::SoVRMLCylinder(); - if (!stlFileKit->readFile(meshFilename.c_str())) + if (!geometries[k].getProperty("length").empty()) { - throw Exception("rl::sg::UrdfFactory::load() - Failed to open file '" + meshFilename + "'"); + cylinder->height.setValue( + ::boost::lexical_cast(geometries[k].getProperty("length")) + ); } - ::SoSeparator* stl = stlFileKit->convert(); - stl->ref(); - stlFileKit->unref(); - - ::SoToVRML2Action toVrml2Action; - toVrml2Action.apply(stl); - ::SoVRMLGroup* vrml2 = toVrml2Action.getVRML2SceneGraph(); - vrml2->ref(); - stl->unref(); - - ::SoSearchAction searchAction; - searchAction.setInterest(::SoSearchAction::ALL); - searchAction.setType(::SoVRMLShape::getClassTypeId()); - searchAction.apply(vrml2); + if (!geometries[k].getProperty("radius").empty()) + { + cylinder->radius.setValue( + ::boost::lexical_cast(geometries[k].getProperty("radius")) + ); + } - for (int l = 0; l < searchAction.getPaths().getLength(); ++l) + vrmlShape->geometry = cylinder; +::std::cout << "\tcylinder height: " << cylinder->height.getValue() << ::std::endl; +::std::cout << "\tcylinder radius: " << cylinder->radius.getValue() << ::std::endl; + } + else if ("mesh" == geometries[k].getName()) + { + if (!geometries[k].getProperty("filename").empty()) { - vrmlShape->geometry = static_cast<::SoVRMLShape*>(static_cast<::SoFullPath*>(searchAction.getPaths()[l])->getTail())->geometry; + ::std::string meshFilename = geometries[k].getLocalPath(geometries[k].getProperty("filename")); +::std::cout << "\tmesh filename: " << meshFilename << ::std::endl; - if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLIndexedFaceSet::getClassTypeId())) +#if defined(HAVE_SOSTLFILEKIT_H) && defined(HAVE_SOSTLFILEKIT_CONVERT) + if (!boost::iends_with(meshFilename, "stl")) { - ::SoVRMLIndexedFaceSet* vrmlIndexedFaceSet = static_cast<::SoVRMLIndexedFaceSet*>(vrmlShape->geometry.getValue()); - vrmlIndexedFaceSet->convex.setValue(false); - - ::SoVRMLCoordinate* vrmlCoordinate = static_cast<::SoVRMLCoordinate*>(vrmlIndexedFaceSet->coord.getValue()); + throw Exception("rl::sg::UrdfFactory::load() - Only STL meshes currently supported"); + } + + ::SoSTLFileKit* stlFileKit = new ::SoSTLFileKit(); + stlFileKit->ref(); + + if (!stlFileKit->readFile(meshFilename.c_str())) + { + throw Exception("rl::sg::UrdfFactory::load() - Failed to open file '" + meshFilename + "'"); + } + + ::SoSeparator* stl = stlFileKit->convert(); + stl->ref(); + stlFileKit->unref(); + + ::SoToVRML2Action toVrml2Action; + toVrml2Action.apply(stl); + ::SoVRMLGroup* vrml2 = toVrml2Action.getVRML2SceneGraph(); + vrml2->ref(); + stl->unref(); + + ::SoSearchAction searchAction; + searchAction.setInterest(::SoSearchAction::ALL); + searchAction.setType(::SoVRMLShape::getClassTypeId()); + searchAction.apply(vrml2); + + for (int l = 0; l < searchAction.getPaths().getLength(); ++l) + { + vrmlShape->geometry = static_cast<::SoVRMLShape*>(static_cast<::SoFullPath*>(searchAction.getPaths()[l])->getTail())->geometry; - if (!shapes[k].getProperty("scale").empty()) + if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLIndexedFaceSet::getClassTypeId())) { - ::SbVec3f scale(1.0f, 1.0f, 1.0f); + ::SoVRMLIndexedFaceSet* vrmlIndexedFaceSet = static_cast<::SoVRMLIndexedFaceSet*>(vrmlShape->geometry.getValue()); + vrmlIndexedFaceSet->convex.setValue(false); - ::std::vector<::std::string> scales; - ::std::string scaleProperty = shapes[k].getProperty("scale"); - ::boost::split(scales, scaleProperty, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); -::std::cout << "\tscale: " << scales[0] << " " << scales[1] << " " << scales[2] << ::std::endl; - scale.setValue(::std::stof(scales[0]), ::std::stof(scales[1]), ::std::stof(scales[2])); + ::SoVRMLCoordinate* vrmlCoordinate = static_cast<::SoVRMLCoordinate*>(vrmlIndexedFaceSet->coord.getValue()); - for (int m = 0; m < vrmlCoordinate->point.getNum(); ++m) + if (!geometries[k].getProperty("scale").empty()) { - vrmlCoordinate->point.set1Value( - m, - vrmlCoordinate->point[m][0] * scale[0], - vrmlCoordinate->point[m][1] * scale[1], - vrmlCoordinate->point[m][2] * scale[2] - ); + ::SbVec3f scale(1.0f, 1.0f, 1.0f); + + ::std::vector<::std::string> scales; + ::std::string scaleProperty = geometries[k].getProperty("scale"); + ::boost::split(scales, scaleProperty, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); +::std::cout << "\tscale: " << scales[0] << " " << scales[1] << " " << scales[2] << ::std::endl; + scale.setValue(::std::stof(scales[0]), ::std::stof(scales[1]), ::std::stof(scales[2])); + + for (int m = 0; m < vrmlCoordinate->point.getNum(); ++m) + { + vrmlCoordinate->point.set1Value( + m, + vrmlCoordinate->point[m][0] * scale[0], + vrmlCoordinate->point[m][1] * scale[1], + vrmlCoordinate->point[m][2] * scale[2] + ); + } } } } - } - - vrml2->unref(); + + vrml2->unref(); #else - throw Exception("rl::sg::UrdfFactory::load() - Mesh support currently not available"); + throw Exception("rl::sg::UrdfFactory::load() - Mesh support currently not available"); #endif + } } - } - else if ("sphere" == shapes[k].getName()) - { - ::SoVRMLSphere* sphere = new ::SoVRMLSphere(); - - if (!shapes[k].getProperty("radius").empty()) + else if ("sphere" == geometries[k].getName()) { - sphere->radius.setValue( - ::boost::lexical_cast(shapes[k].getProperty("radius")) - ); - } - - vrmlShape->geometry = sphere; + ::SoVRMLSphere* sphere = new ::SoVRMLSphere(); + + if (!geometries[k].getProperty("radius").empty()) + { + sphere->radius.setValue( + ::boost::lexical_cast(geometries[k].getProperty("radius")) + ); + } + + vrmlShape->geometry = sphere; ::std::cout << "\tsphere radius: " << sphere->radius.getValue() << ::std::endl; + } } - } - - if (nullptr != vrmlShape->geometry.getValue()) - { - Shape* shape = body->create(vrmlShape); - ::rl::math::Transform origin = ::rl::math::Transform::Identity(); - - if (path.eval("count(origin/@rpy) > 0").getValue()) + if (nullptr != vrmlShape->geometry.getValue()) { - ::std::vector<::std::string> rpy; - ::std::string tmp = path.eval("string(origin/@rpy)").getValue<::std::string>(); - ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); + Shape* shape = body->create(vrmlShape); + + ::rl::math::Transform origin = ::rl::math::Transform::Identity(); + + if (path.eval("count(origin/@rpy) > 0").getValue()) + { + ::std::vector<::std::string> rpy; + ::std::string tmp = path.eval("string(origin/@rpy)").getValue<::std::string>(); + ::boost::split(rpy, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\torigin rpy: " << rpy[0] << " " << rpy[1] << " " << rpy[2] << ::std::endl; + + origin.linear() = ::rl::math::AngleAxis( + ::boost::lexical_cast<::rl::math::Real>(rpy[2]), + ::rl::math::Vector3::UnitZ() + ) * ::rl::math::AngleAxis( + ::boost::lexical_cast<::rl::math::Real>(rpy[1]), + ::rl::math::Vector3::UnitY() + ) * ::rl::math::AngleAxis( + ::boost::lexical_cast<::rl::math::Real>(rpy[0]), + ::rl::math::Vector3::UnitX() + ).toRotationMatrix(); + } - origin.linear() = ::rl::math::AngleAxis( - ::boost::lexical_cast<::rl::math::Real>(rpy[2]), - ::rl::math::Vector3::UnitZ() - ) * ::rl::math::AngleAxis( - ::boost::lexical_cast<::rl::math::Real>(rpy[1]), - ::rl::math::Vector3::UnitY() - ) * ::rl::math::AngleAxis( - ::boost::lexical_cast<::rl::math::Real>(rpy[0]), - ::rl::math::Vector3::UnitX() - ).toRotationMatrix(); - } - - if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLCylinder::getClassTypeId())) - { - origin *= ::rl::math::AngleAxis(90 * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitX()); - } - - if (path.eval("count(origin/@xyz) > 0").getValue()) - { - ::std::vector<::std::string> xyz; - ::std::string tmp = path.eval("string(origin/@xyz)").getValue<::std::string>(); - ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); + if (vrmlShape->geometry.getValue()->isOfType(::SoVRMLCylinder::getClassTypeId())) + { + origin *= ::rl::math::AngleAxis(90 * ::rl::math::constants::deg2rad, ::rl::math::Vector3::UnitX()); + } + + if (path.eval("count(origin/@xyz) > 0").getValue()) + { + ::std::vector<::std::string> xyz; + ::std::string tmp = path.eval("string(origin/@xyz)").getValue<::std::string>(); + ::boost::split(xyz, tmp, ::boost::algorithm::is_space(), ::boost::algorithm::token_compress_on); ::std::cout << "\torigin xyz: " << xyz[0] << " " << xyz[1] << " " << xyz[2] << ::std::endl; + + origin.translation().x() = ::boost::lexical_cast<::rl::math::Real>(xyz[0]); + origin.translation().y() = ::boost::lexical_cast<::rl::math::Real>(xyz[1]); + origin.translation().z() = ::boost::lexical_cast<::rl::math::Real>(xyz[2]); + } - origin.translation().x() = ::boost::lexical_cast<::rl::math::Real>(xyz[0]); - origin.translation().y() = ::boost::lexical_cast<::rl::math::Real>(xyz[1]); - origin.translation().z() = ::boost::lexical_cast<::rl::math::Real>(xyz[2]); + shape->setTransform(origin); } - shape->setTransform(origin); + vrmlShape->unref(); } - vrmlShape->unref(); - // depth first search dfs.pop_front(); From 034bd370217b7c57f4d4a87b395fc48200dc911f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 20 Oct 2021 23:29:01 +0200 Subject: [PATCH 457/546] Remove rl::mdl::Compound --- src/rl/mdl/CMakeLists.txt | 2 - src/rl/mdl/Compound.cpp | 77 ------------------------ src/rl/mdl/Compound.h | 122 -------------------------------------- src/rl/mdl/Element.cpp | 1 - src/rl/mdl/Element.h | 4 -- src/rl/mdl/Model.cpp | 32 ---------- src/rl/mdl/Model.h | 21 +------ 7 files changed, 2 insertions(+), 257 deletions(-) delete mode 100644 src/rl/mdl/Compound.cpp delete mode 100644 src/rl/mdl/Compound.h diff --git a/src/rl/mdl/CMakeLists.txt b/src/rl/mdl/CMakeLists.txt index cf5b801b..b9e4448f 100644 --- a/src/rl/mdl/CMakeLists.txt +++ b/src/rl/mdl/CMakeLists.txt @@ -7,7 +7,6 @@ set( HDRS AnalyticalInverseKinematics.h Body.h - Compound.h Cylindrical.h Dynamic.h Element.h @@ -40,7 +39,6 @@ set( SRCS AnalyticalInverseKinematics.cpp Body.cpp - Compound.cpp Cylindrical.cpp Dynamic.cpp Element.cpp diff --git a/src/rl/mdl/Compound.cpp b/src/rl/mdl/Compound.cpp deleted file mode 100644 index 90e398c8..00000000 --- a/src/rl/mdl/Compound.cpp +++ /dev/null @@ -1,77 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 "Compound.h" -#include "Frame.h" -#include "Transform.h" - -namespace rl -{ - namespace mdl - { - Compound::Compound(Model* model) : - inFrame(nullptr), - inTransform(nullptr), - outFrame(nullptr), - outTransform(nullptr), - model(model), - tree( - model->tree, - ::boost::get(::boost::edge_weight, model->tree), - ::boost::get(::boost::vertex_color, model->tree) - ) - { - } - - Compound::~Compound() - { - } - - void - Compound::add(Frame* frame) - { - frame->compound = this; - } - - void - Compound::add(Transform* transform, const Frame* a, const Frame* b) - { - transform->compound = this; - } - - void - Compound::remove(Frame* frame) - { - frame->compound = nullptr; - } - - void - Compound::remove(Transform* transform) - { - transform->compound = nullptr; - } - } -} diff --git a/src/rl/mdl/Compound.h b/src/rl/mdl/Compound.h deleted file mode 100644 index e27cca39..00000000 --- a/src/rl/mdl/Compound.h +++ /dev/null @@ -1,122 +0,0 @@ -// -// Copyright (c) 2009, Markus Rickert -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright notice, -// this list of conditions and the following disclaimer. -// * Redistributions in binary form must reproduce the above copyright notice, -// this list of conditions and the following disclaimer in the documentation -// and/or other materials provided with the distribution. -// -// 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 RL_MDL_COMPOUND_H -#define RL_MDL_COMPOUND_H - -#include - -#include "Model.h" - -namespace rl -{ - namespace mdl - { - class Frame; - class Transform; - - class RL_MDL_EXPORT Compound - { - public: - Compound(Model* model); - - virtual ~Compound(); - - void add(Frame* frame); - - void add(Transform* transform, const Frame* a, const Frame* b); - - void remove(Frame* frame); - - void remove(Transform* transform); - - Frame* inFrame; - - Transform* inTransform; - - Frame* outFrame; - - Transform* outTransform; - - protected: - - private: - typedef ::boost::property_map< Model::Tree, ::boost::edge_weight_t>::type EdgeWeightMapType; - - typedef ::boost::property_map< Model::Tree, ::boost::vertex_color_t>::type VertexColorMapType; - - template - struct EdgePredicate - { - EdgePredicate() - { - } - - EdgePredicate(const EdgeWeightMap& weight) : - weight(weight) - { - } - - template - bool operator()(const Edge& e) const - { - return this == get(weight, e); - } - - EdgeWeightMap weight; - }; - - template - struct VertexPredicate - { - VertexPredicate() - { - } - - VertexPredicate(const VertexColorMap& color) : - color(color) - { - } - - template - bool operator()(const Vertex& v) const - { - return this == get(color, v); - } - - VertexColorMap color; - }; - - typedef ::boost::filtered_graph, VertexPredicate> Tree; - - Model* model; - - Tree tree; - }; - } -} - -#endif // RL_MDL_COMPOUND_H diff --git a/src/rl/mdl/Element.cpp b/src/rl/mdl/Element.cpp index 63258526..f5528fcc 100644 --- a/src/rl/mdl/Element.cpp +++ b/src/rl/mdl/Element.cpp @@ -31,7 +31,6 @@ namespace rl namespace mdl { Element::Element() : - compound(nullptr), name() { } diff --git a/src/rl/mdl/Element.h b/src/rl/mdl/Element.h index b9f8c80d..db51dbfc 100644 --- a/src/rl/mdl/Element.h +++ b/src/rl/mdl/Element.h @@ -36,8 +36,6 @@ namespace rl { namespace mdl { - class Compound; - class RL_MDL_EXPORT Element { public: @@ -67,8 +65,6 @@ namespace rl void setName(const ::std::string& name); - Compound* compound; - protected: private: diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index d9d93b7b..270be3c6 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -25,7 +25,6 @@ // #include "Body.h" -#include "Compound.h" #include "Exception.h" #include "Joint.h" #include "Model.h" @@ -61,16 +60,6 @@ namespace rl { } - void - Model::add(Compound* compound, const Frame* a, const Frame* b) - { - compound->inTransform = new Transform(); - this->add(compound->inTransform, a, compound->inFrame); - - compound->outTransform = new Transform(); - this->add(compound->outTransform, compound->outFrame, b); - } - void Model::add(Frame* frame) { @@ -572,27 +561,6 @@ namespace rl return this->randDistribution(this->randEngine); } - void - Model::replace(Compound* compound, Transform* transform) - { - this->add(transform, compound->inFrame, compound->outFrame); - this->remove(compound); - } - - void - Model::replace(Transform* transform, Compound* compound) - { - this->add(compound, transform->in, transform->out); - this->remove(transform); - } - - void - Model::remove(Compound* compound) - { - this->remove(compound->inTransform); - this->remove(compound->outTransform); - } - void Model::remove(Frame* frame) { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 8e4e696a..7ad1481c 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -50,7 +50,6 @@ namespace rl namespace mdl { class Body; - class Compound; class Joint; class World; @@ -61,8 +60,6 @@ namespace rl virtual ~Model(); - void add(Compound* compound, const Frame* a, const Frame* b); - void add(Frame* frame); void add(Transform* transform, const Frame* a, const Frame* b); @@ -161,12 +158,6 @@ namespace rl bool isColliding(const ::std::size_t& i) const; - void replace(Compound* compound, Transform* transform); - - void replace(Transform* transform, Compound* compound); - - void remove(Compound* compound); - void remove(Frame* frame); void remove(Transform* transform); @@ -206,20 +197,12 @@ namespace rl const ::rl::math::Transform& world() const; protected: - friend class Compound; - typedef ::boost::adjacency_list< ::boost::listS, ::boost::listS, ::boost::bidirectionalS, - ::boost::property< - ::boost::vertex_color_t, Compound*, - ::std::shared_ptr - >, - ::boost::property< - ::boost::edge_weight_t, Compound*, - ::std::shared_ptr - >, + ::std::shared_ptr, + ::std::shared_ptr, ::boost::no_property, ::boost::listS > Tree; From aafad084a57814c60d113aa848297cdc06065971 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 21 Oct 2021 01:19:15 +0200 Subject: [PATCH 458/546] Use shared pointers in rl::kin::Kinematics and rl::mdl::Model --- src/rl/kin/Kinematics.cpp | 24 +++++++++++------------ src/rl/mdl/Model.cpp | 18 ++++++++++++++--- src/rl/mdl/Model.h | 8 ++++++-- src/rl/mdl/UrdfFactory.cpp | 32 +++++++++++++++--------------- src/rl/mdl/XmlFactory.cpp | 40 +++++++++++++++++++------------------- 5 files changed, 69 insertions(+), 53 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index c0e0f05c..b19ec54b 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -191,7 +191,7 @@ namespace rl if ("frame" == frames[j].getName()) { - Frame* f = new Frame(); + ::std::shared_ptr f = ::std::make_shared(); f->name = path.eval("string(@id)").getValue<::std::string>(); @@ -212,19 +212,19 @@ namespace rl f->frame.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); f->frame.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); - kinematics->tree[v].reset(f); + kinematics->tree[v] = f; } else if ("link" == frames[j].getName()) { - Link* l = new Link(); + ::std::shared_ptr l = ::std::make_shared(); l->name = path.eval("string(@id)").getValue<::std::string>(); - kinematics->tree[v].reset(l); + kinematics->tree[v] = l; } else if ("world" == frames[j].getName()) { - Frame* f = new Frame(); + ::std::shared_ptr f = ::std::make_shared(); f->name = path.eval("string(@id)").getValue<::std::string>(); @@ -247,7 +247,7 @@ namespace rl kinematics->root = v; - kinematics->tree[v].reset(f); + kinematics->tree[v] = f; } ::std::string id = path.eval("string(@id)").getValue<::std::string>(); @@ -335,7 +335,7 @@ namespace rl if ("prismatic" == transforms[j].getName()) { - Prismatic* p = new Prismatic(); + ::std::shared_ptr p = ::std::make_shared(); p->name = name; @@ -352,11 +352,11 @@ namespace rl p->alpha *= ::rl::math::constants::deg2rad; p->theta *= ::rl::math::constants::deg2rad; - kinematics->tree[e].reset(p); + kinematics->tree[e] = p; } else if ("revolute" == transforms[j].getName()) { - Revolute* r = new Revolute(); + ::std::shared_ptr r = ::std::make_shared(); r->name = name; @@ -377,11 +377,11 @@ namespace rl r->speed *= ::rl::math::constants::deg2rad; r->theta *= ::rl::math::constants::deg2rad; - kinematics->tree[e].reset(r); + kinematics->tree[e] = r; } else if ("transform" == transforms[j].getName()) { - Transform* t = new Transform(); + ::std::shared_ptr t = ::std::make_shared(); t->name = name; @@ -402,7 +402,7 @@ namespace rl t->transform.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); t->transform.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); - kinematics->tree[e].reset(t); + kinematics->tree[e] = t; } } } diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 270be3c6..6b377504 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -62,12 +62,18 @@ namespace rl void Model::add(Frame* frame) + { + this->add(::std::shared_ptr(frame)); + } + + void + Model::add(const ::std::shared_ptr& frame) { Vertex vertex = ::boost::add_vertex(this->tree); frame->setVertexDescriptor(vertex); - this->tree[vertex].reset(frame); + this->tree[vertex] = frame; - if (dynamic_cast(frame)) + if (::std::dynamic_pointer_cast(frame)) { this->root = vertex; } @@ -75,10 +81,16 @@ namespace rl void Model::add(Transform* transform, const Frame* a, const Frame* b) + { + this->add(::std::shared_ptr(transform), a, b); + } + + void + Model::add(const ::std::shared_ptr& transform, const Frame* a, const Frame* b) { Edge edge = ::boost::add_edge(a->getVertexDescriptor(), b->getVertexDescriptor(), this->tree).first; transform->setEdgeDescriptor(edge); - this->tree[edge].reset(transform); + this->tree[edge] = transform; } bool diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 7ad1481c..b1ef3eb9 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -60,9 +60,13 @@ namespace rl virtual ~Model(); - void add(Frame* frame); + RL_MDL_DEPRECATED void add(Frame* frame); - void add(Transform* transform, const Frame* a, const Frame* b); + void add(const ::std::shared_ptr& frame); + + RL_MDL_DEPRECATED void add(Transform* transform, const Frame* a, const Frame* b); + + void add(const ::std::shared_ptr& transform, const Frame* a, const Frame* b); bool areColliding(const ::std::size_t& i, const ::std::size_t& j) const; diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 8dfa0c49..73a75a3d 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -102,7 +102,7 @@ ::std::cout << model->getName() << ::std::endl; ::std::cout << "link: " << j << ::std::endl; ::rl::xml::Path path(document, links[j]); - Body* b = new Body(); + ::std::shared_ptr b = ::std::make_shared(); model->add(b); @@ -147,7 +147,7 @@ ::std::cout << "\tmass: " << b->m << ::std::endl; b->setName(path.eval("string(@name)").getValue<::std::string>()); ::std::cout << "\tname: " << b->getName() << ::std::endl; - name2frame[path.eval("string(@name)").getValue<::std::string>()] = b; + name2frame[path.eval("string(@name)").getValue<::std::string>()] = b.get(); } // joints @@ -175,12 +175,12 @@ ::std::cout << "\tchild: " << child->getName() << ::std::endl; // frame - Frame* frame = new Frame(); + ::std::shared_ptr frame = ::std::make_shared(); model->add(frame); // fixed - Fixed* fixed = new Fixed(); + ::std::shared_ptr fixed = ::std::make_shared(); if (path.eval("count(origin/@rpy) > 0").getValue()) { @@ -226,10 +226,10 @@ ::std::cout << "\tname: " << fixed->getName() << ::std::endl; } else if ("floating" == type) { - SixDof* s = new SixDof(); + ::std::shared_ptr s = ::std::make_shared(); - model->add(fixed, parent, frame); - model->add(s, frame, child); + model->add(fixed, parent, frame.get()); + model->add(s, frame.get(), child); s->setName(path.eval("string(@name)").getValue<::std::string>()); ::std::cout << "\tname: " << s->getName() << ::std::endl; @@ -240,10 +240,10 @@ ::std::cout << "\tname: " << s->getName() << ::std::endl; } else if ("prismatic" == type) { - Prismatic* p = new Prismatic(); + ::std::shared_ptr p = ::std::make_shared(); - model->add(fixed, parent, frame); - model->add(p, frame, child); + model->add(fixed, parent, frame.get()); + model->add(p, frame.get(), child); p->max(0) = path.eval("number(limit/@upper)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); ::std::cout << "\tmax: " << p->max(0) << ::std::endl; @@ -277,10 +277,10 @@ ::std::cout << "\tname: " << p->getName() << ::std::endl; } else if ("revolute" == type || "continuous" == type) { - Revolute* r = new Revolute(); + ::std::shared_ptr r = ::std::make_shared(); - model->add(fixed, parent, frame); - model->add(r, frame, child); + model->add(fixed, parent, frame.get()); + model->add(r, frame.get(), child); if ("continuous" == path.eval("string(@type)").getValue<::std::string>()) { @@ -326,7 +326,7 @@ ::std::cout << "\tname: " << r->getName() << ::std::endl; // root - World* world = new World(); + ::std::shared_ptr world = ::std::make_shared(); model->add(world); world->setGravity(::rl::math::Vector3(0, 0, 9.80665)); @@ -340,8 +340,8 @@ ::std::cout << "\tname: " << r->getName() << ::std::endl; { root = name2frame[frame->first]; ::std::cout << "root: " << root->getName() << ::std::endl; - Fixed* fixed = new Fixed(); - model->add(fixed, world, root); + ::std::shared_ptr fixed = ::std::make_shared(); + model->add(fixed, world.get(), root); } else { diff --git a/src/rl/mdl/XmlFactory.cpp b/src/rl/mdl/XmlFactory.cpp index c89f4dcb..07856b03 100644 --- a/src/rl/mdl/XmlFactory.cpp +++ b/src/rl/mdl/XmlFactory.cpp @@ -120,7 +120,7 @@ namespace rl if ("body" == frames[j].getName()) { - Body* b = new Body(); + ::std::shared_ptr b = ::std::make_shared(); model->add(b); @@ -143,19 +143,19 @@ namespace rl path.eval("number(m)").getValue<::rl::math::Real>(1) ); - frame = b; + frame = b.get(); } else if ("frame" == frames[j].getName()) { - Frame* f = new Frame(); + ::std::shared_ptr f = ::std::make_shared(); model->add(f); - frame = f; + frame = f.get(); } else if ("world" == frames[j].getName()) { - World* w = new World(); + ::std::shared_ptr w = ::std::make_shared(); model->add(w); @@ -182,7 +182,7 @@ namespace rl ) ); - frame = w; + frame = w.get(); } if (nullptr != frame) @@ -273,7 +273,7 @@ namespace rl if ("cylindrical" == transforms[j].getName()) { - Cylindrical* c = new Cylindrical(); + ::std::shared_ptr c = ::std::make_shared(); model->add(c, a, b); @@ -297,11 +297,11 @@ namespace rl c->S(4, 1) = path.eval("number(axis[2]/y)").getValue<::rl::math::Real>(0); c->S(5, 1) = path.eval("number(axis[2]/z)").getValue<::rl::math::Real>(1); - transform = c; + transform = c.get(); } else if ("fixed" == transforms[j].getName()) { - Fixed* f = new Fixed(); + ::std::shared_ptr f = ::std::make_shared(); model->add(f, a, b); @@ -320,11 +320,11 @@ namespace rl f->x.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); f->x.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); - transform = f; + transform = f.get(); } else if ("helical" == transforms[j].getName()) { - Helical* h = new Helical(); + ::std::shared_ptr h = ::std::make_shared(); model->add(h, a, b); @@ -344,11 +344,11 @@ namespace rl h->setPitch(path.eval("number(pitch)").getValue<::rl::math::Real>(1)); - transform = h; + transform = h.get(); } else if ("prismatic" == transforms[j].getName()) { - Prismatic* p = new Prismatic(); + ::std::shared_ptr p = ::std::make_shared(); model->add(p, a, b); @@ -362,11 +362,11 @@ namespace rl p->S(4, 0) = path.eval("number(axis/y)").getValue<::rl::math::Real>(0); p->S(5, 0) = path.eval("number(axis/z)").getValue<::rl::math::Real>(1); - transform = p; + transform = p.get(); } else if ("revolute" == transforms[j].getName()) { - Revolute* r = new Revolute(); + ::std::shared_ptr r = ::std::make_shared(); model->add(r, a, b); @@ -385,11 +385,11 @@ namespace rl r->offset *= ::rl::math::constants::deg2rad; r->speed *= ::rl::math::constants::deg2rad; - transform = r; + transform = r.get(); } else if ("sixDof" == transforms[j].getName()) { - SixDof* s = new SixDof(); + ::std::shared_ptr s = ::std::make_shared(); model->add(s, a, b); @@ -406,15 +406,15 @@ namespace rl s->speed(1) = path.eval("number(speed[2])").getValue<::rl::math::Real>(0); s->speed(2) = path.eval("number(speed[3])").getValue<::rl::math::Real>(0); - transform = s; + transform = s.get(); } else if ("spherical" == transforms[j].getName()) { - Spherical* s = new Spherical(); + ::std::shared_ptr s = ::std::make_shared(); model->add(s, a, b); - transform = s; + transform = s.get(); } if (nullptr != transform) From 3144bff5bc81b808673f298f6e80f324d19a4a4b Mon Sep 17 00:00:00 2001 From: Hauptmech Date: Sat, 23 Oct 2021 01:54:09 +1300 Subject: [PATCH 459/546] Allow downstream code to use the Eigen plugin system (#47) --- src/rl/math/MatrixBaseAddons.h | 4 ++++ src/rl/math/QuaternionBaseAddons.h | 4 ++++ src/rl/math/TransformAddons.h | 4 ++++ 3 files changed, 12 insertions(+) diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index 5d9cefcf..a4e320aa 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -332,4 +332,8 @@ voigt33() const } } #endif +#ifdef RL_EIGEN_MATRIXBASE_PLUGIN +#include RL_EIGEN_MATRIXBASE_PLUGIN +#endif + #endif // RL_MATH_MATRIXBASEADDONS_H diff --git a/src/rl/math/QuaternionBaseAddons.h b/src/rl/math/QuaternionBaseAddons.h index a4fb0b85..fefeae82 100644 --- a/src/rl/math/QuaternionBaseAddons.h +++ b/src/rl/math/QuaternionBaseAddons.h @@ -307,4 +307,8 @@ squadFirstDerivative(const Scalar& t, const QuaternionBase& a, co } } #endif +#ifdef RL_EIGEN_QUATERNIONBASE_PLUGIN +#include RL_EIGEN_QUATERNIONBASE_PLUGIN +#endif + #endif // RL_MATH_QUATERNIONBASEADDONS_H diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index a27299ff..ff8b0f04 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -230,4 +230,8 @@ toDenavitHartenbergPaul(OtherScalar1& d, OtherScalar2& theta, OtherScalar3& a, O } } #endif +#ifdef RL_EIGEN_TRANSFORM_PLUGIN +#include RL_EIGEN_TRANSFORM_PLUGIN +#endif + #endif // RL_MATH_TRANSFORMADDONS_H From 601d7bd8fde70fc7bc1a748a6fb87423bdc2942e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Nov 2021 22:51:43 +0100 Subject: [PATCH 460/546] Fix initialization order --- src/rl/plan/Planner.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/plan/Planner.cpp b/src/rl/plan/Planner.cpp index ec49b77f..6c60ed59 100644 --- a/src/rl/plan/Planner.cpp +++ b/src/rl/plan/Planner.cpp @@ -33,12 +33,12 @@ namespace rl namespace plan { Planner::Planner() : - time(), duration(::std::chrono::steady_clock::duration::max()), goal(nullptr), model(nullptr), start(nullptr), - viewer(nullptr) + viewer(nullptr), + time() { } From 524f8d666b1e02deee696ba392fe15ed877176ae Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Nov 2021 15:43:54 +0100 Subject: [PATCH 461/546] Remove memset from Serial::read, Socket::recv, and Socket::recvfrom --- src/rl/hal/Serial.cpp | 2 -- src/rl/hal/Socket.cpp | 4 ---- 2 files changed, 6 deletions(-) diff --git a/src/rl/hal/Serial.cpp b/src/rl/hal/Serial.cpp index e92f4ccc..77b5eafc 100644 --- a/src/rl/hal/Serial.cpp +++ b/src/rl/hal/Serial.cpp @@ -475,8 +475,6 @@ namespace rl { assert(this->isConnected()); - ::std::memset(buf, 0, count); - #ifdef WIN32 ::DWORD numbytes; diff --git a/src/rl/hal/Socket.cpp b/src/rl/hal/Socket.cpp index f95d8f3f..63ddfabb 100644 --- a/src/rl/hal/Socket.cpp +++ b/src/rl/hal/Socket.cpp @@ -388,8 +388,6 @@ namespace rl ::std::size_t Socket::recv(void* buf, const ::std::size_t& count) { - ::std::memset(buf, 0, count); - #ifdef WIN32 int numbytes = ::recv(this->fd, static_cast(buf), count, 0); #else // WIN32 @@ -416,8 +414,6 @@ namespace rl { int addrlen = address.getLength(); - ::std::memset(buf, 0, count); - #ifdef WIN32 int numbytes = ::recvfrom(this->fd, static_cast(buf), count, 0, reinterpret_cast<::sockaddr*>(&address.get()->addr), &addrlen); #else // WIN32 From 121f05de9eb818b9731c392269f00d95a3322869 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Nov 2021 15:44:15 +0100 Subject: [PATCH 462/546] Update socket demos --- demos/rlSocketDemo/rlSocketDemoClient.cpp | 27 +++++++++++++++----- demos/rlSocketDemo/rlSocketDemoServer.cpp | 31 +++++++++++++++++------ 2 files changed, 44 insertions(+), 14 deletions(-) diff --git a/demos/rlSocketDemo/rlSocketDemoClient.cpp b/demos/rlSocketDemo/rlSocketDemoClient.cpp index 2b5086b2..757c01af 100644 --- a/demos/rlSocketDemo/rlSocketDemoClient.cpp +++ b/demos/rlSocketDemo/rlSocketDemoClient.cpp @@ -44,6 +44,20 @@ main(int argc, char** argv) return EXIT_FAILURE; } + std::size_t bufferSize = boost::lexical_cast(argv[4]); + + if (0 == bufferSize) + { + std::cout << "Error: Buffer size is zero" << std::endl; + return EXIT_FAILURE; + } + + if (bufferSize > std::allocator_traits>::max_size(std::allocator())) + { + std::cout << "Error: Buffer size exceeds maximum" << std::endl; + return EXIT_FAILURE; + } + try { #ifdef IPV4 @@ -63,15 +77,16 @@ main(int argc, char** argv) socket.connect(); std::string message = argv[3]; - std::size_t numbytes = socket.send(message.c_str(), message.length()); + std::size_t numbytes = socket.send(message.data(), message.size()); std::cout << numbytes << " characters sent" << std::endl; - std::cout << message.substr(0, numbytes) << std::endl; + std::copy(message.begin(), message.begin() + numbytes, std::ostream_iterator(std::cout)); + std::cout << std::endl; - std::vector buffer(boost::lexical_cast(argv[4]) + 1); - buffer.back() = '\0'; - numbytes = socket.recv(buffer.data(), buffer.size() - 1); + std::vector buffer(bufferSize); + numbytes = socket.recv(buffer.data(), buffer.size()); std::cout << numbytes << " characters received" << std::endl; - std::cout << buffer.data() << std::endl; + std::copy(buffer.begin(), buffer.begin() + numbytes, std::ostream_iterator(std::cout)); + std::cout << std::endl; socket.close(); } diff --git a/demos/rlSocketDemo/rlSocketDemoServer.cpp b/demos/rlSocketDemo/rlSocketDemoServer.cpp index 8a156445..2be8823e 100644 --- a/demos/rlSocketDemo/rlSocketDemoServer.cpp +++ b/demos/rlSocketDemo/rlSocketDemoServer.cpp @@ -40,14 +40,25 @@ int main(int argc, char** argv) { - if (argc < 2) + if (argc < 3) { std::cout << "Usage: rlSocketDemoServer PORT BUFFERSIZE" << std::endl; return EXIT_FAILURE; } - std::vector buffer(boost::lexical_cast(argv[2]) + 1); - buffer.back() = '\0'; + std::size_t bufferSize = boost::lexical_cast(argv[2]); + + if (0 == bufferSize) + { + std::cout << "Error: Buffer size is zero" << std::endl; + return EXIT_FAILURE; + } + + if (bufferSize > std::allocator_traits>::max_size(std::allocator())) + { + std::cout << "Error: Buffer size exceeds maximum" << std::endl; + return EXIT_FAILURE; + } try { @@ -70,20 +81,23 @@ main(int argc, char** argv) socket.listen(); #endif + std::vector buffer(bufferSize); + while (true) { - std::memset(buffer.data(), 0, buffer.size() - 1); + std::memset(buffer.data(), 0, buffer.size()); #ifdef TCP rl::hal::Socket connection = socket.accept(); - std::size_t numbytes = connection.recv(buffer.data(), buffer.size() - 1); + std::size_t numbytes = connection.recv(buffer.data(), buffer.size()); #endif #ifdef UDP rl::hal::Socket::Address address; - std::size_t numbytes = socket.recvfrom(buffer.data(), buffer.size() - 1, address); + std::size_t numbytes = socket.recvfrom(buffer.data(), buffer.size(), address); #endif std::cout << numbytes << " characters received" << std::endl; - std::cout << buffer.data() << std::endl; + std::copy(buffer.begin(), buffer.begin() + numbytes, std::ostream_iterator(std::cout)); + std::cout << std::endl; #ifdef TCP numbytes = connection.send(buffer.data(), numbytes); @@ -92,7 +106,8 @@ main(int argc, char** argv) numbytes = socket.sendto(buffer.data(), numbytes, address); #endif std::cout << numbytes << " characters sent" << std::endl; - std::cout << buffer.data() << std::endl; + std::copy(buffer.begin(), buffer.begin() + numbytes, std::ostream_iterator(std::cout)); + std::cout << std::endl; } socket.close(); From a6983c8bc264b606ad2ce5eeacde8daf4acc3d20 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 17 Nov 2021 17:00:02 +0100 Subject: [PATCH 463/546] Add support for UR firmware 3.13 to 3.15 and 5.7 to 5.10 --- src/rl/hal/UniversalRobotsRealtime.cpp | 22 +++++++++++++++++++++- src/rl/hal/UniversalRobotsRealtime.h | 9 ++++++++- 2 files changed, 29 insertions(+), 2 deletions(-) diff --git a/src/rl/hal/UniversalRobotsRealtime.cpp b/src/rl/hal/UniversalRobotsRealtime.cpp index 1862fdd7..b4d3ec52 100644 --- a/src/rl/hal/UniversalRobotsRealtime.cpp +++ b/src/rl/hal/UniversalRobotsRealtime.cpp @@ -311,7 +311,7 @@ namespace rl void UniversalRobotsRealtime::step() { - ::std::array<::std::uint8_t, 1116> buffer; + ::std::array<::std::uint8_t, 1220> buffer; this->socket.recv(buffer.data(), sizeof(this->in.messageSize)); #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) @@ -330,6 +330,8 @@ namespace rl case 1060: case 1108: case 1116: + case 1140: + case 1220: this->socket.recv(ptr, this->in.messageSize - sizeof(this->in.messageSize)); #if !defined(__APPLE__) && !defined(__QNX__) && !defined(WIN32) && !defined(__CYGWIN__) this->socket.setOption(Socket::Option::quickack, 1); @@ -382,6 +384,8 @@ namespace rl case 1060: case 1108: case 1116: + case 1140: + case 1220: this->unserialize(ptr, this->iControl); this->unserialize(ptr, this->toolVectorActual); this->unserialize(ptr, this->tcpSpeedActual); @@ -452,6 +456,22 @@ namespace rl } this->unserialize(ptr, this->safetyStatus); + + if (this->messageSize < 1140) + { + return; + } + + ptr += 3 * sizeof(double); + + if (this->messageSize < 1220) + { + return; + } + + this->unserialize(ptr, this->payloadMass); + this->unserialize(ptr, this->payloadCog); + this->unserialize(ptr, this->payloadInertia); } template<> diff --git a/src/rl/hal/UniversalRobotsRealtime.h b/src/rl/hal/UniversalRobotsRealtime.h index ca69e1e4..80be4604 100644 --- a/src/rl/hal/UniversalRobotsRealtime.h +++ b/src/rl/hal/UniversalRobotsRealtime.h @@ -49,7 +49,8 @@ namespace rl * Universal Robots realtime interface. * * Supports versions 1.5, 1.6, 1.7, 1.8, 3.0, 3.1, 3.2, 3.3, 3.4, 3.5, 3.6, - * 3.7, 3.8, 3.9, 3.10, 3.11, 3.12, 5.0, 5.1, 5.2, 5.3, 5.4, 5.5, 5.6. + * 3.7, 3.8, 3.9, 3.10, 3.11, 3.12, 3.13, 3.14, 3.15, 5.0, 5.1, 5.2, 5.3, 5.4, + * 5.5, 5.6, 5.7, 5.8, 5.9, 5.10. */ class RL_HAL_EXPORT UniversalRobotsRealtime : public CartesianForceSensor, @@ -341,6 +342,12 @@ namespace rl double elbowVelocity[3]; double safetyStatus; + + double payloadMass; + + double payloadCog[3]; + + double payloadInertia[6]; }; Message in; From 36ff7506d15f2a163266beeb863f3e9386b4339e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 2 Dec 2021 20:42:25 +0100 Subject: [PATCH 464/546] Remove piecewise_construct and forward_as_tuple in emplace --- src/rl/math/GnatNearestNeighbors.h | 4 ++-- src/rl/math/KdtreeBoundingBoxNearestNeighbors.h | 2 +- src/rl/math/KdtreeNearestNeighbors.h | 2 +- src/rl/plan/RecursiveVerifier.cpp | 6 +++--- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index d74c1257..ccf9b852 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -515,7 +515,7 @@ namespace rl neighbors.pop_back(); } - neighbors.emplace_back(::std::piecewise_construct, ::std::forward_as_tuple(distance), ::std::forward_as_tuple(node.data[i])); + neighbors.emplace_back(distance, node.data[i]); ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } } @@ -549,7 +549,7 @@ namespace rl neighbors.pop_back(); } - neighbors.emplace_back(::std::piecewise_construct, ::std::forward_as_tuple(distances[i]), ::std::forward_as_tuple(node.children[i].pivot)); + neighbors.emplace_back(distances[i], node.children[i].pivot); ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } } diff --git a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h index 11388f7b..fb702caa 100644 --- a/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h +++ b/src/rl/math/KdtreeBoundingBoxNearestNeighbors.h @@ -584,7 +584,7 @@ namespace rl neighbors.pop_back(); } - neighbors.emplace_back(::std::piecewise_construct, ::std::forward_as_tuple(distance), ::std::forward_as_tuple(node.data[i])); + neighbors.emplace_back(distance, node.data[i]); ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } } diff --git a/src/rl/math/KdtreeNearestNeighbors.h b/src/rl/math/KdtreeNearestNeighbors.h index 709028d0..ced53842 100644 --- a/src/rl/math/KdtreeNearestNeighbors.h +++ b/src/rl/math/KdtreeNearestNeighbors.h @@ -470,7 +470,7 @@ namespace rl neighbors.pop_back(); } - neighbors.emplace_back(::std::piecewise_construct, ::std::forward_as_tuple(distance), ::std::forward_as_tuple(*node.data)); + neighbors.emplace_back(distance, *node.data); ::std::push_heap(neighbors.begin(), neighbors.end(), NeighborCompare()); } } diff --git a/src/rl/plan/RecursiveVerifier.cpp b/src/rl/plan/RecursiveVerifier.cpp index b72833fe..e6c25ae7 100644 --- a/src/rl/plan/RecursiveVerifier.cpp +++ b/src/rl/plan/RecursiveVerifier.cpp @@ -54,7 +54,7 @@ namespace rl { ::std::queue<::std::pair<::std::size_t, ::std::size_t>> queue; - queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(1), ::std::forward_as_tuple(steps - 1)); + queue.emplace(1, steps - 1); ::rl::math::Vector inter(u.size()); @@ -71,12 +71,12 @@ namespace rl if (queue.front().first < midpoint) { - queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(queue.front().first), ::std::forward_as_tuple(midpoint - 1)); + queue.emplace(queue.front().first, midpoint - 1); } if (queue.front().second > midpoint) { - queue.emplace(::std::piecewise_construct, ::std::forward_as_tuple(midpoint + 1), ::std::forward_as_tuple(queue.front().second)); + queue.emplace(midpoint + 1, queue.front().second); } queue.pop(); From 657951376e2bd5174eefa41e7f5378f3cf9fc163 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 3 Dec 2021 21:07:40 +0100 Subject: [PATCH 465/546] Add support for UrdfFactory in rlPlanDemo --- demos/rlPlanDemo/MainWindow.cpp | 204 ++++++++++++++++++-------------- 1 file changed, 112 insertions(+), 92 deletions(-) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 257f3096..a0433bc4 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -44,6 +44,7 @@ #include #include #include +#include #include #include #include @@ -71,6 +72,7 @@ #include #include #include +#include #include #include #include @@ -872,64 +874,71 @@ MainWindow::load(const QString& filename) } #endif // RL_SG_SOLID - rl::mdl::XmlFactory modelFactory; - rl::sg::XmlFactory sceneFactory; - rl::xml::NodeSet modelScene = path.eval("(/rl/plan|/rlplan)//model/scene").getValue(); - sceneFactory.load(modelScene[0].getUri(modelScene[0].getProperty("href")), this->scene.get()); - this->sceneModel = this->scene->getModel( - path.eval("number((/rl/plan|/rlplan)//model/model)").getValue() - ); + std::string modelSceneFilename = modelScene[0].getLocalPath(modelScene[0].getProperty("href")); - if ("mdl" == path.eval("string((/rl/plan|/rlplan)//model/kinematics/@type)").getValue()) + if ("urdf" == modelSceneFilename.substr(modelSceneFilename.length() - 4, 4)) { - rl::xml::NodeSet mdl = path.eval("(/rl/plan|/rlplan)//model/kinematics").getValue(); - this->mdl = std::dynamic_pointer_cast(modelFactory.create( - mdl[0].getUri(mdl[0].getProperty("href")) - )); - - if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/world) > 0").getValue()) - { - this->mdl->world() = rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitZ() - ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitY() - ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitX() - ); - - this->mdl->world().translation().x() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/x)").getValue(0); - this->mdl->world().translation().y() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/y)").getValue(0); - this->mdl->world().translation().z() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/z)").getValue(0); - } + rl::sg::UrdfFactory sceneFactory; + sceneFactory.load(modelSceneFilename, this->scene.get()); + this->sceneModel = this->scene->getModel( + path.eval("number((/rl/plan|/rlplan)//model/model)").getValue() + ); } else { - rl::xml::NodeSet kin = path.eval("(/rl/plan|/rlplan)//model/kinematics").getValue(); - this->kin = rl::kin::Kinematics::create( - kin[0].getUri(kin[0].getProperty("href")) + rl::sg::XmlFactory sceneFactory; + sceneFactory.load(modelSceneFilename, this->scene.get()); + this->sceneModel = this->scene->getModel( + path.eval("number((/rl/plan|/rlplan)//model/model)").getValue() ); + } + + rl::xml::NodeSet modelKinematics = path.eval("(/rl/plan|/rlplan)//model/kinematics").getValue(); + std::string modelKinematicsFilename = modelKinematics[0].getLocalPath(modelKinematics[0].getProperty("href")); + + if ("urdf" == modelKinematicsFilename.substr(modelKinematicsFilename.length() - 4, 4)) + { + rl::mdl::UrdfFactory modelFactory; + this->mdl = std::dynamic_pointer_cast(modelFactory.create(modelKinematicsFilename)); + } + else if ("mdl" == modelKinematics[0].getProperty("type")) + { + rl::mdl::XmlFactory modelFactory; + this->mdl = std::dynamic_pointer_cast(modelFactory.create(modelKinematicsFilename)); + } + else + { + this->kin = rl::kin::Kinematics::create(modelKinematicsFilename); + } + + if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/world) > 0").getValue()) + { + rl::math::Transform* world = nullptr; - if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/world) > 0").getValue()) + if (nullptr != this->kin.get()) { - this->kin->world() = rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitZ() - ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitY() - ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitX() - ); - - this->kin->world().translation().x() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/x)").getValue(0); - this->kin->world().translation().y() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/y)").getValue(0); - this->kin->world().translation().z() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/z)").getValue(0); + world = &this->kin->world(); } + else if (nullptr != this->mdl.get()) + { + world = &this->mdl->world(); + } + + world->linear() = rl::math::AngleAxis( + path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, + rl::math::Vector3::UnitZ() + ) * rl::math::AngleAxis( + path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, + rl::math::Vector3::UnitY() + ) * rl::math::AngleAxis( + path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, + rl::math::Vector3::UnitX() + ).toRotationMatrix(); + + world->translation().x() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/x)").getValue(0); + world->translation().y() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/y)").getValue(0); + world->translation().z() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/z)").getValue(0); } if (rl::sg::DistanceScene* scene = dynamic_cast(this->scene.get())) @@ -967,60 +976,71 @@ MainWindow::load(const QString& filename) this->scene2 = std::make_shared(); rl::xml::NodeSet viewerScene = path.eval("(/rl/plan|/rlplan)//viewer/model/scene").getValue(); - sceneFactory.load(viewerScene[0].getUri(viewerScene[0].getProperty("href")), this->scene2.get()); - this->sceneModel2 = static_cast(this->scene2->getModel( - path.eval("number((/rl/plan|/rlplan)//viewer/model/model)").getValue() - )); + std::string viewerSceneFilename = viewerScene[0].getLocalPath(viewerScene[0].getProperty("href")); - if ("mdl" == path.eval("string((/rl/plan|/rlplan)//viewer/model/kinematics/@type)").getValue()) + if ("urdf" == viewerSceneFilename.substr(viewerSceneFilename.length() - 4, 4)) { - rl::xml::NodeSet mdl2 = path.eval("(/rl/plan|/rlplan)//viewer/model/kinematics").getValue(); - this->mdl2 = std::dynamic_pointer_cast(modelFactory.create( - mdl2[0].getUri(mdl2[0].getProperty("href")) + rl::sg::UrdfFactory sceneFactory; + sceneFactory.load(viewerSceneFilename, this->scene2.get()); + this->sceneModel2 = static_cast(this->scene2->getModel( + path.eval("number((/rl/plan|/rlplan)//viewer/model/model)").getValue() )); - - if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/world) > 0").getValue()) - { - this->mdl2->world() = rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitZ() - ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitY() - ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitX() - ); - - this->mdl2->world().translation().x() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/x)").getValue(0); - this->mdl2->world().translation().y() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/y)").getValue(0); - this->mdl2->world().translation().z() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/z)").getValue(0); - } + } + else + { + rl::sg::XmlFactory sceneFactory; + sceneFactory.load(viewerSceneFilename, this->scene2.get()); + this->sceneModel2 = static_cast(this->scene2->getModel( + path.eval("number((/rl/plan|/rlplan)//viewer/model/model)").getValue() + )); + } + + rl::xml::NodeSet viewerKinematics = path.eval("(/rl/plan|/rlplan)//viewer/model/kinematics").getValue(); + std::string viewerKinematicsFilename = viewerKinematics[0].getLocalPath(viewerKinematics[0].getProperty("href")); + + if ("urdf" == viewerKinematicsFilename.substr(viewerKinematicsFilename.length() - 4, 4)) + { + rl::mdl::UrdfFactory modelFactory; + this->mdl2 = std::dynamic_pointer_cast(modelFactory.create(viewerKinematicsFilename)); + } + else if ("mdl" == viewerKinematics[0].getProperty("type")) + { + rl::mdl::XmlFactory modelFactory; + this->mdl2 = std::dynamic_pointer_cast(modelFactory.create(viewerKinematicsFilename)); } else { rl::xml::NodeSet kin2 = path.eval("(/rl/plan|/rlplan)//viewer/model/kinematics").getValue(); - this->kin2 = rl::kin::Kinematics::create( - kin2[0].getUri(kin2[0].getProperty("href")) - ); + this->kin2 = rl::kin::Kinematics::create(viewerKinematicsFilename); + } + + if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/world) > 0").getValue()) + { + rl::math::Transform* world = nullptr; - if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/world) > 0").getValue()) + if (nullptr != this->kin2.get()) { - this->kin2->world() = rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitZ() - ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitY() - ) * rl::math::AngleAxis( - path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, - rl::math::Vector3::UnitX() - ); - - this->kin2->world().translation().x() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/x)").getValue(0); - this->kin2->world().translation().y() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/y)").getValue(0); - this->kin2->world().translation().z() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/z)").getValue(0); + world = &this->kin2->world(); + } + else if (nullptr != this->mdl2.get()) + { + world = &this->mdl2->world(); } + + world->linear() = rl::math::AngleAxis( + path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/z)").getValue(0) * rl::math::constants::deg2rad, + rl::math::Vector3::UnitZ() + ) * rl::math::AngleAxis( + path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/y)").getValue(0) * rl::math::constants::deg2rad, + rl::math::Vector3::UnitY() + ) * rl::math::AngleAxis( + path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/rotation/x)").getValue(0) * rl::math::constants::deg2rad, + rl::math::Vector3::UnitX() + ).toRotationMatrix(); + + world->translation().x() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/x)").getValue(0); + world->translation().y() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/y)").getValue(0); + world->translation().z() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/z)").getValue(0); } this->model2 = std::make_shared(); From 577768832bbc5a689e3e0f5ecc7a5fc27e657f3c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 4 Dec 2021 00:16:07 +0100 Subject: [PATCH 466/546] Fix AlignedBox::squaredInteriorDistance --- src/rl/math/AlignedBox.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/math/AlignedBox.h b/src/rl/math/AlignedBox.h index c3a9ba03..37ddebf3 100644 --- a/src/rl/math/AlignedBox.h +++ b/src/rl/math/AlignedBox.h @@ -102,7 +102,7 @@ namespace rl inline Scalar squaredInteriorDistance(const ::Eigen::MatrixBase& p) const { using ::std::pow; - return pow(this->squaredInteriorDistance(p), 2); + return pow(this->interiorDistance(p), 2); } protected: From 7592ee01d023ccaeb60b3d0f215693fff5c465e8 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 10 Dec 2021 14:48:42 +0100 Subject: [PATCH 467/546] Fix default values for URDF lower and upper limit --- src/rl/mdl/UrdfFactory.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rl/mdl/UrdfFactory.cpp b/src/rl/mdl/UrdfFactory.cpp index 73a75a3d..a8e47f94 100644 --- a/src/rl/mdl/UrdfFactory.cpp +++ b/src/rl/mdl/UrdfFactory.cpp @@ -245,9 +245,9 @@ ::std::cout << "\tname: " << s->getName() << ::std::endl; model->add(fixed, parent, frame.get()); model->add(p, frame.get(), child); - p->max(0) = path.eval("number(limit/@upper)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + p->max(0) = path.eval("number(limit/@upper)").getValue<::rl::math::Real>(0); ::std::cout << "\tmax: " << p->max(0) << ::std::endl; - p->min(0) = path.eval("number(limit/@lower)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + p->min(0) = path.eval("number(limit/@lower)").getValue<::rl::math::Real>(0); ::std::cout << "\tmin: " << p->min(0) << ::std::endl; p->offset(0) = 0; p->speed(0) = path.eval("number(limit/@velocity)").getValue<::rl::math::Real>(0); @@ -290,8 +290,8 @@ ::std::cout << "\tname: " << p->getName() << ::std::endl; } else { - r->max(0) = path.eval("number(limit/@upper)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); - r->min(0) = path.eval("number(limit/@lower)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + r->max(0) = path.eval("number(limit/@upper)").getValue<::rl::math::Real>(0); + r->min(0) = path.eval("number(limit/@lower)").getValue<::rl::math::Real>(0); r->wraparound(0) = false; } ::std::cout << "\tmax: " << r->max(0) * ::rl::math::constants::rad2deg << ::std::endl; From bdf0431276d4e175c37d65730679e2fa2c7be08a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 22 Dec 2021 11:43:37 +0100 Subject: [PATCH 468/546] Fix return type --- src/rl/math/spatial/PlueckerTransform.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/math/spatial/PlueckerTransform.h b/src/rl/math/spatial/PlueckerTransform.h index dfe50acf..82a5b08e 100644 --- a/src/rl/math/spatial/PlueckerTransform.h +++ b/src/rl/math/spatial/PlueckerTransform.h @@ -208,7 +208,7 @@ namespace rl return data; } - ConstTransformType transform() const + ConstTransformType& transform() const { return data; } From 8fef4595f010fa8b11d35d586b9bf51354960367 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 22 Dec 2021 12:02:20 +0100 Subject: [PATCH 469/546] Add additional getters and setters --- src/rl/mdl/Body.cpp | 36 +++++++++++++++++++++++++++ src/rl/mdl/Body.h | 8 ++++++ src/rl/mdl/Fixed.cpp | 12 +++++++++ src/rl/mdl/Fixed.h | 4 +++ src/rl/mdl/Joint.cpp | 58 ++++++++++++++++++++++++++++++++++++++------ src/rl/mdl/Joint.h | 22 ++++++++++++++--- src/rl/mdl/Model.cpp | 38 ++++++++++++++++++++++------- src/rl/mdl/Model.h | 6 +++++ 8 files changed, 163 insertions(+), 21 deletions(-) diff --git a/src/rl/mdl/Body.cpp b/src/rl/mdl/Body.cpp index b9ddcadb..98deefa8 100644 --- a/src/rl/mdl/Body.cpp +++ b/src/rl/mdl/Body.cpp @@ -81,6 +81,18 @@ namespace rl { } + bool + Body::getCollision() const + { + return this->collision; + } + + bool + Body::getCollision(Body* body) const + { + return this->selfcollision.count(body) == 0; + } + void Body::inverseDynamics1() { @@ -107,6 +119,30 @@ namespace rl this->i.inertia() = this->ic - this->m * this->cm.cross33() * this->cm.cross33(); } + void + Body::setCollision(const bool& collision) + { + this->collision = collision; + } + + void + Body::setCollision(Body* body, const bool& collision) + { + if (collision) + { + ::std::unordered_set::iterator found = ::std::find(this->selfcollision.begin(), this->selfcollision.end(), body); + + if (found != this->selfcollision.end()) + { + this->selfcollision.erase(found); + } + } + else + { + this->selfcollision.insert(body); + } + } + void Body::setMass(const ::rl::math::Real& m) { diff --git a/src/rl/mdl/Body.h b/src/rl/mdl/Body.h index 1ee10c79..5bc63331 100644 --- a/src/rl/mdl/Body.h +++ b/src/rl/mdl/Body.h @@ -54,12 +54,20 @@ namespace rl void forwardVelocity(); + bool getCollision() const; + + bool getCollision(Body* body) const; + void inverseDynamics1(); void inverseDynamics2(); void setCenterOfMass(const ::rl::math::Real& x, const ::rl::math::Real& y, const ::rl::math::Real& z); + void setCollision(const bool& collision); + + void setCollision(Body* body, const bool& collision); + void setMass(const ::rl::math::Real& m); void setInertia(const ::rl::math::Real& xx, const ::rl::math::Real& yy, const ::rl::math::Real& zz, const ::rl::math::Real& yz, const ::rl::math::Real& xz, const ::rl::math::Real& xy); diff --git a/src/rl/mdl/Fixed.cpp b/src/rl/mdl/Fixed.cpp index c1176813..8a36d47a 100644 --- a/src/rl/mdl/Fixed.cpp +++ b/src/rl/mdl/Fixed.cpp @@ -38,5 +38,17 @@ namespace rl Fixed::~Fixed() { } + + const ::rl::math::Transform& + Fixed::getTransform() const + { + return this->x.transform(); + } + + void + Fixed::setTransform(const ::rl::math::Transform& t) + { + this->x = t; + } } } diff --git a/src/rl/mdl/Fixed.h b/src/rl/mdl/Fixed.h index 9a08c81c..2218abce 100644 --- a/src/rl/mdl/Fixed.h +++ b/src/rl/mdl/Fixed.h @@ -40,6 +40,10 @@ namespace rl virtual ~Fixed(); + const ::rl::math::Transform& getTransform() const; + + void setTransform(const ::rl::math::Transform& t); + protected: private: diff --git a/src/rl/mdl/Joint.cpp b/src/rl/mdl/Joint.cpp index ebeb709a..2ac6c02e 100644 --- a/src/rl/mdl/Joint.cpp +++ b/src/rl/mdl/Joint.cpp @@ -213,6 +213,12 @@ namespace rl return this->min; } + const ::rl::math::Vector& + Joint::getOffset() const + { + return this->offset; + } + const ::rl::math::Vector& Joint::getPosition() const { @@ -226,27 +232,27 @@ namespace rl } const ::rl::math::Vector& - Joint::getTorque() const + Joint::getSpeed() const { - return this->tau; + return this->speed; } const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& - Joint::getTorqueUnits() const + Joint::getSpeedUnits() const { - return this->tauUnits; + return this->speedUnits; } const ::rl::math::Vector& - Joint::getSpeed() const + Joint::getTorque() const { - return this->speed; + return this->tau; } const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& - Joint::getSpeedUnits() const + Joint::getTorqueUnits() const { - return this->speedUnits; + return this->tauUnits; } const ::rl::math::Vector& @@ -261,6 +267,12 @@ namespace rl return this->qdUnits; } + const ::Eigen::Matrix& + Joint::getWraparound() const + { + return this->wraparound; + } + void Joint::interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const { @@ -305,6 +317,30 @@ namespace rl this->a = this->S * this->qdd; } + void + Joint::setMaximum(const ::rl::math::ConstVectorRef& max) + { + this->max = max; + } + + void + Joint::setMinimum(const ::rl::math::ConstVectorRef& min) + { + this->min = min; + } + + void + Joint::setOffset(const ::rl::math::ConstVectorRef& offset) + { + this->offset = offset; + } + + void + Joint::setSpeed(const ::rl::math::ConstVectorRef& speed) + { + this->speed = speed; + } + void Joint::setTorque(const ::rl::math::ConstVectorRef& tau) { @@ -320,6 +356,12 @@ namespace rl this->v = this->S * this->qd; } + void + Joint::setWraparound(const ::Eigen::Ref>& wraparound) + { + this->wraparound = wraparound; + } + void Joint::step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& dq, ::rl::math::VectorRef q2) const { diff --git a/src/rl/mdl/Joint.h b/src/rl/mdl/Joint.h index cbcaabf6..ce7d2737 100644 --- a/src/rl/mdl/Joint.h +++ b/src/rl/mdl/Joint.h @@ -75,22 +75,26 @@ namespace rl const ::rl::math::Vector& getMinimum() const; + const ::rl::math::Vector& getOffset() const; + const ::rl::math::Vector& getPosition() const; const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getPositionUnits() const; - const ::rl::math::Vector& getTorque() const; - - const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getTorqueUnits() const; - const ::rl::math::Vector& getSpeed() const; const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getSpeedUnits() const; + const ::rl::math::Vector& getTorque() const; + + const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getTorqueUnits() const; + const ::rl::math::Vector& getVelocity() const; const ::Eigen::Matrix<::rl::math::Units, ::Eigen::Dynamic, 1>& getVelocityUnits() const; + const ::Eigen::Matrix& getWraparound() const; + virtual void interpolate(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2, const ::rl::math::Real& alpha, ::rl::math::VectorRef q) const; void inverseForce(); @@ -101,12 +105,22 @@ namespace rl void setAcceleration(const ::rl::math::ConstVectorRef& qdd); + void setMaximum(const ::rl::math::ConstVectorRef& max); + + void setMinimum(const ::rl::math::ConstVectorRef& min); + + void setOffset(const ::rl::math::ConstVectorRef& offset); + virtual void setPosition(const ::rl::math::ConstVectorRef& q) = 0; + void setSpeed(const ::rl::math::ConstVectorRef& speed); + void setTorque(const ::rl::math::ConstVectorRef& tau); void setVelocity(const ::rl::math::ConstVectorRef& qd); + void setWraparound(const ::Eigen::Ref>& wraparound); + virtual void step(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& dq, ::rl::math::VectorRef q2) const; virtual ::rl::math::Real transformedDistance(const ::rl::math::ConstVectorRef& q1, const ::rl::math::ConstVectorRef& q2) const; diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 6b377504..1ae62ad6 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -99,14 +99,7 @@ namespace rl assert(i < this->bodies.size()); assert(j < this->bodies.size()); - if (this->bodies[i]->selfcollision.count(this->bodies[j]) > 0 || this->bodies[j]->selfcollision.count(this->bodies[i]) > 0) - { - return false; - } - else - { - return true; - } + return this->bodies[i]->getCollision(this->bodies[j]) || this->bodies[j]->getCollision(this->bodies[i]); } ::rl::math::Vector @@ -564,7 +557,7 @@ namespace rl { assert(i < this->bodies.size()); - return this->bodies[i]->collision; + return this->bodies[i]->getCollision(); } ::std::uniform_real_distribution<::rl::math::Real>::result_type @@ -651,6 +644,24 @@ namespace rl this->manufacturer = manufacturer; } + void + Model::setMaximum(const ::rl::math::Vector& max) + { + for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) + { + this->joints[i]->setMaximum(max.segment(j, this->joints[i]->getDofPosition())); + } + } + + void + Model::setMinimum(const ::rl::math::Vector& min) + { + for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDofPosition(), ++i) + { + this->joints[i]->setMinimum(min.segment(j, this->joints[i]->getDofPosition())); + } + } + void Model::setName(const ::std::string& name) { @@ -674,6 +685,15 @@ namespace rl } } + void + Model::setSpeed(const ::rl::math::Vector& speed) + { + for (::std::size_t i = 0, j = 0; i < this->joints.size(); j += this->joints[i]->getDof(), ++i) + { + this->joints[i]->setSpeed(speed.segment(j, this->joints[i]->getDof())); + } + } + void Model::setTorque(const ::rl::math::Vector& tau) { diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index b1ef3eb9..0eae70cd 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -178,12 +178,18 @@ namespace rl void setManufacturer(const ::std::string& manufacturer); + void setMaximum(const ::rl::math::Vector& max); + + void setMinimum(const ::rl::math::Vector& min); + void setName(const ::std::string& name); void setOperationalVelocity(const ::std::size_t& i, const ::rl::math::MotionVector& v) const; void setPosition(const ::rl::math::Vector& q); + void setSpeed(const ::rl::math::Vector& speed); + void setTorque(const ::rl::math::Vector& tau); void setVelocity(const ::rl::math::Vector& qd); From b46640849a66be8819c4087dd7c3313896976ecf Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 22 Dec 2021 12:50:54 +0100 Subject: [PATCH 470/546] Update planar robot examples --- examples/rlmdl/planar2.param.xml | 51 +++++---- examples/rlmdl/planar2.xml | 51 +++++---- examples/rlmdl/planar3.xml | 171 +++++++++++++++++++++++++++++++ examples/rlsg/planar2.wrl | 95 +++++++++++++++++ examples/rlsg/planar2.xml | 10 ++ examples/rlsg/planar3.wrl | 131 +++++++++++++++++++++++ examples/rlsg/planar3.xml | 11 ++ 7 files changed, 478 insertions(+), 42 deletions(-) create mode 100644 examples/rlmdl/planar3.xml create mode 100644 examples/rlsg/planar2.wrl create mode 100644 examples/rlsg/planar2.xml create mode 100644 examples/rlsg/planar3.wrl create mode 100644 examples/rlsg/planar3.xml diff --git a/examples/rlmdl/planar2.param.xml b/examples/rlmdl/planar2.param.xml index 68ecc2e7..67c4be58 100644 --- a/examples/rlmdl/planar2.param.xml +++ b/examples/rlmdl/planar2.param.xml @@ -6,7 +6,7 @@ Featherstone planar2 - + 0 0 @@ -23,8 +23,12 @@ 9.80665 - - + + + + + + 0 @@ -40,8 +44,9 @@ 1 - - + + + 0 @@ -57,33 +62,35 @@ 1 - - + + - - + + - -90 + 0 0 0 0 0 - + 0 - - + + + 360 + -360 - + - - + + 0 @@ -98,14 +105,16 @@ - - + + + 360 + -360 - + - - + + 0 diff --git a/examples/rlmdl/planar2.xml b/examples/rlmdl/planar2.xml index fe21ce38..42c640ec 100644 --- a/examples/rlmdl/planar2.xml +++ b/examples/rlmdl/planar2.xml @@ -3,7 +3,7 @@ Featherstone planar2 - + 0 0 @@ -20,8 +20,12 @@ 9.80665 - - + + + + + + 0.5 0 @@ -37,8 +41,9 @@ 1 - - + + + 0.5 0 @@ -54,33 +59,35 @@ 1 - - + + - - + + - -90 + 0 0 0 0 0 - 2 + 0 - - + + + 360 + -360 - + - - + + 0 @@ -95,14 +102,16 @@ - - + + + 360 + -360 - + - - + + 0 diff --git a/examples/rlmdl/planar3.xml b/examples/rlmdl/planar3.xml new file mode 100644 index 00000000..badccc34 --- /dev/null +++ b/examples/rlmdl/planar3.xml @@ -0,0 +1,171 @@ + + + + Featherstone + planar3 + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + 0 + 0 + 9.80665 + + + + + + + + + + 0.5 + 0 + 0 + + + 0.01 + 0.083333333 + 0.083333333 + 0 + 0 + 0 + + 1 + + + + + + + 0.5 + 0 + 0 + + + 0.01 + 0.083333333 + 0.083333333 + 0 + 0 + 0 + + 1 + + + + + + 0.5 + 0 + 0 + + + 0.01 + 0.083333333 + 0.083333333 + 0 + 0 + 0 + + 1 + + + + + + + + + 0 + 0 + 0 + + + 0 + 0 + 0 + + + + + + + + 360 + -360 + + + + + + + + 0 + 0 + 0 + + + 1 + 0 + 0 + + + + + + + + 360 + -360 + + + + + + + + 0 + 0 + 0 + + + 1 + 0 + 0 + + + + + + + + 360 + -360 + + + + + + + + 0 + 0 + 0 + + + 1 + 0 + 0 + + +
+ diff --git a/examples/rlsg/planar2.wrl b/examples/rlsg/planar2.wrl new file mode 100644 index 00000000..51bd08ab --- /dev/null +++ b/examples/rlsg/planar2.wrl @@ -0,0 +1,95 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF link0 Transform { + children [ + Transform { + translation 0 0 -0.14 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.7 0.1 0.1 + } + } + geometry Box { + size 0.4 0.6 0.12 + } + } + ] + } + ] + } + DEF link1 Transform { + children [ + Transform { + translation 0.5 0 0 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.45 0.1 + } + } + geometry Box { + size 1 0.14 0.1 + } + } + ] + } + Transform { + rotation 1 0 0 1.570796 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.45 0.1 + } + } + geometry Cylinder { + radius 0.1 + height 0.16 + } + } + ] + } + ] + } + DEF link2 Transform { + translation 1 0 0 + children [ + Transform { + translation 0.5 0 0 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.7 0.1 + } + } + geometry Box { + size 1 0.14 0.1 + } + } + ] + } + Transform { + rotation 1 0 0 1.570796 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.7 0.1 + } + } + geometry Cylinder { + radius 0.1 + height 0.16 + } + } + ] + } + ] + } + ] +} diff --git a/examples/rlsg/planar2.xml b/examples/rlsg/planar2.xml new file mode 100644 index 00000000..f831cc9e --- /dev/null +++ b/examples/rlsg/planar2.xml @@ -0,0 +1,10 @@ + + + + + + + + + + diff --git a/examples/rlsg/planar3.wrl b/examples/rlsg/planar3.wrl new file mode 100644 index 00000000..399b83d2 --- /dev/null +++ b/examples/rlsg/planar3.wrl @@ -0,0 +1,131 @@ +#VRML V2.0 utf8 +Transform { + children [ + DEF link0 Transform { + children [ + Transform { + translation 0 0 -0.14 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.7 0.1 0.1 + } + } + geometry Box { + size 0.4 0.6 0.12 + } + } + ] + } + ] + } + DEF link1 Transform { + children [ + Transform { + translation 0.5 0 0 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.45 0.1 + } + } + geometry Box { + size 1 0.14 0.1 + } + } + ] + } + Transform { + rotation 1 0 0 1.570796 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.45 0.1 + } + } + geometry Cylinder { + radius 0.1 + height 0.16 + } + } + ] + } + ] + } + DEF link2 Transform { + translation 1 0 0 + children [ + Transform { + translation 0.5 0 0 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.7 0.1 + } + } + geometry Box { + size 1 0.14 0.1 + } + } + ] + } + Transform { + rotation 1 0 0 1.570796 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.8 0.7 0.1 + } + } + geometry Cylinder { + radius 0.1 + height 0.16 + } + } + ] + } + ] + } + DEF link3 Transform { + translation 2 0 0 + children [ + Transform { + translation 0.5 0 0 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.5 0.7 0.2 + } + } + geometry Box { + size 1 0.14 0.1 + } + } + ] + } + Transform { + rotation 1 0 0 1.570796 + children [ + Shape { + appearance Appearance { + material Material { + diffuseColor 0.5 0.7 0.2 + } + } + geometry Cylinder { + radius 0.1 + height 0.16 + } + } + ] + } + ] + } + ] +} diff --git a/examples/rlsg/planar3.xml b/examples/rlsg/planar3.xml new file mode 100644 index 00000000..3bf6cef7 --- /dev/null +++ b/examples/rlsg/planar3.xml @@ -0,0 +1,11 @@ + + + + + + + + + + + From fd51866a402f815af02b87dac50750e7fcf3bef1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 22 Dec 2021 12:51:45 +0100 Subject: [PATCH 471/546] Update input parameter check --- demos/rlDynamics1Demo/rlDynamics1Demo.cpp | 6 ++++++ demos/rlDynamics2Demo/rlDynamics2Demo.cpp | 6 ++++++ 2 files changed, 12 insertions(+) diff --git a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp index 0e7045e8..a5a040a5 100644 --- a/demos/rlDynamics1Demo/rlDynamics1Demo.cpp +++ b/demos/rlDynamics1Demo/rlDynamics1Demo.cpp @@ -58,6 +58,12 @@ main(int argc, char** argv) dynamic = std::dynamic_pointer_cast(factory.create(filename)); } + if (argc < 2 + dynamic->getDofPosition() + dynamic->getDof() + dynamic->getDof()) + { + std::cout << "Usage: rlDynamics1Demo MODELFILE Q1 ... Qn QD1 ... QDn QDD1 ... QDDn" << std::endl; + return EXIT_FAILURE; + } + rl::math::Vector q(dynamic->getDofPosition()); rl::math::Vector qd(dynamic->getDof()); rl::math::Vector qdd(dynamic->getDof()); diff --git a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp index da3a901a..88f58962 100644 --- a/demos/rlDynamics2Demo/rlDynamics2Demo.cpp +++ b/demos/rlDynamics2Demo/rlDynamics2Demo.cpp @@ -58,6 +58,12 @@ main(int argc, char** argv) dynamic = std::dynamic_pointer_cast(factory.create(filename)); } + if (argc < 2 + dynamic->getDofPosition() + dynamic->getDof() + dynamic->getDof()) + { + std::cout << "Usage: rlDynamics2Demo MODELFILE Q1 ... Qn QD1 ... QDn QDD1 ... QDDn" << std::endl; + return EXIT_FAILURE; + } + rl::math::Vector q(dynamic->getDofPosition()); rl::math::Vector qd(dynamic->getDof()); rl::math::Vector qdd(dynamic->getDof()); From c66dc5dbffe3f547298e3a2a32276dedaf6a9ceb Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 22 Dec 2021 12:52:10 +0100 Subject: [PATCH 472/546] Add rlDynamics1Planar2Demo --- demos/rlDynamics1Demo/CMakeLists.txt | 12 ++ .../rlDynamics1Planar2Demo.cpp | 171 ++++++++++++++++++ 2 files changed, 183 insertions(+) create mode 100644 demos/rlDynamics1Demo/rlDynamics1Planar2Demo.cpp diff --git a/demos/rlDynamics1Demo/CMakeLists.txt b/demos/rlDynamics1Demo/CMakeLists.txt index 00b80d89..25543af1 100644 --- a/demos/rlDynamics1Demo/CMakeLists.txt +++ b/demos/rlDynamics1Demo/CMakeLists.txt @@ -11,3 +11,15 @@ target_link_libraries( mdl Boost::headers ) + +add_executable( + rlDynamics1Planar2Demo + rlDynamics1Planar2Demo.cpp + ${rl_BINARY_DIR}/robotics-library.rc +) + +target_link_libraries( + rlDynamics1Planar2Demo + mdl + Boost::headers +) diff --git a/demos/rlDynamics1Demo/rlDynamics1Planar2Demo.cpp b/demos/rlDynamics1Demo/rlDynamics1Planar2Demo.cpp new file mode 100644 index 00000000..5fc8bf67 --- /dev/null +++ b/demos/rlDynamics1Demo/rlDynamics1Planar2Demo.cpp @@ -0,0 +1,171 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include +#include +#include +#include +#include +#include +#include + +std::shared_ptr +createPlanar2() +{ + std::shared_ptr dynamic = std::make_shared(); + dynamic->setName("planar2"); + + // frames + + std::shared_ptr world = std::make_shared(); + world->setName("world"); + world->setGravity(rl::math::Vector3(0, 0, rl::math::constants::gravity)); + dynamic->add(world); + + std::shared_ptr link0 = std::make_shared(); + link0->setName("link0"); + dynamic->add(link0); + + std::shared_ptr link1 = std::make_shared(); + link1->setCenterOfMass(static_cast(0.5), 0, 0); + link1->setInertia(static_cast(0.01), static_cast(0.083333333), static_cast(0.083333333), 0, 0, 0); + link1->setMass(1); + link1->setName("link1"); + dynamic->add(link1); + + std::shared_ptr frame0 = std::make_shared(); + frame0->setName("frame0"); + dynamic->add(frame0); + + std::shared_ptr link2 = std::make_shared(); + link2->setCenterOfMass(static_cast(0.5), 0, 0); + link2->setInertia(static_cast(0.01), static_cast(0.083333333), static_cast(0.083333333), 0, 0, 0); + link2->setMass(1); + link2->setName("link2"); + dynamic->add(link2); + + std::shared_ptr frame1 = std::make_shared(); + frame1->setName("frame1"); + dynamic->add(frame1); + + // selfcollision + + link0->setCollision(false); + link1->setCollision(link0.get(), false); + link1->setCollision(link2.get(), false); + link2->setCollision(link1.get(), false); + + // transforms + + std::shared_ptr fixed0 = std::make_shared(); + fixed0->setName("fixed0"); + dynamic->add(fixed0, world.get(), link0.get()); + + std::shared_ptr joint0 = std::make_shared(); + joint0->setMaximum(rl::math::Vector::Constant(1, 360 * rl::math::constants::deg2rad)); + joint0->setMinimum(rl::math::Vector::Constant(1, -360 * rl::math::constants::deg2rad)); + joint0->setName("joint0"); + dynamic->add(joint0, link0.get(), link1.get()); + + std::shared_ptr fixed1 = std::make_shared(); + fixed1->setName("fixed1"); + fixed1->setTransform(rl::math::Transform(rl::math::Translation(rl::math::Vector3(1, 0, 0)))); + dynamic->add(fixed1, link1.get(), frame0.get()); + + std::shared_ptr joint1 = std::make_shared(); + joint1->setMaximum(rl::math::Vector::Constant(1, 360 * rl::math::constants::deg2rad)); + joint1->setMinimum(rl::math::Vector::Constant(1, -360 * rl::math::constants::deg2rad)); + joint1->setName("joint1"); + dynamic->add(joint1, frame0.get(), link2.get()); + + std::shared_ptr fixed2 = std::make_shared(); + fixed2->setName("fixed2"); + fixed2->setTransform(rl::math::Transform(rl::math::Translation(rl::math::Vector3(1, 0, 0)))); + dynamic->add(fixed2, link2.get(), frame1.get()); + + // initialize + + dynamic->update(); + + return dynamic; +} + +int +main(int argc, char** argv) +{ + if (argc < 7) + { + std::cout << "Usage: rlDynamics1Planar2Demo Q1 Q2 QD1 QD2 QDD1 QDD2" << std::endl; + return EXIT_FAILURE; + } + + try + { + std::shared_ptr dynamic = createPlanar2(); + + rl::math::Vector q(dynamic->getDofPosition()); + rl::math::Vector qd(dynamic->getDof()); + rl::math::Vector qdd(dynamic->getDof()); + + for (std::size_t i = 0; i < dynamic->getDofPosition(); ++i) + { + q(i) = boost::lexical_cast(argv[i + 1]); + } + + for (std::size_t i = 0; i < dynamic->getDof(); ++i) + { + qd(i) = boost::lexical_cast(argv[i + 1 + dynamic->getDofPosition()]); + qdd(i) = boost::lexical_cast(argv[i + 1 + dynamic->getDofPosition() + dynamic->getDof()]); + } + + dynamic->setPosition(q); + dynamic->setVelocity(qd); + dynamic->setAcceleration(qdd); + + dynamic->inverseDynamics(); + std::cout << "tau = " << dynamic->getTorque().transpose() << std::endl; + + dynamic->forwardDynamics(); + std::cout << "qdd = " << dynamic->getAcceleration().transpose() << std::endl; + + rl::mdl::RungeKuttaNystromIntegrator integrator(dynamic.get()); + integrator.integrate(1); + std::cout << "q = " << dynamic->getPosition().transpose() << std::endl; + std::cout << "qd = " << dynamic->getVelocity().transpose() << std::endl; + } + catch (const std::exception& e) + { + std::cout << e.what() << std::endl; + return EXIT_FAILURE; + } + + return EXIT_SUCCESS; +} From 3b94b1b51959d55731c6929261aae0e04126b585 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 30 Jan 2022 20:31:18 +0100 Subject: [PATCH 473/546] Update CI workflow --- .github/workflows/ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index d521c566..7cbb93dd 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -101,7 +101,7 @@ jobs: ninja-build - if: matrix.name == 'windows-latest-msvc' name: Enable Developer Command Prompt - uses: ilammy/msvc-dev-cmd@v1.5.0 + uses: ilammy/msvc-dev-cmd@v1 - if: matrix.name == 'windows-latest-msvc' name: Install dependencies for MSVC working-directory: ${{ runner.workspace }} From 102896d1e39459609731b7b250a1fbf40dafed7b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 11 Feb 2022 10:52:50 +0100 Subject: [PATCH 474/546] Update CI workflows --- .github/workflows/ci.yml | 50 ++++++++++++++++++------------------ .github/workflows/codeql.yml | 2 +- 2 files changed, 26 insertions(+), 26 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 7cbb93dd..bfce0e6c 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -14,31 +14,31 @@ jobs: fail-fast: false matrix: name: - - macos-latest - - ubuntu-latest-clang - - ubuntu-latest-gcc - - windows-latest-msvc - - windows-latest-msys2 + - macos-11 + - ubuntu-20.04-clang + - ubuntu-20.04-gcc + - windows-2019-msvc + - windows-2019-msys2 include: - - name: macos-latest + - name: macos-11 cmake_compiler_launcher: ccache cmake_prefix_path: /usr/local/opt/qt/lib/cmake - os: macos-latest - - name: ubuntu-latest-clang + os: macos-11 + - name: ubuntu-20.04-clang cc: clang cmake_compiler_launcher: ccache cxx: clang++ - os: ubuntu-latest - - name: ubuntu-latest-gcc + os: ubuntu-20.04 + - name: ubuntu-20.04-gcc cc: gcc cmake_compiler_launcher: ccache cxx: g++ - os: ubuntu-latest - - name: windows-latest-msvc - os: windows-latest - - name: windows-latest-msys2 + os: ubuntu-20.04 + - name: windows-2019-msvc + os: windows-2019 + - name: windows-2019-msys2 cmake_compiler_launcher: ccache - os: windows-latest + os: windows-2019 env: CC: ${{ matrix.cc }} CCACHE_COMPRESS: true @@ -50,15 +50,15 @@ jobs: steps: - name: Checkout repository uses: actions/checkout@v2 - - if: matrix.os == 'macos-latest' + - if: matrix.os == 'macos-11' name: Set up Tap run: brew tap roboticslibrary/rl - - if: matrix.os == 'ubuntu-latest' + - if: matrix.os == 'ubuntu-20.04' name: Set up PPA run: | sudo apt-get install -y software-properties-common sudo apt-add-repository -y -u ppa:roblib/ppa - - if: matrix.os == 'macos-latest' + - if: matrix.os == 'macos-11' name: Install dependencies for macOS run: > brew install @@ -76,7 +76,7 @@ jobs: qt solid soqt - - if: matrix.os == 'ubuntu-latest' + - if: matrix.os == 'ubuntu-20.04' name: Install dependencies for Ubuntu run: > sudo apt-get install -y @@ -99,17 +99,17 @@ jobs: libxml2-dev libxslt1-dev ninja-build - - if: matrix.name == 'windows-latest-msvc' + - if: matrix.name == 'windows-2019-msvc' name: Enable Developer Command Prompt uses: ilammy/msvc-dev-cmd@v1 - - if: matrix.name == 'windows-latest-msvc' + - if: matrix.name == 'windows-2019-msvc' name: Install dependencies for MSVC working-directory: ${{ runner.workspace }} run: | curl -L https://github.com/roboticslibrary/rl-3rdparty/releases/download/latest/rl-3rdparty-msvc-14.2-x64.7z -o rl-3rdparty-msvc-14.2-x64.7z 7z x rl-3rdparty-msvc-14.2-x64.7z -orl-3rdparty-install Write-Output "${{ runner.workspace }}\rl-3rdparty-install\bin" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append - - if: matrix.name == 'windows-latest-msys2' + - if: matrix.name == 'windows-2019-msys2' name: Set up MSYS2 uses: msys2/setup-msys2@v2 with: @@ -131,16 +131,16 @@ jobs: mingw-w64-x86_64-solid3 mingw-w64-x86_64-soqt update: true - - if: matrix.name == 'windows-latest-msys2' + - if: matrix.name == 'windows-2019-msys2' name: Add MSYS2 to PATH run: | Write-Output (msys2 -c "cygpath -w /mingw64/bin") | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append - - if: matrix.os != 'windows-latest' + - if: matrix.os != 'windows-2019' name: Update environment variables run: | echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV - - if: matrix.os == 'windows-latest' + - if: matrix.os == 'windows-2019' name: Update environment variables run: | Write-Output "CCACHE_BASEDIR=${{ runner.workspace }}" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index 8d7db233..85b659cd 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -11,7 +11,7 @@ on: jobs: analyze: name: Analyze - runs-on: ubuntu-latest + runs-on: ubuntu-20.04 steps: - name: Checkout repository uses: actions/checkout@v2 From b393d8d8a069593927b4a2a39ed7d9543fa10dff Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 26 Jan 2022 21:13:27 +0100 Subject: [PATCH 475/546] Improve DH parameter calculation --- src/rl/math/TransformAddons.h | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/src/rl/math/TransformAddons.h b/src/rl/math/TransformAddons.h index ff8b0f04..7b674497 100644 --- a/src/rl/math/TransformAddons.h +++ b/src/rl/math/TransformAddons.h @@ -207,20 +207,25 @@ toDenavitHartenbergPaul(OtherScalar1& d, OtherScalar2& theta, OtherScalar3& a, O assert(abs((*this)(2, 0)) <= ::std::numeric_limits::epsilon()); d = (*this)(2, 3); - theta = atan2((*this)(1, 0), (*this)(0, 0)); - if (abs((*this)(0, 0)) <= ::std::numeric_limits::epsilon()) + Scalar tmp = (*this)(0, 0) + (*this)(1, 0); + + if (abs(tmp) > 0) + { + a = ((*this)(0, 3) + (*this)(1, 3)) / tmp; + } + else if (abs((*this)(1, 0)) > 0) { a = (*this)(1, 3) / (*this)(1, 0); } - else if (abs((*this)(1, 0)) <= ::std::numeric_limits::epsilon()) + else if (abs((*this)(0, 0)) > 0) { a = (*this)(0, 3) / (*this)(0, 0); } else { - a = ((*this)(1, 3) / (*this)(1, 0) + (*this)(0, 3) / (*this)(0, 0)) * Scalar(0.5); + a = ::std::numeric_limits::quiet_NaN(); } alpha = atan2((*this)(2, 1), (*this)(2, 2)); From dc94c8d6cc35bff89d99279a229765e79624b984 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 10 Feb 2022 12:59:13 +0100 Subject: [PATCH 476/546] Add upper and lower bounds to rl::kin::Kinematics::generatePositionUniform --- src/rl/kin/Kinematics.cpp | 26 ++++++++++++++++++++++++++ src/rl/kin/Kinematics.h | 4 ++++ 2 files changed, 30 insertions(+) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index b19ec54b..c8193f72 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -496,6 +496,32 @@ namespace rl return q; } + ::rl::math::Vector + Kinematics::generatePositionUniform(const ::rl::math::Vector& min, const ::rl::math::Vector& max) + { + ::rl::math::Vector rand(this->getDof()); + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + rand(i) = this->rand(); + } + + return this->generatePositionUniform(rand, min, max); + } + + ::rl::math::Vector + Kinematics::generatePositionUniform(const ::rl::math::Vector& rand, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const + { + ::rl::math::Vector q(this->getDof()); + + for (::std::size_t i = 0; i < this->getDof(); ++i) + { + q(i) = min(i) + rand(i) * (max(i) - min(i)); + } + + return q; + } + ::std::size_t Kinematics::getBodies() const { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index 67cdf015..daf8322b 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -124,6 +124,10 @@ namespace rl ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand) const; + ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& min, const ::rl::math::Vector& max); + + ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; + /** * Get number of links. */ From 978d48653d7de77bdfbeae189827f1e7a2059598 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 10 Feb 2022 12:59:47 +0100 Subject: [PATCH 477/546] Add upper and lower bounds to rl::plan::Model::generatePositionUniform --- src/rl/plan/Model.cpp | 13 +++++++++++++ src/rl/plan/Model.h | 2 ++ 2 files changed, 15 insertions(+) diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index 7ce25866..513b54af 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -148,6 +148,19 @@ namespace rl } } + ::rl::math::Vector + Model::generatePositionUniform(const ::rl::math::Vector& rand, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const + { + if (nullptr != this->kin) + { + return this->kin->generatePositionUniform(rand, min, max); + } + else + { + return this->mdl->generatePositionUniform(rand, min, max); + } + } + ::std::size_t Model::getBodies() const { diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 31a3081d..7a404f06 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -62,6 +62,8 @@ namespace rl virtual ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand) const; + virtual ::rl::math::Vector generatePositionUniform(const ::rl::math::Vector& rand, const ::rl::math::Vector& min, const ::rl::math::Vector& max) const; + virtual ::rl::sg::Body* getBody(const ::std::size_t& i) const; virtual ::std::size_t getBodies() const; From 282395b9d40897facc2de2ef82c51f77a98d9704 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 10 Feb 2022 16:28:28 +0100 Subject: [PATCH 478/546] Add setters for maximum and minimum in rl::kin::Kinematics --- src/rl/kin/Kinematics.cpp | 38 ++++++++++++++++++++++++++++++++++++++ src/rl/kin/Kinematics.h | 8 ++++++++ 2 files changed, 46 insertions(+) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index c8193f72..191823fc 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -890,6 +890,44 @@ namespace rl } } + void + Kinematics::setMaximum(const ::std::size_t& i, const ::rl::math::Real& max) + { + assert(i < this->joints.size()); + + this->joints[i]->max = max; + } + + void + Kinematics::setMaximum(const ::rl::math::Vector& max) + { + assert(max.size() == this->getDof()); + + for (::std::size_t i = 0; i < this->joints.size(); ++i) + { + this->joints[i]->max = max(i); + } + } + + void + Kinematics::setMinimum(const ::std::size_t& i, const ::rl::math::Real& min) + { + assert(i < this->joints.size()); + + this->joints[i]->min = min; + } + + void + Kinematics::setMinimum(const ::rl::math::Vector& min) + { + assert(min.size() == this->getDof()); + + for (::std::size_t i = 0; i < this->joints.size(); ++i) + { + this->joints[i]->min = min(i); + } + } + void Kinematics::setPosition(const ::rl::math::Vector& q) { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index daf8322b..f9df7523 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -272,6 +272,14 @@ namespace rl */ void setColliding(const ::std::size_t& i, const ::std::size_t& j, const bool& doCollide); + void setMaximum(const ::std::size_t& i, const ::rl::math::Real& max); + + void setMaximum(const ::rl::math::Vector& max); + + void setMinimum(const ::std::size_t& i, const ::rl::math::Real& min); + + void setMinimum(const ::rl::math::Vector& min); + /** * Update current joint position. * From 01d776b08cea9b75355ab070405e99e19597de10 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 10 Feb 2022 16:28:47 +0100 Subject: [PATCH 479/546] Add setters for maximum and minimum in rl::plan::Model --- src/rl/plan/Model.cpp | 26 ++++++++++++++++++++++++++ src/rl/plan/Model.h | 4 ++++ 2 files changed, 30 insertions(+) diff --git a/src/rl/plan/Model.cpp b/src/rl/plan/Model.cpp index 513b54af..38e49b29 100644 --- a/src/rl/plan/Model.cpp +++ b/src/rl/plan/Model.cpp @@ -458,6 +458,32 @@ namespace rl this->model->getBody(i)->setFrame(frame); } + void + Model::setMaximum(const ::rl::math::Vector& max) + { + if (nullptr != this->kin) + { + this->kin->setMaximum(max); + } + else + { + this->mdl->setMaximum(max); + } + } + + void + Model::setMinimum(const ::rl::math::Vector& min) + { + if (nullptr != this->kin) + { + this->kin->setMinimum(min); + } + else + { + this->mdl->setMinimum(min); + } + } + void Model::setPosition(const ::rl::math::Vector& q) { diff --git a/src/rl/plan/Model.h b/src/rl/plan/Model.h index 7a404f06..9692bda1 100644 --- a/src/rl/plan/Model.h +++ b/src/rl/plan/Model.h @@ -114,6 +114,10 @@ namespace rl virtual void setFrame(const ::std::size_t& i, const ::rl::math::Transform& frame); + virtual void setMaximum(const ::rl::math::Vector& max); + + virtual void setMinimum(const ::rl::math::Vector& min); + virtual void setPosition(const ::rl::math::Vector& q); virtual void step(const ::rl::math::Vector& q1, const ::rl::math::Vector& dq, ::rl::math::Vector& q2) const; From e92ffb4d7a4c63c4adb44f981a3ed0fda048230a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 10 Feb 2022 16:44:02 +0100 Subject: [PATCH 480/546] Add override for maximum and minimum in rl::plan scenario definitions --- demos/rlPlanDemo/MainWindow.cpp | 160 ++++++++++++++++++++++++++++++++ examples/rlplan/rlplan.xsd | 14 +++ 2 files changed, 174 insertions(+) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index a0433bc4..8fa71a16 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -941,6 +941,86 @@ MainWindow::load(const QString& filename) world->translation().z() = path.eval("number((/rl/plan|/rlplan)//model/kinematics/world/translation/z)").getValue(0); } + if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/max) > 0").getValue()) + { + rl::xml::NodeSet max = path.eval("(/rl/plan|/rlplan)//model/kinematics/max/q").getValue(); + + rl::math::Vector maximum(max.size()); + + if (nullptr != this->kin.get()) + { + this->kin->getMaximum(maximum); + } + else if (nullptr != this->mdl.get()) + { + maximum = this->mdl->getMaximum(); + } + + for (int i = 0; i < max.size(); ++i) + { + std::string content = max[i].getContent(); + + if (!content.empty()) + { + maximum(i) = std::atof(content.c_str()); + + if ("deg" == max[i].getProperty("unit")) + { + maximum(i) *= rl::math::constants::deg2rad; + } + } + } + + if (nullptr != this->kin.get()) + { + this->kin->setMaximum(maximum); + } + else if (nullptr != this->mdl.get()) + { + this->mdl->setMaximum(maximum); + } + } + + if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/min) > 0").getValue()) + { + rl::xml::NodeSet min = path.eval("(/rl/plan|/rlplan)//model/kinematics/min/q").getValue(); + + rl::math::Vector minimum(min.size()); + + if (nullptr != this->kin.get()) + { + this->kin->getMinimum(minimum); + } + else if (nullptr != this->mdl.get()) + { + minimum = this->mdl->getMinimum(); + } + + for (int i = 0; i < min.size(); ++i) + { + std::string content = min[i].getContent(); + + if (!content.empty()) + { + minimum(i) = std::atof(content.c_str()); + + if ("deg" == min[i].getProperty("unit")) + { + minimum(i) *= rl::math::constants::deg2rad; + } + } + } + + if (nullptr != this->kin.get()) + { + this->kin->setMinimum(minimum); + } + else if (nullptr != this->mdl.get()) + { + this->mdl->setMinimum(minimum); + } + } + if (rl::sg::DistanceScene* scene = dynamic_cast(this->scene.get())) { this->model = std::make_shared(); @@ -1043,6 +1123,86 @@ MainWindow::load(const QString& filename) world->translation().z() = path.eval("number((/rl/plan|/rlplan)//viewer/model/kinematics/world/translation/z)").getValue(0); } + if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/max) > 0").getValue()) + { + rl::xml::NodeSet max = path.eval("(/rl/plan|/rlplan)//viewer/model/kinematics/max/q").getValue(); + + rl::math::Vector maximum(max.size()); + + if (nullptr != this->kin2.get()) + { + this->kin2->getMaximum(maximum); + } + else if (nullptr != this->mdl2.get()) + { + maximum = this->mdl2->getMaximum(); + } + + for (int i = 0; i < max.size(); ++i) + { + std::string content = max[i].getContent(); + + if (!content.empty()) + { + maximum(i) = std::atof(content.c_str()); + + if ("deg" == max[i].getProperty("unit")) + { + maximum(i) *= rl::math::constants::deg2rad; + } + } + } + + if (nullptr != this->kin2.get()) + { + this->kin2->setMaximum(maximum); + } + else if (nullptr != this->mdl2.get()) + { + this->mdl2->setMaximum(maximum); + } + } + + if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/min) > 0").getValue()) + { + rl::xml::NodeSet min = path.eval("(/rl/plan|/rlplan)//viewer/model/kinematics/min/q").getValue(); + + rl::math::Vector minimum(min.size()); + + if (nullptr != this->kin2.get()) + { + this->kin2->getMinimum(minimum); + } + else if (nullptr != this->mdl2.get()) + { + minimum = this->mdl2->getMinimum(); + } + + for (int i = 0; i < min.size(); ++i) + { + std::string content = min[i].getContent(); + + if (!content.empty()) + { + minimum(i) = std::atof(content.c_str()); + + if ("deg" == min[i].getProperty("unit")) + { + minimum(i) *= rl::math::constants::deg2rad; + } + } + } + + if (nullptr != this->kin2.get()) + { + this->kin2->setMinimum(minimum); + } + else if (nullptr != this->mdl2.get()) + { + this->mdl2->setMinimum(minimum); + } + } + this->model2 = std::make_shared(); if (nullptr != this->kin2) diff --git a/examples/rlplan/rlplan.xsd b/examples/rlplan/rlplan.xsd index 15b9dfac..d2fc5da8 100644 --- a/examples/rlplan/rlplan.xsd +++ b/examples/rlplan/rlplan.xsd @@ -305,6 +305,20 @@
+ + + + + + + + + + + + + + From c0abf242da666e49074f307f0c46c2386ab60e26 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 14 Apr 2022 11:34:59 +0200 Subject: [PATCH 481/546] Remove unused headers --- src/rl/mdl/Dynamic.cpp | 1 - src/rl/mdl/Kinematic.cpp | 1 - src/rl/xml/DomParser.h | 1 - src/rl/xml/Path.h | 1 - src/rl/xml/Schema.h | 1 - 5 files changed, 5 deletions(-) diff --git a/src/rl/mdl/Dynamic.cpp b/src/rl/mdl/Dynamic.cpp index 37b08ec8..dff5f7f2 100644 --- a/src/rl/mdl/Dynamic.cpp +++ b/src/rl/mdl/Dynamic.cpp @@ -26,7 +26,6 @@ #include #include -#include #include #include #include diff --git a/src/rl/mdl/Kinematic.cpp b/src/rl/mdl/Kinematic.cpp index 88101be1..95a1474c 100644 --- a/src/rl/mdl/Kinematic.cpp +++ b/src/rl/mdl/Kinematic.cpp @@ -26,7 +26,6 @@ #include #include -#include #include #include #include diff --git a/src/rl/xml/DomParser.h b/src/rl/xml/DomParser.h index 7008c08e..6e2eb0ed 100644 --- a/src/rl/xml/DomParser.h +++ b/src/rl/xml/DomParser.h @@ -29,7 +29,6 @@ #include #include -#include #include #include "Document.h" diff --git a/src/rl/xml/Path.h b/src/rl/xml/Path.h index 300d3051..6562654c 100644 --- a/src/rl/xml/Path.h +++ b/src/rl/xml/Path.h @@ -29,7 +29,6 @@ #include #include -#include #include #include diff --git a/src/rl/xml/Schema.h b/src/rl/xml/Schema.h index a78e3d20..ecb92fe9 100644 --- a/src/rl/xml/Schema.h +++ b/src/rl/xml/Schema.h @@ -29,7 +29,6 @@ #include #include -#include #include #include "Document.h" From 8ef5d2f8db8be7af41ab6d46a33a0da891e61beb Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 14 Apr 2022 15:59:26 +0200 Subject: [PATCH 482/546] Replace boost::shared_array with std::unique_ptr --- src/rl/xml/Attribute.h | 6 +++--- src/rl/xml/Document.h | 5 ++--- src/rl/xml/Node.h | 16 ++++++++-------- src/rl/xml/Stylesheet.h | 5 ++--- 4 files changed, 15 insertions(+), 17 deletions(-) diff --git a/src/rl/xml/Attribute.h b/src/rl/xml/Attribute.h index fd42dedd..04ae7576 100644 --- a/src/rl/xml/Attribute.h +++ b/src/rl/xml/Attribute.h @@ -27,8 +27,8 @@ #ifndef RL_XML_ATTRIBUTE_H #define RL_XML_ATTRIBUTE_H +#include #include -#include #include #include "Namespace.h" @@ -100,7 +100,7 @@ namespace rl { if (nullptr != this->attr->ns) { - ::boost::shared_array<::xmlChar> value( + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> value( ::xmlGetNsProp( this->attr->parent, this->attr->name, @@ -113,7 +113,7 @@ namespace rl } else { - ::boost::shared_array<::xmlChar> value( + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> value( ::xmlGetProp( this->attr->parent, this->attr->name diff --git a/src/rl/xml/Document.h b/src/rl/xml/Document.h index 496e51de..8417ca12 100644 --- a/src/rl/xml/Document.h +++ b/src/rl/xml/Document.h @@ -29,7 +29,6 @@ #include #include -#include #include #include @@ -71,7 +70,7 @@ namespace rl int size; ::xmlDocDumpFormatMemory(this->doc.get(), &mem, &size, format ? 1 : 0); - ::boost::shared_array<::xmlChar> memory(mem, ::xmlFree); + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> memory(mem, ::xmlFree); return nullptr != memory.get() ? reinterpret_cast(memory.get()) : ::std::string(); } @@ -82,7 +81,7 @@ namespace rl int size; ::xmlDocDumpMemory(this->doc.get(), &mem, &size); - ::boost::shared_array<::xmlChar> memory(mem, ::xmlFree); + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> memory(mem, ::xmlFree); return nullptr != memory.get() ? reinterpret_cast(memory.get()) : ::std::string(); } diff --git a/src/rl/xml/Node.h b/src/rl/xml/Node.h index 733bbec0..07508814 100644 --- a/src/rl/xml/Node.h +++ b/src/rl/xml/Node.h @@ -28,8 +28,8 @@ #define RL_XML_NODE_H #include +#include #include -#include #include #include #include @@ -110,7 +110,7 @@ namespace rl ::std::string getContent() const { - ::boost::shared_array<::xmlChar> content( + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> content( ::xmlNodeGetContent(this->node), ::xmlFree ); @@ -135,7 +135,7 @@ namespace rl ::std::string getLocalPath(const ::std::string& uri) const { - ::boost::shared_array<::xmlChar> absolute( + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> absolute( ::xmlBuildURI( reinterpret_cast(uri.c_str()), ::xmlNodeGetBase(this->node->doc, this->node) @@ -143,7 +143,7 @@ namespace rl ::xmlFree ); - ::boost::shared_array unescaped( + ::std::unique_ptr unescaped( ::xmlURIUnescapeString( reinterpret_cast(absolute.get()), 0, @@ -213,7 +213,7 @@ namespace rl ::std::string getProperty(const ::std::string& name) const { - ::boost::shared_array<::xmlChar> prop( + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> prop( ::xmlGetProp( this->node, reinterpret_cast(name.c_str()) @@ -226,7 +226,7 @@ namespace rl ::std::string getProperty(const ::std::string& name, const ::std::string& nameSpace) const { - ::boost::shared_array<::xmlChar> prop( + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> prop( ::xmlGetNsProp( this->node, reinterpret_cast(name.c_str()), @@ -240,7 +240,7 @@ namespace rl ::std::string getRelativeUri(const ::std::string& uri) const { - ::boost::shared_array<::xmlChar> relative( + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> relative( ::xmlBuildRelativeURI( reinterpret_cast(uri.c_str()), ::xmlNodeGetBase(this->node->doc, this->node) @@ -253,7 +253,7 @@ namespace rl ::std::string getUri(const ::std::string& uri) const { - ::boost::shared_array<::xmlChar> absolute( + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> absolute( ::xmlBuildURI( reinterpret_cast(uri.c_str()), ::xmlNodeGetBase(this->node->doc, this->node) diff --git a/src/rl/xml/Stylesheet.h b/src/rl/xml/Stylesheet.h index a5774336..36e42c13 100644 --- a/src/rl/xml/Stylesheet.h +++ b/src/rl/xml/Stylesheet.h @@ -31,7 +31,6 @@ #include #include #include -#include #include #include @@ -116,7 +115,7 @@ namespace rl int size; ::xmlDocDumpFormatMemory(this->stylesheet.get()->doc, &mem, &size, format ? 1 : 0); - ::boost::shared_array<::xmlChar> memory(mem, ::xmlFree); + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> memory(mem, ::xmlFree); return nullptr != memory.get() ? reinterpret_cast(memory.get()) : ::std::string(); } @@ -127,7 +126,7 @@ namespace rl int size; ::xmlDocDumpMemory(this->stylesheet.get()->doc, &mem, &size); - ::boost::shared_array<::xmlChar> memory(mem, ::xmlFree); + ::std::unique_ptr<::xmlChar, decltype(::xmlFree)> memory(mem, ::xmlFree); return nullptr != memory.get() ? reinterpret_cast(memory.get()) : ::std::string(); } From 82f8ca9e57c4c94b3fe2a5d4d83a9edbcf1d2183 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 24 Apr 2022 17:11:55 +0200 Subject: [PATCH 483/546] Fix clipboard camera values --- extras/wrlview/MainWindow.cpp | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 75c45dd3..ad429e82 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -214,16 +214,23 @@ MainWindow::~MainWindow() void MainWindow::copyCameraValues() { + SbVec3f axis; + float angle; + this->viewer->getCamera()->orientation.getValue(axis, angle); + QApplication::clipboard()->setText( "position " + QString::number(this->viewer->getCamera()->position.getValue()[0]) + " " + QString::number(this->viewer->getCamera()->position.getValue()[1]) + " " + QString::number(this->viewer->getCamera()->position.getValue()[2]) + "\n" + "orientation " + - QString::number(this->viewer->getCamera()->orientation.getValue().getValue()[0]) + " " + - QString::number(this->viewer->getCamera()->orientation.getValue().getValue()[1]) + " " + - QString::number(this->viewer->getCamera()->orientation.getValue().getValue()[2]) + " " + - QString::number(this->viewer->getCamera()->orientation.getValue().getValue()[3]) + "\n" + + QString::number(axis[0]) + " " + + QString::number(axis[1]) + " " + + QString::number(axis[2]) + " " + + QString::number(angle) + "\n" + + "nearDistance " + QString::number(this->viewer->getCamera()->nearDistance.getValue()) + "\n" + + "farDistance " + QString::number(this->viewer->getCamera()->farDistance.getValue()) + "\n" + + "aspectRatio " + QString::number(this->viewer->getCamera()->aspectRatio.getValue()) + "\n" + "focalDistance " + QString::number(this->viewer->getCamera()->focalDistance.getValue()) + "\n" + ( SoPerspectiveCamera::getClassTypeId() == this->viewer->getCameraType() ? From 459e6d0271bfa3e8325b90f82aa78f9bafefa750 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 24 Apr 2022 17:14:42 +0200 Subject: [PATCH 484/546] Add custom background color option --- extras/wrlview/MainWindow.cpp | 27 ++++++++++++++++++++++++++- extras/wrlview/MainWindow.h | 1 + 2 files changed, 27 insertions(+), 1 deletion(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index ad429e82..f365d939 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -27,6 +27,7 @@ #include #include #include +#include #include #include #include @@ -446,9 +447,14 @@ MainWindow::init() backgroundActionGroup->addAction(backgroundBlackAction); this->displayMenu->addAction(backgroundBlackAction); + QAction* backgroundCustomAction = new QAction("Custom Background...", this); + backgroundCustomAction->setCheckable(true); + backgroundCustomAction->setData(static_cast(Background::custom)); + backgroundActionGroup->addAction(backgroundCustomAction); + this->displayMenu->addAction(backgroundCustomAction); + QAction* backgroundGradientAction = new QAction("Gradient Background", this); backgroundGradientAction->setCheckable(true); - backgroundGradientAction->setChecked(true); backgroundGradientAction->setData(static_cast(Background::gradient)); backgroundActionGroup->addAction(backgroundGradientAction); this->displayMenu->addAction(backgroundGradientAction); @@ -459,6 +465,17 @@ MainWindow::init() backgroundActionGroup->addAction(backgroundWhiteAction); this->displayMenu->addAction(backgroundWhiteAction); + const SbColor& color = this->viewer->getBackgroundColor(); + + if (color[0] > 0 || color[1] > 0 || color[2] > 0) + { + backgroundCustomAction->setChecked(true); + } + else + { + backgroundGradientAction->setChecked(true); + } + this->displayMenu->addSeparator(); QActionGroup* sizeActionGroup = new QActionGroup(this); @@ -779,6 +796,14 @@ MainWindow::selectBackground(QAction* action) this->backgroundSwitch->whichChild = SO_SWITCH_NONE; this->viewer->setBackgroundColor(SbColor(0, 0, 0)); break; + case Background::custom: + { + const float* rgb = this->viewer->getBackgroundColor().getValue(); + QColor color = QColorDialog::getColor(QColor::fromRgbF(rgb[0], rgb[1], rgb[2]), this, "Select Color"); + this->backgroundSwitch->whichChild = SO_SWITCH_NONE; + this->viewer->setBackgroundColor(SbColor(color.redF(), color.greenF(), color.blueF())); + } + break; case Background::gradient: this->backgroundSwitch->whichChild = SO_SWITCH_ALL; break; diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index 6ebad525..890cf647 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -60,6 +60,7 @@ class MainWindow : public QMainWindow enum class Background { black, + custom, gradient, white }; From 5673a795d29099c817d04de89badbaa9c2b201c5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 24 Apr 2022 17:20:45 +0200 Subject: [PATCH 485/546] Update size options --- extras/wrlview/MainWindow.cpp | 131 ++++++++++++---------------------- extras/wrlview/MainWindow.h | 14 ---- 2 files changed, 44 insertions(+), 101 deletions(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index f365d939..cdd36af4 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -479,58 +479,50 @@ MainWindow::init() this->displayMenu->addSeparator(); QActionGroup* sizeActionGroup = new QActionGroup(this); - sizeActionGroup->setExclusive(true); QObject::connect(sizeActionGroup, SIGNAL(triggered(QAction*)), this, SLOT(selectSize(QAction*))); - QAction* size640x480Action = new QAction("640x480", this); - size640x480Action->setData(static_cast(Size::s640x480)); - sizeActionGroup->addAction(size640x480Action); - this->displayMenu->addAction(size640x480Action); - - QAction* size800x600Action = new QAction("800x600", this); - size800x600Action->setData(static_cast(Size::s800x600)); - sizeActionGroup->addAction(size800x600Action); - this->displayMenu->addAction(size800x600Action); - - QAction* size1024x768Action = new QAction("1024x768", this); - size1024x768Action->setData(static_cast(Size::s1024x768)); - sizeActionGroup->addAction(size1024x768Action); - this->displayMenu->addAction(size1024x768Action); - - QAction* size1024x1024Action = new QAction("1024x1024", this); - size1024x1024Action->setData(static_cast(Size::s1024x1024)); - sizeActionGroup->addAction(size1024x1024Action); - this->displayMenu->addAction(size1024x1024Action); - - QAction* size1280x720Action = new QAction("1280x720", this); - size1280x720Action->setData(static_cast(Size::s1280x720)); - sizeActionGroup->addAction(size1280x720Action); - this->displayMenu->addAction(size1280x720Action); - - QAction* size1280x960Action = new QAction("1280x960", this); - size1280x960Action->setData(static_cast(Size::s1280x960)); - sizeActionGroup->addAction(size1280x960Action); - this->displayMenu->addAction(size1280x960Action); - - QAction* size1200x1200Action = new QAction("1200x1200", this); - size1200x1200Action->setData(static_cast(Size::s1200x1200)); - sizeActionGroup->addAction(size1200x1200Action); - this->displayMenu->addAction(size1200x1200Action); - - QAction* size1600x1200Action = new QAction("1600x1200", this); - size1600x1200Action->setData(static_cast(Size::s1600x1200)); - sizeActionGroup->addAction(size1600x1200Action); - this->displayMenu->addAction(size1600x1200Action); - - QAction* size1920x1080Action = new QAction("1920x1080", this); - size1920x1080Action->setData(static_cast(Size::s1920x1080)); - sizeActionGroup->addAction(size1920x1080Action); - this->displayMenu->addAction(size1920x1080Action); - - QAction* size2400x2400Action = new QAction("2400x2400", this); - size2400x2400Action->setData(static_cast(Size::s2400x2400)); - sizeActionGroup->addAction(size2400x2400Action); - this->displayMenu->addAction(size2400x2400Action); + QMenu* sizeMenu0 = this->displayMenu->addMenu("1:1"); + QMenu* sizeMenu1 = this->displayMenu->addMenu("4:3"); + QMenu* sizeMenu2 = this->displayMenu->addMenu("16:9"); + QMenu* sizeMenu3 = this->displayMenu->addMenu("21:9"); + + QList> sizes; + sizes.push_back(std::make_pair(sizeMenu0, QSize(256, 256))); + sizes.push_back(std::make_pair(sizeMenu0, QSize(512, 512))); + sizes.push_back(std::make_pair(sizeMenu0, QSize(1024, 1024))); + sizes.push_back(std::make_pair(sizeMenu0, QSize(2048, 2048))); + sizes.push_back(std::make_pair(sizeMenu1, QSize(320, 240))); + sizes.push_back(std::make_pair(sizeMenu1, QSize(640, 480))); + sizes.push_back(std::make_pair(sizeMenu1, QSize(800, 600))); + sizes.push_back(std::make_pair(sizeMenu1, QSize(1024, 768))); + sizes.push_back(std::make_pair(sizeMenu1, QSize(1152, 864))); + sizes.push_back(std::make_pair(sizeMenu1, QSize(1280, 960))); + sizes.push_back(std::make_pair(sizeMenu1, QSize(1400, 1050))); + sizes.push_back(std::make_pair(sizeMenu1, QSize(1600, 1200))); + sizes.push_back(std::make_pair(sizeMenu1, QSize(2048, 1536))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(426, 240))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(640, 360))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(854, 480))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(960, 540))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(1280, 720))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(1366, 768))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(1600, 900))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(1920, 1080))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(2560, 1440))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(3200, 1800))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(3840, 2160))); + sizes.push_back(std::make_pair(sizeMenu2, QSize(5120, 2880))); + sizes.push_back(std::make_pair(sizeMenu3, QSize(2560, 1080))); + sizes.push_back(std::make_pair(sizeMenu3, QSize(3440, 1440))); + sizes.push_back(std::make_pair(sizeMenu3, QSize(5120, 2160))); + + for (int i = 0; i < sizes.size(); ++i) + { + QAction* sizeAction = new QAction(QString::number(sizes[i].second.width()) + "x" + QString::number(sizes[i].second.height()), this); + sizeAction->setData(sizes[i].second); + sizeActionGroup->addAction(sizeAction); + sizes[i].first->addAction(sizeAction); + } } void @@ -860,43 +852,8 @@ MainWindow::selectOrigin(QAction* action) void MainWindow::selectSize(QAction* action) { - switch (static_cast(action->data().toInt())) - { - case Size::s640x480: - this->widget->setFixedSize(640, 480); - break; - case Size::s800x600: - this->widget->setFixedSize(800, 600); - break; - case Size::s1024x768: - this->widget->setFixedSize(1024, 768); - break; - case Size::s1024x1024: - this->widget->setFixedSize(1024, 1024); - break; - case Size::s1280x720: - this->widget->setFixedSize(1280, 720); - break; - case Size::s1280x960: - this->widget->setFixedSize(1280, 960); - break; - case Size::s1200x1200: - this->widget->setFixedSize(1200, 1200); - break; - case Size::s1600x1200: - this->widget->setFixedSize(1600, 1200); - break; - case Size::s1920x1080: - this->widget->setFixedSize(1920, 1080); - break; - case Size::s2400x2400: - this->widget->setFixedSize(2400, 2400); - break; - default: - break; - } - - this->setFixedSize(this->widget->sizeHint().width(), this->widget->sizeHint().height()); + this->widget->setFixedSize(action->data().toSize()); + this->setFixedSize(this->widget->sizeHint()); this->widget->setFixedSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX); this->setFixedSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX); } diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index 890cf647..3fc6bcff 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -78,20 +78,6 @@ class MainWindow : public QMainWindow o1000 }; - enum class Size - { - s640x480, - s800x600, - s1024x768, - s1024x1024, - s1280x720, - s1280x960, - s1200x1200, - s1600x1200, - s1920x1080, - s2400x2400 - }; - enum class View { back, From d5ed9a355c7add3f303cb8d1bbb643eae20655d5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 24 Apr 2022 17:24:01 +0200 Subject: [PATCH 486/546] Update widget size handling --- extras/wrlview/CMakeLists.txt | 2 ++ extras/wrlview/MainWindow.cpp | 10 +++---- extras/wrlview/MainWindow.h | 3 ++- extras/wrlview/Widget.cpp | 49 +++++++++++++++++++++++++++++++++++ extras/wrlview/Widget.h | 49 +++++++++++++++++++++++++++++++++++ 5 files changed, 107 insertions(+), 6 deletions(-) create mode 100644 extras/wrlview/Widget.cpp create mode 100644 extras/wrlview/Widget.h diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 3715df1b..c477b767 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -39,6 +39,8 @@ if(Coin_FOUND AND OPENGL_FOUND AND QT_FOUND AND SoQt_FOUND) MainWindow.h SoGradientBackground.cpp SoGradientBackground.h + Widget.cpp + Widget.h wrlview.cpp ${CMAKE_CURRENT_BINARY_DIR}/wrlview.rc ) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index cdd36af4..a2035252 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -62,6 +62,7 @@ #include "MainWindow.h" #include "SoGradientBackground.h" +#include "Widget.h" MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QMainWindow(parent, f), @@ -79,7 +80,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : scene(nullptr), supportedFileEndings(), viewer(nullptr), - widget(new QWidget(this)) + widget(new Widget(this)) { SoQt::init(this); SoDB::init(); @@ -852,10 +853,9 @@ MainWindow::selectOrigin(QAction* action) void MainWindow::selectSize(QAction* action) { - this->widget->setFixedSize(action->data().toSize()); - this->setFixedSize(this->widget->sizeHint()); - this->widget->setFixedSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX); - this->setFixedSize(QWIDGETSIZE_MAX, QWIDGETSIZE_MAX); + this->widget->setSizeHint(action->data().toSize()); + this->widget->updateGeometry(); + this->resize(this->sizeHint()); } void diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index 3fc6bcff..2813333c 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -41,6 +41,7 @@ #include class SoGradientBackground; +class Widget; class MainWindow : public QMainWindow { @@ -132,7 +133,7 @@ class MainWindow : public QMainWindow QMenu* viewMenu; - QWidget* widget; + Widget* widget; private slots: void open(); diff --git a/extras/wrlview/Widget.cpp b/extras/wrlview/Widget.cpp new file mode 100644 index 00000000..8e4bee6d --- /dev/null +++ b/extras/wrlview/Widget.cpp @@ -0,0 +1,49 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Widget.h" + +Widget::Widget(QWidget* parent) : + QWidget(parent), + size() +{ +} + +Widget::~Widget() +{ +} + +QSize +Widget::sizeHint() const +{ + return this->size; +} + +void +Widget::setSizeHint(const QSize& size) +{ + this->size = size; +} diff --git a/extras/wrlview/Widget.h b/extras/wrlview/Widget.h new file mode 100644 index 00000000..844c2dfb --- /dev/null +++ b/extras/wrlview/Widget.h @@ -0,0 +1,49 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 WIDGET_H +#define WIDGET_H + +#include + +class Widget : public QWidget +{ + Q_OBJECT + +public: + Widget(QWidget* parent = nullptr); + + virtual ~Widget(); + + QSize sizeHint() const; + + void setSizeHint(const QSize& size); + +private: + QSize size; +}; + +#endif // WIDGET_H From 947a434cee45f72a50868c30c95e2faaed6466a9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 24 Apr 2022 17:24:32 +0200 Subject: [PATCH 487/546] Check for https urls --- extras/wrlview/MainWindow.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index a2035252..f81f027e 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -533,7 +533,7 @@ MainWindow::inlineFetchUrlCallback(const SbString& url, void* userData, SoVRMLIn QString string(node->url.getValues(0)->getString()); - if (string.startsWith("http://") || string.startsWith("ftp://")) + if (string.startsWith("http://") || string.startsWith("https://") || string.startsWith("ftp://")) { QNetworkReply* reply = mainWindow->manager->get(QNetworkRequest(QUrl(node->url.getValues(0)->getString()))); reply->setProperty("node", QVariant::fromValue(static_cast(node))); From 10e5b8942058116eac681d4a72cd8d5601953402 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 24 Apr 2022 17:25:40 +0200 Subject: [PATCH 488/546] Add command line parsing --- extras/wrlview/MainWindow.cpp | 114 +++++++++++++++++++++++++++++++--- extras/wrlview/MainWindow.h | 2 + 2 files changed, 109 insertions(+), 7 deletions(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index f81f027e..d1d7634f 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -54,6 +54,10 @@ #include #include +#if QT_VERSION >= 0x050200 +#include +#endif + #if QT_VERSION >= 0x060000 #include #else @@ -186,14 +190,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->setCentralWidget(this->widget); this->setFocusProxy(this->viewer->getWidget()); - this->init(); - - this->resize(800, 600); + this->parseCommandLine(); - if (QCoreApplication::arguments().size() > 1) - { - this->filename = QCoreApplication::arguments()[1]; - } + this->init(); if (!this->filename.isEmpty()) { @@ -652,6 +651,107 @@ MainWindow::open() this->viewer->viewAll(); } +void +MainWindow::parseCommandLine() +{ + QSize size(800, 600); + +#if QT_VERSION >= 0x050200 + QCommandLineOption backgroundOption(QStringList("background"), "Sets background color of 3D viewer.", "color"); + QCommandLineOption heightOption(QStringList("height"), "Sets initial height of 3D viewer.", "height"); + QCommandLineOption widthOption(QStringList("width"), "Sets initial width of 3D viewer.", "width"); + + QCommandLineParser parser; + parser.addOption(backgroundOption); + parser.addOption(heightOption); + QCommandLineOption helpOption = parser.addHelpOption(); + parser.addOption(widthOption); + parser.addPositionalArgument("filename", "", "[filename]"); + + parser.process(QCoreApplication::arguments()); + + if (parser.isSet(backgroundOption)) + { + QString background = parser.value(backgroundOption); + + if (!QColor::isValidColor(background)) + { + parser.showHelp(); + } + + this->backgroundSwitch->whichChild = SO_SWITCH_NONE; + QColor color(background); + this->viewer->setBackgroundColor(SbColor(color.redF(), color.greenF(), color.blueF())); + } + + if (parser.isSet(heightOption)) + { + bool ok; + size.setHeight(parser.value(heightOption).toInt(&ok)); + + if (!ok) + { + parser.showHelp(); + } + } + + if (parser.isSet(widthOption)) + { + bool ok; + size.setWidth(parser.value(widthOption).toInt(&ok)); + + if (!ok) + { + parser.showHelp(); + } + } + + if (parser.positionalArguments().size() > 1) + { + parser.showHelp(); + } + + if (!parser.positionalArguments().empty()) + { + this->filename = parser.positionalArguments()[0]; + } +#else + QRegExp backgroundRegExp("--background=(\\S*)"); + QRegExp helpRegExp("--help"); + QRegExp heightRegExp("--height=(\\d*)"); + QRegExp widthRegExp("--width=(\\d*)"); + + for (int i = 1; i < QApplication::arguments().size(); ++i) + { + if (-1 != backgroundRegExp.indexIn(QApplication::arguments()[i])) + { + this->backgroundSwitch->whichChild = SO_SWITCH_NONE; + QColor color(backgroundRegExp.cap(1)); + this->viewer->setBackgroundColor(SbColor(color.redF(), color.greenF(), color.blueF())); + } + else if (-1 != helpRegExp.indexIn(QApplication::arguments()[i])) + { + QMessageBox::information(this, "Usage", "wrlview [--background=] [--height=] [--help] [--width=] [filename]"); + exit(EXIT_SUCCESS); + } + else if (-1 != heightRegExp.indexIn(QApplication::arguments()[i])) + { + size.setHeight(heightRegExp.cap(1).toInt()); + } + else if (-1 != widthRegExp.indexIn(QApplication::arguments()[i])) + { + size.setWidth(widthRegExp.cap(1).toInt()); + } + else + { + this->filename = QApplication::arguments()[i]; + } + } +#endif + + this->widget->setSizeHint(size); +} + void MainWindow::reload() { diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index 2813333c..ccb5a11b 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -99,6 +99,8 @@ class MainWindow : public QMainWindow void load(const QString filename); + void parseCommandLine(); + void saveImage(bool withAlpha); void saveImageOffscreen(bool withAlpha); From 75bd29198cb3f6cef8288f66e6b1efb1f7de49a6 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 24 Apr 2022 17:26:22 +0200 Subject: [PATCH 489/546] Add wireframe overlay color option --- extras/wrlview/MainWindow.cpp | 14 ++++++++++++++ extras/wrlview/MainWindow.h | 2 ++ 2 files changed, 16 insertions(+) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index d1d7634f..8d4ecb40 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -478,6 +478,12 @@ MainWindow::init() this->displayMenu->addSeparator(); + QAction* wireframeOverlayColorAction = new QAction("Wireframe Overlay Color...", this); + QObject::connect(wireframeOverlayColorAction, SIGNAL(triggered()), this, SLOT(selectWireframeOverlayColor())); + this->displayMenu->addAction(wireframeOverlayColorAction); + + this->displayMenu->addSeparator(); + QActionGroup* sizeActionGroup = new QActionGroup(this); QObject::connect(sizeActionGroup, SIGNAL(triggered(QAction*)), this, SLOT(selectSize(QAction*))); @@ -1010,6 +1016,14 @@ MainWindow::selectView(QAction* action) this->viewer->viewAll(); } +void +MainWindow::selectWireframeOverlayColor() +{ + const float* rgb = this->viewer->getWireframeOverlayColor().getValue(); + QColor color = QColorDialog::getColor(QColor::fromRgbF(rgb[0], rgb[1], rgb[2]), this, "Select Color"); + this->viewer->setWireframeOverlayColor(SbColor(color.redF(), color.greenF(), color.blueF())); +} + void MainWindow::toggleAxisCross() { diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index ccb5a11b..a73d2573 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -164,6 +164,8 @@ private slots: void selectView(QAction* action); + void selectWireframeOverlayColor(); + void toggleAxisCross(); void toggleFullScreen(); From 8b66bf7c3f60e9f0c05236d781d191249e3425dd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 24 Apr 2022 22:04:08 +0200 Subject: [PATCH 490/546] Add rendering options --- extras/wrlview/MainWindow.cpp | 71 ++++++++++++++++++++++++++++++++++- extras/wrlview/MainWindow.h | 10 +++++ 2 files changed, 79 insertions(+), 2 deletions(-) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 8d4ecb40..df5e2a29 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include #include #include @@ -80,6 +81,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : offscreenRenderer(nullptr), origin1Switch(nullptr), origin1000Switch(nullptr), + ppi(SoOffscreenRenderer::getScreenPixelsPerInch()), root(nullptr), scene(nullptr), supportedFileEndings(), @@ -484,6 +486,30 @@ MainWindow::init() this->displayMenu->addSeparator(); + QMenu* rendererMenu = this->displayMenu->addMenu("Renderer"); + + QAction* selectRenderingPassesAction = new QAction("Rendering Passes...", this); + QObject::connect(selectRenderingPassesAction, SIGNAL(triggered()), this, SLOT(selectRenderingPasses())); + rendererMenu->addAction(selectRenderingPassesAction); + + QAction* selectRenderingSmoothingAction = new QAction("Smoothing", this); + selectRenderingSmoothingAction->setCheckable(true); + selectRenderingSmoothingAction->setChecked(this->viewer->getGLRenderAction()->isSmoothing()); + QObject::connect(selectRenderingSmoothingAction, SIGNAL(triggered(bool)), this, SLOT(selectRenderingSmoothing(bool))); + rendererMenu->addAction(selectRenderingSmoothingAction); + + QMenu* offscreenRendererMenu = this->displayMenu->addMenu("Offscreen Renderer"); + + QAction* selectOffscreenPixelsPerInchAction = new QAction("Pixels per Inch...", this); + QObject::connect(selectOffscreenPixelsPerInchAction, SIGNAL(triggered()), this, SLOT(selectOffscreenPixelsPerInch())); + offscreenRendererMenu->addAction(selectOffscreenPixelsPerInchAction); + + QAction* selectOffscreenPassesAction = new QAction("Rendering Passes...", this); + QObject::connect(selectOffscreenPassesAction, SIGNAL(triggered()), this, SLOT(selectOffscreenPasses())); + offscreenRendererMenu->addAction(selectOffscreenPassesAction); + + this->displayMenu->addSeparator(); + QActionGroup* sizeActionGroup = new QActionGroup(this); QObject::connect(sizeActionGroup, SIGNAL(triggered(QAction*)), this, SLOT(selectSize(QAction*))); @@ -832,7 +858,7 @@ MainWindow::saveImageOffscreen(bool withAlpha) QString filename = "wrlview-" + QDateTime::currentDateTime().toString("yyyyMMdd-HHmmsszzz") + ".png"; SbViewportRegion viewportRegion(this->viewer->getViewportRegion()); - viewportRegion.setPixelsPerInch(300); + viewportRegion.setPixelsPerInch(this->ppi); viewportRegion.setWindowSize( viewportRegion.getViewportSizePixels()[0] * viewportRegion.getPixelsPerInch() / SoOffscreenRenderer::getScreenPixelsPerInch(), viewportRegion.getViewportSizePixels()[1] * viewportRegion.getPixelsPerInch() / SoOffscreenRenderer::getScreenPixelsPerInch() @@ -841,7 +867,6 @@ MainWindow::saveImageOffscreen(bool withAlpha) this->offscreenRenderer->setBackgroundColor(this->viewer->getBackgroundColor()); this->offscreenRenderer->setComponents(withAlpha ? SoOffscreenRenderer::RGB_TRANSPARENCY : SoOffscreenRenderer::RGB); this->offscreenRenderer->setViewportRegion(viewportRegion); - this->offscreenRenderer->getGLRenderAction()->setNumPasses(8); if (!this->offscreenRenderer->render(this->viewer->getSceneManager()->getSceneGraph())) { @@ -1024,6 +1049,48 @@ MainWindow::selectWireframeOverlayColor() this->viewer->setWireframeOverlayColor(SbColor(color.redF(), color.greenF(), color.blueF())); } +void +MainWindow::selectOffscreenPasses() +{ + bool ok; + int num = QInputDialog::getInt(this, "Offscreen Renderer", "Rendering Passes", this->offscreenRenderer->getGLRenderAction()->getNumPasses(), 0, 256, 1, &ok, Qt::WindowTitleHint | Qt::WindowSystemMenuHint); + + if (ok) + { + this->offscreenRenderer->getGLRenderAction()->setNumPasses(num); + } +} + +void +MainWindow::selectOffscreenPixelsPerInch() +{ + bool ok; + float ppi = QInputDialog::getInt(this, "Offscreen Renderer", "Pixels per Inch", this->ppi, 0, 600, 1, &ok, Qt::WindowTitleHint | Qt::WindowSystemMenuHint); + + if (ok) + { + this->ppi = ppi; + } +} + +void +MainWindow::selectRenderingPasses() +{ + bool ok; + int num = QInputDialog::getInt(this, "Renderer", "Rendering Passes", this->viewer->getGLRenderAction()->getNumPasses(), 0, 256, 1, &ok, Qt::WindowTitleHint | Qt::WindowSystemMenuHint); + + if (ok) + { + this->viewer->getGLRenderAction()->setNumPasses(num); + } +} + +void +MainWindow::selectRenderingSmoothing(bool checked) +{ + this->viewer->getGLRenderAction()->setSmoothing(checked); +} + void MainWindow::toggleAxisCross() { diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index a73d2573..db35594b 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -125,6 +125,8 @@ class MainWindow : public QMainWindow SoSwitch* origin1000Switch; + float ppi; + SoSeparator* root; SoSeparator* scene; @@ -166,6 +168,14 @@ private slots: void selectWireframeOverlayColor(); + void selectOffscreenPasses(); + + void selectOffscreenPixelsPerInch(); + + void selectRenderingPasses(); + + void selectRenderingSmoothing(bool checked); + void toggleAxisCross(); void toggleFullScreen(); From ee1a3fc21a4e9a5a85164f58a806755145cc971d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 24 Apr 2022 22:04:27 +0200 Subject: [PATCH 491/546] Update version number --- extras/wrlview/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index c477b767..6b099fb6 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -1,4 +1,4 @@ -project(wrlview VERSION 0.1.14) +project(wrlview VERSION 0.2.0) if(NOT PROJECT_VERSION_TWEAK) set(PROJECT_VERSION_TWEAK 0) From 194782439e862da791e2dbb50b13eb2c6025608a Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 26 Apr 2022 20:47:49 +0200 Subject: [PATCH 492/546] Replace rl::math::NestedFunction with rl::math::CompositeFunction --- src/rl/math/CMakeLists.txt | 1 + src/rl/math/CompositeFunction.h | 104 ++++++++++++ src/rl/math/NestedFunction.h | 8 +- tests/rlSplineTest/CMakeLists.txt | 1 + .../rlSplineTest/rlCompositeFunctionTest.cpp | 159 ++++++++++++++++++ 5 files changed, 272 insertions(+), 1 deletion(-) create mode 100644 src/rl/math/CompositeFunction.h create mode 100644 tests/rlSplineTest/rlCompositeFunctionTest.cpp diff --git a/src/rl/math/CMakeLists.txt b/src/rl/math/CMakeLists.txt index bd9737fc..de706a3c 100644 --- a/src/rl/math/CMakeLists.txt +++ b/src/rl/math/CMakeLists.txt @@ -9,6 +9,7 @@ set( Circular.h CircularVector2.h CircularVector3.h + CompositeFunction.h Constants.h Function.h GnatNearestNeighbors.h diff --git a/src/rl/math/CompositeFunction.h b/src/rl/math/CompositeFunction.h new file mode 100644 index 00000000..5e61aa94 --- /dev/null +++ b/src/rl/math/CompositeFunction.h @@ -0,0 +1,104 @@ +// +// Copyright (c) 2009, Andre Gaschler, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_MATH_COMPOSITEFUNCTION_H +#define RL_MATH_COMPOSITEFUNCTION_H + +#include +#include + +#include "Function.h" + +namespace rl +{ + namespace math + { + /** + * A composite function that takes two functions \f$f\f$ and \f$g\f$ and produces + * a function \f$h = f \circ g\f$ such that \f$h(x) = f(g(x))\f$. + */ + template + class CompositeFunction : public Function + { + public: + CompositeFunction(const Function& f, const Function& g) : + Function(g.lower(), g.upper()), + f(f), + g(g) + { + } + + virtual ~CompositeFunction() + { + } + + CompositeFunction* clone() const + { + return new CompositeFunction(*this); + } + + T operator()(const Real& x, const ::std::size_t& derivative = 0) const + { + using ::std::pow; + + switch (derivative) + { + case 0: + return this->f(this->g(x)); + break; + case 1: + return this->f(this->g(x), 1) * this->g(x, 1); + break; + case 2: + { + T2 g0 = this->g(x); + return pow(this->g(x, 1), 2) * this->f(g0, 2) + this->f(g0, 1) * this->g(x, 2); + } + break; + case 3: + { + T2 g0 = this->g(x); + T2 g1 = this->g(x, 1); + return 3 * g1 * this->f(g0, 2) * this->g(x, 2) + pow(g1, 3) * this->f(g0, 3) + this->f(g0, 1) * this->g(x, 3); + } + break; + default: + throw ::std::runtime_error("rl::math::CompositeFunction: Derivatives > 3 not supported"); + break; + } + } + + protected: + + private: + const Function& f; + + const Function& g; + }; + } +} + +#endif // RL_MATH_COMPOSITEFUNCTION_H diff --git a/src/rl/math/NestedFunction.h b/src/rl/math/NestedFunction.h index beb96357..2564ec8c 100644 --- a/src/rl/math/NestedFunction.h +++ b/src/rl/math/NestedFunction.h @@ -31,12 +31,18 @@ #include "Function.h" +#if defined(__GNUC__) || defined(__clang__) +#define RL_MATH_DEPRECATED __attribute__ ((__deprecated__)) +#elif defined(_MSC_VER) +#define RL_MATH_DEPRECATED __declspec(deprecated) +#endif + namespace rl { namespace math { template - class NestedFunction : public Function + class RL_MATH_DEPRECATED NestedFunction : public Function { public: NestedFunction(const Function& inner, const Function& outer) : diff --git a/tests/rlSplineTest/CMakeLists.txt b/tests/rlSplineTest/CMakeLists.txt index 63693d49..f3c9ab9a 100644 --- a/tests/rlSplineTest/CMakeLists.txt +++ b/tests/rlSplineTest/CMakeLists.txt @@ -1,5 +1,6 @@ set( TESTS + rlCompositeFunctionTest rlPolynomialExtremaTest rlPolynomialTest rlQuarticLinearQuarticTest diff --git a/tests/rlSplineTest/rlCompositeFunctionTest.cpp b/tests/rlSplineTest/rlCompositeFunctionTest.cpp new file mode 100644 index 00000000..291572eb --- /dev/null +++ b/tests/rlSplineTest/rlCompositeFunctionTest.cpp @@ -0,0 +1,159 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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. +// + +#define EIGEN_DEFAULT_IO_FORMAT Eigen::IOFormat(Eigen::StreamPrecision, Eigen::DontAlignCols, ",", ";", "", "", "[", "]") + +#include +#include +#include +#include + +template +std::ostream& +operator<<(std::ostream& o, const rl::math::Polynomial& f) +{ + for (std::size_t i = 0; i < f.degree() + 1; ++i) + { + o << (i > 0 ? " + " : "") << f.coefficient(i) << " * x^" << i; + } + + return o; +} + +template +void +check(const rl::math::Polynomial& f, const rl::math::Polynomial& g, const rl::math::Polynomial& h1, const rl::math::CompositeFunction& h2) +{ + for (rl::math::Real i = h1.lower(); i <= h1.upper(); ++i) + { + for (std::size_t j = 0; j < 3; ++j) + { + T tmp1 = h1(i, j); + T tmp2 = h2(i, j); + + if (!rl::math::TypeTraits::equal(tmp1, tmp2)) + { + std::cerr << "f(x) = " << f << std::endl; + std::cerr << "g(x) = " << g << std::endl; + std::cerr << "h(x) = " << h1 << std::endl; + std::cerr << "h1(" << i << ", " << j << ") != h2(" << i << ", " << j << ")" << std::endl; + std::cerr << "h1(" << i << ", " << j << ") = " << tmp1 << std::endl; + std::cerr << "h2(" << i << ", " << j << ") = " << tmp2 << std::endl; + std::cerr << "g(" << i << ", 0) = " << g(i, 0) << std::endl; + std::cerr << "g(" << i << ", 1) = " << g(i, 1) << std::endl; + std::cerr << "g(" << i << ", 2) = " << g(i, 2) << std::endl; + std::cerr << "g(" << i << ", 3) = " << g(i, 3) << std::endl; + std::cerr << "f(g(" << i << "), 0) = " << f(g(i), 0) << std::endl; + std::cerr << "f(g(" << i << "), 1) = " << f(g(i), 1) << std::endl; + std::cerr << "f(g(" << i << "), 2) = " << f(g(i), 2) << std::endl; + std::cerr << "f(g(" << i << "), 3) = " << f(g(i), 3) << std::endl; + exit(EXIT_FAILURE); + } + } + } +} + +int +main(int argc, char** argv) +{ + { + rl::math::Polynomial f(2); + f.coefficient(0) = 0; + f.coefficient(1) = 0; + f.coefficient(2) = 1; + f.upper() = 10; + + rl::math::Polynomial g(2); + g.coefficient(0) = 0; + g.coefficient(1) = 0; + g.coefficient(2) = 1; + g.upper() = 10; + + rl::math::Polynomial h1(4); + h1.coefficient(0) = 0; + h1.coefficient(1) = 0; + h1.coefficient(2) = 0; + h1.coefficient(3) = 0; + h1.coefficient(4) = 1; + h1.upper() = g.upper(); + + rl::math::CompositeFunction h2(f, g); + + check(f, g, h1, h2); + } + + { + rl::math::Polynomial f(1); + f.coefficient(0) = -5; + f.coefficient(1) = -1; + f.upper() = 1; + + rl::math::Polynomial g(3); + g.coefficient(0) = 0; + g.coefficient(1) = 0; + g.coefficient(2) = -3; + g.coefficient(3) = 4; + g.upper() = 10; + + rl::math::Polynomial h1(3); + h1.coefficient(0) = -5; + h1.coefficient(1) = 0; + h1.coefficient(2) = 3; + h1.coefficient(3) = -4; + h1.upper() = g.upper(); + + rl::math::CompositeFunction h2(f, g); + + check(f, g, h1, h2); + } + + { + rl::math::Polynomial f(3); + f.coefficient(0) = rl::math::Vector3(1, 1, -2); + f.coefficient(1) = rl::math::Vector3(0, 0, 1); + f.coefficient(2) = rl::math::Vector3::Constant(0); + f.coefficient(3) = rl::math::Vector3(2, 2, 4); + f.upper() = 5; + + rl::math::Polynomial g(1); + g.coefficient(0) = 3; + g.coefficient(1) = -2; + g.upper() = 10; + + rl::math::Polynomial h1(3); + h1.coefficient(0) = rl::math::Vector3(55, 55, 109); + h1.coefficient(1) = rl::math::Vector3(-108, -108, -218); + h1.coefficient(2) = rl::math::Vector3(72, 72, 144); + h1.coefficient(3) = rl::math::Vector3(-16, -16, -32); + h1.upper() = g.upper(); + + rl::math::CompositeFunction h2(f, g); + + check(f, g, h1, h2); + } + + return EXIT_SUCCESS; +} From 1503f31c6041da85fd63c8cdf9102da5b680e637 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 6 May 2022 16:26:11 +0200 Subject: [PATCH 493/546] Fix whitespace --- demos/rlCoachKin/MainWindow.h | 2 +- demos/rlPlanDemo/ConfigurationSpaceScene.h | 2 +- demos/rlPlanDemo/Viewer.cpp | 2 +- demos/rlSimulator/MainWindow.h | 2 +- extras/wrlview/MainWindow.cpp | 2 +- extras/wrlview/MainWindow.h | 4 ++-- src/rl/hal/SickS300.cpp | 2 +- src/rl/math/CircularVector2.h | 2 +- src/rl/math/CircularVector3.h | 2 +- src/rl/math/GnatNearestNeighbors.h | 2 +- src/rl/math/NestedFunction.h | 4 ++-- src/rl/plan/WorkspaceSphereExplorer.cpp | 2 +- src/rl/sg/XmlFactory.cpp | 2 +- src/rl/sg/fcl/Body.cpp | 2 +- src/rl/sg/ode/Shape.cpp | 2 +- tests/rlCollisionTest/rlCollisionTest.cpp | 2 +- tests/rlSplineTest/rlPolynomialTest.cpp | 2 +- 17 files changed, 19 insertions(+), 19 deletions(-) diff --git a/demos/rlCoachKin/MainWindow.h b/demos/rlCoachKin/MainWindow.h index 0dcecc6f..d585bcb2 100644 --- a/demos/rlCoachKin/MainWindow.h +++ b/demos/rlCoachKin/MainWindow.h @@ -67,7 +67,7 @@ class MainWindow : public QMainWindow public slots: void saveImageWithAlpha(); - + void saveImageWithoutAlpha(); void saveScene(); diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.h b/demos/rlPlanDemo/ConfigurationSpaceScene.h index 323adbbe..8bb9289c 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.h +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.h @@ -113,7 +113,7 @@ public slots: QGraphicsItemGroup* edges; QGraphicsItemGroup* path; - + QGraphicsRectItem* scene; ConfigurationSpaceThread* thread; diff --git a/demos/rlPlanDemo/Viewer.cpp b/demos/rlPlanDemo/Viewer.cpp index f6b21c99..05f95e3b 100644 --- a/demos/rlPlanDemo/Viewer.cpp +++ b/demos/rlPlanDemo/Viewer.cpp @@ -439,7 +439,7 @@ Viewer::Viewer(QWidget* parent, Qt::WindowFlags f) : this->root->addChild(this->vertices); // work - + this->work->setName("work"); this->work->whichChoice = SO_SWITCH_NONE; diff --git a/demos/rlSimulator/MainWindow.h b/demos/rlSimulator/MainWindow.h index f51ee38b..4ba57fe1 100644 --- a/demos/rlSimulator/MainWindow.h +++ b/demos/rlSimulator/MainWindow.h @@ -102,7 +102,7 @@ public slots: protected: MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); - + void timerEvent(QTimerEvent *event); private: diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index df5e2a29..f3934627 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -845,7 +845,7 @@ MainWindow::saveImage(bool withAlpha) { format = "JPEG"; } - + if (!image.save(filename, format.toStdString().c_str())) { QMessageBox::critical(this, "Error", "Error writing " + filename + "."); diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index db35594b..f17540c6 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -149,11 +149,11 @@ private slots: void replyFinished(QNetworkReply* reply); void saveImageOffscreenWithAlpha(); - + void saveImageOffscreenWithoutAlpha(); void saveImageWithAlpha(); - + void saveImageWithoutAlpha(); void selectBackground(QAction* action); diff --git a/src/rl/hal/SickS300.cpp b/src/rl/hal/SickS300.cpp index 676dcd93..d623e427 100644 --- a/src/rl/hal/SickS300.cpp +++ b/src/rl/hal/SickS300.cpp @@ -379,7 +379,7 @@ ::std::cout << "telegramNumber " << telegramNumber << ::std::endl; throw DeviceException("Checksum error"); } for (::std::size_t i = 0; i < sumbytes; ++i) { ::std::cout << hex(buf[i]) << " "; } ::std::cout << ::std::endl; - + return sumbytes; } diff --git a/src/rl/math/CircularVector2.h b/src/rl/math/CircularVector2.h index c39b605c..48feb8e5 100644 --- a/src/rl/math/CircularVector2.h +++ b/src/rl/math/CircularVector2.h @@ -165,7 +165,7 @@ namespace rl assert(derivative <= 2 && "Circular: higher derivatives not implemented"); Real c = this->angle / this->x1; - + if (derivative == 0) { return this->center + ::std::cos(c * x) * this->axisX + ::std::sin(c * x) * this->axisY; diff --git a/src/rl/math/CircularVector3.h b/src/rl/math/CircularVector3.h index dd28104c..9b355f26 100644 --- a/src/rl/math/CircularVector3.h +++ b/src/rl/math/CircularVector3.h @@ -171,7 +171,7 @@ namespace rl assert(derivative <= 2 && "Circular: higher derivatives not implemented"); Real c = this->angle / this->x1; - + if (derivative == 0) { return this->center + ::std::cos(c * x) * this->axisX + ::std::sin(c * x) * this->axisY; diff --git a/src/rl/math/GnatNearestNeighbors.h b/src/rl/math/GnatNearestNeighbors.h index ccf9b852..aa57065c 100644 --- a/src/rl/math/GnatNearestNeighbors.h +++ b/src/rl/math/GnatNearestNeighbors.h @@ -657,7 +657,7 @@ namespace rl node.data.clear(); node.data.shrink_to_fit(); - + #ifdef _OPENMP #pragma omp parallel for if (size > 2 * this->nodeDataMax) #if _OPENMP < 200805 diff --git a/src/rl/math/NestedFunction.h b/src/rl/math/NestedFunction.h index 2564ec8c..4c69b4db 100644 --- a/src/rl/math/NestedFunction.h +++ b/src/rl/math/NestedFunction.h @@ -60,7 +60,7 @@ namespace rl { return new NestedFunction(*this); } - + T operator()(const Real& x, const ::std::size_t& derivative = 0) const { switch (derivative) @@ -78,7 +78,7 @@ namespace rl } protected: - + private: const Function& inner; diff --git a/src/rl/plan/WorkspaceSphereExplorer.cpp b/src/rl/plan/WorkspaceSphereExplorer.cpp index efcfc3e5..f2b1ca84 100644 --- a/src/rl/plan/WorkspaceSphereExplorer.cpp +++ b/src/rl/plan/WorkspaceSphereExplorer.cpp @@ -107,7 +107,7 @@ namespace rl ); start.radiusSum = start.radius; start.parent = nullptr; - + start.priority = (*this->goal - *start.center).norm() - start.radius; this->queue.insert(start); diff --git a/src/rl/sg/XmlFactory.cpp b/src/rl/sg/XmlFactory.cpp index bc282d2f..f50879ba 100644 --- a/src/rl/sg/XmlFactory.cpp +++ b/src/rl/sg/XmlFactory.cpp @@ -62,7 +62,7 @@ namespace rl { this->load(filename, scene, false, false); } - + void XmlFactory::load(const ::std::string& filename, Scene* scene, const bool& doBoundingBoxPoints, const bool& doPoints) { diff --git a/src/rl/sg/fcl/Body.cpp b/src/rl/sg/fcl/Body.cpp index 20598119..de080d14 100644 --- a/src/rl/sg/fcl/Body.cpp +++ b/src/rl/sg/fcl/Body.cpp @@ -50,7 +50,7 @@ namespace rl { delete this->shapes[0]; } - + this->getModel()->remove(this); } diff --git a/src/rl/sg/ode/Shape.cpp b/src/rl/sg/ode/Shape.cpp index 5cce102b..6c3e5cfa 100644 --- a/src/rl/sg/ode/Shape.cpp +++ b/src/rl/sg/ode/Shape.cpp @@ -113,7 +113,7 @@ namespace rl } this->getBody()->add(this); - + this->setTransform(::rl::math::Transform::Identity()); } diff --git a/tests/rlCollisionTest/rlCollisionTest.cpp b/tests/rlCollisionTest/rlCollisionTest.cpp index da46df5b..21f95806 100644 --- a/tests/rlCollisionTest/rlCollisionTest.cpp +++ b/tests/rlCollisionTest/rlCollisionTest.cpp @@ -111,7 +111,7 @@ main(int argc, char** argv) std::size_t dof = kinematics->getDof(); rl::math::Vector q(kinematics->getDof()); - + for (std::size_t i = 0; i < kinematics->getDof(); ++i) { q(i) = boost::lexical_cast(argv[i + 3]) * rl::math::constants::deg2rad; diff --git a/tests/rlSplineTest/rlPolynomialTest.cpp b/tests/rlSplineTest/rlPolynomialTest.cpp index e14f09cc..8576ad9e 100644 --- a/tests/rlSplineTest/rlPolynomialTest.cpp +++ b/tests/rlSplineTest/rlPolynomialTest.cpp @@ -119,7 +119,7 @@ main(int argc, char** argv) return EXIT_FAILURE; } } - + std::cout << "rlPolynomialTest is ok." << std::endl; return EXIT_SUCCESS; } From f98def905b392e54f8f8f67784a686edd2ccaba4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 6 May 2022 16:26:35 +0200 Subject: [PATCH 494/546] Fix path --- examples/unimation-puma560.mdl.sg.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/unimation-puma560.mdl.sg.xml b/examples/unimation-puma560.mdl.sg.xml index c8e442fc..0d29d129 100644 --- a/examples/unimation-puma560.mdl.sg.xml +++ b/examples/unimation-puma560.mdl.sg.xml @@ -4,6 +4,6 @@ - + From d183fba4b9337b1ff6b13472da1a5a65ee243c07 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 14 May 2022 19:31:22 +0200 Subject: [PATCH 495/546] Update GitHub Actions --- .github/workflows/ci.yml | 6 +++--- .github/workflows/codeql.yml | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index bfce0e6c..48805b37 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -49,7 +49,7 @@ jobs: CXX: ${{ matrix.cxx }} steps: - name: Checkout repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 - if: matrix.os == 'macos-11' name: Set up Tap run: brew tap roboticslibrary/rl @@ -147,7 +147,7 @@ jobs: Write-Output "CCACHE_DIR=${{ runner.workspace }}\.ccache" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append - if: matrix.cmake_compiler_launcher != '' name: Cache compiler - uses: actions/cache@v2 + uses: actions/cache@v3 with: path: ${{ runner.workspace }}/.ccache key: ${{ matrix.name }}-ccache-${{ github.sha }} @@ -169,7 +169,7 @@ jobs: working-directory: ${{ runner.workspace }}/rl-build run: cpack -G 7Z - name: Upload artifacts - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v3 with: name: ${{ matrix.name }} path: ${{ runner.workspace }}/rl-build/rl-*.7z diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index 85b659cd..8bea162c 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -14,7 +14,7 @@ jobs: runs-on: ubuntu-20.04 steps: - name: Checkout repository - uses: actions/checkout@v2 + uses: actions/checkout@v3 - name: Set up PPA run: | sudo apt-get install -y software-properties-common @@ -40,7 +40,7 @@ jobs: libxslt1-dev ninja-build - name: Initialize CodeQL - uses: github/codeql-action/init@v1 + uses: github/codeql-action/init@v2 with: languages: cpp - name: Configure CMake @@ -54,4 +54,4 @@ jobs: working-directory: ${{ runner.workspace }}/rl-build run: cmake --build . - name: Perform CodeQL analysis - uses: github/codeql-action/analyze@v1 + uses: github/codeql-action/analyze@v2 From 1d08e04ae07cba89d8ab0f69beb6ef29e1bb3f61 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 15 May 2022 17:06:36 +0200 Subject: [PATCH 496/546] Cache DOF values --- src/rl/mdl/Model.cpp | 40 ++++++++++++++++++---------------------- src/rl/mdl/Model.h | 4 ++++ 2 files changed, 22 insertions(+), 22 deletions(-) diff --git a/src/rl/mdl/Model.cpp b/src/rl/mdl/Model.cpp index 1ae62ad6..248f6340 100644 --- a/src/rl/mdl/Model.cpp +++ b/src/rl/mdl/Model.cpp @@ -36,6 +36,8 @@ namespace rl { Model::Model() : bodies(), + dof(), + dofPosition(), elements(), frames(), gammaPosition(), @@ -244,27 +246,13 @@ namespace rl ::std::size_t Model::getDof() const { - ::std::size_t dof = 0; - - for (::std::size_t i = 0; i < this->joints.size(); ++i) - { - dof += this->joints[i]->getDof(); - } - - return dof; + return this->dof; } ::std::size_t Model::getDofPosition() const { - ::std::size_t dof = 0; - - for (::std::size_t i = 0; i < this->joints.size(); ++i) - { - dof += this->joints[i]->getDofPosition(); - } - - return dof; + return this->dofPosition; } Frame* @@ -740,6 +728,8 @@ namespace rl Model::update() { this->bodies.clear(); + this->dof = 0; + this->dofPosition = 0; this->elements.clear(); this->joints.clear(); this->leaves.clear(); @@ -747,6 +737,18 @@ namespace rl this->transforms.clear(); this->update(this->root); + + for (::std::size_t i = 0; i < this->joints.size(); ++i) + { + this->dof += this->joints[i]->getDof(); + this->dofPosition += this->joints[i]->getDofPosition(); + } + + this->gammaPosition = ::rl::math::Matrix::Identity(this->getDofPosition(), this->getDofPosition()); + this->gammaVelocity = ::rl::math::Matrix::Identity(this->getDof(), this->getDof()); + this->home = ::rl::math::Vector::Zero(this->getDofPosition()); + this->invGammaPosition = ::rl::math::Matrix::Identity(this->getDofPosition(), this->getDofPosition()); + this->invGammaVelocity = ::rl::math::Matrix::Identity(this->getDof(), this->getDof()); } void @@ -791,12 +793,6 @@ namespace rl this->tools.push_back(*i.first); } } - - this->gammaPosition = ::rl::math::Matrix::Identity(this->getDofPosition(), this->getDofPosition()); - this->gammaVelocity = ::rl::math::Matrix::Identity(this->getDof(), this->getDof()); - this->home = ::rl::math::Vector::Zero(this->getDofPosition()); - this->invGammaPosition = ::rl::math::Matrix::Identity(this->getDofPosition(), this->getDofPosition()); - this->invGammaVelocity = ::rl::math::Matrix::Identity(this->getDof(), this->getDof()); } ::rl::math::Transform& diff --git a/src/rl/mdl/Model.h b/src/rl/mdl/Model.h index 0eae70cd..bc0d00d0 100644 --- a/src/rl/mdl/Model.h +++ b/src/rl/mdl/Model.h @@ -241,6 +241,10 @@ namespace rl ::std::vector bodies; + ::std::size_t dof; + + ::std::size_t dofPosition; + ::std::vector elements; ::std::vector frames; From 430c7b28ed95df85e7a8f833bddac19f04d1faef Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 15 May 2022 19:07:32 +0200 Subject: [PATCH 497/546] Add command-line argument for benchmark filename --- demos/rlPlanDemo/MainWindow.cpp | 14 ++- demos/rlPlanDemo/Thread.cpp | 217 ++++++++++++++++---------------- demos/rlPlanDemo/Thread.h | 2 + 3 files changed, 125 insertions(+), 108 deletions(-) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 8fa71a16..1c036b2c 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -2160,6 +2160,7 @@ MainWindow::parseCommandLine() #if QT_VERSION >= 0x050200 QCommandLineOption backgroundOption(QStringList("background"), "Sets background color of 3D viewer.", "color"); + QCommandLineOption benchmarkOption(QStringList("benchmark"), "Save benchmark statistics in file.", "filename"); QCommandLineOption disableViewerOption(QStringList("disable-viewer"), "Disables viewer during planning."); QCommandLineOption disableWaitOption(QStringList("disable-wait"), "Disables wait before planning."); QCommandLineOption enableQuitOption(QStringList("enable-quit"), "Exits after planning."); @@ -2170,6 +2171,7 @@ MainWindow::parseCommandLine() QCommandLineParser parser; parser.addOption(backgroundOption); + parser.addOption(benchmarkOption); parser.addOption(disableViewerOption); parser.addOption(disableWaitOption); parser.addOption(enableQuitOption); @@ -2194,6 +2196,11 @@ MainWindow::parseCommandLine() this->viewer->setBackgroundColor(QColor(background)); } + if (parser.isSet(benchmarkOption)) + { + this->thread->benchmark = parser.value(benchmarkOption).toStdString(); + } + if (parser.isSet(disableViewerOption)) { QObject::disconnect(this->toggleViewActiveAction, SIGNAL(toggled(bool)), this, SLOT(toggleViewActive(bool))); @@ -2271,6 +2278,7 @@ MainWindow::parseCommandLine() } #else QRegExp backgroundRegExp("--background=(\\S*)"); + QRegExp benchmarkRegExp("--benchmark=([\\s\\S]*)"); QRegExp engineRegExp("--engine=(" + engines.join("|") + ")"); QRegExp helpRegExp("--help"); QRegExp heightRegExp("--height=(\\d*)"); @@ -2286,13 +2294,17 @@ MainWindow::parseCommandLine() { this->viewer->setBackgroundColor(backgroundRegExp.cap(1)); } + else if (-1 != benchmarkRegExp.indexIn(QApplication::arguments()[i])) + { + this->thread->benchmark = benchmarkRegExp.cap(1).toStdString(); + } else if (-1 != engineRegExp.indexIn(QApplication::arguments()[i])) { this->engine = engineRegExp.cap(1); } else if (-1 != helpRegExp.indexIn(QApplication::arguments()[i])) { - QMessageBox::information(this, "Usage", "rlPlanDemo [--background=] [--disable-viewer] [--disable-wait] [--enable-quit] [--engine=<" + engines.join("|") + ">] [--height=] [--help] [--seed=] [--width=] [filename]"); + QMessageBox::information(this, "Usage", "rlPlanDemo [--background=] [--benchmark=] [--disable-viewer] [--disable-wait] [--enable-quit] [--engine=<" + engines.join("|") + ">] [--height=] [--help] [--seed=] [--width=] [filename]"); exit(EXIT_SUCCESS); } else if (-1 != heightRegExp.indexIn(QApplication::arguments()[i])) diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index 0e7d29ca..0f16c7c2 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -44,6 +44,7 @@ Thread::Thread(QObject* parent) : QThread(parent), animate(true), + benchmark(), quit(false), swept(false), running(false) @@ -202,137 +203,139 @@ Thread::run() emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration * 1000) + " ms."); - std::fstream benchmark; - benchmark.open("benchmark.csv", std::ios::app | std::ios::in | std::ios::out); - int peek = benchmark.peek(); + rl::plan::VectorList path; - if (std::ifstream::traits_type::eof() == peek) - { - benchmark.clear(); - benchmark << "Date,Time,Solved,Engine,Planner,Robot,Nearest Neighbors,Vertices,Edges,Total CD,Free CD,Exploration Duration (s),Duration (s), Path Length" << std::endl; - } - else + if (solved) { - benchmark.seekp(peek); + path = MainWindow::instance()->planner->getPath(); } - benchmark << QDateTime::currentDateTime().toString("yyyy-MM-dd,HH:mm:ss.zzz").toStdString(); - benchmark << ","; - benchmark << (solved ? "true" : "false"); - benchmark << ","; - benchmark << MainWindow::instance()->engine.toUpper().toStdString(); - benchmark << ","; - benchmark << MainWindow::instance()->planner->getName(); - benchmark << ","; - benchmark << MainWindow::instance()->model->getManufacturer(); - benchmark << (!MainWindow::instance()->model->getManufacturer().empty() && !MainWindow::instance()->model->getName().empty() ? " " : ""); - benchmark << MainWindow::instance()->model->getName(); - benchmark << ","; - - if (!MainWindow::instance()->nearestNeighbors.empty()) + if (!this->benchmark.empty()) { - if (rl::plan::GnatNearestNeighbors* gnatNearestNeighbors = dynamic_cast(MainWindow::instance()->nearestNeighbors.front().get())) + std::fstream benchmark; + benchmark.open(this->benchmark, std::ios::app | std::ios::in | std::ios::out); + int peek = benchmark.peek(); + + if (std::ifstream::traits_type::eof() == peek) { - benchmark << "GNAT"; - - boost::optional checks = gnatNearestNeighbors->getChecks(); - - if (checks) - { - benchmark << " (" << checks.get() << " Checks)"; - } + benchmark.clear(); + benchmark << "Date,Time,Solved,Engine,Planner,Robot,Nearest Neighbors,Vertices,Edges,Total CD,Free CD,Exploration Duration (s),Duration (s),Path Length" << std::endl; } - else if (rl::plan::KdtreeBoundingBoxNearestNeighbors* kdtreeBoundingBoxNearestNeighbors = dynamic_cast(MainWindow::instance()->nearestNeighbors.front().get())) + else { - benchmark << "k-d Tree Bounding Box"; - - boost::optional checks = kdtreeBoundingBoxNearestNeighbors->getChecks(); - - if (checks) - { - benchmark << " (" << checks.get() << " Checks)"; - } + benchmark.seekp(peek); } - else if (rl::plan::KdtreeNearestNeighbors* kdtreeNearestNeighbors = dynamic_cast(MainWindow::instance()->nearestNeighbors.front().get())) + + benchmark << QDateTime::currentDateTime().toString("yyyy-MM-dd,HH:mm:ss.zzz").toStdString(); + benchmark << ","; + benchmark << (solved ? "true" : "false"); + benchmark << ","; + benchmark << MainWindow::instance()->engine.toUpper().toStdString(); + benchmark << ","; + benchmark << MainWindow::instance()->planner->getName(); + benchmark << ","; + benchmark << MainWindow::instance()->model->getManufacturer(); + benchmark << (!MainWindow::instance()->model->getManufacturer().empty() && !MainWindow::instance()->model->getName().empty() ? " " : ""); + benchmark << MainWindow::instance()->model->getName(); + benchmark << ","; + + if (!MainWindow::instance()->nearestNeighbors.empty()) { - benchmark << "k-d Tree"; - - boost::optional checks = kdtreeNearestNeighbors->getChecks(); - - if (checks) + if (rl::plan::GnatNearestNeighbors* gnatNearestNeighbors = dynamic_cast(MainWindow::instance()->nearestNeighbors.front().get())) { - benchmark << " (" << checks.get() << " Checks)"; + benchmark << "GNAT"; + boost::optional checks = gnatNearestNeighbors->getChecks(); + + if (checks) + { + benchmark << " (" << checks.get() << " Checks)"; + } + } + else if (rl::plan::KdtreeBoundingBoxNearestNeighbors* kdtreeBoundingBoxNearestNeighbors = dynamic_cast(MainWindow::instance()->nearestNeighbors.front().get())) + { + benchmark << "k-d Tree Bounding Box"; + boost::optional checks = kdtreeBoundingBoxNearestNeighbors->getChecks(); + + if (checks) + { + benchmark << " (" << checks.get() << " Checks)"; + } + } + else if (rl::plan::KdtreeNearestNeighbors* kdtreeNearestNeighbors = dynamic_cast(MainWindow::instance()->nearestNeighbors.front().get())) + { + benchmark << "k-d Tree"; + boost::optional checks = kdtreeNearestNeighbors->getChecks(); + + if (checks) + { + benchmark << " (" << checks.get() << " Checks)"; + } + } + else if (rl::plan::LinearNearestNeighbors* linearNearestNeighbors = dynamic_cast(MainWindow::instance()->nearestNeighbors.front().get())) + { + benchmark << "Linear"; } } - else if (rl::plan::LinearNearestNeighbors* linearNearestNeighbors = dynamic_cast(MainWindow::instance()->nearestNeighbors.front().get())) + + benchmark << ","; + + if (rl::plan::Prm* prm = dynamic_cast(MainWindow::instance()->planner.get())) { - benchmark << "Linear"; + benchmark << prm->getNumVertices(); + } + else if (rl::plan::Rrt* rrt = dynamic_cast(MainWindow::instance()->planner.get())) + { + benchmark << rrt->getNumVertices(); } - } - - benchmark << ","; - - if (rl::plan::Prm* prm = dynamic_cast(MainWindow::instance()->planner.get())) - { - benchmark << prm->getNumVertices(); - } - else if (rl::plan::Rrt* rrt = dynamic_cast(MainWindow::instance()->planner.get())) - { - benchmark << rrt->getNumVertices(); - } - - benchmark << ","; - - if (rl::plan::Prm* prm = dynamic_cast(MainWindow::instance()->planner.get())) - { - benchmark << prm->getNumEdges(); - } - else if (rl::plan::Rrt* rrt = dynamic_cast(MainWindow::instance()->planner.get())) - { - benchmark << rrt->getNumEdges(); - } - - benchmark << ","; - benchmark << MainWindow::instance()->model->getTotalQueries(); - benchmark << ","; - benchmark << MainWindow::instance()->model->getFreeQueries(); - benchmark << ","; - - if (rl::plan::Eet* eet = dynamic_cast(MainWindow::instance()->planner.get())) - { - benchmark << std::chrono::duration_cast>(eet->getExplorationDuration()).count(); - } - else - { - benchmark << 0; - } - - benchmark << ","; - benchmark << plannerDuration; - - rl::plan::VectorList path; - - if (solved) - { - path = MainWindow::instance()->planner->getPath(); - rl::plan::VectorList::iterator i = path.begin(); - rl::plan::VectorList::iterator j = ++path.begin(); + benchmark << ","; - rl::math::Real length = 0; + if (rl::plan::Prm* prm = dynamic_cast(MainWindow::instance()->planner.get())) + { + benchmark << prm->getNumEdges(); + } + else if (rl::plan::Rrt* rrt = dynamic_cast(MainWindow::instance()->planner.get())) + { + benchmark << rrt->getNumEdges(); + } + + benchmark << ","; + benchmark << MainWindow::instance()->model->getTotalQueries(); + benchmark << ","; + benchmark << MainWindow::instance()->model->getFreeQueries(); + benchmark << ","; - for (; i != path.end() && j != path.end(); ++i, ++j) + if (rl::plan::Eet* eet = dynamic_cast(MainWindow::instance()->planner.get())) + { + benchmark << std::chrono::duration_cast>(eet->getExplorationDuration()).count(); + } + else { - length += MainWindow::instance()->model->distance(*i, *j); + benchmark << 0; } benchmark << ","; - benchmark << length; + benchmark << plannerDuration; + benchmark << ","; + + if (solved) + { + rl::math::Real length = 0; + rl::plan::VectorList::iterator i = path.begin(); + rl::plan::VectorList::iterator j = ++path.begin(); + + for (; i != path.end() && j != path.end(); ++i, ++j) + { + length += MainWindow::instance()->model->distance(*i, *j); + } + + benchmark << length; + } + + benchmark << std::endl; + benchmark.close(); } - benchmark << std::endl; - benchmark.close(); - if (!this->running) return; if (this->quit) diff --git a/demos/rlPlanDemo/Thread.h b/demos/rlPlanDemo/Thread.h index bb4d9a0b..716c7224 100644 --- a/demos/rlPlanDemo/Thread.h +++ b/demos/rlPlanDemo/Thread.h @@ -83,6 +83,8 @@ class Thread : public QThread, public rl::plan::Viewer bool animate; + std::string benchmark; + bool quit; bool swept; From e5fef8aefe6f430c8e8cc83b10b3b2a36349357b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 13:52:04 +0200 Subject: [PATCH 498/546] Update actions --- demos/rlPlanDemo/MainWindow.cpp | 49 ++------------------------------- demos/rlPlanDemo/MainWindow.h | 8 ------ 2 files changed, 2 insertions(+), 55 deletions(-) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 1c036b2c..47b0cf91 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -180,16 +180,12 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : startThreadAction(new QAction(this)), toggleAnimationAction(new QAction(this)), toggleCameraAction(new QAction(this)), - toggleConfigurationAction(new QAction(this)), toggleConfigurationEdgesAction(new QAction(this)), - toggleConfigurationSpaceAction(new QAction(this)), toggleConfigurationSpaceActiveAction(new QAction(this)), - toggleConfigurationSpaceSceneAction(new QAction(this)), toggleConfigurationVerticesAction(new QAction(this)), toggleLinesAction(new QAction(this)), togglePathEdgesAction(new QAction(this)), togglePathVerticesAction(new QAction(this)), - togglePlannerAction(new QAction(this)), togglePointsAction(new QAction(this)), toggleSpheresAction(new QAction(this)), toggleSweptVolumeAction(new QAction(this)), @@ -598,19 +594,10 @@ MainWindow::init() this->exitAction->setText("Exit"); QObject::connect(this->exitAction, SIGNAL(triggered()), qApp, SLOT(quit())); - this->addAction(this->exitAction); fileMenu->addAction(this->exitAction); QMenu* configurationMenu = this->menuBar()->addMenu("Configuration"); - this->toggleConfigurationAction->setText("Parameters"); - this->toggleConfigurationAction->setShortcut(QKeySequence("F5")); - QObject::connect(this->toggleConfigurationAction, SIGNAL(triggered()), this, SLOT(toggleConfiguration())); - this->addAction(this->toggleConfigurationAction); - configurationMenu->addAction(this->toggleConfigurationAction); - - configurationMenu->addSeparator(); - this->getRandomConfigurationAction->setText("Random"); this->getRandomConfigurationAction->setShortcut(QKeySequence("F3")); QObject::connect(this->getRandomConfigurationAction, SIGNAL(triggered()), this, SLOT(getRandomConfiguration())); @@ -625,25 +612,10 @@ MainWindow::init() QMenu* configurationSpaceMenu = this->menuBar()->addMenu("Configuration Space"); - this->toggleConfigurationSpaceAction->setText("Parameters"); - this->toggleConfigurationSpaceAction->setShortcut(QKeySequence("F6")); - QObject::connect(this->toggleConfigurationSpaceAction, SIGNAL(triggered()), this, SLOT(toggleConfigurationSpace())); - this->addAction(this->toggleConfigurationSpaceAction); - configurationSpaceMenu->addAction(this->toggleConfigurationSpaceAction); - - this->toggleConfigurationSpaceSceneAction->setText("Visualization"); - this->toggleConfigurationSpaceSceneAction->setShortcut(QKeySequence("F10")); - QObject::connect(this->toggleConfigurationSpaceSceneAction, SIGNAL(triggered()), this, SLOT(toggleConfigurationSpaceScene())); - this->addAction(this->toggleConfigurationSpaceSceneAction); - configurationSpaceMenu->addAction(this->toggleConfigurationSpaceSceneAction); - - configurationSpaceMenu->addSeparator(); - this->toggleConfigurationSpaceActiveAction->setCheckable(true); this->toggleConfigurationSpaceActiveAction->setChecked(false); this->toggleConfigurationSpaceActiveAction->setText("Active"); QObject::connect(this->toggleConfigurationSpaceActiveAction, SIGNAL(toggled(bool)), this, SLOT(toggleConfigurationSpaceActive(bool))); - this->addAction(this->toggleConfigurationSpaceActiveAction); configurationSpaceMenu->addAction(this->toggleConfigurationSpaceActiveAction); configurationSpaceMenu->addSeparator(); @@ -656,14 +628,6 @@ MainWindow::init() QMenu* plannerMenu = this->menuBar()->addMenu("Planner"); - this->togglePlannerAction->setText("Parameters"); - this->togglePlannerAction->setShortcut(QKeySequence("F7")); - QObject::connect(this->togglePlannerAction, SIGNAL(triggered()), this, SLOT(togglePlanner())); - this->addAction(this->togglePlannerAction); - plannerMenu->addAction(this->togglePlannerAction); - - plannerMenu->addSeparator(); - this->getStartConfigurationAction->setText("Get Start Configuration"); this->getStartConfigurationAction->setShortcut(QKeySequence("F1")); QObject::connect(this->getStartConfigurationAction, SIGNAL(triggered()), this, SLOT(getStartConfiguration())); @@ -710,7 +674,6 @@ MainWindow::init() this->toggleViewActiveAction->setChecked(true); this->toggleViewActiveAction->setText("Active"); QObject::connect(this->toggleViewActiveAction, SIGNAL(toggled(bool)), this, SLOT(toggleViewActive(bool))); - this->addAction(this->toggleViewActiveAction); viewMenu->addAction(this->toggleViewActiveAction); viewMenu->addSeparator(); @@ -719,21 +682,18 @@ MainWindow::init() this->togglePathEdgesAction->setChecked(true); this->togglePathEdgesAction->setText("Path Edges"); QObject::connect(this->togglePathEdgesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(togglePathEdges(bool))); - this->addAction(this->togglePathEdgesAction); viewMenu->addAction(this->togglePathEdgesAction); this->togglePathVerticesAction->setCheckable(true); this->togglePathVerticesAction->setChecked(false); this->togglePathVerticesAction->setText("Path Vertices"); QObject::connect(this->togglePathVerticesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(togglePathVertices(bool))); - this->addAction(this->togglePathVerticesAction); viewMenu->addAction(this->togglePathVerticesAction); this->toggleAnimationAction->setCheckable(true); this->toggleAnimationAction->setChecked(true); this->toggleAnimationAction->setText("Animation"); QObject::connect(this->toggleAnimationAction, SIGNAL(toggled(bool)), this, SLOT(toggleAnimation(bool))); - this->addAction(this->toggleAnimationAction); viewMenu->addAction(this->toggleAnimationAction); this->toggleSweptVolumeAction->setCheckable(true); @@ -741,23 +701,22 @@ MainWindow::init() this->toggleSweptVolumeAction->setText("Swept Volume"); QObject::connect(this->toggleSweptVolumeAction, SIGNAL(toggled(bool)), this, SLOT(toggleSweptVolume(bool))); QObject::connect(this->toggleSweptVolumeAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleSweptVolume(bool))); - this->addAction(this->toggleSweptVolumeAction); viewMenu->addAction(this->toggleSweptVolumeAction); viewMenu->addSeparator(); this->toggleConfigurationEdgesAction->setCheckable(true); this->toggleConfigurationEdgesAction->setChecked(true); + this->toggleConfigurationEdgesAction->setMenuRole(QAction::NoRole); this->toggleConfigurationEdgesAction->setText("Configuration Edges"); QObject::connect(this->toggleConfigurationEdgesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleConfigurationEdges(bool))); - this->addAction(this->toggleConfigurationEdgesAction); viewMenu->addAction(this->toggleConfigurationEdgesAction); this->toggleConfigurationVerticesAction->setCheckable(true); this->toggleConfigurationVerticesAction->setChecked(false); + this->toggleConfigurationVerticesAction->setMenuRole(QAction::NoRole); this->toggleConfigurationVerticesAction->setText("Configuration Vertices"); QObject::connect(this->toggleConfigurationVerticesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleConfigurationVertices(bool))); - this->addAction(this->toggleConfigurationVerticesAction); viewMenu->addAction(this->toggleConfigurationVerticesAction); viewMenu->addSeparator(); @@ -766,7 +725,6 @@ MainWindow::init() this->toggleWorkFramesAction->setChecked(false); this->toggleWorkFramesAction->setText("Work Frames"); QObject::connect(this->toggleWorkFramesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleWorkFrames(bool))); - this->addAction(this->toggleWorkFramesAction); viewMenu->addAction(this->toggleWorkFramesAction); viewMenu->addSeparator(); @@ -775,21 +733,18 @@ MainWindow::init() this->toggleLinesAction->setChecked(true); this->toggleLinesAction->setText("Lines"); QObject::connect(this->toggleLinesAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleLines(bool))); - this->addAction(this->toggleLinesAction); viewMenu->addAction(this->toggleLinesAction); this->togglePointsAction->setCheckable(true); this->togglePointsAction->setChecked(true); this->togglePointsAction->setText("Points"); QObject::connect(this->togglePointsAction, SIGNAL(toggled(bool)), this->viewer, SLOT(togglePoints(bool))); - this->addAction(this->togglePointsAction); viewMenu->addAction(this->togglePointsAction); this->toggleSpheresAction->setCheckable(true); this->toggleSpheresAction->setChecked(true); this->toggleSpheresAction->setText("Spheres"); QObject::connect(this->toggleSpheresAction, SIGNAL(toggled(bool)), this->viewer, SLOT(toggleSpheres(bool))); - this->addAction(this->toggleSpheresAction); viewMenu->addAction(this->toggleSpheresAction); viewMenu->addSeparator(); diff --git a/demos/rlPlanDemo/MainWindow.h b/demos/rlPlanDemo/MainWindow.h index 73d58ee4..e5994973 100644 --- a/demos/rlPlanDemo/MainWindow.h +++ b/demos/rlPlanDemo/MainWindow.h @@ -253,16 +253,10 @@ public slots: QAction* toggleCameraAction; - QAction* toggleConfigurationAction; - QAction* toggleConfigurationEdgesAction; - QAction* toggleConfigurationSpaceAction; - QAction* toggleConfigurationSpaceActiveAction; - QAction* toggleConfigurationSpaceSceneAction; - QAction* toggleConfigurationVerticesAction; QAction* toggleLinesAction; @@ -271,8 +265,6 @@ public slots: QAction* togglePathVerticesAction; - QAction* togglePlannerAction; - QAction* togglePointsAction; QAction* toggleSpheresAction; From 2764424364974214a76bc2cb0bc0f4dd689acb80 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 14:23:55 +0200 Subject: [PATCH 499/546] Update configuration space members --- demos/rlPlanDemo/ConfigurationSpaceModel.cpp | 18 ++--- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 74 +++++++++++-------- demos/rlPlanDemo/ConfigurationSpaceScene.h | 12 ++- demos/rlPlanDemo/ConfigurationSpaceThread.cpp | 42 ++++------- demos/rlPlanDemo/ConfigurationSpaceThread.h | 13 +--- 5 files changed, 79 insertions(+), 80 deletions(-) diff --git a/demos/rlPlanDemo/ConfigurationSpaceModel.cpp b/demos/rlPlanDemo/ConfigurationSpaceModel.cpp index e33ff5a8..5dc2ffa8 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceModel.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceModel.cpp @@ -71,16 +71,16 @@ ConfigurationSpaceModel::data(const QModelIndex& index, int role) const switch (index.row()) { case 0: - return static_cast(this->configurationSpaceScene->axis0); + return static_cast(this->configurationSpaceScene->axis[0]); break; case 1: - return static_cast(this->configurationSpaceScene->axis1); + return static_cast(this->configurationSpaceScene->axis[1]); break; case 2: - return this->configurationSpaceScene->delta0; + return this->configurationSpaceScene->delta[0]; break; case 3: - return this->configurationSpaceScene->delta1; + return this->configurationSpaceScene->delta[1]; break; default: break; @@ -160,11 +160,11 @@ ConfigurationSpaceModel::rowCount(const QModelIndex& parent) const return 0; } - if (nullptr == this->configurationSpaceScene->model) { return 0; } + return 4; } @@ -193,7 +193,7 @@ ConfigurationSpaceModel::setData(const QModelIndex& index, const QVariant& value case 0: if (value.value() < this->configurationSpaceScene->model->getDofPosition()) { - this->configurationSpaceScene->axis0 = value.value(); + this->configurationSpaceScene->axis[0] = value.value(); } else { @@ -203,7 +203,7 @@ ConfigurationSpaceModel::setData(const QModelIndex& index, const QVariant& value case 1: if (value.value() < this->configurationSpaceScene->model->getDofPosition()) { - this->configurationSpaceScene->axis1 = value.value(); + this->configurationSpaceScene->axis[1] = value.value(); } else { @@ -213,7 +213,7 @@ ConfigurationSpaceModel::setData(const QModelIndex& index, const QVariant& value case 2: if (value.value() > 0) { - this->configurationSpaceScene->delta0 = value.value(); + this->configurationSpaceScene->delta[0] = value.value(); } else { @@ -223,7 +223,7 @@ ConfigurationSpaceModel::setData(const QModelIndex& index, const QVariant& value case 3: if (value.value() > 0) { - this->configurationSpaceScene->delta1 = value.value(); + this->configurationSpaceScene->delta[1] = value.value(); } else { diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 2ab61dd9..9e29c2ab 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -36,17 +36,26 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : QGraphicsScene(parent), - axis0(0), - axis1(1), - delta0(1), - delta1(1), + axis(), + delta(), + maximum(), + minimum(), model(nullptr), + range(), + steps(), collisions(nullptr), edges(nullptr), path(nullptr), scene(nullptr), thread(new ConfigurationSpaceThread(this)) { + this->axis[0] = 0; + this->axis[1] = 1; + this->delta[0] = 1; + this->delta[1] = 1; + + this->thread->scene = this; + QObject::connect( this->thread, SIGNAL(addCollision(const qreal&, const qreal&, const qreal&, const qreal&, const int&)), @@ -96,10 +105,10 @@ void ConfigurationSpaceScene::drawConfigurationEdge(const rl::math::Vector& u, const rl::math::Vector& v, const bool& free) { QGraphicsLineItem* line = this->addLine( - u(this->axis0), - -u(this->axis1), - v(this->axis0), - -v(this->axis1), + u(this->axis[0]), + -u(this->axis[1]), + v(this->axis[0]), + -v(this->axis[1]), free ? QPen(QBrush(QColor(0, 128, 0)), 0) : QPen(QBrush(QColor(128, 0, 0)), 0) ); @@ -122,10 +131,10 @@ ConfigurationSpaceScene::drawConfigurationPath(const rl::plan::VectorList& path) for (; i != path.end() && j != path.end(); ++i, ++j) { QGraphicsLineItem* line = this->addLine( - (*i)(this->axis0), - -(*i)(this->axis1), - (*j)(this->axis0), - -(*j)(this->axis1), + (*i)(this->axis[0]), + -(*i)(this->axis[1]), + (*j)(this->axis[0]), + -(*j)(this->axis[1]), QPen(QBrush(QColor(0, 255, 0)), 0) ); @@ -186,12 +195,6 @@ ConfigurationSpaceScene::eval() return; } - this->thread->axis0 = this->axis0; - this->thread->axis1 = this->axis1; - this->thread->delta0 = this->delta0; - this->thread->delta1 = this->delta1; - this->thread->model = this->model; - this->thread->start(); } @@ -213,11 +216,23 @@ ConfigurationSpaceScene::init() rl::math::Vector maximum = this->model->getMaximum(); rl::math::Vector minimum = this->model->getMinimum(); + this->maximum[0] = maximum(this->axis[0]); + this->maximum[1] = maximum(this->axis[1]); + + this->minimum[0] = minimum(this->axis[0]); + this->minimum[1] = minimum(this->axis[1]); + + this->range[0] = std::abs(this->maximum[0] - this->minimum[0]); + this->range[1] = std::abs(this->maximum[1] - this->minimum[1]); + + this->steps[0] = static_cast(std::ceil(this->range[0] / this->delta[0])); + this->steps[1] = static_cast(std::ceil(this->range[1] / this->delta[1])); + this->scene = this->addRect( - minimum(this->axis0), - -maximum(this->axis1), - std::abs(maximum(this->axis0) - minimum(this->axis0)), - std::abs(maximum(this->axis1) - minimum(this->axis1)), + this->minimum[0], + -this->maximum[1], + this->range[0], + this->range[1], QPen(Qt::NoPen), QBrush(Qt::white) ); @@ -260,19 +275,16 @@ ConfigurationSpaceScene::mousePressEvent(QGraphicsSceneMouseEvent* mouseEvent) { if (!MainWindow::instance()->thread->isRunning()) { - rl::math::Vector maximum = this->model->getMaximum(); - rl::math::Vector minimum = this->model->getMinimum(); - - if (mouseEvent->scenePos().x() > minimum(this->axis0) && - mouseEvent->scenePos().x() < maximum(this->axis0)) + if (mouseEvent->scenePos().x() > this->minimum[0] && + mouseEvent->scenePos().x() < this->maximum[0]) { - (*MainWindow::instance()->q)(this->axis0) = mouseEvent->scenePos().x(); + (*MainWindow::instance()->q)(this->axis[0]) = mouseEvent->scenePos().x(); } - if (-mouseEvent->scenePos().y() > minimum(this->axis1) && - -mouseEvent->scenePos().y() < maximum(this->axis1)) + if (-mouseEvent->scenePos().y() > this->minimum[1] && + -mouseEvent->scenePos().y() < this->maximum[1]) { - (*MainWindow::instance()->q)(this->axis1) = -mouseEvent->scenePos().y(); + (*MainWindow::instance()->q)(this->axis[1]) = -mouseEvent->scenePos().y(); } MainWindow::instance()->configurationModel->invalidate(); diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.h b/demos/rlPlanDemo/ConfigurationSpaceScene.h index 8bb9289c..c9d999ee 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.h +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.h @@ -43,16 +43,20 @@ class ConfigurationSpaceScene : public QGraphicsScene, public rl::plan::Viewer virtual ~ConfigurationSpaceScene(); - std::size_t axis0; + std::array axis; - std::size_t axis1; + std::array delta; - rl::math::Real delta0; + std::array maximum; - rl::math::Real delta1; + std::array minimum; rl::plan::Model* model; + std::array range; + + std::array steps; + public slots: void addCollision(const qreal& x, const qreal& y, const qreal& w, const qreal& h, const int& rgb); diff --git a/demos/rlPlanDemo/ConfigurationSpaceThread.cpp b/demos/rlPlanDemo/ConfigurationSpaceThread.cpp index 48a93a59..2b5421ad 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceThread.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceThread.cpp @@ -27,16 +27,13 @@ #include #include +#include "ConfigurationSpaceScene.h" #include "ConfigurationSpaceThread.h" #include "MainWindow.h" ConfigurationSpaceThread::ConfigurationSpaceThread(QObject* parent) : QThread(parent), - axis0(0), - axis1(1), - delta0(1), - delta1(1), - model(nullptr), + scene(nullptr), running(false) { } @@ -48,41 +45,34 @@ ConfigurationSpaceThread::~ConfigurationSpaceThread() void ConfigurationSpaceThread::run() { + if (nullptr == this->scene) + { + return; + } + QMutexLocker lock(&MainWindow::instance()->mutex); this->running = true; - if (rl::plan::SimpleModel* model = dynamic_cast(this->model)) + if (rl::plan::SimpleModel* model = dynamic_cast(this->scene->model)) { - rl::math::Vector maximum = model->getMaximum(); - rl::math::Vector minimum = model->getMinimum(); - - rl::math::Real range0 = std::abs(maximum(this->axis0) - minimum(this->axis0)); - rl::math::Real range1 = std::abs(maximum(this->axis1) - minimum(this->axis1)); - - rl::math::Real delta0 = range0 / std::ceil(range0 / this->delta0); - rl::math::Real delta1 = range1 / std::ceil(range1 / this->delta1); - - std::size_t steps0 = static_cast(std::ceil(range0 / delta0)); - std::size_t steps1 = static_cast(std::ceil(range1 / delta1)); - rl::math::Vector q(*MainWindow::instance()->q); - for (std::size_t i = 0; i < steps1 + 1 && this->running; ++i) + for (int i = 0; i < this->scene->steps[1] + 1 && this->running; ++i) { - q(this->axis1) = maximum(this->axis1) - i * delta1; + q(this->scene->axis[1]) = this->scene->maximum[1] - i * this->scene->delta[1]; - for (std::size_t j = 0; j < steps0 + 1 && this->running; ++j) + for (int j = 0; j < this->scene->steps[0] + 1 && this->running; ++j) { - q(this->axis0) = minimum(this->axis0) + j * delta0; + q(this->scene->axis[0]) = this->scene->minimum[0] + j * this->scene->delta[0]; if (model->isColliding(q)) { emit addCollision( - q(this->axis0), - q(this->axis1), - delta0, - delta1, + q(this->scene->axis[0]), + q(this->scene->axis[1]), + this->scene->delta[0], + this->scene->delta[1], 0 ); } diff --git a/demos/rlPlanDemo/ConfigurationSpaceThread.h b/demos/rlPlanDemo/ConfigurationSpaceThread.h index f28d14d7..ce74b6a6 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceThread.h +++ b/demos/rlPlanDemo/ConfigurationSpaceThread.h @@ -28,7 +28,8 @@ #define CONFIGURATIONSPACETHREAD_H #include -#include + +class ConfigurationSpaceScene; class ConfigurationSpaceThread : public QThread { @@ -43,15 +44,7 @@ class ConfigurationSpaceThread : public QThread void stop(); - std::size_t axis0; - - std::size_t axis1; - - rl::math::Real delta0; - - rl::math::Real delta1; - - rl::plan::Model* model; + ConfigurationSpaceScene* scene; protected: From 5481426bbc4dc658ccf735f68f39d424d9f8a92b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 16:24:25 +0200 Subject: [PATCH 500/546] Use qDeletaAll --- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 14 ++------------ 1 file changed, 2 insertions(+), 12 deletions(-) diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 9e29c2ab..7be20c33 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -310,12 +310,7 @@ ConfigurationSpaceScene::resetEdges() return; } - QList items = this->edges->childItems(); - - while (!items.isEmpty()) - { - delete items.takeFirst(); - } + qDeleteAll(this->edges->childItems()); } void @@ -331,12 +326,7 @@ ConfigurationSpaceScene::resetPath() return; } - QList items = this->path->childItems(); - - while (!items.isEmpty()) - { - delete items.takeFirst(); - } + qDeleteAll(this->path->childItems()); } void From 5f9793efd7a953f2ded232614cca54b642448c97 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 16:25:25 +0200 Subject: [PATCH 501/546] Reset collision items before computation --- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 12 ++++++++++++ demos/rlPlanDemo/ConfigurationSpaceScene.h | 2 ++ 2 files changed, 14 insertions(+) diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 7be20c33..b3aa9138 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -195,6 +195,7 @@ ConfigurationSpaceScene::eval() return; } + this->resetCollisions(); this->thread->start(); } @@ -302,6 +303,17 @@ ConfigurationSpaceScene::reset() this->resetPath(); } +void +ConfigurationSpaceScene::resetCollisions() +{ + if (nullptr == this->collisions) + { + return; + } + + qDeleteAll(this->collisions->childItems()); +} + void ConfigurationSpaceScene::resetEdges() { diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.h b/demos/rlPlanDemo/ConfigurationSpaceScene.h index c9d999ee..72cc5759 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.h +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.h @@ -92,6 +92,8 @@ public slots: void reset(); + void resetCollisions(); + void resetEdges(); void resetLines(); From 3218455ad9f09488bfd11206fa9439eabb97b89d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 17:06:36 +0200 Subject: [PATCH 502/546] Keep configuration space rectangle and groups --- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 53 +++++++------------- 1 file changed, 17 insertions(+), 36 deletions(-) diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index b3aa9138..78fe2cde 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -56,6 +56,19 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : this->thread->scene = this; + this->scene = this->addRect(0, 0, 0, 0, QPen(Qt::NoPen), QBrush(Qt::white)); + this->scene->setFlag(QGraphicsItem::ItemClipsChildrenToShape, true); + this->scene->setZValue(0); + + this->collisions = this->createItemGroup(QList()); + this->collisions->setZValue(1); + + this->edges = this->createItemGroup(QList()); + this->edges->setZValue(2); + + this->path = this->createItemGroup(QList()); + this->path->setZValue(3); + QObject::connect( this->thread, SIGNAL(addCollision(const qreal&, const qreal&, const qreal&, const qreal&, const int&)), @@ -89,11 +102,8 @@ ConfigurationSpaceScene::addCollision(const qreal& x, const qreal& y, const qrea void ConfigurationSpaceScene::clear() { - QGraphicsScene::clear(); - this->collisions = nullptr; - this->edges = nullptr; - this->path = nullptr; - this->scene = nullptr; + this->reset(); + this->resetCollisions(); } void @@ -229,28 +239,14 @@ ConfigurationSpaceScene::init() this->steps[0] = static_cast(std::ceil(this->range[0] / this->delta[0])); this->steps[1] = static_cast(std::ceil(this->range[1] / this->delta[1])); - this->scene = this->addRect( + this->scene->setRect( this->minimum[0], -this->maximum[1], this->range[0], - this->range[1], - QPen(Qt::NoPen), - QBrush(Qt::white) + this->range[1] ); - this->scene->setFlag(QGraphicsItem::ItemClipsChildrenToShape, true); - this->scene->setZValue(0); - this->setSceneRect(this->scene->boundingRect()); - - this->collisions = this->createItemGroup(QList()); - this->collisions->setZValue(1); - - this->edges = this->createItemGroup(QList()); - this->edges->setZValue(2); - - this->path = this->createItemGroup(QList()); - this->path->setZValue(3); } void @@ -306,22 +302,12 @@ ConfigurationSpaceScene::reset() void ConfigurationSpaceScene::resetCollisions() { - if (nullptr == this->collisions) - { - return; - } - qDeleteAll(this->collisions->childItems()); } void ConfigurationSpaceScene::resetEdges() { - if (nullptr == this->edges) - { - return; - } - qDeleteAll(this->edges->childItems()); } @@ -333,11 +319,6 @@ ConfigurationSpaceScene::resetLines() void ConfigurationSpaceScene::resetPath() { - if (nullptr == this->path) - { - return; - } - qDeleteAll(this->path->childItems()); } From 84c661dd9bdacfbacd0f864a4cf47d59da4f7cec Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 17:08:45 +0200 Subject: [PATCH 503/546] Add actions for toggling configuration space elements --- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 18 +++++++++++++ demos/rlPlanDemo/ConfigurationSpaceScene.h | 6 +++++ demos/rlPlanDemo/MainWindow.cpp | 28 ++++++++++++++++++++ demos/rlPlanDemo/MainWindow.h | 6 +++++ 4 files changed, 58 insertions(+) diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 78fe2cde..02cb47ad 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -341,3 +341,21 @@ void ConfigurationSpaceScene::showMessage(const std::string& message) { } + +void +ConfigurationSpaceScene::toggleCollisions(const bool& doOn) +{ + this->collisions->setVisible(doOn); +} + +void +ConfigurationSpaceScene::toggleConfigurationEdges(const bool& doOn) +{ + this->edges->setVisible(doOn); +} + +void +ConfigurationSpaceScene::togglePathEdges(const bool& doOn) +{ + this->path->setVisible(doOn); +} diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.h b/demos/rlPlanDemo/ConfigurationSpaceScene.h index 72cc5759..c120eaa5 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.h +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.h @@ -108,6 +108,12 @@ public slots: void showMessage(const std::string& message); + void toggleCollisions(const bool& doOn); + + void toggleConfigurationEdges(const bool& doOn); + + void togglePathEdges(const bool& doOn); + protected: void mouseMoveEvent(QGraphicsSceneMouseEvent* mouseEvent); diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 47b0cf91..9c8a6584 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -182,6 +182,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : toggleCameraAction(new QAction(this)), toggleConfigurationEdgesAction(new QAction(this)), toggleConfigurationSpaceActiveAction(new QAction(this)), + toggleConfigurationSpaceCollisionsAction(new QAction(this)), + toggleConfigurationSpaceEdgesAction(new QAction(this)), + toggleConfigurationSpacePathEdgesAction(new QAction(this)), toggleConfigurationVerticesAction(new QAction(this)), toggleLinesAction(new QAction(this)), togglePathEdgesAction(new QAction(this)), @@ -620,6 +623,31 @@ MainWindow::init() configurationSpaceMenu->addSeparator(); + this->toggleConfigurationSpacePathEdgesAction->setCheckable(true); + this->toggleConfigurationSpacePathEdgesAction->setChecked(true); + this->toggleConfigurationSpacePathEdgesAction->setText("Path Edges"); + QObject::connect(this->toggleConfigurationSpacePathEdgesAction, SIGNAL(toggled(bool)), this->configurationSpaceScene, SLOT(togglePathEdges(bool))); + configurationSpaceMenu->addAction(this->toggleConfigurationSpacePathEdgesAction); + + configurationSpaceMenu->addSeparator(); + + this->toggleConfigurationSpaceEdgesAction->setCheckable(true); + this->toggleConfigurationSpaceEdgesAction->setChecked(true); + this->toggleConfigurationSpaceEdgesAction->setMenuRole(QAction::NoRole); + this->toggleConfigurationSpaceEdgesAction->setText("Configuration Edges"); + QObject::connect(this->toggleConfigurationSpaceEdgesAction, SIGNAL(toggled(bool)), this->configurationSpaceScene, SLOT(toggleConfigurationEdges(bool))); + configurationSpaceMenu->addAction(this->toggleConfigurationSpaceEdgesAction); + + configurationSpaceMenu->addSeparator(); + + this->toggleConfigurationSpaceCollisionsAction->setCheckable(true); + this->toggleConfigurationSpaceCollisionsAction->setChecked(true); + this->toggleConfigurationSpaceCollisionsAction->setText("Collisions"); + QObject::connect(this->toggleConfigurationSpaceCollisionsAction, SIGNAL(toggled(bool)), this->configurationSpaceScene, SLOT(toggleCollisions(bool))); + configurationSpaceMenu->addAction(this->toggleConfigurationSpaceCollisionsAction); + + configurationSpaceMenu->addSeparator(); + this->evalAction->setText("Evaluate"); this->evalAction->setShortcut(QKeySequence("F11")); QObject::connect(this->evalAction, SIGNAL(triggered()), this, SLOT(eval())); diff --git a/demos/rlPlanDemo/MainWindow.h b/demos/rlPlanDemo/MainWindow.h index e5994973..f7350b8c 100644 --- a/demos/rlPlanDemo/MainWindow.h +++ b/demos/rlPlanDemo/MainWindow.h @@ -257,6 +257,12 @@ public slots: QAction* toggleConfigurationSpaceActiveAction; + QAction* toggleConfigurationSpaceCollisionsAction; + + QAction* toggleConfigurationSpaceEdgesAction; + + QAction* toggleConfigurationSpacePathEdgesAction; + QAction* toggleConfigurationVerticesAction; QAction* toggleLinesAction; From 34d147ff79ab73b45978dca3da10b589a04975fe Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 17:38:51 +0200 Subject: [PATCH 504/546] Use QGraphicsPathItem for path --- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 29 ++++++++++---------- demos/rlPlanDemo/ConfigurationSpaceScene.h | 3 +- 2 files changed, 17 insertions(+), 15 deletions(-) diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 02cb47ad..97c40c68 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -66,7 +66,9 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : this->edges = this->createItemGroup(QList()); this->edges->setZValue(2); - this->path = this->createItemGroup(QList()); + QPen pathPen(QColor(55, 176, 55), 2); + pathPen.setCosmetic(true); + this->path = this->addPath(QPainterPath(), pathPen); this->path->setZValue(3); QObject::connect( @@ -135,21 +137,20 @@ ConfigurationSpaceScene::drawConfigurationPath(const rl::plan::VectorList& path) { this->resetPath(); - rl::plan::VectorList::const_iterator i = path.begin(); - rl::plan::VectorList::const_iterator j = ++path.begin(); + if (path.empty()) + { + return; + } - for (; i != path.end() && j != path.end(); ++i, ++j) + QPainterPath painterPath; + painterPath.moveTo(path.front()(this->axis[0]), -path.front()(this->axis[1])); + + for (rl::plan::VectorList::const_iterator i = ++path.begin(); i != path.end(); ++i) { - QGraphicsLineItem* line = this->addLine( - (*i)(this->axis[0]), - -(*i)(this->axis[1]), - (*j)(this->axis[0]), - -(*j)(this->axis[1]), - QPen(QBrush(QColor(0, 255, 0)), 0) - ); - - this->path->addToGroup(line); + painterPath.lineTo((*i)(this->axis[0]), -(*i)(this->axis[1])); } + + this->path->setPath(painterPath); } void @@ -319,7 +320,7 @@ ConfigurationSpaceScene::resetLines() void ConfigurationSpaceScene::resetPath() { - qDeleteAll(this->path->childItems()); + this->path->setPath(QPainterPath()); } void diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.h b/demos/rlPlanDemo/ConfigurationSpaceScene.h index c120eaa5..984c1a84 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.h +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.h @@ -28,6 +28,7 @@ #define CONFIGURATIONSPACESCENE_H #include +#include #include #include #include @@ -124,7 +125,7 @@ public slots: QGraphicsItemGroup* edges; - QGraphicsItemGroup* path; + QGraphicsPathItem* path; QGraphicsRectItem* scene; From 70237953c251d3c7cca0e988a13394582b34eb0e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 18:07:09 +0200 Subject: [PATCH 505/546] Show current configuration in configuration space view --- demos/rlPlanDemo/ConfigurationModel.cpp | 2 +- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 22 ++++++++++++++++++++ demos/rlPlanDemo/ConfigurationSpaceScene.h | 4 ++++ demos/rlPlanDemo/MainWindow.cpp | 12 ++++++----- 4 files changed, 34 insertions(+), 6 deletions(-) diff --git a/demos/rlPlanDemo/ConfigurationModel.cpp b/demos/rlPlanDemo/ConfigurationModel.cpp index 864b143d..6725963f 100644 --- a/demos/rlPlanDemo/ConfigurationModel.cpp +++ b/demos/rlPlanDemo/ConfigurationModel.cpp @@ -151,7 +151,7 @@ ConfigurationModel::setData(const QModelIndex& index, const QVariant& value, int (*MainWindow::instance()->q)(index.row()) = value.value(); } - MainWindow::instance()->viewer->drawConfiguration(*MainWindow::instance()->q); + MainWindow::instance()->thread->drawConfiguration(*MainWindow::instance()->q); emit dataChanged(index, index); diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 97c40c68..149a69fa 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -44,6 +44,7 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : range(), steps(), collisions(nullptr), + configuration(nullptr), edges(nullptr), path(nullptr), scene(nullptr), @@ -63,6 +64,11 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : this->collisions = this->createItemGroup(QList()); this->collisions->setZValue(1); + this->configuration = this->addEllipse(-3, -3, 6, 6, QPen(Qt::NoPen), QBrush((QColor(247, 127, 7)))); + this->configuration->setFlag(QGraphicsItem::ItemIgnoresTransformations); + this->configuration->setVisible(false); + this->configuration->setZValue(4); + this->edges = this->createItemGroup(QList()); this->edges->setZValue(2); @@ -111,6 +117,10 @@ ConfigurationSpaceScene::clear() void ConfigurationSpaceScene::drawConfiguration(const rl::math::Vector& q) { + this->configuration->setPos( + q(this->axis[0]), + -q(this->axis[1]) + ); } void @@ -240,6 +250,11 @@ ConfigurationSpaceScene::init() this->steps[0] = static_cast(std::ceil(this->range[0] / this->delta[0])); this->steps[1] = static_cast(std::ceil(this->range[1] / this->delta[1])); + this->configuration->setPos( + (*MainWindow::instance()->q)(this->axis[0]), + -(*MainWindow::instance()->q)(this->axis[1]) + ); + this->scene->setRect( this->minimum[0], -this->maximum[1], @@ -286,6 +301,7 @@ ConfigurationSpaceScene::mousePressEvent(QGraphicsSceneMouseEvent* mouseEvent) } MainWindow::instance()->configurationModel->invalidate(); + this->drawConfiguration(*MainWindow::instance()->q); MainWindow::instance()->viewer->drawConfiguration(*MainWindow::instance()->q); } } @@ -349,6 +365,12 @@ ConfigurationSpaceScene::toggleCollisions(const bool& doOn) this->collisions->setVisible(doOn); } +void +ConfigurationSpaceScene::toggleConfiguration(const bool& doOn) +{ + this->configuration->setVisible(doOn); +} + void ConfigurationSpaceScene::toggleConfigurationEdges(const bool& doOn) { diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.h b/demos/rlPlanDemo/ConfigurationSpaceScene.h index 984c1a84..42ffc824 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.h +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.h @@ -111,6 +111,8 @@ public slots: void toggleCollisions(const bool& doOn); + void toggleConfiguration(const bool& doOn); + void toggleConfigurationEdges(const bool& doOn); void togglePathEdges(const bool& doOn); @@ -123,6 +125,8 @@ public slots: private: QGraphicsItemGroup* collisions; + QGraphicsEllipseItem* configuration; + QGraphicsItemGroup* edges; QGraphicsPathItem* path; diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 9c8a6584..3caa1fe5 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -523,7 +523,7 @@ MainWindow::getGoalConfiguration() { *this->q = *this->goal; this->configurationModel->invalidate(); - this->viewer->drawConfiguration(*this->q); + this->thread->drawConfiguration(*this->q); this->statusBar()->showMessage("Showing goal configuration.", 1000); } @@ -532,7 +532,7 @@ MainWindow::getRandomConfiguration() { *this->q = this->sampler2->generate(); this->configurationModel->invalidate(); - this->viewer->drawConfiguration(*this->q); + this->thread->drawConfiguration(*this->q); this->statusBar()->showMessage("Showing random configuration.", 1000); } @@ -541,7 +541,7 @@ MainWindow::getRandomFreeConfiguration() { *this->q = this->sampler2->generateCollisionFree(); this->configurationModel->invalidate(); - this->viewer->drawConfiguration(*this->q); + this->thread->drawConfiguration(*this->q); this->statusBar()->showMessage("Showing random collision-free configuration.", 1000); } @@ -550,7 +550,7 @@ MainWindow::getStartConfiguration() { *this->q = *this->start; this->configurationModel->invalidate(); - this->viewer->drawConfiguration(*this->q); + this->thread->drawConfiguration(*this->q); this->statusBar()->showMessage("Showing start configuration.", 1000); } @@ -2075,7 +2075,7 @@ MainWindow::load(const QString& filename) path.eval("number((/rl/plan|/rlplan)//viewer/camera/scale)").getValue(1) ); - this->viewer->drawConfiguration(*this->start); + this->thread->drawConfiguration(*this->start); this->configurationModel->invalidate(); this->configurationSpaceModel->invalidate(); @@ -2521,6 +2521,8 @@ MainWindow::toggleConfigurationSpaceActive(const bool& doOn) { this->disconnect(this->thread, this->configurationSpaceScene); } + + this->configurationSpaceScene->toggleConfiguration(doOn); } void From db3499d0a454cee7436b9a56f77b3ac8fa3f8491 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 18:12:47 +0200 Subject: [PATCH 506/546] Update configuration space rendering --- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 112 ++++++++++-------- demos/rlPlanDemo/ConfigurationSpaceScene.h | 13 +- demos/rlPlanDemo/ConfigurationSpaceThread.cpp | 23 ++-- demos/rlPlanDemo/ConfigurationSpaceThread.h | 2 +- demos/rlPlanDemo/MainWindow.cpp | 2 +- 5 files changed, 81 insertions(+), 71 deletions(-) diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 149a69fa..8043876f 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -24,8 +24,8 @@ // POSSIBILITY OF SUCH DAMAGE. // -#include #include +#include #include "ConfigurationModel.h" #include "ConfigurationSpaceScene.h" @@ -43,11 +43,12 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : model(nullptr), range(), steps(), - collisions(nullptr), + collisions(true), configuration(nullptr), + data(), edges(nullptr), + image(), path(nullptr), - scene(nullptr), thread(new ConfigurationSpaceThread(this)) { this->axis[0] = 0; @@ -57,13 +58,6 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : this->thread->scene = this; - this->scene = this->addRect(0, 0, 0, 0, QPen(Qt::NoPen), QBrush(Qt::white)); - this->scene->setFlag(QGraphicsItem::ItemClipsChildrenToShape, true); - this->scene->setZValue(0); - - this->collisions = this->createItemGroup(QList()); - this->collisions->setZValue(1); - this->configuration = this->addEllipse(-3, -3, 6, 6, QPen(Qt::NoPen), QBrush((QColor(247, 127, 7)))); this->configuration->setFlag(QGraphicsItem::ItemIgnoresTransformations); this->configuration->setVisible(false); @@ -79,9 +73,9 @@ ConfigurationSpaceScene::ConfigurationSpaceScene(QObject* parent) : QObject::connect( this->thread, - SIGNAL(addCollision(const qreal&, const qreal&, const qreal&, const qreal&, const int&)), + SIGNAL(addCollision(const int&, const int&, const unsigned char&)), this, - SLOT(addCollision(const qreal&, const qreal&, const qreal&, const qreal&, const int&)) + SLOT(addCollision(const int&, const int&, const unsigned char&)) ); QObject::connect(this->thread, SIGNAL(finished()), this, SIGNAL(evalFinished())); @@ -93,18 +87,16 @@ ConfigurationSpaceScene::~ConfigurationSpaceScene() } void -ConfigurationSpaceScene::addCollision(const qreal& x, const qreal& y, const qreal& w, const qreal& h, const int& rgb) -{ - QGraphicsRectItem* rect = this->addRect( - x - w * static_cast(0.5), - -y - h * static_cast(0.5), - w, - h, - QPen(Qt::NoPen), - QBrush(QColor(rgb, rgb, rgb)) +ConfigurationSpaceScene::addCollision(const int& x, const int& y, const unsigned char& rgb) +{ + this->data[y * this->steps[0] + x] = rgb; + this->invalidate( + this->minimum[0] + x * this->delta[0], + this->minimum[1] + y * this->delta[1], + this->delta[0], + this->delta[1], + QGraphicsScene::BackgroundLayer ); - - this->collisions->addToGroup(rect); } void @@ -114,12 +106,30 @@ ConfigurationSpaceScene::clear() this->resetCollisions(); } +void +ConfigurationSpaceScene::drawBackground(QPainter* painter, const QRectF& rect) +{ + painter->fillRect(rect, this->palette().color(QPalette::Window)); + + if (this->collisions) + { + QRectF target = rect.intersected(this->sceneRect()); + QRectF source( + (target.x() - this->minimum[0]) / this->delta[0], + (target.y() - this->minimum[1]) / this->delta[1], + target.width() / this->delta[0], + target.height() / this->delta[1] + ); + painter->drawImage(target, image, source, Qt::NoFormatConversion); + } +} + void ConfigurationSpaceScene::drawConfiguration(const rl::math::Vector& q) { this->configuration->setPos( q(this->axis[0]), - -q(this->axis[1]) + q(this->axis[1]) ); } @@ -128,10 +138,10 @@ ConfigurationSpaceScene::drawConfigurationEdge(const rl::math::Vector& u, const { QGraphicsLineItem* line = this->addLine( u(this->axis[0]), - -u(this->axis[1]), + u(this->axis[1]), v(this->axis[0]), - -v(this->axis[1]), - free ? QPen(QBrush(QColor(0, 128, 0)), 0) : QPen(QBrush(QColor(128, 0, 0)), 0) + v(this->axis[1]), + QPen(QBrush(QColor(96, 96, 96)), 0) ); this->edges->addToGroup(line); @@ -153,11 +163,11 @@ ConfigurationSpaceScene::drawConfigurationPath(const rl::plan::VectorList& path) } QPainterPath painterPath; - painterPath.moveTo(path.front()(this->axis[0]), -path.front()(this->axis[1])); + painterPath.moveTo(path.front()(this->axis[0]), path.front()(this->axis[1])); for (rl::plan::VectorList::const_iterator i = ++path.begin(); i != path.end(); ++i) { - painterPath.lineTo((*i)(this->axis[0]), -(*i)(this->axis[1])); + painterPath.lineTo((*i)(this->axis[0]), (*i)(this->axis[1])); } this->path->setPath(painterPath); @@ -252,17 +262,25 @@ ConfigurationSpaceScene::init() this->configuration->setPos( (*MainWindow::instance()->q)(this->axis[0]), - -(*MainWindow::instance()->q)(this->axis[1]) + (*MainWindow::instance()->q)(this->axis[1]) ); - this->scene->setRect( - this->minimum[0], - -this->maximum[1], - this->range[0], - this->range[1] - ); + this->data.assign(this->steps[0] * this->steps[1], 128); + +#if QT_VERSION >= 0x050500 + this->image = QImage(this->data.data(), this->steps[0], this->steps[1], this->steps[0], QImage::Format_Grayscale8); +#else + this->image = QImage(this->data.data(), this->steps[0], this->steps[1], this->steps[0], QImage::Format_Indexed8); + QVector colors; + colors.reserve(256); + for (int i = 0; i < 256; ++i) + { + colors.push_back(qRgb(i, i, i)); + } + this->image.setColorTable(colors); +#endif - this->setSceneRect(this->scene->boundingRect()); + this->setSceneRect(this->minimum[0], this->minimum[1], this->range[0], this->range[1]); } void @@ -288,17 +306,11 @@ ConfigurationSpaceScene::mousePressEvent(QGraphicsSceneMouseEvent* mouseEvent) { if (!MainWindow::instance()->thread->isRunning()) { - if (mouseEvent->scenePos().x() > this->minimum[0] && - mouseEvent->scenePos().x() < this->maximum[0]) - { - (*MainWindow::instance()->q)(this->axis[0]) = mouseEvent->scenePos().x(); - } + qreal x = qBound(this->minimum[0], mouseEvent->scenePos().x(), this->maximum[0]); + qreal y = qBound(this->minimum[1], mouseEvent->scenePos().y(), this->maximum[1]); - if (-mouseEvent->scenePos().y() > this->minimum[1] && - -mouseEvent->scenePos().y() < this->maximum[1]) - { - (*MainWindow::instance()->q)(this->axis[1]) = -mouseEvent->scenePos().y(); - } + (*MainWindow::instance()->q)(this->axis[0]) = x; + (*MainWindow::instance()->q)(this->axis[1]) = y; MainWindow::instance()->configurationModel->invalidate(); this->drawConfiguration(*MainWindow::instance()->q); @@ -319,7 +331,8 @@ ConfigurationSpaceScene::reset() void ConfigurationSpaceScene::resetCollisions() { - qDeleteAll(this->collisions->childItems()); + std::fill(this->data.begin(), this->data.end(), 128); + this->invalidate(this->sceneRect(), QGraphicsScene::BackgroundLayer); } void @@ -362,7 +375,8 @@ ConfigurationSpaceScene::showMessage(const std::string& message) void ConfigurationSpaceScene::toggleCollisions(const bool& doOn) { - this->collisions->setVisible(doOn); + this->collisions = doOn; + this->invalidate(this->sceneRect(), QGraphicsScene::BackgroundLayer); } void diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.h b/demos/rlPlanDemo/ConfigurationSpaceScene.h index 42ffc824..b1db2f0c 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.h +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.h @@ -27,6 +27,7 @@ #ifndef CONFIGURATIONSPACESCENE_H #define CONFIGURATIONSPACESCENE_H +#include #include #include #include @@ -59,7 +60,7 @@ class ConfigurationSpaceScene : public QGraphicsScene, public rl::plan::Viewer std::array steps; public slots: - void addCollision(const qreal& x, const qreal& y, const qreal& w, const qreal& h, const int& rgb); + void addCollision(const int& x, const int& y, const unsigned char& rgb); void clear(); @@ -118,20 +119,24 @@ public slots: void togglePathEdges(const bool& doOn); protected: + void drawBackground(QPainter* painter, const QRectF& rect); + void mouseMoveEvent(QGraphicsSceneMouseEvent* mouseEvent); void mousePressEvent(QGraphicsSceneMouseEvent* mouseEvent); private: - QGraphicsItemGroup* collisions; + bool collisions; QGraphicsEllipseItem* configuration; + std::vector data; + QGraphicsItemGroup* edges; - QGraphicsPathItem* path; + QImage image; - QGraphicsRectItem* scene; + QGraphicsPathItem* path; ConfigurationSpaceThread* thread; diff --git a/demos/rlPlanDemo/ConfigurationSpaceThread.cpp b/demos/rlPlanDemo/ConfigurationSpaceThread.cpp index 2b5421ad..a75dd19b 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceThread.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceThread.cpp @@ -58,24 +58,15 @@ ConfigurationSpaceThread::run() { rl::math::Vector q(*MainWindow::instance()->q); - for (int i = 0; i < this->scene->steps[1] + 1 && this->running; ++i) + for (int i = 0; i < this->scene->steps[0] && this->running; ++i) { - q(this->scene->axis[1]) = this->scene->maximum[1] - i * this->scene->delta[1]; + q(this->scene->axis[0]) = this->scene->minimum[0] + i * this->scene->delta[0]; - for (int j = 0; j < this->scene->steps[0] + 1 && this->running; ++j) + for (int j = 0; j < this->scene->steps[1] && this->running; ++j) { - q(this->scene->axis[0]) = this->scene->minimum[0] + j * this->scene->delta[0]; - - if (model->isColliding(q)) - { - emit addCollision( - q(this->scene->axis[0]), - q(this->scene->axis[1]), - this->scene->delta[0], - this->scene->delta[1], - 0 - ); - } + q(this->scene->axis[1]) = this->scene->minimum[1] + j * this->scene->delta[1]; + unsigned char rgb = model->isColliding(q) ? 0 : 255; + emit addCollision(i, j, rgb); } } } @@ -92,7 +83,7 @@ ConfigurationSpaceThread::stop() while (!this->isFinished()) { - QThread::usleep(0); + QThread::yieldCurrentThread(); } } } diff --git a/demos/rlPlanDemo/ConfigurationSpaceThread.h b/demos/rlPlanDemo/ConfigurationSpaceThread.h index ce74b6a6..cc62604f 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceThread.h +++ b/demos/rlPlanDemo/ConfigurationSpaceThread.h @@ -52,7 +52,7 @@ class ConfigurationSpaceThread : public QThread bool running; signals: - void addCollision(const qreal& x, const qreal& y, const qreal& w, const qreal& h, const int& rgb); + void addCollision(const int& x, const int& y, const unsigned char& rgb); }; #endif // CONFIGURATIONSPACETHREAD_H diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 3caa1fe5..47f22434 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -227,7 +227,7 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->configurationSpaceView->setAlternatingRowColors(true); this->configurationSpaceView->setModel(this->configurationSpaceModel); - this->configurationSpaceSceneView->setBackgroundBrush(QBrush(QWidget::palette().color(QWidget::backgroundRole()))); + this->configurationSpaceSceneView->scale(1, -1); this->configurationSpaceSceneView->setScene(this->configurationSpaceScene); #if QT_VERSION >= 0x050000 From 9e15e30369931634d45b0a2992504dae32f47f47 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 21:13:24 +0200 Subject: [PATCH 507/546] Test selected body against all other bodies --- demos/rlCollisionDemo/MainWindow.cpp | 104 +++++++++++++++++++-------- 1 file changed, 74 insertions(+), 30 deletions(-) diff --git a/demos/rlCollisionDemo/MainWindow.cpp b/demos/rlCollisionDemo/MainWindow.cpp index 0394d8aa..437cc460 100644 --- a/demos/rlCollisionDemo/MainWindow.cpp +++ b/demos/rlCollisionDemo/MainWindow.cpp @@ -392,20 +392,44 @@ MainWindow::parseCommandLine() void MainWindow::test() { + this->distanceCoordinate->point.setNum(0); + this->distanceLineSet->coordIndex.setNum(0); + this->distanceCoordinate->point.setNum(0); + + this->depthCoordinate->point.setNum(0); + this->depthLineSet->coordIndex.setNum(0); + this->depthCoordinate->point.setNum(0); + + rl::sg::Body* body = this->collisionScene->getModel(this->model)->getBody(this->body); + if (rl::sg::SimpleScene* simpleScene = dynamic_cast(this->collisionScene.get())) { - bool test = simpleScene->isColliding(); + std::size_t collisions = 0; + + for (rl::sg::Scene::Iterator i = this->collisionScene->begin(); i != this->collisionScene->end(); ++i) + { + for (rl::sg::Model::Iterator j = (*i)->begin(); j != (*i)->end(); ++j) + { + if (body != *j) + { + if (simpleScene->areColliding(body, *j)) + { + ++collisions; + } + } + } + } + + this->simpleLabel->setText("Collisions: " + QString::number(collisions)); - if (test) + if (collisions > 0) { - this->simpleLabel->setText("Collision: true"); this->viewer->setBackgroundColor(SbColor(0.5, 0, 0)); this->gradientBackground->color0.setValue(0.5f, 0.0f, 0.0f); this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); } else { - this->simpleLabel->setText("Collision: false"); this->viewer->setBackgroundColor(SbColor(0, 0, 0)); this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); @@ -414,23 +438,33 @@ MainWindow::test() if (rl::sg::DistanceScene* distanceScene = dynamic_cast(this->collisionScene.get())) { - this->distanceCoordinate->point.setNum(0); - this->distanceLineSet->coordIndex.setNum(0); - this->distanceCoordinate->point.setNum(0); + rl::math::Vector3 point1 = rl::math::Vector3::Zero(); + rl::math::Vector3 point2 = rl::math::Vector3::Zero(); + rl::math::Real distance = std::numeric_limits::max(); - rl::math::Vector3 point1; - rl::math::Vector3 point2; - - rl::math::Real distance = distanceScene->distance( - this->collisionScene->getModel(0)->getBody(0), - this->collisionScene->getModel(1)->getBody(0), - point1, - point2 - ); + for (rl::sg::Scene::Iterator i = this->collisionScene->begin(); i != this->collisionScene->end(); ++i) + { + for (rl::sg::Model::Iterator j = (*i)->begin(); j != (*i)->end(); ++j) + { + if (body != *j) + { + rl::math::Vector3 tmpPoint1; + rl::math::Vector3 tmpPoint2; + rl::math::Real tmpDistance = distanceScene->distance(body, *j, tmpPoint1, tmpPoint2); + + if (tmpDistance < distance) + { + distance = tmpDistance; + point1 = tmpPoint1; + point2 = tmpPoint2; + } + } + } + } this->distanceLabel->setText("Distance: " + QString::number(distance)); - if (distance > std::numeric_limits::epsilon()) + if (distance > 0 && distance < std::numeric_limits::max()) { this->distanceCoordinate->point.set1Value( this->distanceCoordinate->point.getNum(), @@ -462,23 +496,33 @@ MainWindow::test() if (rl::sg::DepthScene* depthScene = dynamic_cast(this->collisionScene.get())) { - this->depthCoordinate->point.setNum(0); - this->depthLineSet->coordIndex.setNum(0); - this->depthCoordinate->point.setNum(0); + rl::math::Vector3 point1 = rl::math::Vector3::Zero(); + rl::math::Vector3 point2 = rl::math::Vector3::Zero(); + rl::math::Real depth = 0; - rl::math::Vector3 point1; - rl::math::Vector3 point2; - - rl::math::Real depth = depthScene->depth( - this->collisionScene->getModel(0)->getBody(0), - this->collisionScene->getModel(1)->getBody(0), - point1, - point2 - ); + for (rl::sg::Scene::Iterator i = this->collisionScene->begin(); i != this->collisionScene->end(); ++i) + { + for (rl::sg::Model::Iterator j = (*i)->begin(); j != (*i)->end(); ++j) + { + if (body != *j) + { + rl::math::Vector3 tmpPoint1; + rl::math::Vector3 tmpPoint2; + rl::math::Real tmpDepth = depthScene->depth(body, *j, tmpPoint1, tmpPoint2); + + if (tmpDepth > depth) + { + depth = tmpDepth; + point1 = tmpPoint1; + point2 = tmpPoint2; + } + } + } + } this->depthLabel->setText("Depth: " + QString::number(depth)); - if (depth > std::numeric_limits::epsilon()) + if (depth > 0) { this->depthCoordinate->point.set1Value( this->depthCoordinate->point.getNum(), From 2992288cd697954f51f4ad15eec3a624b849ddf9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 21:32:50 +0200 Subject: [PATCH 508/546] Add support for selecting and deselecting bodies via mouse pick --- demos/rlCollisionDemo/CMakeLists.txt | 2 + demos/rlCollisionDemo/MainWindow.cpp | 173 +++++++---- demos/rlCollisionDemo/MainWindow.h | 24 +- .../SoMaterialHighlightRenderAction.cpp | 271 ++++++++++++++++++ .../SoMaterialHighlightRenderAction.h | 98 +++++++ 5 files changed, 506 insertions(+), 62 deletions(-) create mode 100644 demos/rlCollisionDemo/SoMaterialHighlightRenderAction.cpp create mode 100644 demos/rlCollisionDemo/SoMaterialHighlightRenderAction.h diff --git a/demos/rlCollisionDemo/CMakeLists.txt b/demos/rlCollisionDemo/CMakeLists.txt index d791d02c..9184c6b2 100644 --- a/demos/rlCollisionDemo/CMakeLists.txt +++ b/demos/rlCollisionDemo/CMakeLists.txt @@ -26,6 +26,7 @@ if(QT_FOUND AND SoQt_FOUND AND (RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUIL BodyModel.h MainWindow.h SoGradientBackground.h + SoMaterialHighlightRenderAction.h ) set( @@ -35,6 +36,7 @@ if(QT_FOUND AND SoQt_FOUND AND (RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUIL MainWindow.cpp rlCollisionDemo.cpp SoGradientBackground.cpp + SoMaterialHighlightRenderAction.cpp ) add_executable( diff --git a/demos/rlCollisionDemo/MainWindow.cpp b/demos/rlCollisionDemo/MainWindow.cpp index 437cc460..024d6894 100644 --- a/demos/rlCollisionDemo/MainWindow.cpp +++ b/demos/rlCollisionDemo/MainWindow.cpp @@ -31,11 +31,12 @@ #include #include #include +#include #include #include #include #include -#include +#include #include #include #include @@ -43,6 +44,8 @@ #include #include #include +#include +#include #if QT_VERSION >= 0x050200 #include @@ -68,12 +71,13 @@ #include "BodyModel.h" #include "MainWindow.h" #include "SoGradientBackground.h" +#include "SoMaterialHighlightRenderAction.h" MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : QMainWindow(parent, f), collisionScene(), viewScene(), - body(0), + bodyModel(new BodyModel(this)), depthCoordinate(nullptr), depthLabel(new QLabel(this)), depthLineSet(nullptr), @@ -85,8 +89,12 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : engine(), filename(), gradientBackground(), - model(0), + highlightRenderAction(nullptr), + root(nullptr), + selected(nullptr), + selection(nullptr), simpleLabel(new QLabel(this)), + view2collision(), viewer(nullptr) { MainWindow::singleton = this; @@ -94,6 +102,10 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : SoQt::init(this); SoDB::init(); SoGradientBackground::initClass(); + SoMaterialHighlightRenderAction::initClass(); + + this->root = new SoSeparator(); + this->root->ref(); this->parseCommandLine(); @@ -145,11 +157,22 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->gradientBackground->ref(); this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); - this->viewScene->root->insertChild(this->gradientBackground, 0); + this->root->insertChild(this->gradientBackground, 0); + + this->selection = new SoSelection(); + this->selection->addSelectionCallback(MainWindow::selectionCallback, this); + this->selection->addDeselectionCallback(MainWindow::deselectionCallback, this); + this->selection->setPickFilterCallback(MainWindow::pickFilterCallback, this); + this->selection->policy = SoSelection::SINGLE; + this->selection->addChild(this->viewScene->root); + this->root->addChild(this->selection); + + this->highlightRenderAction = new SoMaterialHighlightRenderAction(); this->viewer = new SoQtExaminerViewer(this, nullptr, true, SoQtFullViewer::BUILD_POPUP); this->viewer->setFeedbackVisibility(true); - this->viewer->setSceneGraph(this->viewScene->root); + this->viewer->setGLRenderAction(this->highlightRenderAction); + this->viewer->setSceneGraph(this->root); this->viewer->setTransparencyType(SoGLRenderAction::SORTED_OBJECT_BLEND); this->setCentralWidget(this->viewer->getWidget()); @@ -161,16 +184,18 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : factory.load(this->filename.toStdString(), this->collisionScene.get()); factory.load(this->filename.toStdString(), this->viewScene.get()); + for (rl::sg::Scene::Iterator i = this->viewScene->begin(), j = this->collisionScene->begin(); i != this->viewScene->end(); ++i, ++j) + { + for (rl::sg::Model::Iterator k = (*i)->begin(), l = (*j)->begin(); k != (*i)->end(); ++k, ++l) + { + this->view2collision[*k] = *l; + } + } + this->viewer->viewAll(); BodyDelegate* bodyDelegate = new BodyDelegate(this); - BodyModel* bodyModel = new BodyModel(this); - bodyModel->setBody( - this->viewScene->getModel(this->model)->getBody(this->body), - this->collisionScene->getModel(this->model)->getBody(this->body) - ); - QTableView* bodyView = new QTableView(this); #if QT_VERSION >= 0x050000 bodyView->horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); @@ -180,14 +205,14 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : bodyView->horizontalHeader()->hide(); bodyView->setAlternatingRowColors(true); bodyView->setItemDelegate(bodyDelegate); - bodyView->setModel(bodyModel); + bodyView->setModel(this->bodyModel); QDockWidget* bodyDockWidget = new QDockWidget(this); bodyDockWidget->resize(160, 240); bodyDockWidget->setFeatures(QDockWidget::NoDockWidgetFeatures | QDockWidget::DockWidgetFloatable | QDockWidget::DockWidgetMovable); bodyDockWidget->setFloating(true); bodyDockWidget->setWidget(bodyView); - bodyDockWidget->setWindowTitle("Model[" + QString::number(this->model) + "]->Body[" + QString::number(this->body) + "]"); + bodyDockWidget->setWindowTitle("Body"); SoDrawStyle* drawStyle = new SoDrawStyle(); drawStyle->lineWidth = 0.0f; @@ -253,15 +278,36 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->statusBar()->addWidget(this->depthLabel); } + if (this->viewScene->getNumModels() > 0) + { + rl::sg::Model* model = this->viewScene->getModel(0); + + if (model->getNumBodies() > 0) + { + rl::sg::Body* body = model->getBody(0); + this->selection->select(dynamic_cast(body)->root); + } + } + this->test(); } MainWindow::~MainWindow() { - this->gradientBackground->unref(); + this->root->unref(); MainWindow::singleton = nullptr; } +void +MainWindow::deselectionCallback(void* data, SoPath* path) +{ + MainWindow* mainWindow = static_cast(data); + mainWindow->bodyModel->setBody(nullptr, nullptr); + mainWindow->selected = nullptr; + mainWindow->selection->touch(); + mainWindow->test(); +} + MainWindow* MainWindow::instance() { @@ -300,30 +346,15 @@ MainWindow::parseCommandLine() engines.sort(); #if QT_VERSION >= 0x050200 - QCommandLineOption bodyOption(QStringList("body"), "Sets active body.", "body"); QCommandLineOption engineOption(QStringList("engine"), "Sets collision engine.", engines.join("|")); - QCommandLineOption modelOption(QStringList("model"), "Sets model of active body.", "model"); QCommandLineParser parser; - parser.addOption(bodyOption); parser.addOption(engineOption); const QCommandLineOption helpOption = parser.addHelpOption(); - parser.addOption(modelOption); parser.addPositionalArgument("filename", "", "[filename]"); parser.process(QCoreApplication::arguments()); - if (parser.isSet(bodyOption)) - { - bool ok; - this->body = parser.value(bodyOption).toUInt(&ok); - - if (!ok) - { - parser.showHelp(); - } - } - if (parser.isSet(engineOption)) { QString engine = parser.value(engineOption); @@ -336,17 +367,6 @@ MainWindow::parseCommandLine() this->engine = engine; } - if (parser.isSet(modelOption)) - { - bool ok; - this->model = parser.value(modelOption).toUInt(&ok); - - if (!ok) - { - parser.showHelp(); - } - } - if (parser.positionalArguments().size() > 1) { parser.showHelp(); @@ -357,30 +377,20 @@ MainWindow::parseCommandLine() this->filename = parser.positionalArguments()[0]; } #else - QRegExp bodyRegExp("--body=(\\d*)"); QRegExp engineRegExp("--engine=(" + engines.join("|") + ")"); QRegExp helpRegExp("--help"); - QRegExp modelRegExp("--model=(\\d*)"); for (int i = 1; i < QApplication::arguments().size(); ++i) { - if (-1 != bodyRegExp.indexIn(QApplication::arguments()[i])) - { - this->body = bodyRegExp.cap(1).toUInt(); - } - else if (-1 != engineRegExp.indexIn(QApplication::arguments()[i])) + if (-1 != engineRegExp.indexIn(QApplication::arguments()[i])) { this->engine = engineRegExp.cap(1); } else if (-1 != helpRegExp.indexIn(QApplication::arguments()[i])) { - QMessageBox::information(this, "Usage", "rlCollisionDemo [--body=] [--engine=<" + engines.join("|") + ">] [--help] [--model=] [filename]"); + QMessageBox::information(this, "Usage", "rlCollisionDemo [--engine=<" + engines.join("|") + ">] [--help] [filename]"); exit(0); } - else if (-1 != modelRegExp.indexIn(QApplication::arguments()[i])) - { - this->model = modelRegExp.cap(1).toUInt(); - } else { this->filename = QApplication::arguments()[i]; @@ -389,6 +399,38 @@ MainWindow::parseCommandLine() #endif } +SoPath* +MainWindow::pickFilterCallback(void* data, const SoPickedPoint* pick) +{ + SoFullPath* path = static_cast(pick->getPath()); + path->pop(); + path->pop(); + path->pop(); + return path; +} + +void +MainWindow::selectionCallback(void* data, SoPath* path) +{ + MainWindow* mainWindow = static_cast(data); + + if (path->getTail()->isOfType(SoVRMLTransform::getClassTypeId())) + { + SoVRMLTransform* vrmlTransform = static_cast(path->getTail()); + + if (nullptr != vrmlTransform->getUserData()) + { + rl::sg::so::Body* view = static_cast(vrmlTransform->getUserData()); + rl::sg::Body* collision = dynamic_cast(mainWindow->view2collision[view]); + mainWindow->bodyModel->setBody(collision, view); + mainWindow->selected = view; + } + } + + mainWindow->selection->touch(); + mainWindow->test(); +} + void MainWindow::test() { @@ -400,7 +442,17 @@ MainWindow::test() this->depthLineSet->coordIndex.setNum(0); this->depthCoordinate->point.setNum(0); - rl::sg::Body* body = this->collisionScene->getModel(this->model)->getBody(this->body); + rl::sg::Base* collision = this->view2collision[this->selected]; + + if (nullptr == this->selected || nullptr == collision) + { + this->simpleLabel->hide(); + this->distanceLabel->hide(); + this->depthLabel->hide(); + return; + } + + rl::sg::Body* body = dynamic_cast(collision); if (rl::sg::SimpleScene* simpleScene = dynamic_cast(this->collisionScene.get())) { @@ -420,19 +472,20 @@ MainWindow::test() } } + this->simpleLabel->show(); this->simpleLabel->setText("Collisions: " + QString::number(collisions)); if (collisions > 0) { - this->viewer->setBackgroundColor(SbColor(0.5, 0, 0)); - this->gradientBackground->color0.setValue(0.5f, 0.0f, 0.0f); - this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + this->highlightRenderAction->setDiffuseColor(SbColor(0.8f, 0.0f, 0.0f)); + this->highlightRenderAction->setEmissiveColor(SbColor(0.25f, 0.0f, 0.0f)); + this->highlightRenderAction->setSpecularColor(SbColor(1.0f, 0.0f, 0.0f)); } else { - this->viewer->setBackgroundColor(SbColor(0, 0, 0)); - this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); - this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + this->highlightRenderAction->setDiffuseColor(SbColor(0.8f, 0.8f, 0.8f)); + this->highlightRenderAction->setEmissiveColor(SbColor(0.0f, 0.0f, 0.25f)); + this->highlightRenderAction->setSpecularColor(SbColor(0.0f, 0.0f, 1.0f)); } } @@ -462,6 +515,7 @@ MainWindow::test() } } + this->distanceLabel->show(); this->distanceLabel->setText("Distance: " + QString::number(distance)); if (distance > 0 && distance < std::numeric_limits::max()) @@ -520,6 +574,7 @@ MainWindow::test() } } + this->depthLabel->show(); this->depthLabel->setText("Depth: " + QString::number(depth)); if (depth > 0) diff --git a/demos/rlCollisionDemo/MainWindow.h b/demos/rlCollisionDemo/MainWindow.h index 517c44bd..b1920f25 100644 --- a/demos/rlCollisionDemo/MainWindow.h +++ b/demos/rlCollisionDemo/MainWindow.h @@ -31,15 +31,19 @@ #include #include #include +#include +#include +#include #include #include #include #include -#include #include #include +class BodyModel; class SoGradientBackground; +class SoMaterialHighlightRenderAction; class MainWindow : public QMainWindow { @@ -58,9 +62,15 @@ class MainWindow : public QMainWindow MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); private: + static void deselectionCallback(void* data, SoPath* path); + void parseCommandLine(); - std::size_t body; + static SoPath* pickFilterCallback(void* data, const SoPickedPoint* pick); + + static void selectionCallback(void* data, SoPath* path); + + BodyModel* bodyModel; SoVRMLCoordinate* depthCoordinate; @@ -84,12 +94,20 @@ class MainWindow : public QMainWindow SoGradientBackground* gradientBackground; - std::size_t model; + SoMaterialHighlightRenderAction* highlightRenderAction; + + SoSeparator* root; + + rl::sg::Base* selected; + + SoSelection* selection; QLabel* simpleLabel; static MainWindow* singleton; + std::unordered_map view2collision; + SoQtExaminerViewer* viewer; }; diff --git a/demos/rlCollisionDemo/SoMaterialHighlightRenderAction.cpp b/demos/rlCollisionDemo/SoMaterialHighlightRenderAction.cpp new file mode 100644 index 00000000..1b41792f --- /dev/null +++ b/demos/rlCollisionDemo/SoMaterialHighlightRenderAction.cpp @@ -0,0 +1,271 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "SoMaterialHighlightRenderAction.h" + +SO_ACTION_SOURCE(SoMaterialHighlightRenderAction) + +SoMaterialHighlightRenderAction::SoMaterialHighlightRenderAction() : + SoGLRenderAction(SbViewportRegion()), + colorPackerStorage( + sizeof(void*), + SoMaterialHighlightRenderAction::allocColorPacker, + SoMaterialHighlightRenderAction::freeColorPacker + ), + diffuseColor(SbColor(0.8f, 0.8f, 0.8f)), + emissiveColor(0.0f, 0.0f, 0.25f), + postProcPath(new SoTempPath(32)), + searchAction(), + specularColor(0.0f, 0.0f, 1.0f), + visible(true) +{ + SO_ACTION_CONSTRUCTOR(SoMaterialHighlightRenderAction); + this->postProcPath->ref(); +} + +SoMaterialHighlightRenderAction::SoMaterialHighlightRenderAction(const SbViewportRegion& viewportRegion) : + SoGLRenderAction(viewportRegion), + colorPackerStorage( + sizeof(void*), + SoMaterialHighlightRenderAction::allocColorPacker, + SoMaterialHighlightRenderAction::freeColorPacker + ), + diffuseColor(SbColor(0.8f, 0.8f, 0.8f)), + emissiveColor(0.0f, 0.0f, 0.25f), + postProcPath(new SoTempPath(32)), + searchAction(), + specularColor(0.0f, 0.0f, 1.0f), + visible(true) +{ + SO_ACTION_CONSTRUCTOR(SoMaterialHighlightRenderAction); + this->postProcPath->ref(); +} + +SoMaterialHighlightRenderAction::~SoMaterialHighlightRenderAction() +{ + this->postProcPath->unref(); +} + +void +SoMaterialHighlightRenderAction::allocColorPacker(void* data) +{ + SoColorPacker** colorPacker = static_cast(data); + *colorPacker = new SoColorPacker(); +} + +void +SoMaterialHighlightRenderAction::apply(SoNode* node) +{ + SoGLRenderAction::apply(node); + + if (this->visible) + { + const SbBool searchall = false; + this->searchAction.setInterest(searchall ? SoSearchAction::ALL : SoSearchAction::FIRST); + this->searchAction.setType(SoSelection::getClassTypeId()); + this->searchAction.apply(node); + + if (searchall) + { + const SoPathList& pathList = this->searchAction.getPaths(); + + if (pathList.getLength() > 0) + { + for (int i = 0; i < pathList.getLength(); ++i) + { + SoFullPath* path = static_cast(pathList[i]); + assert(path); + SoSelection* selection = static_cast(path->getTail()); + + if (selection->getNumSelected() > 0) + { + this->highlight(path, selection->getList()); + } + } + } + } + else + { + SoFullPath* path = static_cast(this->searchAction.getPath()); + + if (path) + { + SoSelection* selection = static_cast(path->getTail()); + assert(selection->getTypeId().isDerivedFrom(SoSelection::getClassTypeId())); + + if (selection->getNumSelected() > 0) + { + this->highlight(path, selection->getList()); + } + } + } + + this->searchAction.reset(); + } +} + +void +SoMaterialHighlightRenderAction::apply(SoPath* path) +{ + SoGLRenderAction::apply(path); +} + +void +SoMaterialHighlightRenderAction::apply(const SoPathList& pathList, SbBool obeysRules) +{ + SoGLRenderAction::apply(pathList, obeysRules); +} + +void +SoMaterialHighlightRenderAction::freeColorPacker(void* data) +{ + SoColorPacker** colorPacker = static_cast(data); + delete *colorPacker; +} + +const SbColor& +SoMaterialHighlightRenderAction::getDiffuseColor() +{ + return this->diffuseColor; +} + +const SbColor& +SoMaterialHighlightRenderAction::getEmissiveColor() +{ + return this->emissiveColor; +} + +const SbColor& +SoMaterialHighlightRenderAction::getSpecularColor() +{ + return this->specularColor; +} + +void +SoMaterialHighlightRenderAction::highlight(SoPath* path, const SoPathList* pathList) +{ + int pos = static_cast(path)->getLength() - 1; + assert(pos >= 0); + this->postProcPath->setHead(path->getHead()); + + for (int i = 1; i < pos; ++i) + { + this->postProcPath->append(path->getIndex(i)); + } + + SoState* state = this->getState(); + state->push(); + + int oldNumPasses = this->getNumPasses(); + this->setNumPasses(1); + + SoColorPacker** colorPacker = static_cast(this->colorPackerStorage.get()); + + SoLazyElement::setDiffuse(state, path->getHead(), 1, &this->diffuseColor, *colorPacker); + SoLazyElement::setEmissive(state, &this->emissiveColor); + SoLazyElement::setSpecular(state, &this->specularColor); + SoMaterialBindingElement::set(state, nullptr, SoMaterialBindingElement::OVERALL); + SoLineWidthElement::set(state, 5.0f); + SoTextureQualityElement::set(state, 0.0f); + + SoOverrideElement::setDiffuseColorOverride(state, nullptr, true); + SoOverrideElement::setEmissiveColorOverride(state, nullptr, true); + SoOverrideElement::setSpecularColorOverride(state, nullptr, true); + SoOverrideElement::setMaterialBindingOverride(state, nullptr, true); + SoOverrideElement::setLineWidthOverride(state, nullptr, true); + SoTextureOverrideElement::setQualityOverride(state, true); + + for (int i = 0; i < pathList->getLength(); ++i) + { + SoFullPath* fullPath = static_cast((*pathList)[i]); + this->postProcPath->append(fullPath->getHead()); + + for (int j = 1; j < fullPath->getLength(); ++j) + { + this->postProcPath->append(fullPath->getIndex(j)); + } + + this->SoGLRenderAction::apply(this->postProcPath); + this->postProcPath->truncate(pos); + } + + this->setNumPasses(oldNumPasses); + state->pop(); +} + +void +SoMaterialHighlightRenderAction::initClass() +{ + SO_ACTION_INIT_CLASS(SoMaterialHighlightRenderAction, SoGLRenderAction); +} + +SbBool +SoMaterialHighlightRenderAction::isVisible() const +{ + return this->visible; +} + +void +SoMaterialHighlightRenderAction::setDiffuseColor(const SbColor& diffuseColor) +{ + this->diffuseColor = diffuseColor; +} + +void +SoMaterialHighlightRenderAction::setEmissiveColor(const SbColor& emissiveColor) +{ + this->emissiveColor = emissiveColor; +} + +void +SoMaterialHighlightRenderAction::setSpecularColor(const SbColor& specularColor) +{ + this->specularColor = specularColor; +} + +void +SoMaterialHighlightRenderAction::setVisible(const SbBool visible) +{ + this->visible = visible; +} diff --git a/demos/rlCollisionDemo/SoMaterialHighlightRenderAction.h b/demos/rlCollisionDemo/SoMaterialHighlightRenderAction.h new file mode 100644 index 00000000..9f201e0e --- /dev/null +++ b/demos/rlCollisionDemo/SoMaterialHighlightRenderAction.h @@ -0,0 +1,98 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 SOMATERIALHIGHLIGHTRENDERACTION_H +#define SOMATERIALHIGHLIGHTRENDERACTION_H + +#include +#include +#include +#include + +class SoMaterialHighlightRenderAction : public SoGLRenderAction +{ + SO_ACTION_HEADER(SoMaterialHighlightRenderAction); + +public: + SoMaterialHighlightRenderAction(); + + SoMaterialHighlightRenderAction(const SbViewportRegion& viewportRegion); + + virtual ~SoMaterialHighlightRenderAction(); + + virtual void apply(SoNode* node); + + virtual void apply(SoPath* path); + + virtual void apply(const SoPathList& pathList, SbBool obeysRules = false); + + const SbColor& getDiffuseColor(); + + const SbColor& getEmissiveColor(); + + const SbColor& getSpecularColor(); + + static void initClass(void); + + SbBool isVisible() const; + + void setVisible(const SbBool visible); + + void setDiffuseColor(const SbColor& diffuseColor); + + void setEmissiveColor(const SbColor& emissiveColor); + + void setSpecularColor(const SbColor& specularColor); + +protected: + +private: + SoMaterialHighlightRenderAction(const SoMaterialHighlightRenderAction& rhs); + + static void allocColorPacker(void* data); + + static void freeColorPacker(void* data); + + void highlight(SoPath* path, const SoPathList* pathList); + + SoMaterialHighlightRenderAction& operator=(const SoMaterialHighlightRenderAction& rhs); + + SbStorage colorPackerStorage; + + SbColor diffuseColor; + + SbColor emissiveColor; + + SoTempPath* postProcPath; + + SoSearchAction searchAction; + + SbColor specularColor; + + SbBool visible; +}; + +#endif // SOMATERIALHIGHLIGHTRENDERACTION_H From 01c62f874b4b630ba2a80b143d4255e27640219f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 21:53:11 +0200 Subject: [PATCH 509/546] Remove action shortcut --- demos/rlSimulator/MainWindow.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index 01bee4ba..26ba6641 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -439,9 +439,6 @@ MainWindow::instance() void MainWindow::init() { - this->positionDockWidget->toggleViewAction()->setShortcut(QKeySequence("F5")); - this->addAction(this->positionDockWidget->toggleViewAction()); - this->saveImageAction->setShortcut(QKeySequence("Return")); QObject::connect(this->saveImageAction, SIGNAL(triggered()), this, SLOT(saveImage())); this->addAction(this->saveImageAction); From 1fe80ad5aa0a02e657c2dc8170908b9b3628e278 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 May 2022 21:54:56 +0200 Subject: [PATCH 510/546] Set gradient background colors based on palette --- demos/rlCoachKin/MainWindow.cpp | 34 +++++++++++++++++++++++-- demos/rlCoachKin/MainWindow.h | 2 ++ demos/rlCoachMdl/MainWindow.cpp | 34 +++++++++++++++++++++++-- demos/rlCoachMdl/MainWindow.h | 2 ++ demos/rlCollisionDemo/MainWindow.cpp | 34 +++++++++++++++++++++++-- demos/rlCollisionDemo/MainWindow.h | 2 ++ demos/rlPlanDemo/Viewer.cpp | 37 +++++++++++++++++++++++++--- demos/rlPlanDemo/Viewer.h | 1 + demos/rlSimulator/MainWindow.cpp | 34 +++++++++++++++++++++++-- demos/rlSimulator/MainWindow.h | 2 ++ extras/wrlview/CMakeLists.txt | 2 +- extras/wrlview/MainWindow.cpp | 33 +++++++++++++++++++++++-- extras/wrlview/MainWindow.h | 2 ++ 13 files changed, 204 insertions(+), 15 deletions(-) diff --git a/demos/rlCoachKin/MainWindow.cpp b/demos/rlCoachKin/MainWindow.cpp index d7b339b6..c2441ef9 100644 --- a/demos/rlCoachKin/MainWindow.cpp +++ b/demos/rlCoachKin/MainWindow.cpp @@ -175,8 +175,18 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->gradientBackground = new SoGradientBackground(); this->gradientBackground->ref(); - this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); - this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + this->scene->root->insertChild(this->gradientBackground, 0); this->viewer = new SoQtExaminerViewer(this, nullptr, true, SoQtFullViewer::BUILD_POPUP); @@ -200,6 +210,26 @@ MainWindow::~MainWindow() MainWindow::singleton = nullptr; } +void +MainWindow::changeEvent(QEvent* event) +{ + if (QEvent::PaletteChange == event->type()) + { + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + } + + QMainWindow::changeEvent(event); +} + MainWindow* MainWindow::instance() { diff --git a/demos/rlCoachKin/MainWindow.h b/demos/rlCoachKin/MainWindow.h index d585bcb2..9a1a9117 100644 --- a/demos/rlCoachKin/MainWindow.h +++ b/demos/rlCoachKin/MainWindow.h @@ -75,6 +75,8 @@ public slots: protected: MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); + void changeEvent(QEvent* event); + private: void init(); diff --git a/demos/rlCoachMdl/MainWindow.cpp b/demos/rlCoachMdl/MainWindow.cpp index e24293f9..cbc8cd36 100644 --- a/demos/rlCoachMdl/MainWindow.cpp +++ b/demos/rlCoachMdl/MainWindow.cpp @@ -246,8 +246,18 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->gradientBackground = new SoGradientBackground(); this->gradientBackground->ref(); - this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); - this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + this->scene->root->insertChild(this->gradientBackground, 0); this->viewer = new SoQtExaminerViewer(this, nullptr, true, SoQtFullViewer::BUILD_POPUP); @@ -271,6 +281,26 @@ MainWindow::~MainWindow() MainWindow::singleton = nullptr; } +void +MainWindow::changeEvent(QEvent* event) +{ + if (QEvent::PaletteChange == event->type()) + { + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + } + + QMainWindow::changeEvent(event); +} + void MainWindow::changeIkAlgorithm() { diff --git a/demos/rlCoachMdl/MainWindow.h b/demos/rlCoachMdl/MainWindow.h index dfe079f3..f2b22e6b 100644 --- a/demos/rlCoachMdl/MainWindow.h +++ b/demos/rlCoachMdl/MainWindow.h @@ -89,6 +89,8 @@ public slots: protected: MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); + void changeEvent(QEvent* event); + private: void init(); diff --git a/demos/rlCollisionDemo/MainWindow.cpp b/demos/rlCollisionDemo/MainWindow.cpp index 024d6894..5361cbe3 100644 --- a/demos/rlCollisionDemo/MainWindow.cpp +++ b/demos/rlCollisionDemo/MainWindow.cpp @@ -155,8 +155,18 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->gradientBackground = new SoGradientBackground(); this->gradientBackground->ref(); - this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); - this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + this->root->insertChild(this->gradientBackground, 0); this->selection = new SoSelection(); @@ -298,6 +308,26 @@ MainWindow::~MainWindow() MainWindow::singleton = nullptr; } +void +MainWindow::changeEvent(QEvent* event) +{ + if (QEvent::PaletteChange == event->type()) + { + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + } + + QMainWindow::changeEvent(event); +} + void MainWindow::deselectionCallback(void* data, SoPath* path) { diff --git a/demos/rlCollisionDemo/MainWindow.h b/demos/rlCollisionDemo/MainWindow.h index b1920f25..64fde46f 100644 --- a/demos/rlCollisionDemo/MainWindow.h +++ b/demos/rlCollisionDemo/MainWindow.h @@ -61,6 +61,8 @@ class MainWindow : public QMainWindow protected: MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); + void changeEvent(QEvent* event); + private: static void deselectionCallback(void* data, SoPath* path); diff --git a/demos/rlPlanDemo/Viewer.cpp b/demos/rlPlanDemo/Viewer.cpp index 05f95e3b..a165d008 100644 --- a/demos/rlPlanDemo/Viewer.cpp +++ b/demos/rlPlanDemo/Viewer.cpp @@ -25,6 +25,7 @@ // #include +#include #include #include #include @@ -151,12 +152,20 @@ Viewer::Viewer(QWidget* parent, Qt::WindowFlags f) : // background + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->backgroundGradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->backgroundGradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->backgroundGradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->backgroundGradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + this->background->setName("background"); this->background->whichChoice = SO_SWITCH_ALL; - - this->backgroundGradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); - this->backgroundGradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); - this->background->addChild(backgroundGradientBackground); + this->background->addChild(this->backgroundGradientBackground); this->root->addChild(this->background); @@ -474,6 +483,26 @@ Viewer::~Viewer() this->root->unref(); } +void +Viewer::changeEvent(QEvent* event) +{ + if (QEvent::PaletteChange == event->type()) + { + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->backgroundGradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->backgroundGradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->backgroundGradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->backgroundGradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + } + + QWidget::changeEvent(event); +} + void Viewer::drawConfiguration(const rl::math::Vector& q) { diff --git a/demos/rlPlanDemo/Viewer.h b/demos/rlPlanDemo/Viewer.h index 366c729f..f0c78b08 100644 --- a/demos/rlPlanDemo/Viewer.h +++ b/demos/rlPlanDemo/Viewer.h @@ -133,6 +133,7 @@ public slots: void toggleWorkFrames(const bool& doOn); protected: + void changeEvent(QEvent* event); private: SoVRMLSwitch* background; diff --git a/demos/rlSimulator/MainWindow.cpp b/demos/rlSimulator/MainWindow.cpp index 26ba6641..7d8574eb 100644 --- a/demos/rlSimulator/MainWindow.cpp +++ b/demos/rlSimulator/MainWindow.cpp @@ -353,8 +353,18 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->gradientBackground = new SoGradientBackground(); this->gradientBackground->ref(); - this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); - this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + this->scene->root->insertChild(this->gradientBackground, 0); this->viewer = new SoQtExaminerViewer(this, nullptr, true, SoQtFullViewer::BUILD_POPUP); @@ -381,6 +391,26 @@ MainWindow::~MainWindow() MainWindow::singleton = nullptr; } +void +MainWindow::changeEvent(QEvent* event) +{ + if (QEvent::PaletteChange == event->type()) + { + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + } + + QMainWindow::changeEvent(event); +} + void MainWindow::changeSimulationGravity(double value) { diff --git a/demos/rlSimulator/MainWindow.h b/demos/rlSimulator/MainWindow.h index 4ba57fe1..3fb12a33 100644 --- a/demos/rlSimulator/MainWindow.h +++ b/demos/rlSimulator/MainWindow.h @@ -103,6 +103,8 @@ public slots: protected: MainWindow(QWidget* parent = nullptr, Qt::WindowFlags f = Qt::WindowFlags()); + void changeEvent(QEvent* event); + void timerEvent(QTimerEvent *event); private: diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index 6b099fb6..dd60e48c 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -1,4 +1,4 @@ -project(wrlview VERSION 0.2.0) +project(wrlview VERSION 0.2.1) if(NOT PROJECT_VERSION_TWEAK) set(PROJECT_VERSION_TWEAK 0) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index f3934627..9438051a 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -119,8 +119,17 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->viewer->setTransparencyType(SoGLRenderAction::SORTED_OBJECT_BLEND); this->gradientBackground = new SoGradientBackground(); - this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); - this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } this->backgroundSwitch = new SoSwitch(); this->backgroundSwitch->whichChild = SO_SWITCH_ALL; @@ -214,6 +223,26 @@ MainWindow::~MainWindow() } } +void +MainWindow::changeEvent(QEvent* event) +{ + if (QEvent::PaletteChange == event->type()) + { + if (this->palette().color(QPalette::Window).lightness() < 128) + { + this->gradientBackground->color0.setValue(0.0f, 0.0f, 0.0f); + this->gradientBackground->color1.setValue(0.2f, 0.2f, 0.2f); + } + else + { + this->gradientBackground->color0.setValue(0.8f, 0.8f, 0.8f); + this->gradientBackground->color1.setValue(1.0f, 1.0f, 1.0f); + } + } + + QMainWindow::changeEvent(event); +} + void MainWindow::copyCameraValues() { diff --git a/extras/wrlview/MainWindow.h b/extras/wrlview/MainWindow.h index f17540c6..da386950 100644 --- a/extras/wrlview/MainWindow.h +++ b/extras/wrlview/MainWindow.h @@ -53,6 +53,8 @@ class MainWindow : public QMainWindow virtual ~MainWindow(); protected: + void changeEvent(QEvent* event); + void dragEnterEvent(QDragEnterEvent* event); void dropEvent(QDropEvent* event); From 3a61e56118d3e86bd338a8c75dbdc5125d5fb98c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 May 2022 13:08:29 +0200 Subject: [PATCH 511/546] Add labels as permanent widgets --- demos/rlCollisionDemo/MainWindow.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/demos/rlCollisionDemo/MainWindow.cpp b/demos/rlCollisionDemo/MainWindow.cpp index 5361cbe3..8b2092ae 100644 --- a/demos/rlCollisionDemo/MainWindow.cpp +++ b/demos/rlCollisionDemo/MainWindow.cpp @@ -275,17 +275,17 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : if (dynamic_cast(this->collisionScene.get())) { - this->statusBar()->addWidget(this->simpleLabel); + this->statusBar()->addPermanentWidget(this->simpleLabel); } if (dynamic_cast(this->collisionScene.get())) { - this->statusBar()->addWidget(this->distanceLabel); + this->statusBar()->addPermanentWidget(this->distanceLabel); } if (dynamic_cast(this->collisionScene.get())) { - this->statusBar()->addWidget(this->depthLabel); + this->statusBar()->addPermanentWidget(this->depthLabel); } if (this->viewScene->getNumModels() > 0) From b5811853db1ade8b96d8708f6d9bdf3367367175 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 23 May 2022 13:09:41 +0200 Subject: [PATCH 512/546] Add body dock widget to left dock widget area --- demos/rlCollisionDemo/MainWindow.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/demos/rlCollisionDemo/MainWindow.cpp b/demos/rlCollisionDemo/MainWindow.cpp index 8b2092ae..0aa96394 100644 --- a/demos/rlCollisionDemo/MainWindow.cpp +++ b/demos/rlCollisionDemo/MainWindow.cpp @@ -218,11 +218,9 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : bodyView->setModel(this->bodyModel); QDockWidget* bodyDockWidget = new QDockWidget(this); - bodyDockWidget->resize(160, 240); - bodyDockWidget->setFeatures(QDockWidget::NoDockWidgetFeatures | QDockWidget::DockWidgetFloatable | QDockWidget::DockWidgetMovable); - bodyDockWidget->setFloating(true); bodyDockWidget->setWidget(bodyView); bodyDockWidget->setWindowTitle("Body"); + this->addDockWidget(Qt::LeftDockWidgetArea, bodyDockWidget); SoDrawStyle* drawStyle = new SoDrawStyle(); drawStyle->lineWidth = 0.0f; From 1a12b8b4fd68494175e9d26847c51dd8358cb2cc Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 29 May 2022 14:07:27 +0200 Subject: [PATCH 513/546] Minor fix --- src/rl/plan/SequentialVerifier.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/rl/plan/SequentialVerifier.cpp b/src/rl/plan/SequentialVerifier.cpp index b6e441cc..feb09485 100644 --- a/src/rl/plan/SequentialVerifier.cpp +++ b/src/rl/plan/SequentialVerifier.cpp @@ -46,7 +46,7 @@ namespace rl assert(u.size() == this->getModel()->getDofPosition()); assert(v.size() == this->getModel()->getDofPosition()); - ::std::size_t steps = this->getSteps(d);; + ::std::size_t steps = this->getSteps(d); ::rl::math::Vector inter(u.size()); From 5064ded3b75bd0da8933a8bcba494cebe6c95ff5 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 29 May 2022 16:34:59 +0200 Subject: [PATCH 514/546] Update optimizer loops --- src/rl/plan/AdvancedOptimizer.cpp | 44 ++++--------------------------- src/rl/plan/SimpleOptimizer.cpp | 12 +-------- 2 files changed, 6 insertions(+), 50 deletions(-) diff --git a/src/rl/plan/AdvancedOptimizer.cpp b/src/rl/plan/AdvancedOptimizer.cpp index 3e6bdd6b..4371ef17 100644 --- a/src/rl/plan/AdvancedOptimizer.cpp +++ b/src/rl/plan/AdvancedOptimizer.cpp @@ -60,11 +60,6 @@ namespace rl AdvancedOptimizer::process(VectorList& path) { bool changed = true; - - VectorList::iterator i; - VectorList::iterator j; - VectorList::iterator k; - ::rl::math::Vector inter(this->getModel()->getDofPosition()); while (changed && path.size() > 2) @@ -73,11 +68,7 @@ namespace rl { changed = false; - i = path.begin(); - j = ++path.begin(); - k = ++++path.begin(); - - while (i != path.end() && j != path.end() && k != path.end()) + for (VectorList::iterator i = path.begin(), j = ::std::next(i), k = ::std::next(j); i != path.end() && j != path.end() && k != path.end(); ++i, ++j, ++k) { ::rl::math::Real ik = this->getModel()->distance(*i, *k); @@ -85,11 +76,7 @@ namespace rl { ::rl::math::Real ij = this->getModel()->distance(*i, *j); ::rl::math::Real jk = this->getModel()->distance(*j, *k); - - ::rl::math::Real alpha = ij / (ij + jk); - - this->getModel()->interpolate(*i, *k, alpha, inter); - + this->getModel()->interpolate(*i, *k, ij / (ij + jk), inter); ::rl::math::Real ratio = this->getModel()->distance(*j, inter) / ik; if (ratio > this->ratio) @@ -106,32 +93,16 @@ namespace rl changed = true; } - else - { - ++i; - ++j; - ++k; - } - } - else - { - ++i; - ++j; - ++k; } } } - i = path.begin(); - j = ++path.begin(); - - while (i != path.end() && j != path.end()) + for (VectorList::iterator i = path.begin(), j = ::std::next(i); i != path.end() && j != path.end(); ++i, ++j) { - if (this->getModel()->distance(*i, *j) > this->length) + if (this->getModel()->distance(*i, *j) > length) { this->getModel()->interpolate(*i, *j, static_cast<::rl::math::Real>(0.5), inter); - - j = path.insert(j, inter); + i = path.insert(j, inter); if (nullptr != this->getViewer()) { @@ -140,11 +111,6 @@ namespace rl changed = true; } - else - { - ++i; - ++j; - } } } } diff --git a/src/rl/plan/SimpleOptimizer.cpp b/src/rl/plan/SimpleOptimizer.cpp index ad51c8d9..b4c6533a 100644 --- a/src/rl/plan/SimpleOptimizer.cpp +++ b/src/rl/plan/SimpleOptimizer.cpp @@ -51,11 +51,7 @@ namespace rl { changed = false; - VectorList::iterator i = path.begin(); - VectorList::iterator j = ++path.begin(); - VectorList::iterator k = ++++path.begin(); - - while (i != path.end() && j != path.end() && k != path.end()) + for (VectorList::iterator i = path.begin(), j = ::std::next(i), k = ::std::next(j); i != path.end() && j != path.end() && k != path.end(); ++i, ++j, ++k) { ::rl::math::Real ik = this->getModel()->distance(*i, *k); @@ -73,12 +69,6 @@ namespace rl changed = true; } - else - { - ++i; - ++j; - ++k; - } } } } From aa6eb334b5279ece8523258957b70e3b8c0c42ce Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 29 May 2022 16:35:39 +0200 Subject: [PATCH 515/546] Refactor subdivide --- src/rl/plan/AdvancedOptimizer.cpp | 15 ++------------- src/rl/plan/Optimizer.cpp | 27 +++++++++++++++++++++++++++ src/rl/plan/Optimizer.h | 2 ++ 3 files changed, 31 insertions(+), 13 deletions(-) diff --git a/src/rl/plan/AdvancedOptimizer.cpp b/src/rl/plan/AdvancedOptimizer.cpp index 4371ef17..fa301b66 100644 --- a/src/rl/plan/AdvancedOptimizer.cpp +++ b/src/rl/plan/AdvancedOptimizer.cpp @@ -97,20 +97,9 @@ namespace rl } } - for (VectorList::iterator i = path.begin(), j = ::std::next(i); i != path.end() && j != path.end(); ++i, ++j) + if (this->subdivide(path, this->length)) { - if (this->getModel()->distance(*i, *j) > length) - { - this->getModel()->interpolate(*i, *j, static_cast<::rl::math::Real>(0.5), inter); - i = path.insert(j, inter); - - if (nullptr != this->getViewer()) - { - this->getViewer()->drawConfigurationPath(path); - } - - changed = true; - } + changed = true; } } } diff --git a/src/rl/plan/Optimizer.cpp b/src/rl/plan/Optimizer.cpp index 8482a5d8..404c562e 100644 --- a/src/rl/plan/Optimizer.cpp +++ b/src/rl/plan/Optimizer.cpp @@ -25,6 +25,8 @@ // #include "Optimizer.h" +#include "SimpleModel.h" +#include "Viewer.h" namespace rl { @@ -76,5 +78,30 @@ namespace rl { this->viewer = viewer; } + + bool + Optimizer::subdivide(VectorList& path, const ::rl::math::Real& length) + { + bool changed = false; + ::rl::math::Vector inter(this->getModel()->getDofPosition()); + + for (VectorList::iterator i = path.begin(), j = ::std::next(i); i != path.end() && j != path.end(); ++i, ++j) + { + if (0 == length || this->getModel()->distance(*i, *j) > length) + { + this->getModel()->interpolate(*i, *j, static_cast<::rl::math::Real>(0.5), inter); + i = path.insert(j, inter); + + if (nullptr != this->getViewer()) + { + this->getViewer()->drawConfigurationPath(path); + } + + changed = true; + } + } + + return changed; + } } } diff --git a/src/rl/plan/Optimizer.h b/src/rl/plan/Optimizer.h index 33f57055..37f93a96 100644 --- a/src/rl/plan/Optimizer.h +++ b/src/rl/plan/Optimizer.h @@ -60,6 +60,8 @@ namespace rl void setViewer(Viewer* viewer); + bool subdivide(VectorList& path, const ::rl::math::Real& length = 0); + SimpleModel* model; Verifier* verifier; From 1d516ad6165a74874f8414e84a1edf8810ff58b1 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 4 Jun 2022 13:52:26 +0200 Subject: [PATCH 516/546] Fix whitespace --- src/rl/mdl/SixDof.cpp | 2 +- src/rl/mdl/Spherical.cpp | 2 +- src/rl/util/xenomai/mutex.h | 2 +- tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/rl/mdl/SixDof.cpp b/src/rl/mdl/SixDof.cpp index 122bb7d8..13a4d29d 100644 --- a/src/rl/mdl/SixDof.cpp +++ b/src/rl/mdl/SixDof.cpp @@ -104,7 +104,7 @@ namespace rl q(i) = ::rl::std17::clamp(mean(i) + rand(i) * sigma(i), this->min(i), this->max(i)); } - q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>(), ::Eigen::Map< const ::rl::math::Quaternion>(mean.tail<4>().data()), sigma.tail<3>()).coeffs(); + q.tail<4>() = ::rl::math::Quaternion::Random(rand.tail<3>(), ::Eigen::Map(mean.tail<4>().data()), sigma.tail<3>()).coeffs(); } void diff --git a/src/rl/mdl/Spherical.cpp b/src/rl/mdl/Spherical.cpp index 04d1bbaf..b1ec7f13 100644 --- a/src/rl/mdl/Spherical.cpp +++ b/src/rl/mdl/Spherical.cpp @@ -79,7 +79,7 @@ namespace rl void Spherical::generatePositionGaussian(const ::rl::math::ConstVectorRef& rand, const ::rl::math::ConstVectorRef& mean, const ::rl::math::ConstVectorRef& sigma, ::rl::math::VectorRef q) const { - q = ::rl::math::Quaternion::Random(rand, ::Eigen::Map< const ::rl::math::Quaternion>(mean.data()), sigma).coeffs(); + q = ::rl::math::Quaternion::Random(rand, ::Eigen::Map(mean.data()), sigma).coeffs(); } void diff --git a/src/rl/util/xenomai/mutex.h b/src/rl/util/xenomai/mutex.h index 29c1f381..eed219e2 100644 --- a/src/rl/util/xenomai/mutex.h +++ b/src/rl/util/xenomai/mutex.h @@ -148,7 +148,7 @@ namespace rl typedef chrono::system_clock clock_t; template - bool M_try_lock_for(const ::std::chrono::duration< Rep, Period>& rtime) + bool M_try_lock_for(const ::std::chrono::duration& rtime) { clock_t::duration rt = ::std::chrono::duration_cast(rtime); diff --git a/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp b/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp index 49b57b56..e1e28700 100644 --- a/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp +++ b/tests/rlSplineTest/rlTrapezoidalAccelerationTest.cpp @@ -49,7 +49,7 @@ main(int argc, char** argv) int steps = 2000; for (std::size_t i = 0; i < steps; ++i) { - rl::math::Real t = f.duration() * i / static_cast< rl::math::Real >(steps - 1); + rl::math::Real t = f.duration() * i / static_cast(steps - 1); stream << t << "\t" << f(t)(0) << "\t" << f(t, 1)(0) << "\t" << f(t, 2)(0) << "\t" << f(t, 3)(0) << std::endl; } #endif From 040c0329c6bd5e989747c059d0a90ec3823792e4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 4 Jun 2022 18:21:35 +0200 Subject: [PATCH 517/546] Add value_type definition --- src/rl/math/Function.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/rl/math/Function.h b/src/rl/math/Function.h index 83dcdedf..efa7d199 100644 --- a/src/rl/math/Function.h +++ b/src/rl/math/Function.h @@ -44,6 +44,8 @@ namespace rl class Function { public: + typedef T value_type; + Function(const Real& x0 = 0, const Real& x1 = 1) : x0(x0), x1(x1) From bfa07c8bbd554ede887a251f9b324780edc73310 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 16 Jun 2022 14:54:54 +0200 Subject: [PATCH 518/546] Fix type definition --- src/rl/math/TypeTraits.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/math/TypeTraits.h b/src/rl/math/TypeTraits.h index 2f24ef95..0cb668fe 100644 --- a/src/rl/math/TypeTraits.h +++ b/src/rl/math/TypeTraits.h @@ -137,7 +137,7 @@ namespace rl return 0; } - static T abs(const float& t) + static T abs(const T& t) { return ::std::abs(t); } @@ -184,7 +184,7 @@ namespace rl return 0; } - static T abs(const float& t) + static T abs(const T& t) { return ::std::abs(t); } From 4db5228d191bfbf0727b065b4ef462f30813a815 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 16 Jun 2022 14:56:07 +0200 Subject: [PATCH 519/546] Fix status message --- demos/rlPlanDemo/Thread.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/demos/rlPlanDemo/Thread.cpp b/demos/rlPlanDemo/Thread.cpp index 0f16c7c2..6b5a5249 100644 --- a/demos/rlPlanDemo/Thread.cpp +++ b/demos/rlPlanDemo/Thread.cpp @@ -360,15 +360,15 @@ Thread::run() QThread::usleep(static_cast(2.0 * 1000.0 * 1000.0)); } - emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration) + " ms. Optimizing..."); + emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration * 1000) + " ms. Optimizing..."); start = std::chrono::steady_clock::now(); MainWindow::instance()->optimizer->process(path); stop = std::chrono::steady_clock::now(); - double optimizerDuration = std::chrono::duration_cast>(stop - start).count() * 1000; + double optimizerDuration = std::chrono::duration_cast>(stop - start).count(); - emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration) + " ms. Optimizer finished in " + QString::number(optimizerDuration) + " ms."); + emit statusChanged("Planner " + QString(solved ? "succeeded" : "failed") + " in " + QString::number(plannerDuration * 1000) + " ms. Optimizer finished in " + QString::number(optimizerDuration * 1000) + " ms."); if (nullptr != MainWindow::instance()->planner->getViewer()) { From 0b1c027863f817c585e41bad0bdbff9d83161bfd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 16 Jun 2022 20:57:11 +0200 Subject: [PATCH 520/546] Add parameter for random restart attempts --- src/rl/mdl/IterativeInverseKinematics.cpp | 15 +++++++++++++- src/rl/mdl/IterativeInverseKinematics.h | 6 ++++++ src/rl/mdl/JacobianInverseKinematics.cpp | 24 ++++++++++++----------- src/rl/mdl/NloptInverseKinematics.cpp | 20 +++++++++++-------- 4 files changed, 45 insertions(+), 20 deletions(-) diff --git a/src/rl/mdl/IterativeInverseKinematics.cpp b/src/rl/mdl/IterativeInverseKinematics.cpp index f653292d..0f55d886 100644 --- a/src/rl/mdl/IterativeInverseKinematics.cpp +++ b/src/rl/mdl/IterativeInverseKinematics.cpp @@ -34,7 +34,8 @@ namespace rl InverseKinematics(kinematic), duration(::std::chrono::milliseconds(1000)), epsilon(static_cast<::rl::math::Real>(1.0e-6)), - iterations(10000) + iterations(10000), + restarts(::std::numeric_limits<::std::size_t>::max()) { } @@ -60,6 +61,12 @@ namespace rl return this->iterations; } + const ::std::size_t& + IterativeInverseKinematics::getRandomRestarts() const + { + return this->restarts; + } + void IterativeInverseKinematics::setDuration(const ::std::chrono::nanoseconds& duration) { @@ -77,5 +84,11 @@ namespace rl { this->iterations = iterations; } + + void + IterativeInverseKinematics::setRandomRestarts(const ::std::size_t& restarts) + { + this->restarts = restarts; + } } } diff --git a/src/rl/mdl/IterativeInverseKinematics.h b/src/rl/mdl/IterativeInverseKinematics.h index 9efb9d9d..a929c7f5 100644 --- a/src/rl/mdl/IterativeInverseKinematics.h +++ b/src/rl/mdl/IterativeInverseKinematics.h @@ -48,12 +48,16 @@ namespace rl const ::std::size_t& getIterations() const; + const ::std::size_t& getRandomRestarts() const; + void setDuration(const ::std::chrono::nanoseconds& duration); virtual void setEpsilon(const ::rl::math::Real& epsilon); void setIterations(const ::std::size_t& iterations); + void setRandomRestarts(const ::std::size_t& restarts); + protected: private: @@ -62,6 +66,8 @@ namespace rl ::rl::math::Real epsilon; ::std::size_t iterations; + + ::std::size_t restarts; }; } } diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index 040302da..f82813a0 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -83,6 +83,7 @@ namespace rl { ::std::chrono::steady_clock::time_point start = ::std::chrono::steady_clock::now(); double remaining = ::std::chrono::duration(this->getDuration()).count(); + ::std::size_t attempt = 0; ::std::size_t iteration = 0; ::rl::math::Vector q = this->kinematic->getPosition(); @@ -94,6 +95,17 @@ namespace rl do { + if (attempt > 0) + { + for (::std::size_t i = 0; i < this->kinematic->getDof(); ++i) + { + rand(i) = this->randDistribution(this->randEngine); + } + + q = this->kinematic->generatePositionUniform(rand); + this->kinematic->setPosition(q); + } + do { this->kinematic->forwardPosition(); @@ -157,18 +169,8 @@ namespace rl } } while (remaining > 0 && iteration < this->getIterations()); - - for (::std::size_t i = 0; i < this->kinematic->getDof(); ++i) - { - rand(i) = this->randDistribution(this->randEngine); - } - - q = this->kinematic->generatePositionUniform(rand); - this->kinematic->setPosition(q); - - remaining = ::std::chrono::duration(this->getDuration() - (::std::chrono::steady_clock::now() - start)).count(); } - while (remaining > 0 && iteration < this->getIterations()); + while (attempt++ < this->getRandomRestarts() && remaining > 0 && iteration < this->getIterations()); return false; } diff --git a/src/rl/mdl/NloptInverseKinematics.cpp b/src/rl/mdl/NloptInverseKinematics.cpp index 9e7d97f0..a32b6860 100644 --- a/src/rl/mdl/NloptInverseKinematics.cpp +++ b/src/rl/mdl/NloptInverseKinematics.cpp @@ -187,6 +187,7 @@ namespace rl { ::std::chrono::steady_clock::time_point start = ::std::chrono::steady_clock::now(); double remaining = ::std::chrono::duration(this->getDuration()).count(); + ::std::size_t attempt = 0; this->iteration = 0; ::rl::math::Vector rand(this->kinematic->getDof()); @@ -195,6 +196,16 @@ namespace rl do { + if (attempt > 0) + { + for (::std::size_t i = 0; i < this->kinematic->getDof(); ++i) + { + rand(i) = this->randDistribution(this->randEngine); + } + + q = this->kinematic->generatePositionUniform(rand, this->lb, this->ub); + } + if (::nlopt_set_maxeval(opt.get(), this->getIterations() - this->iteration) < 0) { return false; @@ -216,16 +227,9 @@ namespace rl return false; } - for (::std::size_t i = 0; i < this->kinematic->getDof(); ++i) - { - rand(i) = this->randDistribution(this->randEngine); - } - - q = this->kinematic->generatePositionUniform(rand, this->lb, this->ub); - remaining = ::std::chrono::duration(this->getDuration() - (::std::chrono::steady_clock::now() - start)).count(); } - while (remaining > 0 && this->iteration < this->getIterations()); + while (attempt++ < this->getRandomRestarts() && remaining > 0 && iteration < this->getIterations()); return false; } From 09072eaf7174932cb02f5eab93dfe2ad60ec16c3 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 18 Jun 2022 15:29:54 +0200 Subject: [PATCH 521/546] Add parameter for Jacobian steps --- src/rl/mdl/JacobianInverseKinematics.cpp | 29 +++++++++++++++--------- src/rl/mdl/JacobianInverseKinematics.h | 6 +++++ 2 files changed, 24 insertions(+), 11 deletions(-) diff --git a/src/rl/mdl/JacobianInverseKinematics.cpp b/src/rl/mdl/JacobianInverseKinematics.cpp index f82813a0..74034f27 100644 --- a/src/rl/mdl/JacobianInverseKinematics.cpp +++ b/src/rl/mdl/JacobianInverseKinematics.cpp @@ -40,7 +40,8 @@ namespace rl delta(::std::numeric_limits<::rl::math::Real>::infinity()), method(Method::svd), randDistribution(0, 1), - randEngine(::std::random_device()()) + randEngine(::std::random_device()()), + steps(100) { } @@ -60,6 +61,12 @@ namespace rl return this->method; } + const ::std::size_t& + JacobianInverseKinematics::getSteps() const + { + return this->steps; + } + void JacobianInverseKinematics::seed(const ::std::mt19937::result_type& value) { @@ -78,6 +85,12 @@ namespace rl this->method = method; } + void + JacobianInverseKinematics::setSteps(const ::std::size_t& steps) + { + this->steps = steps; + } + bool JacobianInverseKinematics::solve() { @@ -106,15 +119,15 @@ namespace rl this->kinematic->setPosition(q); } - do + for (::std::size_t i = 0; i < this->steps && remaining > 0 && iteration < this->getIterations(); ++i, ++iteration) { this->kinematic->forwardPosition(); dx.setZero(); - for (::std::size_t i = 0; i < this->goals.size(); ++i) + for (::std::size_t j = 0; j < this->goals.size(); ++j) { - ::rl::math::VectorBlock dxi = dx.segment(6 * this->goals[i].second, 6); - dxi = this->kinematic->getOperationalPosition(this->goals[i].second).toDelta(this->goals[i].first); + ::rl::math::VectorBlock dxi = dx.segment(6 * this->goals[j].second, 6); + dxi = this->kinematic->getOperationalPosition(this->goals[j].second).toDelta(this->goals[j].first); } if (dx.squaredNorm() < ::std::pow(this->getEpsilon(), 2)) @@ -162,13 +175,7 @@ namespace rl this->kinematic->setPosition(q); remaining = ::std::chrono::duration(this->getDuration() - (::std::chrono::steady_clock::now() - start)).count(); - - if (0 == ++iteration % 100) - { - break; - } } - while (remaining > 0 && iteration < this->getIterations()); } while (attempt++ < this->getRandomRestarts() && remaining > 0 && iteration < this->getIterations()); diff --git a/src/rl/mdl/JacobianInverseKinematics.h b/src/rl/mdl/JacobianInverseKinematics.h index b053e23b..c735d0cb 100644 --- a/src/rl/mdl/JacobianInverseKinematics.h +++ b/src/rl/mdl/JacobianInverseKinematics.h @@ -67,12 +67,16 @@ namespace rl const Method& getMethod() const; + const ::std::size_t& getSteps() const; + void seed(const ::std::mt19937::result_type& value); void setDelta(const ::rl::math::Real& delta); void setMethod(const Method& method); + void setSteps(const ::std::size_t& steps); + bool solve(); protected: @@ -85,6 +89,8 @@ namespace rl ::std::uniform_real_distribution<::rl::math::Real> randDistribution; ::std::mt19937 randEngine; + + ::std::size_t steps; }; } } From 471b85768127ca68d75271a41dbad1fc19fe9245 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sat, 20 Aug 2022 16:37:49 +0200 Subject: [PATCH 522/546] Add support for libxml2 2.10.0 --- src/rl/xml/Object.h | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/src/rl/xml/Object.h b/src/rl/xml/Object.h index b0613447..5e2e2bca 100644 --- a/src/rl/xml/Object.h +++ b/src/rl/xml/Object.h @@ -53,14 +53,16 @@ namespace rl { if (nullptr != this->object) { - if (::XPATH_LOCATIONSET == this->object->type && nullptr != this->object->user) + if (::XPATH_STRING == this->object->type && nullptr != this->object->stringval) { - ::xmlXPtrFreeLocationSet(static_cast<::xmlLocationSetPtr>(this->object->user)); + ::xmlFree(this->object->stringval); } - else if (::XPATH_STRING == this->object->type && nullptr != this->object->stringval) +#if LIBXML_VERSION < 21000 || defined(LIBXML_XPTR_LOCS_ENABLED) + else if (::XPATH_LOCATIONSET == this->object->type && nullptr != this->object->user) { - ::xmlFree(this->object->stringval); + ::xmlXPtrFreeLocationSet(static_cast<::xmlLocationSetPtr>(this->object->user)); } +#endif } } @@ -104,9 +106,11 @@ namespace rl case ::XPATH_STRING: return typeid(this->object->stringval); break; +#if LIBXML_VERSION < 21000 || defined(LIBXML_XPTR_LOCS_ENABLED) case ::XPATH_POINT: case ::XPATH_RANGE: case ::XPATH_LOCATIONSET: +#endif case ::XPATH_USERS: case ::XPATH_XSLT_TREE: default: From 0c0cf5fb7f360761a63bdc8ca74ed6de00dc5bd7 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 16 Jun 2022 18:23:43 +0200 Subject: [PATCH 523/546] Add constructors from rest to rest for cubic, quintic, and septic polynomials --- .../rlInterpolatorDemo/rlInterpolatorDemo.cpp | 57 +++++ src/rl/math/Polynomial.h | 237 ++++++++++++++++++ tests/rlSplineTest/CMakeLists.txt | 1 + tests/rlSplineTest/rlPolynomialAtRestTest.cpp | 126 ++++++++++ 4 files changed, 421 insertions(+) create mode 100644 tests/rlSplineTest/rlPolynomialAtRestTest.cpp diff --git a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp index e08c2e52..b80234f3 100644 --- a/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp +++ b/demos/rlInterpolatorDemo/rlInterpolatorDemo.cpp @@ -237,6 +237,63 @@ main(int argc, char** argv) eval(f4); } + { + rl::math::Polynomial f0 = rl::math::Polynomial::CubicAtRest( + rl::math::Vector::Constant(1, 0), + rl::math::Vector::Constant(1, 1), + rl::math::Vector::Constant(1, 1), + rl::math::Vector::Constant(1, 2), + rl::math::Vector::Constant(1, 4) + ); + eval(f0); + rl::math::Polynomial f1 = rl::math::Polynomial::CubicAtRest( + rl::math::ArrayX::Constant(1, 0), + rl::math::ArrayX::Constant(1, 1), + rl::math::ArrayX::Constant(1, 1), + rl::math::ArrayX::Constant(1, 2), + rl::math::ArrayX::Constant(1, 4) + ); + eval(f1); + } + + { + rl::math::Polynomial f0 = rl::math::Polynomial::QuinticAtRest( + rl::math::Vector::Constant(1, 0), + rl::math::Vector::Constant(1, 1), + rl::math::Vector::Constant(1, 1), + rl::math::Vector::Constant(1, 2), + rl::math::Vector::Constant(1, 4) + ); + eval(f0); + rl::math::Polynomial f1 = rl::math::Polynomial::QuinticAtRest( + rl::math::ArrayX::Constant(1, 0), + rl::math::ArrayX::Constant(1, 1), + rl::math::ArrayX::Constant(1, 1), + rl::math::ArrayX::Constant(1, 2), + rl::math::ArrayX::Constant(1, 4) + ); + eval(f1); + } + + { + rl::math::Polynomial f0 = rl::math::Polynomial::SepticAtRest( + rl::math::Vector::Constant(1, 0), + rl::math::Vector::Constant(1, 1), + rl::math::Vector::Constant(1, 1), + rl::math::Vector::Constant(1, 2), + rl::math::Vector::Constant(1, 4) + ); + eval(f0); + rl::math::Polynomial f1 = rl::math::Polynomial::SepticAtRest( + rl::math::ArrayX::Constant(1, 0), + rl::math::ArrayX::Constant(1, 1), + rl::math::ArrayX::Constant(1, 1), + rl::math::ArrayX::Constant(1, 2), + rl::math::ArrayX::Constant(1, 4) + ); + eval(f1); + } + { rl::math::Spline f0 = rl::math::Spline::QuarticLinearQuarticAtRest( rl::math::Vector::Constant(1, 0), diff --git a/src/rl/math/Polynomial.h b/src/rl/math/Polynomial.h index c0ffc8d6..ba4635f6 100644 --- a/src/rl/math/Polynomial.h +++ b/src/rl/math/Polynomial.h @@ -77,6 +77,81 @@ namespace rl { } + template + static Polynomial CubicAtRest( + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& y0, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& y1, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& ydmax, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& yddmax, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& ydddmax + ) + { + using ::std::abs; + using ::std::cbrt; + using ::std::max; + using ::std::pow; + using ::std::sqrt; + + T dy = y0 - y1; + + T x1v = 3 * abs(dy) / (2 * abs(ydmax)); + T x1a = sqrt(6 * abs(yddmax) * abs(dy)) / abs(yddmax); + T x1j = cbrt(12 * abs(dy) * pow(ydddmax, 2)) / abs(ydddmax); + T x1 = max({x1v, x1a, x1j}); + + Polynomial f(3); + + f.c[0] = y0; + f.c[1] = 0; + f.c[2] = -3 * dy / pow(x1, 2); + f.c[3] = 2 * dy / pow(x1, 3); + f.x1 = x1; + + return f; + } + + template + static Polynomial CubicAtRest( + const typename ::std::enable_if<::std::is_class::value, U>::type& y0, + const typename ::std::enable_if<::std::is_class::value, U>::type& y1, + const typename ::std::enable_if<::std::is_class::value, U>::type& ydmax, + const typename ::std::enable_if<::std::is_class::value, U>::type& yddmax, + const typename ::std::enable_if<::std::is_class::value, U>::type& ydddmax + ) + { + using ::std::abs; + using ::std::cbrt; + using ::std::max; + using ::std::pow; + using ::std::sqrt; + + T dy = y0 - y1; + + ::std::size_t dim = TypeTraits::size(y0); + + T x1(dim); + + for (::std::size_t i = 0; i < dim; ++i) + { + auto x1v = 3 * abs(dy[i]) / (2 * abs(ydmax[i])); + auto x1a = sqrt(6 * abs(yddmax[i]) * abs(dy[i])) / abs(yddmax[i]); + auto x1j = cbrt(12 * abs(dy[i]) * pow(ydddmax[i], 2)) / abs(ydddmax[i]); + x1[i] = max({x1v, x1a, x1j}); + } + + Real x1max = TypeTraits::max_element(x1); + + Polynomial f(3); + + f.c[0] = y0; + f.c[1] = TypeTraits::Zero(dim); + f.c[2] = -3 * dy / pow(x1max, 2); + f.c[3] = 2 * dy / pow(x1max, 3); + f.x1 = x1max; + + return f; + } + static Polynomial CubicFirst(const T& y0, const T& y1, const T& yd0, const T& yd1, const Real& x1 = 1) { Polynomial f(3); @@ -140,6 +215,85 @@ namespace rl return f; } + template + static Polynomial QuinticAtRest( + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& y0, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& y1, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& ydmax, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& yddmax, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& ydddmax + ) + { + using ::std::abs; + using ::std::cbrt; + using ::std::max; + using ::std::pow; + using ::std::sqrt; + + T dy = y0 - y1; + + T x1v = 15 * abs(dy) / (8 * abs(ydmax)); + T x1a = sqrt(30 * abs(yddmax) * sqrt(3) * abs(dy)) / (3 * abs(yddmax)); + T x1j = cbrt(60 * abs(dy) * pow(ydddmax, 2)) / abs(ydddmax); + T x1 = max({x1v, x1a, x1j}); + + Polynomial f(5); + + f.c[0] = y0; + f.c[1] = 0; + f.c[2] = 0; + f.c[3] = -10 * dy / pow(x1, 3); + f.c[4] = 15 * dy / pow(x1, 4); + f.c[5] = -6 * dy / pow(x1, 5); + f.x1 = x1; + + return f; + } + + template + static Polynomial QuinticAtRest( + const typename ::std::enable_if<::std::is_class::value, U>::type& y0, + const typename ::std::enable_if<::std::is_class::value, U>::type& y1, + const typename ::std::enable_if<::std::is_class::value, U>::type& ydmax, + const typename ::std::enable_if<::std::is_class::value, U>::type& yddmax, + const typename ::std::enable_if<::std::is_class::value, U>::type& ydddmax + ) + { + using ::std::abs; + using ::std::cbrt; + using ::std::max; + using ::std::pow; + using ::std::sqrt; + + T dy = y0 - y1; + + ::std::size_t dim = TypeTraits::size(y0); + + T x1(dim); + + for (::std::size_t i = 0; i < dim; ++i) + { + auto x1v = 15 * abs(dy[i]) / (8 * abs(ydmax[i])); + auto x1a = sqrt(30 * abs(yddmax[i]) * sqrt(3) * abs(dy[i])) / (3 * abs(yddmax[i])); + auto x1j = cbrt(60 * abs(dy[i]) * pow(ydddmax[i], 2)) / abs(ydddmax[i]); + x1[i] = max({x1v, x1a, x1j}); + } + + Real x1max = TypeTraits::max_element(x1); + + Polynomial f(5); + + f.c[0] = y0; + f.c[1] = TypeTraits::Zero(dim); + f.c[2] = TypeTraits::Zero(dim); + f.c[3] = -10 * dy / pow(x1max, 3); + f.c[4] = 15 * dy / pow(x1max, 4); + f.c[5] = -6 * dy / pow(x1max, 5); + f.x1 = x1max; + + return f; + } + static Polynomial QuinticFirstSecond(const T& y0, const T& y1, const T& yd0, const T& yd1, const T& ydd0, const T& ydd1, const Real& x1 = 1) { Polynomial f(5); @@ -155,6 +309,89 @@ namespace rl return f; } + template + static Polynomial SepticAtRest( + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& y0, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& y1, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& ydmax, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& yddmax, + const typename ::std::enable_if<::std::is_floating_point::value, U>::type& ydddmax + ) + { + using ::std::abs; + using ::std::cbrt; + using ::std::max; + using ::std::pow; + using ::std::sqrt; + + T dy = y0 - y1; + + T x1v = 35 * abs(dy) / (16 * abs(ydmax)); + T x1a = (2 * sqrt(21 * abs(yddmax) * sqrt(5) * abs(dy))) / (5 * abs(yddmax)); + T x1j = cbrt((420 * abs(dy)) * pow(ydddmax, 2)) / (2 * abs(ydddmax)); + T x1 = max({x1v, x1a, x1j}); + + Polynomial f(7); + + f.c[0] = y0; + f.c[1] = 0; + f.c[2] = 0; + f.c[3] = 0; + f.c[4] = -35 * dy / pow(x1, 4); + f.c[5] = 84 * dy / pow(x1, 5); + f.c[6] = -70 * dy / pow(x1, 6); + f.c[7] = 20 * dy / pow(x1, 7); + f.x1 = x1; + + return f; + } + + template + static Polynomial SepticAtRest( + const typename ::std::enable_if<::std::is_class::value, U>::type& y0, + const typename ::std::enable_if<::std::is_class::value, U>::type& y1, + const typename ::std::enable_if<::std::is_class::value, U>::type& ydmax, + const typename ::std::enable_if<::std::is_class::value, U>::type& yddmax, + const typename ::std::enable_if<::std::is_class::value, U>::type& ydddmax + ) + { + using ::std::abs; + using ::std::cbrt; + using ::std::max; + using ::std::pow; + using ::std::sqrt; + + T dy = y0 - y1; + + ::std::size_t dim = TypeTraits::size(y0); + + T x1(dim); + + for (::std::size_t i = 0; i < dim; ++i) + { + auto x1v = 35 * abs(dy[i]) / (16 * abs(ydmax[i])); + auto x1a = (2 * sqrt(21 * abs(yddmax[i]) * sqrt(5) * abs(dy[i]))) / (5 * abs(yddmax[i])); + auto x1j = cbrt((420 * abs(dy[i])) * pow(ydddmax[i], 2)) / (2 * abs(ydddmax[i])); + x1[i] = max({x1v, x1a, x1j}); + } + + Real x1max = TypeTraits::max_element(x1); + + Polynomial f(7); + + f.c[0] = y0; + f.c[1] = TypeTraits::Zero(dim); + f.c[2] = TypeTraits::Zero(dim); + f.c[3] = TypeTraits::Zero(dim); + f.c[4] = -35 * dy / pow(x1max, 4); + f.c[5] = 84 * dy / pow(x1max, 5); + f.c[6] = -70 * dy / pow(x1max, 6); + f.c[7] = 20 * dy / pow(x1max, 7); + f.x1 = x1max; + + return f; + } + static Polynomial SepticFirstSecondThird(const T& y0, const T& y1, const T& yd0, const T& yd1, const T& ydd0, const T& ydd1, const T& yddd0, const T& yddd1, const Real& x1 = 1) { Polynomial f(7); diff --git a/tests/rlSplineTest/CMakeLists.txt b/tests/rlSplineTest/CMakeLists.txt index f3c9ab9a..6d3de7ea 100644 --- a/tests/rlSplineTest/CMakeLists.txt +++ b/tests/rlSplineTest/CMakeLists.txt @@ -1,6 +1,7 @@ set( TESTS rlCompositeFunctionTest + rlPolynomialAtRestTest rlPolynomialExtremaTest rlPolynomialTest rlQuarticLinearQuarticTest diff --git a/tests/rlSplineTest/rlPolynomialAtRestTest.cpp b/tests/rlSplineTest/rlPolynomialAtRestTest.cpp new file mode 100644 index 00000000..d8b0eba1 --- /dev/null +++ b/tests/rlSplineTest/rlPolynomialAtRestTest.cpp @@ -0,0 +1,126 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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. +// + +#define EIGEN_DEFAULT_IO_FORMAT Eigen::IOFormat(Eigen::StreamPrecision, Eigen::DontAlignCols, ",", ";", "", "", "[", "]") + +#include +#include + +template +void +check(const rl::math::Polynomial& f, const T& y0, const T& y1, const T& ydmax, const T& yddmax, const T& ydddmax) +{ + rl::math::Real epsilon = Eigen::NumTraits::dummy_precision(); + + T f0 = f(f.lower()); + T f1 = f(f.upper()); + + rl::math::Polynomial fd = f.derivative(); + rl::math::Polynomial fdd = fd.derivative(); + rl::math::Polynomial fddd = fdd.derivative(); + + T fdmax = fd.getAbsoluteMaximum(); + T fddmax = fdd.getAbsoluteMaximum(); + T fdddmax = fddd.getAbsoluteMaximum(); + + bool result = true; + + if (!rl::math::TypeTraits::equal(f0, y0)) + { + std::cerr << "f(" << f.lower() << ") != y0" << std::endl; + result = false;; + } + + if (!rl::math::TypeTraits::equal(f1, y1)) + { + std::cerr << "f(" << f.upper() << ") != y1" << std::endl; + result = false;; + } + + if ((fdmax.array().abs() > ydmax.array() + epsilon).any()) + { + std::cerr << "abs(fdmax) > ydmax" << std::endl; + result = false;; + } + + if ((fddmax.array().abs() > yddmax.array() + epsilon).any()) + { + std::cerr << "abs(fddmax) > yddmax" << std::endl; + result = false;; + } + + if ((fdddmax.array().abs() > ydddmax.array() + epsilon).any()) + { + std::cerr << "abs(fdddmax) > ydddmax" << std::endl; + result = false;; + } + + if (!result) + { + std::cerr << "--------------------------------------------------------------------------------" << std::endl; + std::cerr << "degree(f) = " << f.degree() << std::endl; + std::cerr << "y0 = " << f0 << std::endl; + std::cerr << "y1 = " << y1 << std::endl; + std::cerr << "ydmax = " << ydmax << std::endl; + std::cerr << "yddmax = " << yddmax << std::endl; + std::cerr << "ydddmax = " << ydddmax << std::endl; + std::cerr << "--------------------------------------------------------------------------------" << std::endl; + std::cerr << "x0 = " << f.lower() << std::endl; + std::cerr << "x1 = " << f.upper() << std::endl; + std::cerr << "f0 = " << f0 << std::endl; + std::cerr << "f1 = " << f1 << std::endl; + std::cerr << "fdmax = " << fdmax << std::endl; + std::cerr << "fddmax = " << fddmax << std::endl; + std::cerr << "fdddmax = " << fdddmax << std::endl; + exit(EXIT_FAILURE); + } +} + +int +main(int argc, char** argv) +{ + std::size_t n = 6; + + for (std::size_t i = 0; i < 100; ++i) + { + rl::math::Vector y0 = rl::math::Vector::Random(n) * 10; + rl::math::Vector y1 = rl::math::Vector::Random(n) * 10; + rl::math::Vector ydmax = rl::math::Vector::Random(n).cwiseAbs() * 10; + rl::math::Vector yddmax = rl::math::Vector::Random(n).cwiseAbs() * 20; + rl::math::Vector ydddmax = rl::math::Vector::Random(n).cwiseAbs() * 40; + + rl::math::Polynomial f3 = rl::math::Polynomial::CubicAtRest(y0, y1, ydmax, yddmax, ydddmax); + check(f3, y0, y1, ydmax, yddmax, ydddmax); + + rl::math::Polynomial f5 = rl::math::Polynomial::QuinticAtRest(y0, y1, ydmax, yddmax, ydddmax); + check(f5, y0, y1, ydmax, yddmax, ydddmax); + + rl::math::Polynomial f7 = rl::math::Polynomial::SepticAtRest(y0, y1, ydmax, yddmax, ydddmax); + check(f7, y0, y1, ydmax, yddmax, ydddmax); + } + + return EXIT_SUCCESS; +} From 8e0d4169eb4908bc697df0cf3aa36c8d70ce377f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Thu, 16 Jun 2022 18:35:10 +0200 Subject: [PATCH 524/546] Use max. velocity, acceleration, and jerk values for interpolators --- .../rlAxisControllerDemo.cpp | 71 ++++++++++--------- 1 file changed, 38 insertions(+), 33 deletions(-) diff --git a/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp b/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp index f553d137..d8da876d 100644 --- a/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp +++ b/demos/rlAxisControllerDemo/rlAxisControllerDemo.cpp @@ -32,14 +32,17 @@ #include #include #include +#include #define COACH //#define GNUPLOT //#define MITSUBISHI //#define UNIVERSAL_ROBOTS_RTDE -#define CUBIC +//#define CUBIC //#define QUINTIC +//#define SEPTIC +#define TRAPEZOIDAL int main(int argc, char** argv) @@ -61,6 +64,10 @@ main(int argc, char** argv) rl::math::Real updateRate = std::chrono::duration_cast>(controller.getUpdateRate()).count(); + rl::math::Vector vmax = rl::math::Vector::Constant(controller.getDof(), 5 * rl::math::constants::deg2rad); + rl::math::Vector amax = rl::math::Vector::Constant(controller.getDof(), 15 * rl::math::constants::deg2rad); + rl::math::Vector jmax = rl::math::Vector::Constant(controller.getDof(), 45 * rl::math::constants::deg2rad); + controller.open(); controller.start(); @@ -69,32 +76,30 @@ main(int argc, char** argv) rl::math::Vector q0 = controller.getJointPosition(); rl::math::Vector q1 = q0 + rl::math::Vector::Constant(controller.getDof(), 5 * rl::math::constants::deg2rad); - rl::math::Real te = updateRate * 300.0f; - rl::math::Vector q(controller.getDof()); #ifdef CUBIC - rl::math::Polynomial interpolator = rl::math::Polynomial::CubicFirst( - q0, - q1, - rl::math::Vector::Zero(controller.getDof()), - rl::math::Vector::Zero(controller.getDof()), - te - ); + rl::math::Polynomial interpolator = rl::math::Polynomial::CubicAtRest( #endif // CUBIC #ifdef QUINTIC - rl::math::Polynomial interpolator = rl::math::Polynomial::QuinticFirstSecond( + rl::math::Polynomial interpolator = rl::math::Polynomial::QuinticAtRest( +#endif // QUINTIC +#ifdef SEPTIC + rl::math::Polynomial interpolator = rl::math::Polynomial::SepticAtRest( +#endif // SEPTIC +#ifdef TRAPEZOIDAL + rl::math::Spline interpolator = rl::math::Spline::TrapezoidalAccelerationAtRest( +#endif // TRAPEZOIDAL q0, q1, - rl::math::Vector::Zero(controller.getDof()), - rl::math::Vector::Zero(controller.getDof()), - rl::math::Vector::Zero(controller.getDof()), - rl::math::Vector::Zero(controller.getDof()), - te + vmax, + amax, + jmax ); -#endif // QUINTIC - for (std::size_t i = 0; i <= std::ceil(te / updateRate); ++i) + std::size_t steps = static_cast(std::ceil(interpolator.duration() / updateRate)) + 1; + + for (std::size_t i = 0; i < steps; ++i) { q = interpolator(i * updateRate); controller.setJointPosition(q); @@ -102,27 +107,27 @@ main(int argc, char** argv) } #ifdef CUBIC - interpolator = rl::math::Polynomial::CubicFirst( - q1, - q0, - rl::math::Vector::Zero(controller.getDof()), - rl::math::Vector::Zero(controller.getDof()), - te - ); + interpolator = rl::math::Polynomial::CubicAtRest( #endif // CUBIC #ifdef QUINTIC - interpolator = rl::math::Polynomial::QuinticFirstSecond( + interpolator = rl::math::Polynomial::QuinticAtRest( +#endif // QUINTIC +#ifdef SEPTIC + interpolator = rl::math::Polynomial::SepticAtRest( +#endif // SEPTIC +#ifdef TRAPEZOIDAL + interpolator = rl::math::Spline::TrapezoidalAccelerationAtRest( +#endif // TRAPEZOIDAL q1, q0, - rl::math::Vector::Zero(controller.getDof()), - rl::math::Vector::Zero(controller.getDof()), - rl::math::Vector::Zero(controller.getDof()), - rl::math::Vector::Zero(controller.getDof()), - te + vmax, + amax, + jmax ); -#endif // QUINTIC - for (std::size_t i = 0; i <= std::ceil(te / updateRate); ++i) + steps = static_cast(std::ceil(interpolator.duration() / updateRate)) + 1; + + for (std::size_t i = 0; i < steps; ++i) { q = interpolator(i * updateRate); controller.setJointPosition(q); From 2da1f81077247676e5bfd638db206a3ab7cb84a4 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 15 Feb 2023 19:49:29 +0100 Subject: [PATCH 525/546] Fix target definition for older CMake versions --- cmake/FindIconv.cmake | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/cmake/FindIconv.cmake b/cmake/FindIconv.cmake index 82e4a041..cdc55fa2 100644 --- a/cmake/FindIconv.cmake +++ b/cmake/FindIconv.cmake @@ -76,7 +76,11 @@ else() endif() if(Iconv_FOUND AND NOT TARGET Iconv::Iconv) - add_library(Iconv::Iconv INTERFACE IMPORTED) + if(Iconv_IS_BUILT_IN) + add_library(Iconv::Iconv INTERFACE IMPORTED) + else() + add_library(Iconv::Iconv UNKNOWN IMPORTED) + endif() if(NOT Iconv_IS_BUILT_IN AND Iconv_LIBRARY_RELEASE) set_property(TARGET Iconv::Iconv APPEND PROPERTY IMPORTED_CONFIGURATIONS RELEASE) set_target_properties(Iconv::Iconv PROPERTIES IMPORTED_LOCATION_RELEASE "${Iconv_LIBRARY_RELEASE}") From 5dce6f335834e5a347d2792b5d130cc8115a290b Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Wed, 7 Dec 2022 13:35:02 +0100 Subject: [PATCH 526/546] Add parameters for Jacobian steps and random restart attempts --- src/rl/kin/Kinematics.cpp | 22 ++++++++++------------ src/rl/kin/Kinematics.h | 4 +++- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index 191823fc..cc644e32 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -732,12 +732,13 @@ namespace rl } bool - Kinematics::inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const ::std::size_t& leaf, const ::rl::math::Real& delta, const ::rl::math::Real& epsilon, const ::std::size_t& iterations, const ::std::chrono::nanoseconds& duration) + Kinematics::inversePosition(const ::rl::math::Transform& x, ::rl::math::Vector& q, const ::std::size_t& leaf, const ::rl::math::Real& delta, const ::rl::math::Real& epsilon, const ::std::size_t& iterations, const ::std::chrono::nanoseconds& duration, const ::std::size_t& steps, const ::std::size_t& restarts) { assert(q.size() == this->getDof()); ::std::chrono::steady_clock::time_point start = ::std::chrono::steady_clock::now(); double remaining = ::std::chrono::duration(duration).count(); + ::std::size_t attempt = 0; ::std::size_t iteration = 0; this->getPosition(q); @@ -747,7 +748,13 @@ namespace rl do { - do + if (attempt > 0) + { + q = this->generatePositionUniform(); + this->setPosition(q); + } + + for (::std::size_t i = 0; i < steps && remaining > 0 && iteration < iterations; ++i, ++iteration) { this->updateFrames(); dx.setZero(); @@ -781,20 +788,11 @@ namespace rl this->setPosition(q); remaining = ::std::chrono::duration(duration - (::std::chrono::steady_clock::now() - start)).count(); - - if (0 == ++iteration % 100) - { - break; - } } - while (remaining > 0 && iteration < iterations); - - q = this->generatePositionUniform(); - this->setPosition(q); remaining = ::std::chrono::duration(duration - (::std::chrono::steady_clock::now() - start)).count(); } - while (remaining > 0 && iteration < iterations); + while (attempt++ < restarts && remaining > 0 && iteration < iterations); return false; } diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index f9df7523..c597eb07 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -226,7 +226,9 @@ namespace rl const ::rl::math::Real& delta = ::std::numeric_limits<::rl::math::Real>::infinity(), const ::rl::math::Real& epsilon = static_cast<::rl::math::Real>(1.0e-3), const ::std::size_t& iterations = 10000, - const ::std::chrono::nanoseconds& duration = ::std::chrono::milliseconds(1000) + const ::std::chrono::nanoseconds& duration = ::std::chrono::milliseconds(1000), + const ::std::size_t& steps = 100, + const ::std::size_t& restarts = ::std::numeric_limits<::std::size_t>::max() ); /** From a1b1d95ef167866dd846a8057ca07f1257c2d6e0 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 Oct 2023 17:28:57 +0200 Subject: [PATCH 527/546] Fix argument order --- src/rl/math/MatrixBaseAddons.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index a4e320aa..4084066b 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -238,8 +238,8 @@ static SphericalFromCartesian(const Scalar& x, const Scalar& y, const Scalar& z) return Matrix( sqrt(x_2 + y_2 + z_2), - atan2(sqrt(x_2 + y_2), z), - atan2(y, x) + atan2(y, x), + atan2(sqrt(x_2 + y_2), z) ); } From a23d6c758d736694a70c834e50b58ad70cb193a2 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 22 Oct 2023 17:29:10 +0200 Subject: [PATCH 528/546] Fix function definition --- src/rl/math/MatrixBaseAddons.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/rl/math/MatrixBaseAddons.h b/src/rl/math/MatrixBaseAddons.h index 4084066b..ce2223f0 100644 --- a/src/rl/math/MatrixBaseAddons.h +++ b/src/rl/math/MatrixBaseAddons.h @@ -222,7 +222,6 @@ static SphericalFromCartesian(const MatrixBase& cartesian) * * http://mathworld.wolfram.com/SphericalCoordinates.html */ -template Matrix static SphericalFromCartesian(const Scalar& x, const Scalar& y, const Scalar& z) { From 67dddab6eafaea4d0595ccf1b43aca26e500a117 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 29 Oct 2023 21:20:10 +0100 Subject: [PATCH 529/546] Add tests for polar and spherical coordinate system calculations --- tests/CMakeLists.txt | 1 + tests/rlCoordinatesTest/CMakeLists.txt | 31 ++++++++ .../rlCoordinatesPolarTest.cpp | 76 ++++++++++++++++++ .../rlCoordinatesSpatialTest.cpp | 78 +++++++++++++++++++ 4 files changed, 186 insertions(+) create mode 100644 tests/rlCoordinatesTest/CMakeLists.txt create mode 100644 tests/rlCoordinatesTest/rlCoordinatesPolarTest.cpp create mode 100644 tests/rlCoordinatesTest/rlCoordinatesSpatialTest.cpp diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index af2ee738..feaf6ee7 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -1,5 +1,6 @@ if(RL_BUILD_MATH) add_subdirectory(rlCircularTest) + add_subdirectory(rlCoordinatesTest) add_subdirectory(rlMathDeltaTest) add_subdirectory(rlNearestNeighborsTest) add_subdirectory(rlSpatialTest) diff --git a/tests/rlCoordinatesTest/CMakeLists.txt b/tests/rlCoordinatesTest/CMakeLists.txt new file mode 100644 index 00000000..9ccdaf2f --- /dev/null +++ b/tests/rlCoordinatesTest/CMakeLists.txt @@ -0,0 +1,31 @@ +add_executable( + rlCoordinatesPolarTest + rlCoordinatesPolarTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc +) + +target_link_libraries( + rlCoordinatesPolarTest + math +) + +add_test( + NAME rlCoordinatesPolarTest + COMMAND rlCoordinatesPolarTest +) + +add_executable( + rlCoordinatesSpatialTest + rlCoordinatesSpatialTest.cpp + ${rl_BINARY_DIR}/robotics-library.rc +) + +target_link_libraries( + rlCoordinatesSpatialTest + math +) + +add_test( + NAME rlCoordinatesSpatialTest + COMMAND rlCoordinatesSpatialTest +) diff --git a/tests/rlCoordinatesTest/rlCoordinatesPolarTest.cpp b/tests/rlCoordinatesTest/rlCoordinatesPolarTest.cpp new file mode 100644 index 00000000..b13aacf1 --- /dev/null +++ b/tests/rlCoordinatesTest/rlCoordinatesPolarTest.cpp @@ -0,0 +1,76 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 + +void +test(const rl::math::Vector2& cartesian, std::size_t& success, std::size_t& failure) +{ + rl::math::Vector2 polar = rl::math::Vector2::PolarFromCartesian(cartesian); + rl::math::Vector2 cartesian2 = rl::math::Vector2::CartesianFromPolar(polar); + + if (cartesian.isApprox(cartesian2)) + { + ++success; + } + else + { + std::cout << "Cartesian: x = " << cartesian.x() << ", y = " << cartesian.y() << std::endl; + std::cout << "Cartesian -> Polar: r = " << polar(0) << ", theta = " << polar(1) << " rad = " << polar(1) * rl::math::constants::rad2deg << " deg" << std::endl; + std::cout << "Polar -> Cartesian: x = " << cartesian2.x() << ", y = " << cartesian2.y() << std::endl; + std::cout << "--------------------------------------------------------------------------------" << std::endl; + ++failure; + } +} + +int +main(int argc, char** argv) +{ + std::size_t success = 0; + std::size_t failure = 0; + + test(rl::math::Vector2::Zero(), success, failure); + test(rl::math::Vector2::UnitX(), success, failure); + test(rl::math::Vector2::UnitY(), success, failure); + test(-rl::math::Vector2::UnitX(), success, failure); + test(-rl::math::Vector2::UnitY(), success, failure); + + for (std::size_t i = 0; i < 100000; ++i) + { + test(rl::math::Vector2::Random(), success, failure); + } + + std::cout << "success: " << success << " failure: " << failure << std::endl; + + if (failure > 0) + { + return EXIT_FAILURE; + } + + return EXIT_SUCCESS; +} diff --git a/tests/rlCoordinatesTest/rlCoordinatesSpatialTest.cpp b/tests/rlCoordinatesTest/rlCoordinatesSpatialTest.cpp new file mode 100644 index 00000000..13e7445f --- /dev/null +++ b/tests/rlCoordinatesTest/rlCoordinatesSpatialTest.cpp @@ -0,0 +1,78 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 + +void +test(const rl::math::Vector3& cartesian, std::size_t& success, std::size_t& failure) +{ + rl::math::Vector3 spherical = rl::math::Vector3::SphericalFromCartesian(cartesian); + rl::math::Vector3 cartesian2 = rl::math::Vector3::CartesianFromSpherical(spherical); + + if (cartesian.isApprox(cartesian2)) + { + ++success; + } + else + { + std::cout << "Cartesian: x = " << cartesian.x() << ", y = " << cartesian.y() << ", z = " << cartesian.z() << std::endl; + std::cout << "Cartesian -> Spherical: r = " << spherical(0) << ", theta = " << spherical(1) << " rad = " << spherical(1) * rl::math::constants::rad2deg << " deg, phi = " << spherical(2) << " rad = " << spherical(2) * rl::math::constants::rad2deg << " deg" << std::endl; + std::cout << "Spherical -> Cartesian: x = " << cartesian2.x() << ", y = " << cartesian2.y() << ", z = " << cartesian2.z() << std::endl; + std::cout << "--------------------------------------------------------------------------------" << std::endl; + ++failure; + } +} + +int +main(int argc, char** argv) +{ + std::size_t success = 0; + std::size_t failure = 0; + + test(rl::math::Vector3::Zero(), success, failure); + test(rl::math::Vector3::UnitX(), success, failure); + test(rl::math::Vector3::UnitY(), success, failure); + test(rl::math::Vector3::UnitZ(), success, failure); + test(-rl::math::Vector3::UnitX(), success, failure); + test(-rl::math::Vector3::UnitY(), success, failure); + test(-rl::math::Vector3::UnitZ(), success, failure); + + for (std::size_t i = 0; i < 100000; ++i) + { + test(rl::math::Vector3::Random(), success, failure); + } + + std::cout << "success: " << success << " failure: " << failure << std::endl; + + if (failure > 0) + { + return EXIT_FAILURE; + } + + return EXIT_SUCCESS; +} From c8c9619381362f52a8ab4a7ea674a3f436f698dd Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 2 Jan 2024 16:27:23 +0100 Subject: [PATCH 530/546] Add missing headers --- demos/rlSocketDemo/rlSocketDemoClient.cpp | 1 + demos/rlSocketDemo/rlSocketDemoServer.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/demos/rlSocketDemo/rlSocketDemoClient.cpp b/demos/rlSocketDemo/rlSocketDemoClient.cpp index 757c01af..be5a95b2 100644 --- a/demos/rlSocketDemo/rlSocketDemoClient.cpp +++ b/demos/rlSocketDemo/rlSocketDemoClient.cpp @@ -25,6 +25,7 @@ // #include +#include #include #include #include diff --git a/demos/rlSocketDemo/rlSocketDemoServer.cpp b/demos/rlSocketDemo/rlSocketDemoServer.cpp index 2be8823e..6bee78a2 100644 --- a/demos/rlSocketDemo/rlSocketDemoServer.cpp +++ b/demos/rlSocketDemo/rlSocketDemoServer.cpp @@ -26,6 +26,7 @@ #include #include +#include #include #include #include From 3f3d2c24c3460be69ed607278086c098188d6ec9 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 2 Jan 2024 16:58:23 +0100 Subject: [PATCH 531/546] Update CodeQL workflow --- .github/workflows/codeql.yml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index 8bea162c..4cfb9594 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -8,13 +8,14 @@ on: - master schedule: - cron: '30 14 * * 2' + workflow_dispatch: jobs: analyze: name: Analyze - runs-on: ubuntu-20.04 + runs-on: ubuntu-22.04 steps: - name: Checkout repository - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Set up PPA run: | sudo apt-get install -y software-properties-common @@ -27,7 +28,7 @@ jobs: libboost-dev libbullet-dev libcomedi-dev - libdc1394-22-dev + libdc1394-dev libeigen3-dev libfcl-dev libnlopt-dev From c2f8621da5625ad9f0e8c3148f888f1f53887610 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 2 Jan 2024 16:58:29 +0100 Subject: [PATCH 532/546] Update CI workflow --- .github/workflows/ci.yml | 290 +++++++++++++++++++++++++-------------- 1 file changed, 186 insertions(+), 104 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 48805b37..28cb7fad 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -6,60 +6,27 @@ on: pull_request: branches: - master + workflow_dispatch: jobs: - build: + build-macos: name: Build runs-on: ${{ matrix.os }} strategy: fail-fast: false matrix: - name: - - macos-11 - - ubuntu-20.04-clang - - ubuntu-20.04-gcc - - windows-2019-msvc - - windows-2019-msys2 - include: - - name: macos-11 - cmake_compiler_launcher: ccache - cmake_prefix_path: /usr/local/opt/qt/lib/cmake - os: macos-11 - - name: ubuntu-20.04-clang - cc: clang - cmake_compiler_launcher: ccache - cxx: clang++ - os: ubuntu-20.04 - - name: ubuntu-20.04-gcc - cc: gcc - cmake_compiler_launcher: ccache - cxx: g++ - os: ubuntu-20.04 - - name: windows-2019-msvc - os: windows-2019 - - name: windows-2019-msys2 - cmake_compiler_launcher: ccache - os: windows-2019 + os: + - macos-12 env: - CC: ${{ matrix.cc }} CCACHE_COMPRESS: true CCACHE_MAXSIZE: 500M - CMAKE_C_COMPILER_LAUNCHER: ${{ matrix.cmake_compiler_launcher }} - CMAKE_CXX_COMPILER_LAUNCHER: ${{ matrix.cmake_compiler_launcher }} - CMAKE_PREFIX_PATH: ${{ matrix.cmake_prefix_path }} - CXX: ${{ matrix.cxx }} + CMAKE_C_COMPILER_LAUNCHER: ccache + CMAKE_CXX_COMPILER_LAUNCHER: ccache steps: - name: Checkout repository - uses: actions/checkout@v3 - - if: matrix.os == 'macos-11' - name: Set up Tap + uses: actions/checkout@v4 + - name: Set up Tap run: brew tap roboticslibrary/rl - - if: matrix.os == 'ubuntu-20.04' - name: Set up PPA - run: | - sudo apt-get install -y software-properties-common - sudo apt-add-repository -y -u ppa:roblib/ppa - - if: matrix.os == 'macos-11' - name: Install dependencies for macOS + - name: Install dependencies run: > brew install boost @@ -73,11 +40,174 @@ jobs: nlopt ode pqp - qt solid soqt - - if: matrix.os == 'ubuntu-20.04' - name: Install dependencies for Ubuntu + - name: Update environment variables + run: | + echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV + echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV + - name: Cache compiler + uses: actions/cache@v3 + with: + path: ${{ runner.workspace }}/.ccache + key: ${{ matrix.os }}-ccache-${{ github.sha }} + restore-keys: ${{ matrix.os }}-ccache- + - name: Configure CMake + run: cmake -GNinja -DCMAKE_BUILD_TYPE=Release -S"${{ github.workspace }}" -B"${{ runner.workspace }}/rl-build" + - name: Build + working-directory: ${{ runner.workspace }}/rl-build + run: cmake --build . + - name: Test + working-directory: ${{ runner.workspace }}/rl-build + run: ctest --output-on-failure + - name: Create archive + working-directory: ${{ runner.workspace }}/rl-build + run: cpack -G TXZ + - name: Upload archive + uses: actions/upload-artifact@v4 + with: + name: ${{ matrix.os }} + path: ${{ runner.workspace }}/rl-build/rl-*.tar.xz + build-msvc: + name: Build + runs-on: ${{ matrix.os }} + strategy: + fail-fast: false + matrix: + os: + - windows-2019 + - windows-2022 + qt: + - qt5 + - qt6 + include: + - os: windows-2019 + toolchain: 14.2 + - os: windows-2022 + toolchain: 14.3 + steps: + - name: Checkout repository + uses: actions/checkout@v4 + - name: Enable Developer Command Prompt + uses: ilammy/msvc-dev-cmd@v1 + - name: Install dependencies + working-directory: ${{ runner.workspace }} + run: | + curl -L https://github.com/roboticslibrary/rl-3rdparty/releases/download/latest/rl-3rdparty-msvc-${{ matrix.toolchain }}-x64-${{ matrix.qt }}.7z -o rl-3rdparty.7z + 7z x rl-3rdparty.7z -orl-3rdparty-install + Write-Output "${{ runner.workspace }}\rl-3rdparty-install\bin" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append + - name: Configure CMake + run: cmake -GNinja -DCMAKE_BUILD_TYPE=Release -S"${{ github.workspace }}" -B"${{ runner.workspace }}/rl-build" + - name: Build + working-directory: ${{ runner.workspace }}/rl-build + run: cmake --build . + - name: Test + working-directory: ${{ runner.workspace }}/rl-build + run: ctest --output-on-failure + - name: Create archive + working-directory: ${{ runner.workspace }}/rl-build + run: cpack -G 7Z + - name: Upload archive + uses: actions/upload-artifact@v4 + with: + name: ${{ matrix.os }}-msvc-${{ matrix.toolchain }}-${{ matrix.qt }} + path: ${{ runner.workspace }}/rl-build/rl-*.7z + build-msys2: + name: Build + runs-on: ${{ matrix.os }} + strategy: + fail-fast: false + matrix: + os: + - windows-2022 + sys: + - ucrt64 + env: + CCACHE_COMPRESS: true + CCACHE_MAXSIZE: 500M + CMAKE_C_COMPILER_LAUNCHER: ccache + CMAKE_CXX_COMPILER_LAUNCHER: ccache + defaults: + run: + shell: msys2 {0} + steps: + - name: Checkout repository + uses: actions/checkout@v4 + - name: Set up MSYS2 + uses: msys2/setup-msys2@v2 + with: + msystem: ${{matrix.sys}} + pacboy: >- + boost:p + bullet:p + ccache:p + cmake:p + coin:p + eigen3:p + libxml2:p + libxslt:p + ninja:p + nlopt:p + ode:p + pqp:p + solid3:p + soqt:p + toolchain:p + update: true + - name: Update environment variables + run: | + echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV + echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV + - name: Cache compiler + uses: actions/cache@v3 + with: + path: ${{ runner.workspace }}/.ccache + key: ${{ matrix.os }}-msys2-${{ matrix.sys }}-ccache-${{ github.sha }} + restore-keys: ${{ matrix.os }}-msys2-${{ matrix.sys }}-ccache- + - name: Configure CMake + run: cmake -GNinja -DCMAKE_BUILD_TYPE=Release -S"${{ github.workspace }}" -B"${{ runner.workspace }}/rl-build" + - name: Build + working-directory: ${{ runner.workspace }}/rl-build + run: cmake --build . + - name: Test + working-directory: ${{ runner.workspace }}/rl-build + run: ctest --output-on-failure + - name: Create archive + working-directory: ${{ runner.workspace }}/rl-build + run: cpack -G TXZ + - name: Upload archive + uses: actions/upload-artifact@v4 + with: + name: ${{ matrix.os }}-msys2-${{ matrix.sys }} + path: ${{ runner.workspace }}/rl-build/rl-*.tar.xz + build-ubuntu: + name: Build + runs-on: ${{ matrix.os }} + strategy: + fail-fast: false + matrix: + os: + - ubuntu-22.04 + compiler: + - cc: clang + cxx: clang++ + - cc: gcc + cxx: g++ + env: + CC: ${{ matrix.compiler.cc }} + CCACHE_COMPRESS: true + CCACHE_MAXSIZE: 500M + CMAKE_C_COMPILER_LAUNCHER: ccache + CMAKE_CXX_COMPILER_LAUNCHER: ccache + CXX: ${{ matrix.compiler.cxx }} + steps: + - name: Checkout repository + uses: actions/checkout@v4 + - name: Set up PPA + run: | + sudo apt-get install -y software-properties-common + sudo apt-add-repository -y -u ppa:roblib/ppa + - name: Install dependencies run: > sudo apt-get install -y build-essential @@ -87,7 +217,7 @@ jobs: libboost-dev libbullet-dev libcomedi-dev - libdc1394-22-dev + libdc1394-dev libeigen3-dev libfcl-dev libnlopt-dev @@ -99,66 +229,18 @@ jobs: libxml2-dev libxslt1-dev ninja-build - - if: matrix.name == 'windows-2019-msvc' - name: Enable Developer Command Prompt - uses: ilammy/msvc-dev-cmd@v1 - - if: matrix.name == 'windows-2019-msvc' - name: Install dependencies for MSVC - working-directory: ${{ runner.workspace }} - run: | - curl -L https://github.com/roboticslibrary/rl-3rdparty/releases/download/latest/rl-3rdparty-msvc-14.2-x64.7z -o rl-3rdparty-msvc-14.2-x64.7z - 7z x rl-3rdparty-msvc-14.2-x64.7z -orl-3rdparty-install - Write-Output "${{ runner.workspace }}\rl-3rdparty-install\bin" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append - - if: matrix.name == 'windows-2019-msys2' - name: Set up MSYS2 - uses: msys2/setup-msys2@v2 - with: - install: >- - mingw-w64-x86_64-boost - mingw-w64-x86_64-bullet - mingw-w64-x86_64-ccache - mingw-w64-x86_64-cmake - mingw-w64-x86_64-coin - mingw-w64-x86_64-eigen3 - mingw-w64-x86_64-gcc - mingw-w64-x86_64-libxml2 - mingw-w64-x86_64-libxslt - mingw-w64-x86_64-ninja - mingw-w64-x86_64-nlopt - mingw-w64-x86_64-ode - mingw-w64-x86_64-pqp - mingw-w64-x86_64-qt5 - mingw-w64-x86_64-solid3 - mingw-w64-x86_64-soqt - update: true - - if: matrix.name == 'windows-2019-msys2' - name: Add MSYS2 to PATH - run: | - Write-Output (msys2 -c "cygpath -w /mingw64/bin") | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append - - if: matrix.os != 'windows-2019' - name: Update environment variables + - name: Update environment variables run: | echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV - - if: matrix.os == 'windows-2019' - name: Update environment variables - run: | - Write-Output "CCACHE_BASEDIR=${{ runner.workspace }}" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append - Write-Output "CCACHE_DIR=${{ runner.workspace }}\.ccache" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append - - if: matrix.cmake_compiler_launcher != '' - name: Cache compiler + - name: Cache compiler uses: actions/cache@v3 with: path: ${{ runner.workspace }}/.ccache - key: ${{ matrix.name }}-ccache-${{ github.sha }} - restore-keys: ${{ matrix.name }}-ccache- + key: ${{ matrix.os }}-${{ matrix.compiler.cc }}-ccache-${{ github.sha }} + restore-keys: ${{ matrix.os }}-${{ matrix.compiler.cc }}-ccache- - name: Configure CMake - run: > - cmake - -GNinja - -DCMAKE_BUILD_TYPE=Release - -S"${{ github.workspace }}" - -B"${{ runner.workspace }}/rl-build" + run: cmake -GNinja -DCMAKE_BUILD_TYPE=Release -S"${{ github.workspace }}" -B"${{ runner.workspace }}/rl-build" - name: Build working-directory: ${{ runner.workspace }}/rl-build run: cmake --build . @@ -167,9 +249,9 @@ jobs: run: ctest --output-on-failure - name: Create archive working-directory: ${{ runner.workspace }}/rl-build - run: cpack -G 7Z - - name: Upload artifacts - uses: actions/upload-artifact@v3 + run: cpack -G TXZ + - name: Upload archive + uses: actions/upload-artifact@v4 with: - name: ${{ matrix.name }} - path: ${{ runner.workspace }}/rl-build/rl-*.7z + name: ${{ matrix.os }}-${{ matrix.compiler.cc }} + path: ${{ runner.workspace }}/rl-build/rl-*.tar.xz From 0b3797215345a1d37903634095361233d190b2e6 Mon Sep 17 00:00:00 2001 From: Kazfyx <1073716894@qq.com> Date: Wed, 21 Feb 2024 03:33:37 +0800 Subject: [PATCH 533/546] fix iterator bugs in path optimizers (#77) --- src/rl/plan/AdvancedOptimizer.cpp | 17 +++++++++++++++-- src/rl/plan/Optimizer.cpp | 11 ++++++++--- src/rl/plan/SimpleOptimizer.cpp | 8 +++++++- 3 files changed, 30 insertions(+), 6 deletions(-) diff --git a/src/rl/plan/AdvancedOptimizer.cpp b/src/rl/plan/AdvancedOptimizer.cpp index fa301b66..b3a9363d 100644 --- a/src/rl/plan/AdvancedOptimizer.cpp +++ b/src/rl/plan/AdvancedOptimizer.cpp @@ -68,7 +68,7 @@ namespace rl { changed = false; - for (VectorList::iterator i = path.begin(), j = ::std::next(i), k = ::std::next(j); i != path.end() && j != path.end() && k != path.end(); ++i, ++j, ++k) + for (VectorList::iterator i = path.begin(), j = ::std::next(i), k = ::std::next(j); i != path.end() && j != path.end() && k != path.end();) { ::rl::math::Real ik = this->getModel()->distance(*i, *k); @@ -76,7 +76,8 @@ namespace rl { ::rl::math::Real ij = this->getModel()->distance(*i, *j); ::rl::math::Real jk = this->getModel()->distance(*j, *k); - this->getModel()->interpolate(*i, *k, ij / (ij + jk), inter); + ::rl::math::Real alpha = ij / (ij + jk); + this->getModel()->interpolate(*i, *k, alpha, inter); ::rl::math::Real ratio = this->getModel()->distance(*j, inter) / ik; if (ratio > this->ratio) @@ -93,6 +94,18 @@ namespace rl changed = true; } + else + { + ++i; + ++j; + ++k; + } + } + else + { + ++i; + ++j; + ++k; } } } diff --git a/src/rl/plan/Optimizer.cpp b/src/rl/plan/Optimizer.cpp index 404c562e..c05ac13a 100644 --- a/src/rl/plan/Optimizer.cpp +++ b/src/rl/plan/Optimizer.cpp @@ -85,12 +85,12 @@ namespace rl bool changed = false; ::rl::math::Vector inter(this->getModel()->getDofPosition()); - for (VectorList::iterator i = path.begin(), j = ::std::next(i); i != path.end() && j != path.end(); ++i, ++j) + for (VectorList::iterator i = path.begin(), j = ::std::next(i); i != path.end() && j != path.end();) { - if (0 == length || this->getModel()->distance(*i, *j) > length) + if (length > 0 && this->getModel()->distance(*i, *j) > length) { this->getModel()->interpolate(*i, *j, static_cast<::rl::math::Real>(0.5), inter); - i = path.insert(j, inter); + j = path.insert(j, inter); if (nullptr != this->getViewer()) { @@ -99,6 +99,11 @@ namespace rl changed = true; } + else + { + ++i; + ++j; + } } return changed; diff --git a/src/rl/plan/SimpleOptimizer.cpp b/src/rl/plan/SimpleOptimizer.cpp index b4c6533a..9f033513 100644 --- a/src/rl/plan/SimpleOptimizer.cpp +++ b/src/rl/plan/SimpleOptimizer.cpp @@ -51,7 +51,7 @@ namespace rl { changed = false; - for (VectorList::iterator i = path.begin(), j = ::std::next(i), k = ::std::next(j); i != path.end() && j != path.end() && k != path.end(); ++i, ++j, ++k) + for (VectorList::iterator i = path.begin(), j = ::std::next(i), k = ::std::next(j); i != path.end() && j != path.end() && k != path.end();) { ::rl::math::Real ik = this->getModel()->distance(*i, *k); @@ -69,6 +69,12 @@ namespace rl changed = true; } + else + { + ++i; + ++j; + ++k; + } } } } From 2a77ceefcf32a667105780c6e1459bea06ee2cdb Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Mon, 4 Mar 2024 21:08:57 +0100 Subject: [PATCH 534/546] Refactor rl::kin::Kinematics::create to rl::kin::XmlFactory --- demos/rlCoachKin/MainWindow.cpp | 4 +- demos/rlPlanDemo/MainWindow.cpp | 8 +- demos/rlPumaDemo/rlPumaDemo.cpp | 4 +- src/rl/kin/CMakeLists.txt | 6 + src/rl/kin/Factory.cpp | 41 ++ src/rl/kin/Factory.h | 57 +++ src/rl/kin/Frame.cpp | 15 +- src/rl/kin/Frame.h | 16 +- src/rl/kin/Joint.h | 12 +- src/rl/kin/Kinematics.cpp | 363 +++--------------- src/rl/kin/Kinematics.h | 24 +- src/rl/kin/Transform.cpp | 15 +- src/rl/kin/Transform.h | 16 +- src/rl/kin/World.cpp | 42 ++ src/rl/kin/World.h | 51 +++ src/rl/kin/XmlFactory.cpp | 356 +++++++++++++++++ src/rl/kin/XmlFactory.h | 53 +++ .../rlInverseKinematicsKinTest.cpp | 4 +- tests/rlJacobianKinTest/rlJacobianKinTest.cpp | 5 +- 19 files changed, 768 insertions(+), 324 deletions(-) create mode 100644 src/rl/kin/Factory.cpp create mode 100644 src/rl/kin/Factory.h create mode 100644 src/rl/kin/World.cpp create mode 100644 src/rl/kin/World.h create mode 100644 src/rl/kin/XmlFactory.cpp create mode 100644 src/rl/kin/XmlFactory.h diff --git a/demos/rlCoachKin/MainWindow.cpp b/demos/rlCoachKin/MainWindow.cpp index c2441ef9..936b1bcd 100644 --- a/demos/rlCoachKin/MainWindow.cpp +++ b/demos/rlCoachKin/MainWindow.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #if QT_VERSION >= 0x060000 @@ -84,11 +85,12 @@ MainWindow::MainWindow(QWidget* parent, Qt::WindowFlags f) : this->scene = std::make_shared(); rl::sg::XmlFactory geometryFactory; geometryFactory.load(QApplication::arguments()[1].toStdString(), this->scene.get()); + rl::kin::XmlFactory kinematicFactory; for (int i = 2; i < QApplication::arguments().size(); ++i) { this->geometryModels.push_back(this->scene->getModel(i - 2)); - this->kinematicModels.push_back(rl::kin::Kinematics::create(QApplication::arguments()[i].toStdString())); + this->kinematicModels.push_back(kinematicFactory.create(QApplication::arguments()[i].toStdString())); } for (std::size_t i = 0; i < this->kinematicModels.size(); ++i) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 47f22434..34d44da7 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -42,6 +42,7 @@ #include #include #include +#include #include #include #include @@ -892,7 +893,8 @@ MainWindow::load(const QString& filename) } else { - this->kin = rl::kin::Kinematics::create(modelKinematicsFilename); + rl::kin::XmlFactory modelFactory; + this->kin = modelFactory.create(modelKinematicsFilename); } if (path.eval("count((/rl/plan|/rlplan)//model/kinematics/world) > 0").getValue()) @@ -1073,8 +1075,8 @@ MainWindow::load(const QString& filename) } else { - rl::xml::NodeSet kin2 = path.eval("(/rl/plan|/rlplan)//viewer/model/kinematics").getValue(); - this->kin2 = rl::kin::Kinematics::create(viewerKinematicsFilename); + rl::kin::XmlFactory modelFactory; + this->kin2 = modelFactory.create(viewerKinematicsFilename); } if (path.eval("count((/rl/plan|/rlplan)//viewer/model/kinematics/world) > 0").getValue()) diff --git a/demos/rlPumaDemo/rlPumaDemo.cpp b/demos/rlPumaDemo/rlPumaDemo.cpp index 25a5c62b..7164a4b0 100644 --- a/demos/rlPumaDemo/rlPumaDemo.cpp +++ b/demos/rlPumaDemo/rlPumaDemo.cpp @@ -34,6 +34,7 @@ #include #include #include +#include #include #include @@ -48,7 +49,8 @@ main(int argc, char** argv) try { - std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[1])); + rl::kin::XmlFactory factory; + std::shared_ptr kinematics(factory.create(argv[1])); if (rl::kin::Puma* puma = dynamic_cast(kinematics.get())) { diff --git a/src/rl/kin/CMakeLists.txt b/src/rl/kin/CMakeLists.txt index 997a7555..38a65a02 100644 --- a/src/rl/kin/CMakeLists.txt +++ b/src/rl/kin/CMakeLists.txt @@ -4,6 +4,7 @@ set( HDRS Element.h Exception.h + Factory.h Frame.h Joint.h Kinematics.h @@ -13,12 +14,15 @@ set( Revolute.h Rhino.h Transform.h + World.h + XmlFactory.h ) set( SRCS Element.cpp Exception.cpp + Factory.cpp Frame.cpp Joint.cpp Kinematics.cpp @@ -28,6 +32,8 @@ set( Revolute.cpp Rhino.cpp Transform.cpp + World.cpp + XmlFactory.cpp ) add_library( diff --git a/src/rl/kin/Factory.cpp b/src/rl/kin/Factory.cpp new file mode 100644 index 00000000..d3c4bfae --- /dev/null +++ b/src/rl/kin/Factory.cpp @@ -0,0 +1,41 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "Factory.h" + +namespace rl +{ + namespace kin + { + Factory::Factory() + { + } + + Factory::~Factory() + { + } + } +} diff --git a/src/rl/kin/Factory.h b/src/rl/kin/Factory.h new file mode 100644 index 00000000..c2fcd871 --- /dev/null +++ b/src/rl/kin/Factory.h @@ -0,0 +1,57 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_KIN_FACTORY_H +#define RL_KIN_FACTORY_H + +#include +#include +#include + +namespace rl +{ + namespace kin + { + class Kinematics; + + class RL_KIN_EXPORT Factory + { + public: + Factory(); + + virtual ~Factory(); + + virtual ::std::shared_ptr create(const ::std::string& filename) = 0; + + protected: + + private: + + }; + } +} + +#endif // RL_KIN_FACTORY_H diff --git a/src/rl/kin/Frame.cpp b/src/rl/kin/Frame.cpp index d6068490..343135fc 100644 --- a/src/rl/kin/Frame.cpp +++ b/src/rl/kin/Frame.cpp @@ -32,12 +32,25 @@ namespace rl { Frame::Frame() : Element(), - frame(::rl::math::Transform::Identity()) + frame(::rl::math::Transform::Identity()), + descriptor() { } Frame::~Frame() { } + + const Frame::Vertex& + Frame::getVertexDescriptor() const + { + return this->descriptor; + } + + void + Frame::setVertexDescriptor(const Vertex& descriptor) + { + this->descriptor = descriptor; + } } } diff --git a/src/rl/kin/Frame.h b/src/rl/kin/Frame.h index b3968995..70afda7e 100644 --- a/src/rl/kin/Frame.h +++ b/src/rl/kin/Frame.h @@ -27,6 +27,7 @@ #ifndef RL_KIN_FRAME_H #define RL_KIN_FRAME_H +#include #include #include "Element.h" @@ -40,16 +41,29 @@ namespace rl public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW + typedef ::boost::adjacency_list< + ::boost::listS, + ::boost::listS, + ::boost::bidirectionalS, + ::boost::listS + > Tree; + + typedef Tree::vertex_descriptor Vertex; + Frame(); virtual ~Frame(); + const Vertex& getVertexDescriptor() const; + + void setVertexDescriptor(const Vertex& descriptor); + ::rl::math::Transform frame; protected: private: - + Vertex descriptor; }; } } diff --git a/src/rl/kin/Joint.h b/src/rl/kin/Joint.h index 76ead66c..0d6ff739 100644 --- a/src/rl/kin/Joint.h +++ b/src/rl/kin/Joint.h @@ -28,6 +28,7 @@ #define RL_KIN_JOINT_H #include +#include #include #include "Transform.h" @@ -39,6 +40,15 @@ namespace rl class RL_KIN_EXPORT Joint : public Transform { public: + typedef ::boost::adjacency_list< + ::boost::listS, + ::boost::listS, + ::boost::bidirectionalS, + ::boost::listS + > Tree; + + typedef Tree::vertex_descriptor Vertex; + Joint(); virtual ~Joint(); @@ -61,7 +71,7 @@ namespace rl ::rl::math::Real d; - ::std::unordered_set<::std::size_t> leaves; + ::std::unordered_set leaves; ::rl::math::Real max; diff --git a/src/rl/kin/Kinematics.cpp b/src/rl/kin/Kinematics.cpp index cc644e32..ed031a02 100644 --- a/src/rl/kin/Kinematics.cpp +++ b/src/rl/kin/Kinematics.cpp @@ -25,28 +25,15 @@ // #include -#include -#include #include -#include -#include -#include -#include -#include -#include -#include -#include "Element.h" #include "Exception.h" #include "Frame.h" #include "Kinematics.h" -#include "Link.h" #include "Joint.h" -#include "Prismatic.h" -#include "Puma.h" -#include "Revolute.h" -#include "Rhino.h" -#include "Transform.h" +#include "Link.h" +#include "World.h" +#include "XmlFactory.h" namespace rl { @@ -75,6 +62,27 @@ namespace rl { } + void + Kinematics::add(const ::std::shared_ptr& frame) + { + Vertex vertex = ::boost::add_vertex(this->tree); + frame->setVertexDescriptor(vertex); + this->tree[vertex] = frame; + + if (::std::dynamic_pointer_cast(frame)) + { + this->root = vertex; + } + } + + void + Kinematics::add(const ::std::shared_ptr& transform, const Frame* a, const Frame* b) + { + Edge edge = ::boost::add_edge(a->getVertexDescriptor(), b->getVertexDescriptor(), this->tree).first; + transform->setEdgeDescriptor(edge); + this->tree[edge] = transform; + } + bool Kinematics::areColliding(const ::std::size_t& i, const ::std::size_t& j) const { @@ -120,296 +128,8 @@ namespace rl ::std::shared_ptr Kinematics::create(const ::std::string& filename) { - ::std::shared_ptr kinematics; - - ::rl::xml::DomParser parser; - - ::rl::xml::Document document = parser.readFile(filename, "", XML_PARSE_NOENT | XML_PARSE_XINCLUDE); - document.substitute(XML_PARSE_NOENT | XML_PARSE_XINCLUDE); - - if ("stylesheet" == document.getRootElement().getName() || "transform" == document.getRootElement().getName()) - { - if ("1.0" == document.getRootElement().getProperty("version")) - { - if (document.getRootElement().hasNamespace() && "http://www.w3.org/1999/XSL/Transform" == document.getRootElement().getNamespace().getHref()) - { - ::rl::xml::Stylesheet stylesheet(document); - document = stylesheet.apply(); - } - } - } - - ::rl::xml::Path path(document); - - ::rl::xml::NodeSet instances = path.eval("(/rl/kin|/rlkin)/kinematics|(/rl/kin|/rlkin)/puma|(/rl/kin|/rlkin)/rhino").getValue<::rl::xml::NodeSet>(); - - if (instances.empty()) - { - throw Exception("rl::kin::Kinematics::create() - No models found in file " + filename); - } - - for (int i = 0; i < ::std::min(1, instances.size()); ++i) - { - ::rl::xml::Path path(document, instances[i]); - - if ("puma" == instances[i].getName()) - { - kinematics = ::std::make_shared(); - } - else if ("rhino" == instances[i].getName()) - { - kinematics = ::std::make_shared(); - } - else if ("kinematics" == instances[i].getName()) - { - kinematics = ::std::make_shared(); - } - else - { - continue; - } - - // manufacturer - - kinematics->manufacturer = path.eval("string(manufacturer)").getValue<::std::string>(); - - // name - - kinematics->name = path.eval("string(name)").getValue<::std::string>(); - - // frames - - ::rl::xml::NodeSet frames = path.eval("frame|link|world").getValue<::rl::xml::NodeSet>(); - - ::std::map<::std::string, Vertex> id2vertex; - - for (int j = 0; j < frames.size(); ++j) - { - ::rl::xml::Path path(document, frames[j]); - - Vertex v = ::boost::add_vertex(kinematics->tree); - - if ("frame" == frames[j].getName()) - { - ::std::shared_ptr f = ::std::make_shared(); - - f->name = path.eval("string(@id)").getValue<::std::string>(); - - f->frame.setIdentity(); - - f->frame = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, - ::rl::math::Vector3::UnitZ() - ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, - ::rl::math::Vector3::UnitY() - ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, - ::rl::math::Vector3::UnitX() - ); - - f->frame.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); - f->frame.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); - f->frame.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); - - kinematics->tree[v] = f; - } - else if ("link" == frames[j].getName()) - { - ::std::shared_ptr l = ::std::make_shared(); - - l->name = path.eval("string(@id)").getValue<::std::string>(); - - kinematics->tree[v] = l; - } - else if ("world" == frames[j].getName()) - { - ::std::shared_ptr f = ::std::make_shared(); - - f->name = path.eval("string(@id)").getValue<::std::string>(); - - f->frame.setIdentity(); - - f->frame = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, - ::rl::math::Vector3::UnitZ() - ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, - ::rl::math::Vector3::UnitY() - ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, - ::rl::math::Vector3::UnitX() - ); - - f->frame.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); - f->frame.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); - f->frame.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); - - kinematics->root = v; - - kinematics->tree[v] = f; - } - - ::std::string id = path.eval("string(@id)").getValue<::std::string>(); - - if (id2vertex.find(id) != id2vertex.end()) - { - throw Exception("Frame with ID " + id + " not unique in file " + filename); - } - - id2vertex[id] = v; - } - - for (int j = 0; j < frames.size(); ++j) - { - ::rl::xml::Path path(document, frames[j]); - - if ("link" == frames[j].getName()) - { - ::std::string v1Id = path.eval("string(@id)").getValue<::std::string>(); - - if (id2vertex.find(v1Id) == id2vertex.end()) - { - throw Exception("Link with ID " + v1Id + " not found in file " + filename); - } - - Vertex v1 = id2vertex[v1Id]; - Link* l1 = dynamic_cast(kinematics->tree[v1].get()); - - ::rl::xml::NodeSet ignores = path.eval("ignore").getValue<::rl::xml::NodeSet>(); - - for (int k = 0; k < ignores.size(); ++k) - { - if (!ignores[k].getProperty("idref").empty()) - { - ::std::string v2IdRef = ignores[k].getProperty("idref"); - - if (id2vertex.find(v2IdRef) == id2vertex.end()) - { - throw Exception("Link with IDREF " + v2IdRef + " in Link with ID " + v1Id + " not found in file " + filename); - } - - Vertex v2 = id2vertex[v2IdRef]; - Link* l2 = dynamic_cast(kinematics->tree[v2].get()); - - l1->selfcollision.insert(l2); - l2->selfcollision.insert(l1); - } - else - { - l1->collision = false; - } - } - } - } - - // transforms - - ::rl::xml::NodeSet transforms = path.eval("prismatic|revolute|transform").getValue<::rl::xml::NodeSet>(); - - for (int j = 0; j < transforms.size(); ++j) - { - ::rl::xml::Path path(document, transforms[j]); - - ::std::string name = path.eval("string(@id)").getValue<::std::string>(); - - ::std::string aIdRef = path.eval("string(frame/a/@idref)").getValue<::std::string>(); - - if (id2vertex.find(aIdRef) == id2vertex.end()) - { - throw Exception("Frame A with IDREF " + aIdRef + " in Transform with ID " + name + " not found in file " + filename); - } - - Vertex a = id2vertex[aIdRef]; - - ::std::string bIdRef = path.eval("string(frame/b/@idref)").getValue<::std::string>(); - - if (id2vertex.find(bIdRef) == id2vertex.end()) - { - throw Exception("Frame B with IDREF " + bIdRef + " in Transform with ID " + name + " not found in file " + filename); - } - - Vertex b = id2vertex[bIdRef]; - - Edge e = ::boost::add_edge(a, b, kinematics->tree).first; - - if ("prismatic" == transforms[j].getName()) - { - ::std::shared_ptr p = ::std::make_shared(); - - p->name = name; - - p->a = path.eval("number(dh/a)").getValue<::rl::math::Real>(0); - p->alpha = path.eval("number(dh/alpha)").getValue<::rl::math::Real>(0); - p->d = path.eval("number(dh/d)").getValue<::rl::math::Real>(0); - p->max = path.eval("number(max)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); - p->min = path.eval("number(min)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); - p->offset = path.eval("number(offset)").getValue<::rl::math::Real>(0); - p->speed = path.eval("number(speed)").getValue<::rl::math::Real>(0); - p->theta = path.eval("number(dh/theta)").getValue<::rl::math::Real>(0); - p->wraparound = path.eval("count(wraparound) > 0").getValue(); - - p->alpha *= ::rl::math::constants::deg2rad; - p->theta *= ::rl::math::constants::deg2rad; - - kinematics->tree[e] = p; - } - else if ("revolute" == transforms[j].getName()) - { - ::std::shared_ptr r = ::std::make_shared(); - - r->name = name; - - r->a = path.eval("number(dh/a)").getValue<::rl::math::Real>(0); - r->alpha = path.eval("number(dh/alpha)").getValue<::rl::math::Real>(0); - r->d = path.eval("number(dh/d)").getValue<::rl::math::Real>(0); - r->max = path.eval("number(max)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); - r->min = path.eval("number(min)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); - r->offset = path.eval("number(offset)").getValue<::rl::math::Real>(0); - r->speed = path.eval("number(speed)").getValue<::rl::math::Real>(0); - r->theta = path.eval("number(dh/theta)").getValue<::rl::math::Real>(0); - r->wraparound = path.eval("count(wraparound) > 0").getValue(); - - r->alpha *= ::rl::math::constants::deg2rad; - r->max *= ::rl::math::constants::deg2rad; - r->min *= ::rl::math::constants::deg2rad; - r->offset *= ::rl::math::constants::deg2rad; - r->speed *= ::rl::math::constants::deg2rad; - r->theta *= ::rl::math::constants::deg2rad; - - kinematics->tree[e] = r; - } - else if ("transform" == transforms[j].getName()) - { - ::std::shared_ptr t = ::std::make_shared(); - - t->name = name; - - t->transform.setIdentity(); - - t->transform = ::rl::math::AngleAxis( - path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, - ::rl::math::Vector3::UnitZ() - ) * ::rl::math::AngleAxis( - path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, - ::rl::math::Vector3::UnitY() - ) * ::rl::math::AngleAxis( - path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, - ::rl::math::Vector3::UnitX() - ); - - t->transform.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); - t->transform.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); - t->transform.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); - - kinematics->tree[e] = t; - } - } - } - - kinematics->update(); - - return kinematics; + XmlFactory factory; + return factory.create(filename); } ::rl::math::Real @@ -856,6 +576,25 @@ namespace rl return this->randDistribution(this->randEngine); } + void + Kinematics::remove(Frame* frame) + { + ::boost::clear_vertex(frame->getVertexDescriptor(), this->tree); + + if (dynamic_cast(frame)) + { + this->root = 0; + } + + ::boost::remove_vertex(frame->getVertexDescriptor(), this->tree); + } + + void + Kinematics::remove(Transform* transform) + { + ::boost::remove_edge(transform->getEdgeDescriptor(), this->tree); + } + void Kinematics::seed(const ::std::mt19937::result_type& value) { @@ -888,6 +627,12 @@ namespace rl } } + void + Kinematics::setManufacturer(const ::std::string& manufacturer) + { + this->manufacturer = manufacturer; + } + void Kinematics::setMaximum(const ::std::size_t& i, const ::rl::math::Real& max) { @@ -926,6 +671,12 @@ namespace rl } } + void + Kinematics::setName(const ::std::string& name) + { + this->name = name; + } + void Kinematics::setPosition(const ::rl::math::Vector& q) { diff --git a/src/rl/kin/Kinematics.h b/src/rl/kin/Kinematics.h index c597eb07..5c0d91d7 100644 --- a/src/rl/kin/Kinematics.h +++ b/src/rl/kin/Kinematics.h @@ -60,6 +60,10 @@ namespace rl virtual ~Kinematics(); + void add(const ::std::shared_ptr& frame); + + void add(const ::std::shared_ptr& transform, const Frame* a, const Frame* b); + /** * See if specified bodies should be tested for collisions with each other. */ @@ -72,7 +76,7 @@ namespace rl */ virtual void clamp(::rl::math::Vector& q) const; - static ::std::shared_ptr create(const ::std::string& filename); + RL_KIN_DEPRECATED static ::std::shared_ptr create(const ::std::string& filename); /** * Calculate distance measure between specified configuration. @@ -262,6 +266,10 @@ namespace rl void normalize(::rl::math::Vector& q) const; + void remove(Frame* frame); + + void remove(Transform* transform); + void seed(const ::std::mt19937::result_type& value); /** @@ -274,6 +282,8 @@ namespace rl */ void setColliding(const ::std::size_t& i, const ::std::size_t& j, const bool& doCollide); + void setManufacturer(const ::std::string& manufacturer); + void setMaximum(const ::std::size_t& i, const ::rl::math::Real& max); void setMaximum(const ::rl::math::Vector& max); @@ -282,6 +292,8 @@ namespace rl void setMinimum(const ::rl::math::Vector& min); + void setName(const ::std::string& name); + /** * Update current joint position. * @@ -301,6 +313,8 @@ namespace rl virtual ::rl::math::Real transformedDistance(const ::rl::math::Real& q1, const ::rl::math::Real& q2, const ::std::size_t& i) const; + virtual void update(); + /** * Update frames. * @@ -338,13 +352,13 @@ namespace rl protected: typedef ::boost::adjacency_list< - ::boost::vecS, - ::boost::vecS, + ::boost::listS, + ::boost::listS, ::boost::bidirectionalS, ::std::shared_ptr, ::std::shared_ptr, ::boost::no_property, - ::boost::vecS + ::boost::listS > Tree; typedef ::boost::graph_traits::edge_descriptor Edge; @@ -367,8 +381,6 @@ namespace rl typedef ::std::pair VertexIteratorPair; - virtual void update(); - void update(Vertex& u); ::std::vector elements; diff --git a/src/rl/kin/Transform.cpp b/src/rl/kin/Transform.cpp index 9089acc4..f55cb963 100644 --- a/src/rl/kin/Transform.cpp +++ b/src/rl/kin/Transform.cpp @@ -35,7 +35,8 @@ namespace rl Element(), in(nullptr), out(nullptr), - transform(::rl::math::Transform::Identity()) + transform(::rl::math::Transform::Identity()), + descriptor() { } @@ -43,6 +44,18 @@ namespace rl { } + const Transform::Edge& + Transform::getEdgeDescriptor() const + { + return this->descriptor; + } + + void + Transform::setEdgeDescriptor(const Edge& descriptor) + { + this->descriptor = descriptor; + } + void Transform::updateFrames() { diff --git a/src/rl/kin/Transform.h b/src/rl/kin/Transform.h index fa310500..89c559dc 100644 --- a/src/rl/kin/Transform.h +++ b/src/rl/kin/Transform.h @@ -27,6 +27,7 @@ #ifndef RL_KIN_TRANSFORM_H #define RL_KIN_TRANSFORM_H +#include #include #include "Element.h" @@ -42,10 +43,23 @@ namespace rl public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW + typedef ::boost::adjacency_list< + ::boost::listS, + ::boost::listS, + ::boost::bidirectionalS, + ::boost::listS + > Tree; + + typedef Tree::edge_descriptor Edge; + Transform(); virtual ~Transform(); + const Edge& getEdgeDescriptor() const; + + void setEdgeDescriptor(const Edge& descriptor); + virtual void updateFrames(); Frame* in; @@ -57,7 +71,7 @@ namespace rl protected: private: - + Edge descriptor; }; } } diff --git a/src/rl/kin/World.cpp b/src/rl/kin/World.cpp new file mode 100644 index 00000000..a98e18bc --- /dev/null +++ b/src/rl/kin/World.cpp @@ -0,0 +1,42 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 "World.h" + +namespace rl +{ + namespace kin + { + World::World() : + Frame() + { + } + + World::~World() + { + } + } +} diff --git a/src/rl/kin/World.h b/src/rl/kin/World.h new file mode 100644 index 00000000..dc6a34fb --- /dev/null +++ b/src/rl/kin/World.h @@ -0,0 +1,51 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_KIN_WORLD_H +#define RL_KIN_WORLD_H + +#include "Frame.h" + +namespace rl +{ + namespace kin + { + class RL_KIN_EXPORT World : public Frame + { + public: + World(); + + virtual ~World(); + + protected: + + private: + + }; + } +} + +#endif // RL_KIN_WORLD_H diff --git a/src/rl/kin/XmlFactory.cpp b/src/rl/kin/XmlFactory.cpp new file mode 100644 index 00000000..c590d26a --- /dev/null +++ b/src/rl/kin/XmlFactory.cpp @@ -0,0 +1,356 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 +#include +#include +#include +#include +#include +#include +#include + +#include "Exception.h" +#include "Joint.h" +#include "Kinematics.h" +#include "Link.h" +#include "Prismatic.h" +#include "Puma.h" +#include "Revolute.h" +#include "Rhino.h" +#include "World.h" +#include "XmlFactory.h" + +namespace rl +{ + namespace kin + { + XmlFactory::XmlFactory() + { + } + + XmlFactory::~XmlFactory() + { + } + + ::std::shared_ptr + XmlFactory::create(const ::std::string& filename) + { + ::std::shared_ptr kinematics; + + ::rl::xml::DomParser parser; + + ::rl::xml::Document document = parser.readFile(filename, "", XML_PARSE_NOENT | XML_PARSE_XINCLUDE); + document.substitute(XML_PARSE_NOENT | XML_PARSE_XINCLUDE); + + if ("stylesheet" == document.getRootElement().getName() || "transform" == document.getRootElement().getName()) + { + if ("1.0" == document.getRootElement().getProperty("version")) + { + if (document.getRootElement().hasNamespace() && "http://www.w3.org/1999/XSL/Transform" == document.getRootElement().getNamespace().getHref()) + { + ::rl::xml::Stylesheet stylesheet(document); + document = stylesheet.apply(); + } + } + } + + ::rl::xml::Path path(document); + + ::rl::xml::NodeSet instances = path.eval("(/rl/kin|/rlkin)/kinematics|(/rl/kin|/rlkin)/puma|(/rl/kin|/rlkin)/rhino").getValue<::rl::xml::NodeSet>(); + + if (instances.empty()) + { + throw Exception("rl::kin::XmlFactory::create() - No models found in file " + filename); + } + + for (int i = 0; i < ::std::min(1, instances.size()); ++i) + { + ::rl::xml::Path path(document, instances[i]); + + if ("puma" == instances[i].getName()) + { + kinematics = ::std::make_shared(); + } + else if ("rhino" == instances[i].getName()) + { + kinematics = ::std::make_shared(); + } + else if ("kinematics" == instances[i].getName()) + { + kinematics = ::std::make_shared(); + } + else + { + continue; + } + + // manufacturer + + kinematics->setManufacturer(path.eval("string(manufacturer)").getValue<::std::string>()); + + // name + + kinematics->setName(path.eval("string(name)").getValue<::std::string>()); + + // frames + + ::rl::xml::NodeSet frames = path.eval("frame|link|world").getValue<::rl::xml::NodeSet>(); + + ::std::unordered_map<::std::string, Frame*> id2frame; + + for (int j = 0; j < frames.size(); ++j) + { + ::rl::xml::Path path(document, frames[j]); + + Frame* frame = nullptr; + + if ("frame" == frames[j].getName()) + { + ::std::shared_ptr f = ::std::make_shared(); + + kinematics->add(f); + + f->frame.linear() = ::rl::math::AngleAxis( + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, + ::rl::math::Vector3::UnitZ() + ) * ::rl::math::AngleAxis( + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, + ::rl::math::Vector3::UnitY() + ) * ::rl::math::AngleAxis( + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, + ::rl::math::Vector3::UnitX() + ).toRotationMatrix(); + + f->frame.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); + f->frame.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); + f->frame.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); + + frame = f.get(); + } + else if ("link" == frames[j].getName()) + { + ::std::shared_ptr l = ::std::make_shared(); + + kinematics->add(l); + + frame = l.get(); + } + else if ("world" == frames[j].getName()) + { + ::std::shared_ptr w = ::std::make_shared(); + + kinematics->add(w); + + w->frame.linear() = ::rl::math::AngleAxis( + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, + ::rl::math::Vector3::UnitZ() + ) * ::rl::math::AngleAxis( + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, + ::rl::math::Vector3::UnitY() + ) * ::rl::math::AngleAxis( + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, + ::rl::math::Vector3::UnitX() + ).toRotationMatrix(); + + w->frame.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); + w->frame.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); + w->frame.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); + + frame = w.get(); + } + + if (nullptr != frame) + { + frame->name = path.eval("string(@id)").getValue<::std::string>(); + + if (id2frame.find(frame->name) != id2frame.end()) + { + throw Exception("rl::kin::XmlFactory::create() - Frame with ID '" + frame->name + "' not unique in file '" + filename + "'"); + } + + id2frame[frame->name] = frame; + } + } + + for (int j = 0; j < frames.size(); ++j) + { + ::rl::xml::Path path(document, frames[j]); + + if ("link" == frames[j].getName()) + { + ::std::string f1Id = path.eval("string(@id)").getValue<::std::string>(); + + if (id2frame.find(f1Id) == id2frame.end()) + { + throw Exception("rl::kin::XmlFactory::create() - Link with ID '" + f1Id + "' not found in file '" + filename + "'"); + } + + Link* l1 = dynamic_cast(id2frame[f1Id]); + + ::rl::xml::NodeSet ignores = path.eval("ignore").getValue<::rl::xml::NodeSet>(); + + for (int k = 0; k < ignores.size(); ++k) + { + if (!ignores[k].getProperty("idref").empty()) + { + ::std::string f2IdRef = ignores[k].getProperty("idref"); + + if (id2frame.find(f2IdRef) == id2frame.end()) + { + throw Exception("rl::kin::XmlFactory::create() - Link with IDREF '" + f2IdRef + "' in Link with ID '" + f1Id + "' not found in file '" + filename + "'"); + } + + Link* l2 = dynamic_cast(id2frame[f2IdRef]); + + l1->selfcollision.insert(l2); + l2->selfcollision.insert(l1); + } + else + { + l1->collision = false; + } + } + } + } + + // transforms + + ::rl::xml::NodeSet transforms = path.eval("prismatic|revolute|transform").getValue<::rl::xml::NodeSet>(); + + for (int j = 0; j < transforms.size(); ++j) + { + ::rl::xml::Path path(document, transforms[j]); + + ::std::string name = path.eval("string(@id)").getValue<::std::string>(); + + ::std::string aIdRef = path.eval("string(frame/a/@idref)").getValue<::std::string>(); + + if (id2frame.find(aIdRef) == id2frame.end()) + { + throw Exception("rl::kin::XmlFactory::create() - Frame A with IDREF '" + aIdRef + "' in Transform with ID '" + name + "' not found in file '" + filename + "'"); + } + + Frame* a = id2frame[aIdRef]; + + ::std::string bIdRef = path.eval("string(frame/b/@idref)").getValue<::std::string>(); + + if (id2frame.find(bIdRef) == id2frame.end()) + { + throw Exception("rl::kin::XmlFactory::create() - Frame B with IDREF '" + bIdRef + "' in Transform with ID '" + name + "' not found in file '" + filename + "'"); + } + + Frame* b = id2frame[bIdRef]; + + Transform* transform = nullptr; + + if ("prismatic" == transforms[j].getName()) + { + ::std::shared_ptr p = ::std::make_shared(); + + kinematics->add(p, a, b); + + p->a = path.eval("number(dh/a)").getValue<::rl::math::Real>(0); + p->alpha = path.eval("number(dh/alpha)").getValue<::rl::math::Real>(0); + p->d = path.eval("number(dh/d)").getValue<::rl::math::Real>(0); + p->max = path.eval("number(max)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + p->min = path.eval("number(min)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + p->offset = path.eval("number(offset)").getValue<::rl::math::Real>(0); + p->speed = path.eval("number(speed)").getValue<::rl::math::Real>(0); + p->theta = path.eval("number(dh/theta)").getValue<::rl::math::Real>(0); + p->wraparound = path.eval("count(wraparound) > 0").getValue(); + + p->alpha *= ::rl::math::constants::deg2rad; + p->theta *= ::rl::math::constants::deg2rad; + + transform = p.get(); + } + else if ("revolute" == transforms[j].getName()) + { + ::std::shared_ptr r = ::std::make_shared(); + + kinematics->add(r, a, b); + + r->a = path.eval("number(dh/a)").getValue<::rl::math::Real>(0); + r->alpha = path.eval("number(dh/alpha)").getValue<::rl::math::Real>(0); + r->d = path.eval("number(dh/d)").getValue<::rl::math::Real>(0); + r->max = path.eval("number(max)").getValue<::rl::math::Real>(::std::numeric_limits<::rl::math::Real>::max()); + r->min = path.eval("number(min)").getValue<::rl::math::Real>(-::std::numeric_limits<::rl::math::Real>::max()); + r->offset = path.eval("number(offset)").getValue<::rl::math::Real>(0); + r->speed = path.eval("number(speed)").getValue<::rl::math::Real>(0); + r->theta = path.eval("number(dh/theta)").getValue<::rl::math::Real>(0); + r->wraparound = path.eval("count(wraparound) > 0").getValue(); + + r->alpha *= ::rl::math::constants::deg2rad; + r->max *= ::rl::math::constants::deg2rad; + r->min *= ::rl::math::constants::deg2rad; + r->offset *= ::rl::math::constants::deg2rad; + r->speed *= ::rl::math::constants::deg2rad; + r->theta *= ::rl::math::constants::deg2rad; + + transform = r.get(); + } + else if ("transform" == transforms[j].getName()) + { + ::std::shared_ptr t = ::std::make_shared(); + + kinematics->add(t, a, b); + + t->transform.setIdentity(); + + t->transform = ::rl::math::AngleAxis( + path.eval("number(rotation/z)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, + ::rl::math::Vector3::UnitZ() + ) * ::rl::math::AngleAxis( + path.eval("number(rotation/y)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, + ::rl::math::Vector3::UnitY() + ) * ::rl::math::AngleAxis( + path.eval("number(rotation/x)").getValue<::rl::math::Real>(0) * ::rl::math::constants::deg2rad, + ::rl::math::Vector3::UnitX() + ); + + t->transform.translation().x() = path.eval("number(translation/x)").getValue<::rl::math::Real>(0); + t->transform.translation().y() = path.eval("number(translation/y)").getValue<::rl::math::Real>(0); + t->transform.translation().z() = path.eval("number(translation/z)").getValue<::rl::math::Real>(0); + + transform = t.get(); + } + + if (nullptr != transform) + { + transform->name = name; + } + } + + kinematics->update(); + } + + return kinematics; + } + } +} diff --git a/src/rl/kin/XmlFactory.h b/src/rl/kin/XmlFactory.h new file mode 100644 index 00000000..bd0bfed8 --- /dev/null +++ b/src/rl/kin/XmlFactory.h @@ -0,0 +1,53 @@ +// +// Copyright (c) 2009, Markus Rickert +// All rights reserved. +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright notice, +// this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above copyright notice, +// this list of conditions and the following disclaimer in the documentation +// and/or other materials provided with the distribution. +// +// 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 RL_KIN_XMLFACTORY_H +#define RL_KIN_XMLFACTORY_H + +#include "Factory.h" + +namespace rl +{ + namespace kin + { + class RL_KIN_EXPORT XmlFactory : public Factory + { + public: + XmlFactory(); + + virtual ~XmlFactory(); + + ::std::shared_ptr create(const ::std::string& filename); + + protected: + + private: + + }; + } +} + +#endif // RL_KIN_XMLFACTORY_H diff --git a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp index 2efa7587..9f6f277e 100644 --- a/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp +++ b/tests/rlInverseKinematicsKinTest/rlInverseKinematicsKinTest.cpp @@ -29,6 +29,7 @@ #include #include #include +#include int main(int argc, char** argv) @@ -43,7 +44,8 @@ main(int argc, char** argv) { std::string filename = argv[1]; - std::shared_ptr kinematics(rl::kin::Kinematics::create(filename)); + rl::kin::XmlFactory factory; + std::shared_ptr kinematics(factory.create(filename)); kinematics->seed(0); for (std::size_t n = 0; n < 100; ++n) diff --git a/tests/rlJacobianKinTest/rlJacobianKinTest.cpp b/tests/rlJacobianKinTest/rlJacobianKinTest.cpp index 36f1d0d7..1cd5c427 100644 --- a/tests/rlJacobianKinTest/rlJacobianKinTest.cpp +++ b/tests/rlJacobianKinTest/rlJacobianKinTest.cpp @@ -29,6 +29,7 @@ #include #include #include +#include #include #include @@ -41,7 +42,9 @@ main(int argc, char** argv) return EXIT_FAILURE; } - std::shared_ptr kinematics(rl::kin::Kinematics::create(argv[1])); + rl::kin::XmlFactory factory; + std::shared_ptr kinematics(factory.create(argv[1])); + std::size_t dof = kinematics->getDof(); std::srand(0); // get reproducible results From 8694418314224f180115d64b9175abb9e119259f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 8 Sep 2024 21:37:42 +0200 Subject: [PATCH 535/546] Update GitHub Actions --- .github/workflows/ci.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 28cb7fad..85b1e388 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -47,7 +47,7 @@ jobs: echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV - name: Cache compiler - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ${{ runner.workspace }}/.ccache key: ${{ matrix.os }}-ccache-${{ github.sha }} @@ -159,7 +159,7 @@ jobs: echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV - name: Cache compiler - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ${{ runner.workspace }}/.ccache key: ${{ matrix.os }}-msys2-${{ matrix.sys }}-ccache-${{ github.sha }} @@ -234,7 +234,7 @@ jobs: echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV echo "CCACHE_DIR=${{ runner.workspace }}/.ccache" >> $GITHUB_ENV - name: Cache compiler - uses: actions/cache@v3 + uses: actions/cache@v4 with: path: ${{ runner.workspace }}/.ccache key: ${{ matrix.os }}-${{ matrix.compiler.cc }}-ccache-${{ github.sha }} From ec616275fd8876493e3a346647481c1ff3e36313 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 8 Sep 2024 21:38:06 +0200 Subject: [PATCH 536/546] Update CI workflow --- .github/workflows/ci.yml | 24 +++++++++++++++++++++++- 1 file changed, 23 insertions(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 85b1e388..ead54eee 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -84,7 +84,12 @@ jobs: - os: windows-2019 toolchain: 14.2 - os: windows-2022 - toolchain: 14.3 + toolchain: 14.4 + env: + CCACHE_COMPRESS: true + CCACHE_MAXSIZE: 500M + CMAKE_C_COMPILER_LAUNCHER: ccache + CMAKE_CXX_COMPILER_LAUNCHER: ccache steps: - name: Checkout repository uses: actions/checkout@v4 @@ -95,7 +100,24 @@ jobs: run: | curl -L https://github.com/roboticslibrary/rl-3rdparty/releases/download/latest/rl-3rdparty-msvc-${{ matrix.toolchain }}-x64-${{ matrix.qt }}.7z -o rl-3rdparty.7z 7z x rl-3rdparty.7z -orl-3rdparty-install + Write-Output "CMAKE_PREFIX_PATH=${{ runner.workspace }}\rl-3rdparty-install" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append Write-Output "${{ runner.workspace }}\rl-3rdparty-install\bin" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append + - name: Install ccache + working-directory: ${{ runner.workspace }} + run: | + curl -L https://github.com/ccache/ccache/releases/download/v4.10.2/ccache-4.10.2-windows-x86_64.zip -o ccache-4.10.2-windows-x86_64.zip + 7z x ccache-4.10.2-windows-x86_64.zip + Write-Output "${{ runner.workspace }}\ccache-4.10.2-windows-x86_64" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append + - name: Update environment variables + run: | + Write-Output "CCACHE_BASEDIR=${{ runner.workspace }}" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append + Write-Output "CCACHE_DIR=${{ runner.workspace }}\.ccache" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append + - name: Cache compiler + uses: actions/cache@v4 + with: + path: ${{ runner.workspace }}/.ccache + key: ${{ matrix.os }}-msvc-${{ matrix.toolchain }}-${{ matrix.qt }}-ccache-${{ github.sha }} + restore-keys: ${{ matrix.os }}-msvc-${{ matrix.toolchain }}-${{ matrix.qt }}-ccache- - name: Configure CMake run: cmake -GNinja -DCMAKE_BUILD_TYPE=Release -S"${{ github.workspace }}" -B"${{ runner.workspace }}/rl-build" - name: Build From a05e05a4667d7ada65044cddffcda1bb9a2ec36d Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 13 Sep 2024 18:37:26 +0200 Subject: [PATCH 537/546] Update CI workflow --- .github/workflows/ci.yml | 23 +++++++++++++---------- 1 file changed, 13 insertions(+), 10 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index ead54eee..660882ed 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -15,7 +15,7 @@ jobs: fail-fast: false matrix: os: - - macos-12 + - macos-14 env: CCACHE_COMPRESS: true CCACHE_MAXSIZE: 500M @@ -24,8 +24,10 @@ jobs: steps: - name: Checkout repository uses: actions/checkout@v4 - - name: Set up Tap + - name: Set up tap run: brew tap roboticslibrary/rl + - name: Update index + run: brew update - name: Install dependencies run: > brew install @@ -33,7 +35,7 @@ jobs: bullet ccache cmake - coin + coin3d eigen fcl ninja @@ -41,7 +43,6 @@ jobs: ode pqp solid - soqt - name: Update environment variables run: | echo "CCACHE_BASEDIR=${{ runner.workspace }}" >> $GITHUB_ENV @@ -82,9 +83,9 @@ jobs: - qt6 include: - os: windows-2019 - toolchain: 14.2 + toolset: 14.2 - os: windows-2022 - toolchain: 14.4 + toolset: 14.4 env: CCACHE_COMPRESS: true CCACHE_MAXSIZE: 500M @@ -98,7 +99,7 @@ jobs: - name: Install dependencies working-directory: ${{ runner.workspace }} run: | - curl -L https://github.com/roboticslibrary/rl-3rdparty/releases/download/latest/rl-3rdparty-msvc-${{ matrix.toolchain }}-x64-${{ matrix.qt }}.7z -o rl-3rdparty.7z + curl -L https://github.com/roboticslibrary/rl-3rdparty/releases/download/latest/rl-3rdparty-msvc-${{ matrix.toolset }}-x64-${{ matrix.qt }}.7z -o rl-3rdparty.7z 7z x rl-3rdparty.7z -orl-3rdparty-install Write-Output "CMAKE_PREFIX_PATH=${{ runner.workspace }}\rl-3rdparty-install" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append Write-Output "${{ runner.workspace }}\rl-3rdparty-install\bin" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append @@ -116,8 +117,8 @@ jobs: uses: actions/cache@v4 with: path: ${{ runner.workspace }}/.ccache - key: ${{ matrix.os }}-msvc-${{ matrix.toolchain }}-${{ matrix.qt }}-ccache-${{ github.sha }} - restore-keys: ${{ matrix.os }}-msvc-${{ matrix.toolchain }}-${{ matrix.qt }}-ccache- + key: ${{ matrix.os }}-msvc-${{ matrix.toolset }}-${{ matrix.qt }}-ccache-${{ github.sha }} + restore-keys: ${{ matrix.os }}-msvc-${{ matrix.toolset }}-${{ matrix.qt }}-ccache- - name: Configure CMake run: cmake -GNinja -DCMAKE_BUILD_TYPE=Release -S"${{ github.workspace }}" -B"${{ runner.workspace }}/rl-build" - name: Build @@ -132,7 +133,7 @@ jobs: - name: Upload archive uses: actions/upload-artifact@v4 with: - name: ${{ matrix.os }}-msvc-${{ matrix.toolchain }}-${{ matrix.qt }} + name: ${{ matrix.os }}-msvc-${{ matrix.toolset }}-${{ matrix.qt }} path: ${{ runner.workspace }}/rl-build/rl-*.7z build-msys2: name: Build @@ -229,6 +230,8 @@ jobs: run: | sudo apt-get install -y software-properties-common sudo apt-add-repository -y -u ppa:roblib/ppa + - name: Update index + run: sudo apt-get update - name: Install dependencies run: > sudo apt-get install -y From 4a8e401b5a3b707fa1c2ce43f349062c8511fe76 Mon Sep 17 00:00:00 2001 From: ahgnuoy <135145432+ahgnuoy@users.noreply.github.com> Date: Sat, 14 Sep 2024 01:55:48 +0900 Subject: [PATCH 538/546] fix memory leak when rl::sg::ode::Shape is destroyed (#92) --- src/rl/sg/ode/Shape.cpp | 6 ++++-- src/rl/sg/ode/Shape.h | 2 ++ 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/rl/sg/ode/Shape.cpp b/src/rl/sg/ode/Shape.cpp index 6c3e5cfa..9d144fc6 100644 --- a/src/rl/sg/ode/Shape.cpp +++ b/src/rl/sg/ode/Shape.cpp @@ -49,6 +49,7 @@ namespace rl ::rl::sg::Shape(body), geom(nullptr), baseTransform(::rl::math::Transform::Identity()), + data(nullptr), indices(), transform(::rl::math::Transform::Identity()), vertices() @@ -92,9 +93,9 @@ namespace rl callbackAction.addTriangleCallback(geometry->getTypeId(), Shape::triangleCallback, this); callbackAction.apply(geometry); - ::dTriMeshDataID data = ::dGeomTriMeshDataCreate(); + this->data = ::dGeomTriMeshDataCreate(); ::dGeomTriMeshDataBuildSimple(data, &this->vertices[0], this->vertices.size() / 4, &this->indices[0], this->indices.size()); - this->geom = ::dCreateTriMesh(static_cast(this->getBody())->space, data, nullptr, nullptr, nullptr); + this->geom = ::dCreateTriMesh(static_cast(this->getBody())->space, this->data, nullptr, nullptr, nullptr); } else if (geometry->isOfType(::SoVRMLSphere::getClassTypeId())) { @@ -121,6 +122,7 @@ namespace rl { this->getBody()->remove(this); ::dGeomDestroy(this->geom); + ::dGeomTriMeshDataDestroy(this->data); } ::rl::math::Transform diff --git a/src/rl/sg/ode/Shape.h b/src/rl/sg/ode/Shape.h index 056dff76..a4b20801 100644 --- a/src/rl/sg/ode/Shape.h +++ b/src/rl/sg/ode/Shape.h @@ -63,6 +63,8 @@ namespace rl ::rl::math::Transform baseTransform; + ::dTriMeshDataID data; + ::std::vector<::dTriIndex> indices; ::rl::math::Transform transform; From 0440811884ea5f79687b3a08667ade98932aba5f Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 Mar 2024 19:08:56 +0100 Subject: [PATCH 539/546] Update desktop entry files --- demos/rlCoachKin/rlCoachKin.desktop.in | 5 +++-- demos/rlCoachMdl/rlCoachMdl.desktop.in | 5 +++-- demos/rlCollisionDemo/rlCollisionDemo.desktop.in | 5 +++-- demos/rlPlanDemo/rlPlanDemo.desktop.in | 5 +++-- .../rlRotationConverterDemo.desktop.in | 5 +++-- demos/rlSimulator/rlSimulator.desktop.in | 5 +++-- demos/rlViewDemo/rlViewDemo.desktop.in | 5 +++-- extras/wrlview/wrlview.desktop | 1 + 8 files changed, 22 insertions(+), 14 deletions(-) diff --git a/demos/rlCoachKin/rlCoachKin.desktop.in b/demos/rlCoachKin/rlCoachKin.desktop.in index 864d5628..7e72a53b 100644 --- a/demos/rlCoachKin/rlCoachKin.desktop.in +++ b/demos/rlCoachKin/rlCoachKin.desktop.in @@ -1,8 +1,9 @@ [Desktop Entry] Categories=Science;Robotics; Comment=Visualization and kinematics demo with Unimation Puma 560 -Exec=sh -c "rlCoachKin $(dirname %k)/../rl-@VERSION@/examples/rlsg/unimation-puma560_boxes.xml $(dirname %k)/../rl-@VERSION@/examples/rlkin/unimation-puma560.xml" +Exec=sh -c "rlCoachKin $(dirname %k)/../rl-@PROJECT_VERSION@/examples/rlsg/unimation-puma560_boxes.xml $(dirname %k)/../rl-@PROJECT_VERSION@/examples/rlkin/unimation-puma560.xml" Icon=robotics-library -Name=Robotics Library (rlCoachKin) +Keywords=Coach;Kinematics;Library;Puma;Robot;Robotics;Visualization; +Name=rlCoachKin Type=Application X-Unity-IconBackgroundColor=#ffffff diff --git a/demos/rlCoachMdl/rlCoachMdl.desktop.in b/demos/rlCoachMdl/rlCoachMdl.desktop.in index 1c3ee0a7..a3b061c6 100644 --- a/demos/rlCoachMdl/rlCoachMdl.desktop.in +++ b/demos/rlCoachMdl/rlCoachMdl.desktop.in @@ -1,8 +1,9 @@ [Desktop Entry] Categories=Science;Robotics; Comment=Visualization and kinematics demo with Unimation Puma 560 -Exec=sh -c "rlCoachMdl $(dirname %k)/../rl-@VERSION@/examples/rlsg/unimation-puma560_boxes.xml $(dirname %k)/../rl-@VERSION@/examples/rlmdl/unimation-puma560.xml" +Exec=sh -c "rlCoachMdl $(dirname %k)/../rl-@PROJECT_VERSION@/examples/rlsg/unimation-puma560_boxes.xml $(dirname %k)/../rl-@PROJECT_VERSION@/examples/rlmdl/unimation-puma560.xml" Icon=robotics-library -Name=Robotics Library (rlCoachMdl) +Keywords=Coach;Kinematics;Library;Puma;Robot;Robotics;Visualization; +Name=rlCoachMdl Type=Application X-Unity-IconBackgroundColor=#ffffff diff --git a/demos/rlCollisionDemo/rlCollisionDemo.desktop.in b/demos/rlCollisionDemo/rlCollisionDemo.desktop.in index c1e1a146..996a5dcd 100644 --- a/demos/rlCollisionDemo/rlCollisionDemo.desktop.in +++ b/demos/rlCollisionDemo/rlCollisionDemo.desktop.in @@ -1,8 +1,9 @@ [Desktop Entry] Categories=Science;Robotics; Comment=Collision detection and distance computation demo with basic scene -Exec=sh -c "rlCollisionDemo $(dirname %k)/../rl-@VERSION@/examples/rlsg/scene.xml" +Exec=sh -c "rlCollisionDemo $(dirname %k)/../rl-@PROJECT_VERSION@/examples/rlsg/scene.xml" Icon=robotics-library -Name=Robotics Library (rlCollisionDemo) +Keywords=Collision;Detection;Distance;Robot;Robotics; +Name=rlCollisionDemo Type=Application X-Unity-IconBackgroundColor=#ffffff diff --git a/demos/rlPlanDemo/rlPlanDemo.desktop.in b/demos/rlPlanDemo/rlPlanDemo.desktop.in index 30d2356a..148c1b3f 100644 --- a/demos/rlPlanDemo/rlPlanDemo.desktop.in +++ b/demos/rlPlanDemo/rlPlanDemo.desktop.in @@ -1,8 +1,9 @@ [Desktop Entry] Categories=Science;Robotics; Comment=Path planning demo with Unimation Puma 560 and RRT algorithm -Exec=sh -c "rlPlanDemo $(dirname %k)/../rl-@VERSION@/examples/rlplan/unimation-puma560_boxes_rrtConCon.mdl.xml" +Exec=sh -c "rlPlanDemo $(dirname %k)/../rl-@PROJECT_VERSION@/examples/rlplan/unimation-puma560_boxes_rrtConCon.mdl.xml" Icon=robotics-library -Name=Robotics Library (rlPlanDemo) +Keywords=Library;Motion;Path;Planning;Puma;Robot;Robotics;RRT; +Name=rlPlanDemo Type=Application X-Unity-IconBackgroundColor=#ffffff diff --git a/demos/rlRotationConverterDemo/rlRotationConverterDemo.desktop.in b/demos/rlRotationConverterDemo/rlRotationConverterDemo.desktop.in index 7a79260f..6ce43311 100644 --- a/demos/rlRotationConverterDemo/rlRotationConverterDemo.desktop.in +++ b/demos/rlRotationConverterDemo/rlRotationConverterDemo.desktop.in @@ -1,8 +1,9 @@ [Desktop Entry] Categories=Science;Robotics; -Comment=Rotation conversion demo +Comment=Rotation conversion demo for axis-angle, rotation matrix, quaternion, and Euler angle representations Exec=rlRotationConverterDemo Icon=robotics-library -Name=Robotics Library (rlRotationConverterDemo) +Keywords=Angle;Axis;Euler;Library;Matrix;Quaternion;Robot;Robotics;Rotation; +Name=rlRotationConverterDemo Type=Application X-Unity-IconBackgroundColor=#ffffff diff --git a/demos/rlSimulator/rlSimulator.desktop.in b/demos/rlSimulator/rlSimulator.desktop.in index 87f27358..d8be2fd6 100644 --- a/demos/rlSimulator/rlSimulator.desktop.in +++ b/demos/rlSimulator/rlSimulator.desktop.in @@ -1,8 +1,9 @@ [Desktop Entry] Categories=Science;Robotics; Comment=Simulation demo with Unimation Puma 560 -Exec=sh -c "rlSimulator $(dirname %k)/../rl-@VERSION@/examples/rlsg/unimation-puma560_boxes.xml $(dirname %k)/../rl-@VERSION@/examples/rlmdl/unimation-puma560.xml" +Exec=sh -c "rlSimulator $(dirname %k)/../rl-@PROJECT_VERSION@/examples/rlsg/unimation-puma560_boxes.xml $(dirname %k)/../rl-@PROJECT_VERSION@/examples/rlmdl/unimation-puma560.xml" Icon=robotics-library -Name=Robotics Library (rlSimulator) +Keywords=Dynamics;Kinematics;Library;Puma;Robot;Robotics;Simulation;Simulator; +Name=rlSimulator Type=Application X-Unity-IconBackgroundColor=#ffffff diff --git a/demos/rlViewDemo/rlViewDemo.desktop.in b/demos/rlViewDemo/rlViewDemo.desktop.in index 11947a76..3bbd4fd6 100644 --- a/demos/rlViewDemo/rlViewDemo.desktop.in +++ b/demos/rlViewDemo/rlViewDemo.desktop.in @@ -1,8 +1,9 @@ [Desktop Entry] Categories=Science;Robotics; Comment=Visualization demo with Unimation Puma 560 -Exec=sh -c "rlViewDemo $(dirname %k)/../rl-@VERSION@/examples/rlsg/unimation-puma560_boxes.xml" +Exec=sh -c "rlViewDemo $(dirname %k)/../rl-@PROJECT_VERSION@/examples/rlsg/unimation-puma560_boxes.xml" Icon=robotics-library -Name=Robotics Library (rlViewDemo) +Keywords=Library;Puma;Robot;Robotics;Visualization; +Name=rlViewDemo Type=Application X-Unity-IconBackgroundColor=#ffffff diff --git a/extras/wrlview/wrlview.desktop b/extras/wrlview/wrlview.desktop index b6422b31..a5c69d8e 100644 --- a/extras/wrlview/wrlview.desktop +++ b/extras/wrlview/wrlview.desktop @@ -3,6 +3,7 @@ Categories=Graphics;3DGraphics; Comment=Viewer for VRML and Open Inventor files Exec=wrlview %f Icon=wrlview +Keywords=Inventor;Open;Viewer;VRML; MimeType=graphics/x-inventor;model/vrml;object/x-inventor;x-world/x-vrml; Name=wrlview Type=Application From 725573ef0b2a3cc1d4d8d7f7344990c8dc662262 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 Mar 2024 19:11:35 +0100 Subject: [PATCH 540/546] Fix whitespace --- demos/rlPlanDemo/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/rlPlanDemo/CMakeLists.txt b/demos/rlPlanDemo/CMakeLists.txt index b3f33d81..c0742f28 100644 --- a/demos/rlPlanDemo/CMakeLists.txt +++ b/demos/rlPlanDemo/CMakeLists.txt @@ -68,7 +68,7 @@ if(QT_FOUND AND SoQt_FOUND AND (RL_BUILD_SG_BULLET OR RL_BUILD_SG_FCL OR RL_BUIL Boost::headers SoQt::SoQt ) - + if(TARGET OpenGL::GL) target_link_libraries(rlPlanDemo OpenGL::GL) else() From e6db11d2234075f32afad05d348ed11c61e3a786 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 8 Mar 2024 19:12:07 +0100 Subject: [PATCH 541/546] Update reload behavior --- extras/wrlview/CMakeLists.txt | 2 +- extras/wrlview/MainWindow.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/extras/wrlview/CMakeLists.txt b/extras/wrlview/CMakeLists.txt index dd60e48c..e3e66b24 100644 --- a/extras/wrlview/CMakeLists.txt +++ b/extras/wrlview/CMakeLists.txt @@ -1,4 +1,4 @@ -project(wrlview VERSION 0.2.1) +project(wrlview VERSION 0.2.2) if(NOT PROJECT_VERSION_TWEAK) set(PROJECT_VERSION_TWEAK 0) diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index 9438051a..cabab1f5 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -654,10 +654,11 @@ MainWindow::load(const QString filename) if (nullptr != this->scene) { this->root->removeChild(this->scene); - this->filename.clear(); - this->setWindowTitle("wrlview"); } + this->filename = absoluteFilename; + this->setWindowTitle("wrlview"); + #if defined(HAVE_SOSTLFILEKIT_H) && defined(HAVE_SOSTLFILEKIT_CONVERT) if (absoluteFilename.endsWith(".stl", Qt::CaseInsensitive)) { @@ -695,7 +696,6 @@ MainWindow::load(const QString filename) } this->root->addChild(this->scene); - this->filename = absoluteFilename; this->setWindowTitle(absoluteFilename + " - wrlview"); } From 7edaf083c6728f967f79ffeb6d485fbacb5a7460 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Fri, 13 Sep 2024 13:10:10 +0200 Subject: [PATCH 542/546] Use isValidColorName instead of deprecated isValidColor --- demos/rlPlanDemo/MainWindow.cpp | 4 ++++ extras/wrlview/MainWindow.cpp | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/demos/rlPlanDemo/MainWindow.cpp b/demos/rlPlanDemo/MainWindow.cpp index 34d44da7..05fcd662 100644 --- a/demos/rlPlanDemo/MainWindow.cpp +++ b/demos/rlPlanDemo/MainWindow.cpp @@ -2173,7 +2173,11 @@ MainWindow::parseCommandLine() { QString background = parser.value(backgroundOption); +#if QT_VERSION >= 0x060400 + if (!QColor::isValidColorName(background)) +#else if (!QColor::isValidColor(background)) +#endif { parser.showHelp(); } diff --git a/extras/wrlview/MainWindow.cpp b/extras/wrlview/MainWindow.cpp index cabab1f5..ff6532e5 100644 --- a/extras/wrlview/MainWindow.cpp +++ b/extras/wrlview/MainWindow.cpp @@ -735,7 +735,11 @@ MainWindow::parseCommandLine() { QString background = parser.value(backgroundOption); +#if QT_VERSION >= 0x060400 + if (!QColor::isValidColorName(background)) +#else if (!QColor::isValidColor(background)) +#endif { parser.showHelp(); } From 52fc029ad08e740f2dc2ec1332f663051b161b3c Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 15 Apr 2025 23:01:33 +0200 Subject: [PATCH 543/546] Fix possible overflow --- demos/rlPlanDemo/ConfigurationSpaceScene.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp index 8043876f..605f86e0 100644 --- a/demos/rlPlanDemo/ConfigurationSpaceScene.cpp +++ b/demos/rlPlanDemo/ConfigurationSpaceScene.cpp @@ -265,7 +265,7 @@ ConfigurationSpaceScene::init() (*MainWindow::instance()->q)(this->axis[1]) ); - this->data.assign(this->steps[0] * this->steps[1], 128); + this->data.assign(static_cast(this->steps[0]) * this->steps[1], 128); #if QT_VERSION >= 0x050500 this->image = QImage(this->data.data(), this->steps[0], this->steps[1], this->steps[0], QImage::Format_Grayscale8); From b1e70f0efb491df588f2557213bf42d472a0071e Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Sun, 13 Apr 2025 19:12:08 +0200 Subject: [PATCH 544/546] Update minimum required CMake version --- CMakeLists.txt | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 13ea685a..87ba44a7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,12 +1,4 @@ -cmake_minimum_required(VERSION 3.1) - -if(POLICY CMP0072) - cmake_policy(SET CMP0072 NEW) -endif() - -if(POLICY CMP0075) - cmake_policy(SET CMP0075 NEW) -endif() +cmake_minimum_required(VERSION 3.1...3.31 FATAL_ERROR) project(rl VERSION 0.7.0) From 96ffb9621432e38a5376e72c216dd8d9be36ca32 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 15 Apr 2025 23:04:38 +0200 Subject: [PATCH 545/546] Update CodeQL workflow --- .github/workflows/codeql.yml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/codeql.yml b/.github/workflows/codeql.yml index 4cfb9594..b68b0a2c 100644 --- a/.github/workflows/codeql.yml +++ b/.github/workflows/codeql.yml @@ -12,7 +12,7 @@ on: jobs: analyze: name: Analyze - runs-on: ubuntu-22.04 + runs-on: ubuntu-24.04 steps: - name: Checkout repository uses: actions/checkout@v4 @@ -41,7 +41,7 @@ jobs: libxslt1-dev ninja-build - name: Initialize CodeQL - uses: github/codeql-action/init@v2 + uses: github/codeql-action/init@v3 with: languages: cpp - name: Configure CMake @@ -55,4 +55,4 @@ jobs: working-directory: ${{ runner.workspace }}/rl-build run: cmake --build . - name: Perform CodeQL analysis - uses: github/codeql-action/analyze@v2 + uses: github/codeql-action/analyze@v3 From 91df9f231ba08dfd6c540edee2838d75508ca848 Mon Sep 17 00:00:00 2001 From: Markus Rickert Date: Tue, 15 Apr 2025 23:04:47 +0200 Subject: [PATCH 546/546] Update CI workflow --- .github/workflows/ci.yml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 660882ed..ba80f3b5 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -106,9 +106,9 @@ jobs: - name: Install ccache working-directory: ${{ runner.workspace }} run: | - curl -L https://github.com/ccache/ccache/releases/download/v4.10.2/ccache-4.10.2-windows-x86_64.zip -o ccache-4.10.2-windows-x86_64.zip - 7z x ccache-4.10.2-windows-x86_64.zip - Write-Output "${{ runner.workspace }}\ccache-4.10.2-windows-x86_64" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append + curl -L https://github.com/ccache/ccache/releases/download/v4.11.2/ccache-4.11.2-windows-x86_64.zip -o ccache-4.11.2-windows-x86_64.zip + 7z x ccache-4.11.2-windows-x86_64.zip + Write-Output "${{ runner.workspace }}\ccache-4.11.2-windows-x86_64" | Out-File -FilePath $Env:GITHUB_PATH -Encoding utf8 -Append - name: Update environment variables run: | Write-Output "CCACHE_BASEDIR=${{ runner.workspace }}" | Out-File -FilePath $Env:GITHUB_ENV -Encoding utf8 -Append @@ -210,7 +210,7 @@ jobs: fail-fast: false matrix: os: - - ubuntu-22.04 + - ubuntu-24.04 compiler: - cc: clang cxx: clang++