Skip to content

Commit

Permalink
w3
Browse files Browse the repository at this point in the history
  • Loading branch information
jslee02 committed Apr 5, 2024
1 parent 7b90079 commit f237b49
Show file tree
Hide file tree
Showing 20 changed files with 68 additions and 68 deletions.
2 changes: 1 addition & 1 deletion dart/dynamics/BodyNode.cpp
Expand Up @@ -1383,7 +1383,7 @@ void BodyNode::init(const SkeletonPtr& _skeleton)
mConstDependentDofs.push_back(_skeleton->getDof(index));
}

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
// Check whether there is duplicated indices.
std::size_t nDepGenCoordIndices = mDependentGenCoordIndices.size();
for (std::size_t i = 0; i < nDepGenCoordIndices; ++i) {
Expand Down
6 changes: 3 additions & 3 deletions dart/dynamics/EulerJoint.cpp
Expand Up @@ -209,7 +209,7 @@ Eigen::Matrix<double, 6, 3> EulerJoint::getRelativeJacobianStatic(
J1 << s2, c2, 0.0, 0.0, 0.0, 0.0;
J2 << 0.0, 0.0, 1.0, 0.0, 0.0, 0.0;

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
if (std::abs(getPositionsStatic()[1]) == math::constantsd::pi() * 0.5)
std::cout << "Singular configuration in ZYX-euler joint ["
<< Joint::mAspectProperties.mName << "]. (" << _positions[0]
Expand All @@ -232,7 +232,7 @@ Eigen::Matrix<double, 6, 3> EulerJoint::getRelativeJacobianStatic(
J1 << 0.0, c2, -s2, 0.0, 0.0, 0.0;
J2 << 1.0, 0.0, 0.0, 0.0, 0.0, 0.0;

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
if (std::abs(_positions[1]) == math::constantsd::pi() * 0.5)
std::cout << "Singular configuration in ZYX-euler joint ["
<< Joint::mAspectProperties.mName << "]. (" << _positions[0]
Expand All @@ -254,7 +254,7 @@ Eigen::Matrix<double, 6, 3> EulerJoint::getRelativeJacobianStatic(

assert(!math::isNan(J));

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
Eigen::MatrixXd JTJ = J.transpose() * J;
Eigen::FullPivLU<Eigen::MatrixXd> luJTJ(JTJ);
// Eigen::FullPivLU<Eigen::MatrixXd> luS(mS);
Expand Down
4 changes: 2 additions & 2 deletions dart/dynamics/Node.cpp
Expand Up @@ -189,7 +189,7 @@ void Node::attach()

// If we are in release mode, and the Node believes it is attached, then we
// can shortcut this procedure
#if DART_BUILD_MODE_RELEASE
#ifdef NDEBUG
if (mAmAttached)
return;
#endif
Expand Down Expand Up @@ -241,7 +241,7 @@ void Node::stageForRemoval()

// If we are in release mode, and the Node believes it is detached, then we
// can shortcut this procedure.
#if DART_BUILD_MODE_RELEASE
#ifdef NDEBUG
if (!mAmAttached)
return;
#endif
Expand Down
12 changes: 6 additions & 6 deletions dart/dynamics/Skeleton.cpp
Expand Up @@ -2106,7 +2106,7 @@ void Skeleton::constructNewTree()
//==============================================================================
void Skeleton::registerBodyNode(BodyNode* _newBodyNode)
{
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
std::vector<BodyNode*>::iterator repeat = std::find(
mSkelCache.mBodyNodes.begin(), mSkelCache.mBodyNodes.end(), _newBodyNode);
if (repeat != mSkelCache.mBodyNodes.end()) {
Expand Down Expand Up @@ -2155,7 +2155,7 @@ void Skeleton::registerBodyNode(BodyNode* _newBodyNode)
updateTotalMass();
updateCacheDimensions(_newBodyNode->mTreeIndex);

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i) {
if (mSkelCache.mBodyNodes[i]->mIndexInSkeleton != i) {
dterr << "[Skeleton::registerBodyNode] BodyNode named ["
Expand Down Expand Up @@ -3656,7 +3656,7 @@ void Skeleton::updateBiasImpulse(BodyNode* _bodyNode)
// This skeleton should contain _bodyNode
assert(_bodyNode->getSkeleton().get() == this);

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
// All the constraint impulse should be zero
for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i)
assert(
Expand Down Expand Up @@ -3687,7 +3687,7 @@ void Skeleton::updateBiasImpulse(
// This skeleton should contain _bodyNode
assert(_bodyNode->getSkeleton().get() == this);

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
// All the constraint impulse should be zero
for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i)
assert(
Expand Down Expand Up @@ -3734,7 +3734,7 @@ void Skeleton::updateBiasImpulse(
assert(_bodyNode1->getSkeleton().get() == this);
assert(_bodyNode2->getSkeleton().get() == this);

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
// All the constraint impulse should be zero
for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i)
assert(
Expand Down Expand Up @@ -3775,7 +3775,7 @@ void Skeleton::updateBiasImpulse(
std::find(mSoftBodyNodes.begin(), mSoftBodyNodes.end(), _softBodyNode)
!= mSoftBodyNodes.end());

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
// All the constraint impulse should be zero
for (std::size_t i = 0; i < mSkelCache.mBodyNodes.size(); ++i)
assert(
Expand Down
2 changes: 1 addition & 1 deletion dart/math/Geometry.cpp
Expand Up @@ -1478,7 +1478,7 @@ bool verifyTransform(const Eigen::Isometry3d& _T)

Eigen::Vector3d fromSkewSymmetric(const Eigen::Matrix3d& _m)
{
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
if (std::abs(_m(0, 0)) > DART_EPSILON || std::abs(_m(1, 1)) > DART_EPSILON
|| std::abs(_m(2, 2)) > DART_EPSILON) {
dtwarn << "[math::fromSkewSymmetric] Not skew a symmetric matrix:\n"
Expand Down
2 changes: 1 addition & 1 deletion examples/wam_ikfast/Helpers.cpp
Expand Up @@ -109,7 +109,7 @@ void setupEndEffectors(const dart::dynamics::SkeletonPtr& wam)

std::stringstream ss;
ss << DART_SHARED_LIB_PREFIX << "wamIk";
#if (DART_OS_LINUX || DART_OS_MACOS) && DART_BUILD_MODE_DEBUG
#if (DART_OS_LINUX || DART_OS_MACOS) && !defined(NDEBUG)
ss << "d";
#endif
ss << "." << DART_SHARED_LIB_EXTENSION;
Expand Down
8 changes: 4 additions & 4 deletions python/dartpy/eigen_geometry_pybind.cpp
Expand Up @@ -34,12 +34,12 @@

#include "eigen_geometry_pybind.h"

#include <cassert>
#include <cmath>
#include "pybind11/pybind11.h"

#include <dart/common/common.hpp>

#include "pybind11/pybind11.h"
#include <cassert>
#include <cmath>

using std::fabs;

Expand All @@ -60,7 +60,7 @@ namespace {

// N.B. Use a loose tolerance, so that we don't have to be super strict with
// C++.
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
const double kCheckTolerance = 1e-5;
#endif

Expand Down
4 changes: 2 additions & 2 deletions tests/integration/test_Constraint.cpp
Expand Up @@ -112,7 +112,7 @@ void ConstraintTest::SingleContactTest(const std::string& /*_fileName*/)
// Settings
//----------------------------------------------------------------------------
// Number of random state tests for each skeletons
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
// std::size_t testCount = 1;
#else
// std::size_t testCount = 1;
Expand Down Expand Up @@ -222,7 +222,7 @@ TEST_F(ConstraintTest, SingleContactTest)
{
// for (int i = 0; i < getList().size(); ++i)
// {
// #if DART_BUILD_MODE_DEBUG
// #ifndef NDEBUG
// dtdbg << getList()[i] << std::endl;
// #endif
// SingleContactTest(getList()[i]);
Expand Down
46 changes: 23 additions & 23 deletions tests/integration/test_Dynamics.cpp
Expand Up @@ -862,7 +862,7 @@ void DynamicsTest::testJacobians(const common::Uri& uri)

//----------------------------- Settings -------------------------------------
const double TOLERANCE = 1.0e-6;
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
int nTestItr = 2;
#else
int nTestItr = 5;
Expand Down Expand Up @@ -958,7 +958,7 @@ void DynamicsTest::testJacobians(const common::Uri& uri)

compareBodyNodeFkToJacobianRelative(bn, bn, Frame::World(), TOLERANCE);

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
if (skeleton->getNumBodyNodes() == 0u)
continue;

Expand Down Expand Up @@ -1034,7 +1034,7 @@ void DynamicsTest::testFiniteDifferenceGeneralizedCoordinates(
using namespace utils;

//----------------------------- Settings -------------------------------------
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
int nRandomItr = 2;
#else
int nRandomItr = 10;
Expand Down Expand Up @@ -1121,7 +1121,7 @@ void DynamicsTest::testFiniteDifferenceBodyNodeVelocity(const common::Uri& uri)
using namespace utils;

//----------------------------- Settings -------------------------------------
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
int nRandomItr = 2;
std::size_t numSteps = 1e+1;
#else
Expand Down Expand Up @@ -1211,7 +1211,7 @@ void DynamicsTest::testFiniteDifferenceBodyNodeAcceleration(

//----------------------------- Settings -------------------------------------
const double TOLERANCE = 1.0e-2;
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
int nRandomItr = 2;
#else
int nRandomItr = 10;
Expand Down Expand Up @@ -1342,7 +1342,7 @@ void DynamicsTest::testFiniteDifferenceBodyNodeAcceleration(
//==============================================================================
void testForwardKinematicsSkeleton(const dynamics::SkeletonPtr& skel)
{
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
std::size_t nRandomItr = 1e+1;
std::size_t numSteps = 1e+1;
#else
Expand Down Expand Up @@ -1471,7 +1471,7 @@ void DynamicsTest::testInverseDynamics(const common::Uri& uri)
{
//---------------------------- Settings --------------------------------------
// Number of random state tests for each skeleton
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
const std::size_t nRandomItr = 2;
#else
const std::size_t nRandomItr = 100;
Expand Down Expand Up @@ -1554,7 +1554,7 @@ void DynamicsTest::compareEquationsOfMotion(const common::Uri& uri)

//---------------------------- Settings --------------------------------------
// Number of random state tests for each skeletons
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
std::size_t nRandomItr = 2;
#else
std::size_t nRandomItr = 100;
Expand Down Expand Up @@ -1831,7 +1831,7 @@ void DynamicsTest::testCenterOfMass(const common::Uri& uri)

//---------------------------- Settings --------------------------------------
// Number of random state tests for each skeletons
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
std::size_t nRandomItr = 2;
#else
std::size_t nRandomItr = 100;
Expand Down Expand Up @@ -1984,7 +1984,7 @@ void DynamicsTest::testCenterOfMassFreeFall(const common::Uri& uri)

//---------------------------- Settings --------------------------------------
// Number of random state tests for each skeletons
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
std::size_t nRandomItr = 2;
#else
std::size_t nRandomItr = 10;
Expand Down Expand Up @@ -2021,7 +2021,7 @@ void DynamicsTest::testCenterOfMassFreeFall(const common::Uri& uri)
auto dof = skel->getNumDofs();

if (nullptr == rootFreeJoint || !skel->isMobile() || 0 == dof) {
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtmsg << "Skipping COM free fall test for Skeleton [" << skel->getName()
<< "] since the Skeleton doesn't have FreeJoint at the root body "
<< " or immobile." << endl;
Expand Down Expand Up @@ -2090,7 +2090,7 @@ void DynamicsTest::testConstraintImpulse(const common::Uri& uri)

//---------------------------- Settings --------------------------------------
// Number of random state tests for each skeletons
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
std::size_t nRandomItr = 1;
#else
std::size_t nRandomItr = 1;
Expand Down Expand Up @@ -2177,7 +2177,7 @@ void DynamicsTest::testImpulseBasedDynamics(const common::Uri& uri)

//---------------------------- Settings --------------------------------------
// Number of random state tests for each skeletons
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
std::size_t nRandomItr = 1;
#else
std::size_t nRandomItr = 100;
Expand Down Expand Up @@ -2260,7 +2260,7 @@ void DynamicsTest::testImpulseBasedDynamics(const common::Uri& uri)
TEST_F(DynamicsTest, testJacobians)
{
for (std::size_t i = 0; i < getList().size(); ++i) {
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtdbg << getList()[i].toString() << std::endl;
#endif
testJacobians(getList()[i]);
Expand All @@ -2271,7 +2271,7 @@ TEST_F(DynamicsTest, testJacobians)
TEST_F(DynamicsTest, testFiniteDifference)
{
for (std::size_t i = 0; i < getList().size(); ++i) {
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtdbg << getList()[i].toString() << std::endl;
#endif
testFiniteDifferenceGeneralizedCoordinates(getList()[i]);
Expand All @@ -2284,7 +2284,7 @@ TEST_F(DynamicsTest, testFiniteDifference)
TEST_F(DynamicsTest, testForwardKinematics)
{
for (std::size_t i = 0; i < getList().size(); ++i) {
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtdbg << getList()[i].toString() << std::endl;
#endif
testForwardKinematics(getList()[i]);
Expand All @@ -2295,7 +2295,7 @@ TEST_F(DynamicsTest, testForwardKinematics)
TEST_F(DynamicsTest, testInverseDynamics)
{
for (std::size_t i = 0; i < getList().size(); ++i) {
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtdbg << getList()[i].toString() << std::endl;
#endif
testInverseDynamics(getList()[i]);
Expand All @@ -2321,7 +2321,7 @@ TEST_F(DynamicsTest, compareEquationsOfMotion)
}
////////////////////////////////////////////////////////////////////////////

#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtdbg << getList()[i].toString() << std::endl;
#endif
compareEquationsOfMotion(getList()[i]);
Expand All @@ -2332,7 +2332,7 @@ TEST_F(DynamicsTest, compareEquationsOfMotion)
TEST_F(DynamicsTest, testCenterOfMass)
{
for (std::size_t i = 0; i < getList().size(); ++i) {
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtdbg << getList()[i].toString() << std::endl;
#endif
testCenterOfMass(getList()[i]);
Expand All @@ -2343,7 +2343,7 @@ TEST_F(DynamicsTest, testCenterOfMass)
TEST_F(DynamicsTest, testCenterOfMassFreeFall)
{
for (std::size_t i = 0; i < getList().size(); ++i) {
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtdbg << getList()[i].toString() << std::endl;
#endif
testCenterOfMassFreeFall(getList()[i]);
Expand All @@ -2354,7 +2354,7 @@ TEST_F(DynamicsTest, testCenterOfMassFreeFall)
TEST_F(DynamicsTest, testConstraintImpulse)
{
for (std::size_t i = 0; i < getList().size(); ++i) {
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtdbg << getList()[i].toString() << std::endl;
#endif
testConstraintImpulse(getList()[i]);
Expand All @@ -2365,7 +2365,7 @@ TEST_F(DynamicsTest, testConstraintImpulse)
TEST_F(DynamicsTest, testImpulseBasedDynamics)
{
for (std::size_t i = 0; i < getList().size(); ++i) {
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
dtdbg << getList()[i].toString() << std::endl;
#endif
testImpulseBasedDynamics(getList()[i]);
Expand All @@ -2377,7 +2377,7 @@ TEST_F(DynamicsTest, HybridDynamics)
{
const double tol = 1e-8;
const double timeStep = 1e-3;
#if DART_BUILD_MODE_DEBUG
#ifndef NDEBUG
const std::size_t numFrames = 50; // 0.05 secs
#else
const std::size_t numFrames = 5e+3; // 5 secs
Expand Down
2 changes: 1 addition & 1 deletion tests/integration/test_IkFast.cpp
Expand Up @@ -134,7 +134,7 @@ TEST(IkFast, LoadWamArmIk)
ik->setHierarchyLevel(1);
std::stringstream ss;
ss << DART_SHARED_LIB_PREFIX << "GeneratedWamIkFast";
#if (DART_OS_LINUX || DART_OS_MACOS) && DART_BUILD_MODE_DEBUG
#if (DART_OS_LINUX || DART_OS_MACOS) && !defined(NDEBUG)
ss << "d";
#endif
ss << "." << DART_SHARED_LIB_EXTENSION;
Expand Down

0 comments on commit f237b49

Please sign in to comment.