Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
26 commits
Select commit Hold shift + click to select a range
4afbcd0
Add mimic pendulum repro test and GUI debug example
jslee02 Nov 22, 2025
59ceb15
Improve mimic tracking tests and example tuning
jslee02 Nov 22, 2025
aec220a
Format code
jslee02 Nov 22, 2025
07d1c21
Adjust cfm and erp
jslee02 Nov 22, 2025
c6400fa
Fix mimic pendulum instability: Reference middle pendulum joints inst…
jslee02 Nov 22, 2025
ee8d855
Adjust mimic motor constraint
jslee02 Nov 22, 2025
ce5163c
Merge branch 'main' into gz/mimic_constraint
jslee02 Nov 22, 2025
769d733
Format code
jslee02 Nov 22, 2025
e29a2ac
Use mimic motor references and lock pendulum bases
jslee02 Nov 23, 2025
5d07ee6
Remove base locking from mimic pendulum demo
jslee02 Nov 23, 2025
0691f9b
Test mimic followers track middle pendulum
jslee02 Nov 23, 2025
b0975f8
Enable setting cfm and erp
jslee02 Nov 23, 2025
67cc9f7
Align mimic example/tests with SDF-only setup
jslee02 Nov 23, 2025
490cfd2
Cleanup mimic constraint defaults and stabilize mimic tests
jslee02 Nov 23, 2025
c403ca2
Tidy mimic constraint test includes
jslee02 Nov 23, 2025
236f7ba
Merge remote-tracking branch 'origin/main' into gz/mimic_constraint
jslee02 Nov 23, 2025
942fccb
Restore mimic motor ERP API and declare PlanarJoint converters
jslee02 Nov 23, 2025
9cb5ef8
Guard mimic constraint test from Bullet dependency
jslee02 Nov 23, 2025
6b9855f
Guard mimic example from optional Bullet dependency
jslee02 Nov 23, 2025
cb6f46b
Merge branch 'main' into gz/mimic_constraint
jslee02 Nov 23, 2025
57e39e0
Keep baseline pendulum uncoupled when configuring mimic motors
jslee02 Nov 23, 2025
e7f482e
Parse SDF mimic joints and retarget mimic demo
jslee02 Nov 23, 2025
d3ca3f6
Merge origin/main into gz/sdformat_mimic
jslee02 Nov 24, 2025
c334598
Merge branch 'main' into gz/sdformat_mimic
jslee02 Nov 24, 2025
2477254
Merge branch 'main' into gz/sdformat_mimic
jslee02 Nov 24, 2025
2f3be00
Merge remote-tracking branch 'origin/main' into gz/sdformat_mimic
jslee02 Nov 24, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@
- Removed all APIs deprecated in DART 6.13 (the legacy `dart::common::Timer` utility, `ConstraintSolver::getConstraints()`/`containSkeleton()`, `ContactConstraint`'s raw constructor and material helper statistics, and the `MetaSkeleton` vector-returning `getBodyNodes()`/`getJoints()` accessors).
- Removed the remaining 6.13 compatibility shims: deleted `dart/utils/urdf/URDFTypes.hpp`, the Eigen alias typedefs in `math/MathTypes.hpp`, the `dart7::comps::NameComponent` alias, and the legacy `dInfinity`/`dPAD` helpers, and tightened `SkelParser` plane parsing to treat `<point>` as an error.
- Updated `dart::utils::SdfParser` to canonicalize input through libsdformat so it can parse SDF 1.7+ models without the legacy version gate: [#264](https://github.com/dartsim/dart/issues/264)
- `dart::utils::SdfParser` now imports SDF mimic metadata (reference joint/DoF, multiplier/offset, and constraint type), and the mimic pendulum example/tests rely on those parsed joints when reproducing gz-physics #432 instead of bespoke SDF readers.
- Fixed Collada mesh imports ignoring `<unit>` metadata by preserving the Assimp-provided scale transform ([#287](https://github.com/dartsim/dart/issues/287)).

- dartpy
Expand Down
120 changes: 120 additions & 0 deletions dart/utils/sdf/SdfParser.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include "dart/dynamics/CylinderShape.hpp"
#include "dart/dynamics/FreeJoint.hpp"
#include "dart/dynamics/MeshShape.hpp"
#include "dart/dynamics/MimicDofProperties.hpp"
#include "dart/dynamics/PrismaticJoint.hpp"
#include "dart/dynamics/RevoluteJoint.hpp"
#include "dart/dynamics/ScrewJoint.hpp"
Expand Down Expand Up @@ -193,8 +194,21 @@ struct SDFJoint
std::string parentName;
std::string childName;
std::string type;
struct MimicInfo
{
std::string referenceJointName;
std::size_t referenceDof = 0;
double multiplier = 1.0;
double offset = 0.0;
dynamics::MimicConstraintType constraintType
= dynamics::MimicConstraintType::Motor;
};
std::vector<MimicInfo> mimicInfos;
};

std::vector<SDFJoint::MimicInfo> readMimicElements(
const ElementPtr& axisElement);

// Maps the name of a BodyNode to its properties
using BodyMap = common::aligned_map<std::string, SDFBodyNode>;

Expand All @@ -213,6 +227,9 @@ dynamics::SkeletonPtr readSkeleton(
const common::Uri& baseUri,
const ResolvedOptions& options);

void applyMimicConstraints(
const dynamics::SkeletonPtr& skeleton, const JointMap& sdfJoints);

bool createPair(
dynamics::SkeletonPtr skeleton,
dynamics::BodyNode* parent,
Expand Down Expand Up @@ -807,6 +824,8 @@ dynamics::SkeletonPtr readSkeleton(
// Set positions to their initial values
newSkeleton->resetPositions();

applyMimicConstraints(newSkeleton, sdfJoints);

return newSkeleton;
}

Expand Down Expand Up @@ -878,6 +897,62 @@ NextResult getNextJointAndNodePair(
return VALID;
}

//==============================================================================
void applyMimicConstraints(
const dynamics::SkeletonPtr& skeleton, const JointMap& sdfJoints)
{
for (const auto& entry : sdfJoints) {
const auto& jointInfo = entry.second;
if (jointInfo.mimicInfos.empty())
continue;

auto* joint = skeleton->getJoint(jointInfo.properties->mName);
if (!joint)
continue;

std::vector<dynamics::MimicDofProperties> props
= joint->getMimicDofProperties();
props.resize(joint->getNumDofs());

bool applied = false;
bool useCoupler = false;
for (const auto& mimic : jointInfo.mimicInfos) {
auto* ref = skeleton->getJoint(mimic.referenceJointName);
if (!ref) {
DART_WARN(
"[SdfParser] Ignoring mimic joint [{}] referencing missing joint "
"[{}]",
jointInfo.properties->mName,
mimic.referenceJointName);
continue;
}

const std::size_t followerIndex
= std::min(mimic.referenceDof, joint->getNumDofs() - 1);
const std::size_t referenceIndex
= std::min(mimic.referenceDof, ref->getNumDofs() - 1);

auto& prop = props[followerIndex];
prop.mReferenceJoint = ref;
prop.mReferenceDofIndex = referenceIndex;
prop.mMultiplier = mimic.multiplier;
prop.mOffset = mimic.offset;
prop.mConstraintType = mimic.constraintType;
applied = true;
useCoupler
= useCoupler
|| mimic.constraintType == dynamics::MimicConstraintType::Coupler;
}

if (!applied)
continue;

joint->setMimicJointDofs(props);
joint->setActuatorType(dynamics::Joint::MIMIC);
joint->setUseCouplerConstraint(useCoupler);
}
}

dynamics::SkeletonPtr makeSkeleton(
const ElementPtr& _skeletonElement, Eigen::Isometry3d& skeletonFrame)
{
Expand Down Expand Up @@ -1343,6 +1418,34 @@ JointMap readAllJoints(
return sdfJoints;
}

std::vector<SDFJoint::MimicInfo> readMimicElements(
const ElementPtr& axisElement)
{
std::vector<SDFJoint::MimicInfo> mimics;
if (!axisElement || !hasElement(axisElement, "mimic"))
return mimics;

const auto mimicElement = getElement(axisElement, "mimic");
if (!mimicElement)
return mimics;

SDFJoint::MimicInfo info;
info.referenceJointName = getAttributeString(mimicElement, "joint");
if (hasAttribute(mimicElement, "axis")) {
const auto axisAttr = getAttributeString(mimicElement, "axis");
info.referenceDof = axisAttr == "axis2" ? 1u : 0u;
}
info.multiplier = hasElement(mimicElement, "multiplier")
? getValueDouble(mimicElement, "multiplier")
: 1.0;
info.offset = hasElement(mimicElement, "offset")
? getValueDouble(mimicElement, "offset")
: 0.0;
mimics.push_back(info);

return mimics;
}

SDFJoint readJoint(
const ElementPtr& _jointElement,
const BodyMap& _sdfBodyNodes,
Expand Down Expand Up @@ -1410,6 +1513,23 @@ SDFJoint readJoint(
= (parent_it == _sdfBodyNodes.end()) ? "" : parent_it->first;
newJoint.childName = (child_it == _sdfBodyNodes.end()) ? "" : child_it->first;

//--------------------------------------------------------------------------
// Mimic metadata (captured before joint creation)
if (hasElement(_jointElement, "axis")) {
const ElementPtr& axisElement = getElement(_jointElement, "axis");
const auto mimics = readMimicElements(axisElement);
newJoint.mimicInfos.insert(
newJoint.mimicInfos.end(), mimics.begin(), mimics.end());
}
if (hasElement(_jointElement, "axis2")) {
const ElementPtr& axis2Element = getElement(_jointElement, "axis2");
auto mimics = readMimicElements(axis2Element);
for (auto& m : mimics)
m.referenceDof = 1u; // axis2 maps to the second DoF
newJoint.mimicInfos.insert(
newJoint.mimicInfos.end(), mimics.begin(), mimics.end());
}

//--------------------------------------------------------------------------
// transformation
Eigen::Isometry3d parentWorld = Eigen::Isometry3d::Identity();
Expand Down
Loading
Loading