Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/master' into js/h_to_hpp
Browse files Browse the repository at this point in the history
Conflicts:
	dart/dynamics/BodyNode.cpp
	dart/dynamics/BodyNode.hpp
	dart/dynamics/InverseKinematics.cpp
	dart/dynamics/Skeleton.hpp
  • Loading branch information
jslee02 committed Apr 26, 2016
2 parents 46ab700 + 579cb2e commit e0dab88
Show file tree
Hide file tree
Showing 14 changed files with 941 additions and 889 deletions.
40 changes: 20 additions & 20 deletions .travis.yml
Original file line number Diff line number Diff line change
@@ -1,35 +1,35 @@
language: cpp

os:
- linux
- osx

sudo: required

dist: trusty

compiler:
- gcc
- clang

env:
- BUILD_TYPE=Debug TREAT_WARNINGS_AS_ERRORS=ON COVERALLS=ON
- BUILD_TYPE=Release TREAT_WARNINGS_AS_ERRORS=ON COVERALLS=OFF

matrix:
exclude:
- os: osx
include:
- os: linux
compiler: gcc
env: BUILD_TYPE=Debug COVERALLS=ON COMPILER=GCC
- os: linux
compiler: gcc
env: BUILD_TYPE=Release COVERALLS=OFF COMPILER=GCC
- os: linux
compiler: clang
env: BUILD_TYPE=Debug COVERALLS=OFF COMPILER=CLANG
- os: linux
compiler: clang
env: BUILD_TYPE=Release COVERALLS=OFF COMPILER=CLANG
- os: osx
compiler: clang
env: BUILD_TYPE=Debug COVERALLS=OFF COMPILER=CLANG
- os: osx
compiler: clang
env: BUILD_TYPE=Release COVERALLS=OFF COMPILER=CLANG

install:
- if [ "$TRAVIS_OS_NAME" = "linux" ]; then 'ci/install_linux.sh' ; fi
- if [ "$TRAVIS_OS_NAME" = "osx" ]; then 'ci/install_osx.sh' ; fi
- 'ci/install.sh'

script:
- mkdir build && cd build
- cmake -DCMAKE_BUILD_TYPE=$BUILD_TYPE -DDART_TREAT_WARNINGS_AS_ERRORS=$TREAT_WARNINGS_AS_ERRORS -DDART_COVERALLS=$COVERALLS ..
- make -j4 all tutorials examples tests test
- if [ $COVERALLS = ON ] && [ "$TRAVIS_OS_NAME" = "linux" ]; then make -j4 coveralls; fi
- 'ci/script.sh'

after_failure:
- cat Testing/Temporary/LastTest.log
Expand Down
7 changes: 7 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,13 @@ if(HAVE_BULLET_COLLISION)
endif()
include_directories("${CMAKE_BINARY_DIR}")

set(DART_INCLUDE_DIRS
"${CMAKE_INSTALL_PREFIX}/include"
"${EIGEN3_INCLUDE_DIRS}")
if(HAVE_BULLET_COLLISION)
list(APPEND DART_INCLUDE_DIRS "${BULLET_INCLUDE_DIRS}")
endif()

#===============================================================================
# Check for non-case-sensitive filesystems
#===============================================================================
Expand Down
5 changes: 5 additions & 0 deletions ci/install.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
if [ "$TRAVIS_PULL_REQUEST" = "false" ] && [ "$COMPILER" = "CLANG" ]; then exit; fi

if [ "$TRAVIS_OS_NAME" = "linux" ]; then 'ci/install_linux.sh' ; fi
if [ "$TRAVIS_OS_NAME" = "osx" ]; then 'ci/install_osx.sh' ; fi

7 changes: 7 additions & 0 deletions ci/script.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
if [ "$TRAVIS_PULL_REQUEST" = "false" ] && [ "$COMPILER" = "CLANG" ]; then exit; fi

mkdir build && cd build
cmake -DCMAKE_BUILD_TYPE=$BUILD_TYPE -DDART_TREAT_WARNINGS_AS_ERRORS=ON -DDART_COVERALLS=$COVERALLS ..
make -j4 tutorials examples tests
if [ $COVERALLS = ON ]; then make -j4 coveralls; else make -j4 test; fi

5 changes: 1 addition & 4 deletions cmake/DARTConfig.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -9,10 +9,7 @@
#===============================================================================
# DART_INCLUDE_DIRS
#===============================================================================
set(DART_INCLUDE_DIRS
"@CMAKE_INSTALL_PREFIX@/include"
"@EIGEN3_INCLUDE_DIRS@"
"@BULLET_INCLUDE_DIRS@")
set(DART_INCLUDE_DIRS "@DART_INCLUDE_DIRS@")

#===============================================================================
# DART_LIBRARIES
Expand Down
4 changes: 2 additions & 2 deletions dart/constraint/BalanceConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -411,11 +411,11 @@ void BalanceConstraint::convertJacobianMethodOutputToGradient(

mInitialPositionsCache = skel->getPositions();

for(size_t i=0; i < skel->getNumJoints(); ++i)
for(std::size_t i=0; i < skel->getNumJoints(); ++i)
skel->getJoint(i)->integratePositions(1.0);

// Clear out the velocities so we don't interfere with other Jacobian methods
for(size_t i=0; i < skel->getNumDofs(); ++i)
for(std::size_t i=0; i < skel->getNumDofs(); ++i)
skel->setVelocity(i, 0.0);

grad = skel->getPositions();
Expand Down
1 change: 1 addition & 0 deletions dart/constraint/ConstraintSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,6 +228,7 @@ void ConstraintSolver::setCollisionDetector(
dtwarn << "[ConstraintSolver::setCollisionDetector] Attempting to assign "
<< "nullptr as the new collision detector to the constraint solver, "
<< "which is not allowed. Ignoring.\n";
return;
}

if (mCollisionDetector == collisionDetector)
Expand Down
27 changes: 20 additions & 7 deletions dart/dynamics/BodyNode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -947,6 +947,13 @@ void BodyNode::removeAllShapeNodes()
//==============================================================================
DART_BAKE_SPECIALIZED_NODE_DEFINITIONS( BodyNode, EndEffector )

//==============================================================================
EndEffector* BodyNode::createEndEffector(
const EndEffector::BasicProperties& _properties)
{
return createNode<EndEffector>(_properties);
}

//==============================================================================
EndEffector* BodyNode::createEndEffector(const std::string& _name)
{
Expand Down Expand Up @@ -978,6 +985,12 @@ Marker* BodyNode::createMarker(const std::string& name,
return createNode<Marker>(properties);
}

//==============================================================================
Marker* BodyNode::createMarker(const Marker::BasicProperties& properties)
{
return createNode<Marker>(properties);
}

//==============================================================================
bool BodyNode::dependsOn(std::size_t _genCoordIndex) const
{
Expand Down Expand Up @@ -1399,8 +1412,8 @@ void BodyNode::processNewEntity(Entity* _newChildEntity)

// Check if it's a child BodyNode (if not, then it's just some other arbitrary
// type of Entity)
if(find(mChildBodyNodes.begin(), mChildBodyNodes.end(), _newChildEntity) !=
mChildBodyNodes.end())
if(std::find(mChildBodyNodes.begin(), mChildBodyNodes.end(),
_newChildEntity) != mChildBodyNodes.end())
return;

// Check if it's already accounted for in our Non-BodyNode Entities
Expand All @@ -1419,17 +1432,17 @@ void BodyNode::processNewEntity(Entity* _newChildEntity)
//==============================================================================
void BodyNode::processRemovedEntity(Entity* _oldChildEntity)
{
std::vector<BodyNode*>::iterator it = find(mChildBodyNodes.begin(),
mChildBodyNodes.end(),
_oldChildEntity);
std::vector<BodyNode*>::iterator it = std::find(mChildBodyNodes.begin(),
mChildBodyNodes.end(),
_oldChildEntity);
if(it != mChildBodyNodes.end())
mChildBodyNodes.erase(it);

if(JacobianNode* node = dynamic_cast<JacobianNode*>(_oldChildEntity))
mChildJacobianNodes.erase(node);

if(find(mNonBodyNodeEntities.begin(), mNonBodyNodeEntities.end(),
_oldChildEntity) != mNonBodyNodeEntities.end())
if(std::find(mNonBodyNodeEntities.begin(), mNonBodyNodeEntities.end(),
_oldChildEntity) != mNonBodyNodeEntities.end())
mNonBodyNodeEntities.erase(_oldChildEntity);
}

Expand Down
9 changes: 6 additions & 3 deletions dart/dynamics/BodyNode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class Marker;
/// BodyNode of the BodyNode.
class BodyNode :
public detail::BodyNodeCompositeBase,
public virtual BodyNodeSpecializedFor<ShapeNode, EndEffector>,
public virtual BodyNodeSpecializedFor<ShapeNode, EndEffector, Marker>,
public SkeletonRefCountingBase,
public TemplatedJacobianNode<BodyNode>
{
Expand Down Expand Up @@ -596,8 +596,8 @@ class BodyNode :

/// Create an EndEffector attached to this BodyNode. Pass an
/// EndEffector::Properties argument into this function.
template <class EndEffectorProperties>
EndEffector* createEndEffector(const EndEffectorProperties& _properties);
EndEffector* createEndEffector(
const EndEffector::BasicProperties& _properties);

/// Create an EndEffector with the specified name
EndEffector* createEndEffector(const std::string& _name = "EndEffector");
Expand All @@ -613,6 +613,9 @@ class BodyNode :
const Eigen::Vector3d& position = Eigen::Vector3d::Zero(),
const Eigen::Vector4d& color = Eigen::Vector4d::Constant(1.0));

/// Create a Marker given its basic properties
Marker* createMarker(const Marker::BasicProperties& properties);

// Documentation inherited
bool dependsOn(std::size_t _genCoordIndex) const override;

Expand Down
28 changes: 14 additions & 14 deletions dart/dynamics/InverseKinematics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,9 +95,9 @@ bool InverseKinematics::solve(bool _applySolution)

// Many GradientMethod implementations use Joint::integratePositions, so we
// need to clear out any velocities that might be in the Skeleton and then
// reset those velocities later.
// reset those velocities later. This has been opened as issue #699.
Eigen::VectorXd originalVelocities = skel->getVelocities();
for(size_t i=0; i < skel->getNumDofs(); ++i)
for(std::size_t i=0; i < skel->getNumDofs(); ++i)
skel->getDof(i)->setVelocity(0.0);

if(_applySolution)
Expand Down Expand Up @@ -709,23 +709,23 @@ InverseKinematics::GradientMethod::getComponentWeights() const

//==============================================================================
void InverseKinematics::GradientMethod::convertJacobianMethodOutputToGradient(
Eigen::VectorXd& grad, const std::vector<size_t>& dofs)
Eigen::VectorXd& grad, const std::vector<std::size_t>& dofs)
{
const SkeletonPtr& skel = mIK->getNode()->getSkeleton();
mInitialPositionsCache = skel->getPositions(dofs);

for(size_t i=0; i < dofs.size(); ++i)
for(std::size_t i=0; i < dofs.size(); ++i)
skel->getDof(dofs[i])->setVelocity(grad[i]);
// Velocities of unused DOFs should already be set to zero.

for(size_t i=0; i < dofs.size(); ++i)
for(std::size_t i=0; i < dofs.size(); ++i)
{
Joint* joint = skel->getDof(dofs[i])->getJoint();
joint->integratePositions(1.0);

// Reset this joint's velocities to zero to avoid double-integrating
const size_t numJointDofs = joint->getNumDofs();
for(size_t j=0; j < numJointDofs; ++j)
const std::size_t numJointDofs = joint->getNumDofs();
for(std::size_t j=0; j < numJointDofs; ++j)
joint->setVelocity(j, 0.0);
}

Expand Down Expand Up @@ -866,7 +866,7 @@ InverseKinematics::Analytical::Solution::Solution(

//==============================================================================
InverseKinematics::Analytical::UniqueProperties::UniqueProperties(
ExtraDofUtilization_t extraDofUtilization, double extraErrorLengthClamp)
ExtraDofUtilization extraDofUtilization, double extraErrorLengthClamp)
: mExtraDofUtilization(extraDofUtilization),
mExtraErrorLengthClamp(extraErrorLengthClamp)
{
Expand All @@ -875,7 +875,7 @@ InverseKinematics::Analytical::UniqueProperties::UniqueProperties(

//==============================================================================
InverseKinematics::Analytical::UniqueProperties::UniqueProperties(
ExtraDofUtilization_t extraDofUtilization,
ExtraDofUtilization extraDofUtilization,
double extraErrorLengthClamp,
QualityComparison qualityComparator)
: mExtraDofUtilization(extraDofUtilization),
Expand Down Expand Up @@ -1031,7 +1031,7 @@ const std::vector<IK::Analytical::Solution>& IK::Analytical::getSolutions(
void InverseKinematics::Analytical::addExtraDofGradient(
Eigen::VectorXd& grad,
const Eigen::Vector6d& error,
ExtraDofUtilization_t /*utilization*/)
ExtraDofUtilization /*utilization*/)
{
mExtraDofGradCache.resize(mExtraDofs.size());
const math::Jacobian& J = mIK->computeJacobian();
Expand All @@ -1049,9 +1049,9 @@ void InverseKinematics::Analytical::addExtraDofGradient(

convertJacobianMethodOutputToGradient(mExtraDofGradCache, mExtraDofs);

for(size_t i=0; i < mExtraDofs.size(); ++i)
for(std::size_t i=0; i < mExtraDofs.size(); ++i)
{
size_t depIndex = mExtraDofs[i];
std::size_t depIndex = mExtraDofs[i];
int gradIndex = gradMap[depIndex];
if(gradIndex == -1)
continue;
Expand Down Expand Up @@ -1160,13 +1160,13 @@ Eigen::VectorXd InverseKinematics::Analytical::getPositions() const

//==============================================================================
void InverseKinematics::Analytical::setExtraDofUtilization(
ExtraDofUtilization_t _utilization)
ExtraDofUtilization _utilization)
{
mAnalyticalP.mExtraDofUtilization = _utilization;
}

//==============================================================================
IK::Analytical::ExtraDofUtilization_t
IK::Analytical::ExtraDofUtilization
IK::Analytical::getExtraDofUtilization() const
{
return mAnalyticalP.mExtraDofUtilization;
Expand Down
Loading

0 comments on commit e0dab88

Please sign in to comment.