Skip to content

Commit

Permalink
Fix servo motor doesn't respect joint position limits
Browse files Browse the repository at this point in the history
  • Loading branch information
Jeongseok Lee committed Jul 7, 2021
1 parent 2cb0ec4 commit c5e4de0
Show file tree
Hide file tree
Showing 22 changed files with 1,001 additions and 180 deletions.
4 changes: 4 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,10 @@
* Fixed incorrect MultiSphereConvexHull rendering: [#1579](https://github.com/dartsim/dart/pull/1579)
* Use GLVND over the legacy OpenGL libraries: [#1584](https://github.com/dartsim/dart/pull/1584)

* Build and testing

* Add DART_ prefix to macros to avoid potential conflicts: [#1586](https://github.com/dartsim/dart/pull/1586)

### [DART 6.10.1 (2021-04-19)](https://github.com/dartsim/dart/milestone/65?closed=1)

* Dynamics
Expand Down
4 changes: 2 additions & 2 deletions dart/constraint/BallJointConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ namespace constraint {
//==============================================================================
BallJointConstraint::BallJointConstraint(
dynamics::BodyNode* _body, const Eigen::Vector3d& _jointPos)
: JointConstraint(_body),
: DynamicJointConstraint(_body),
mOffset1(_body->getTransform().inverse() * _jointPos),
mOffset2(_jointPos),
mViolation(Eigen::Vector3d::Zero()),
Expand All @@ -65,7 +65,7 @@ BallJointConstraint::BallJointConstraint(
dynamics::BodyNode* _body1,
dynamics::BodyNode* _body2,
const Eigen::Vector3d& _jointPos)
: JointConstraint(_body1, _body2),
: DynamicJointConstraint(_body1, _body2),
mOffset1(_body1->getTransform().inverse() * _jointPos),
mOffset2(_body2->getTransform().inverse() * _jointPos),
mViolation(Eigen::Vector3d::Zero()),
Expand Down
4 changes: 2 additions & 2 deletions dart/constraint/BallJointConstraint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,15 +35,15 @@

#include <Eigen/Dense>

#include "dart/constraint/JointConstraint.hpp"
#include "dart/constraint/DynamicJointConstraint.hpp"
#include "dart/math/MathTypes.hpp"

namespace dart {
namespace constraint {

/// BallJointConstraint represents ball joint constraint between a body and the
/// world or between two bodies
class BallJointConstraint : public JointConstraint
class BallJointConstraint : public DynamicJointConstraint
{
public:
/// Constructor that takes one body and the joint position in the world frame
Expand Down
28 changes: 6 additions & 22 deletions dart/constraint/ConstraintSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,10 @@
#include "dart/common/Console.hpp"
#include "dart/constraint/ConstrainedGroup.hpp"
#include "dart/constraint/ContactConstraint.hpp"
#include "dart/constraint/JointConstraint.hpp"
#include "dart/constraint/JointCoulombFrictionConstraint.hpp"
#include "dart/constraint/JointLimitConstraint.hpp"
#include "dart/constraint/LCPSolver.hpp"
#include "dart/constraint/MimicMotorConstraint.hpp"
#include "dart/constraint/ServoMotorConstraint.hpp"
#include "dart/constraint/SoftContactConstraint.hpp"
#include "dart/dynamics/BodyNode.hpp"
#include "dart/dynamics/Joint.hpp"
Expand Down Expand Up @@ -588,8 +587,7 @@ void ConstraintSolver::updateConstraints()
// Update automatic constraints: joint constraints
//----------------------------------------------------------------------------
// Destroy previous joint constraints
mJointLimitConstraints.clear();
mServoMotorConstraints.clear();
mJointConstraints.clear();
mMimicMotorConstraints.clear();
mJointCoulombFrictionConstraints.clear();

Expand All @@ -615,16 +613,10 @@ void ConstraintSolver::updateConstraints()
}
}

if (joint->areLimitsEnforced())
if (joint->areLimitsEnforced()
|| joint->getActuatorType() == dynamics::Joint::SERVO)
{
mJointLimitConstraints.push_back(
std::make_shared<JointLimitConstraint>(joint));
}

if (joint->getActuatorType() == dynamics::Joint::SERVO)
{
mServoMotorConstraints.push_back(
std::make_shared<ServoMotorConstraint>(joint));
mJointConstraints.push_back(std::make_shared<JointConstraint>(joint));
}

if (joint->getActuatorType() == dynamics::Joint::MIMIC
Expand All @@ -640,22 +632,14 @@ void ConstraintSolver::updateConstraints()
}

// Add active joint limit
for (auto& jointLimitConstraint : mJointLimitConstraints)
for (auto& jointLimitConstraint : mJointConstraints)
{
jointLimitConstraint->update();

if (jointLimitConstraint->isActive())
mActiveConstraints.push_back(jointLimitConstraint);
}

for (auto& servoMotorConstraint : mServoMotorConstraints)
{
servoMotorConstraint->update();

if (servoMotorConstraint->isActive())
mActiveConstraints.push_back(servoMotorConstraint);
}

for (auto& mimicMotorConstraint : mMimicMotorConstraints)
{
mimicMotorConstraint->update();
Expand Down
5 changes: 1 addition & 4 deletions dart/constraint/ConstraintSolver.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,10 +239,7 @@ class ConstraintSolver
std::vector<SoftContactConstraintPtr> mSoftContactConstraints;

/// Joint limit constraints those are automatically created
std::vector<JointLimitConstraintPtr> mJointLimitConstraints;

/// Servo motor constraints those are automatically created
std::vector<ServoMotorConstraintPtr> mServoMotorConstraints;
std::vector<JointConstraintPtr> mJointConstraints;

/// Mimic motor constraints those are automatically created
std::vector<MimicMotorConstraintPtr> mMimicMotorConstraints;
Expand Down
176 changes: 176 additions & 0 deletions dart/constraint/DynamicJointConstraint.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,176 @@
/*
* Copyright (c) 2011-2021, The DART development contributors
* All rights reserved.
*
* The list of contributors can be found at:
* https://github.com/dartsim/dart/blob/master/LICENSE
*
* This file is provided under the following "BSD-style" License:
* Redistribution and use in source and binary forms, with or
* without modification, are permitted provided that the following
* conditions are met:
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
* USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/

#include "dart/constraint/DynamicJointConstraint.hpp"

#include <cassert>

#include "dart/common/Console.hpp"

#define DART_ERROR_ALLOWANCE 0.0
#define DART_ERP 0.01
#define DART_MAX_ERV 1e+1
#define DART_CFM 1e-9

namespace dart {
namespace constraint {

double DynamicJointConstraint::mErrorAllowance = DART_ERROR_ALLOWANCE;
double DynamicJointConstraint::mErrorReductionParameter = DART_ERP;
double DynamicJointConstraint::mMaxErrorReductionVelocity = DART_MAX_ERV;
double DynamicJointConstraint::mConstraintForceMixing = DART_CFM;

//==============================================================================
DynamicJointConstraint::DynamicJointConstraint(dynamics::BodyNode* body)
: ConstraintBase(), mBodyNode1(body), mBodyNode2(nullptr)
{
assert(body);
}

//==============================================================================
DynamicJointConstraint::DynamicJointConstraint(
dynamics::BodyNode* body1, dynamics::BodyNode* body2)
: ConstraintBase(), mBodyNode1(body1), mBodyNode2(body2)
{
assert(body1);
assert(body2);
}

//==============================================================================
DynamicJointConstraint::~DynamicJointConstraint()
{
// Do nothing
}

//==============================================================================
void DynamicJointConstraint::setErrorAllowance(double allowance)
{
// Clamp error reduction parameter if it is out of the range
if (allowance < 0.0)
{
dtwarn << "Error reduction parameter[" << allowance
<< "] is lower than 0.0. "
<< "It is set to 0.0." << std::endl;
mErrorAllowance = 0.0;
}

mErrorAllowance = allowance;
}

//==============================================================================
double DynamicJointConstraint::getErrorAllowance()
{
return mErrorAllowance;
}

//==============================================================================
void DynamicJointConstraint::setErrorReductionParameter(double erp)
{
// Clamp error reduction parameter if it is out of the range [0, 1]
if (erp < 0.0)
{
dtwarn << "Error reduction parameter [" << erp << "] is lower than 0.0. "
<< "It is set to 0.0." << std::endl;
mErrorReductionParameter = 0.0;
}
if (erp > 1.0)
{
dtwarn << "Error reduction parameter [" << erp << "] is greater than 1.0. "
<< "It is set to 1.0." << std::endl;
mErrorReductionParameter = 1.0;
}

mErrorReductionParameter = erp;
}

//==============================================================================
double DynamicJointConstraint::getErrorReductionParameter()
{
return mErrorReductionParameter;
}

//==============================================================================
void DynamicJointConstraint::setMaxErrorReductionVelocity(double erv)
{
// Clamp maximum error reduction velocity if it is out of the range
if (erv < 0.0)
{
dtwarn << "Maximum error reduction velocity [" << erv
<< "] is lower than 0.0. "
<< "It is set to 0.0." << std::endl;
mMaxErrorReductionVelocity = 0.0;
}

mMaxErrorReductionVelocity = erv;
}

//==============================================================================
double DynamicJointConstraint::getMaxErrorReductionVelocity()
{
return mMaxErrorReductionVelocity;
}

//==============================================================================
void DynamicJointConstraint::setConstraintForceMixing(double cfm)
{
// Clamp constraint force mixing parameter if it is out of the range
if (cfm < 1e-9)
{
dtwarn << "Constraint force mixing parameter [" << cfm
<< "] is lower than 1e-9. "
<< "It is set to 1e-9." << std::endl;
mConstraintForceMixing = 1e-9;
}

mConstraintForceMixing = cfm;
}

//==============================================================================
double DynamicJointConstraint::getConstraintForceMixing()
{
return mConstraintForceMixing;
}

//==============================================================================
dynamics::BodyNode* DynamicJointConstraint::getBodyNode1() const
{
return mBodyNode1;
}

//==============================================================================
dynamics::BodyNode* DynamicJointConstraint::getBodyNode2() const
{
return mBodyNode2;
}

} // namespace constraint
} // namespace dart
Loading

0 comments on commit c5e4de0

Please sign in to comment.