Skip to content

Commit d1fa38f

Browse files
committed
Merge remote-tracking branch 'origin/main' into feature/visual-aspect-default-color
# Conflicts: # .github/workflows/ci_macos.yml
2 parents 55ab01f + 987e7c3 commit d1fa38f

File tree

10 files changed

+222
-8
lines changed

10 files changed

+222
-8
lines changed

.github/workflows/ci_macos.yml

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -46,8 +46,8 @@ jobs:
4646
- name: Checkout
4747
uses: actions/checkout@v5
4848

49-
- name: Clean pixi cache
50-
run: rm -rf "$HOME/.pixi"
49+
- name: Ensure pixi home exists
50+
run: mkdir -p "${HOME}/.pixi/bin"
5151

5252
- name: Setup pixi
5353
uses: prefix-dev/setup-pixi@v0.9.3
@@ -97,8 +97,8 @@ jobs:
9797
- name: Checkout
9898
uses: actions/checkout@v5
9999

100-
- name: Clean pixi cache
101-
run: rm -rf "$HOME/.pixi"
100+
- name: Ensure pixi home exists
101+
run: mkdir -p "${HOME}/.pixi/bin"
102102

103103
- name: Setup pixi
104104
uses: prefix-dev/setup-pixi@v0.9.3

.github/workflows/publish_dartpy.yml

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -76,9 +76,11 @@ jobs:
7676
- uses: actions/checkout@v5
7777
if: (matrix.skip-on-commit != true) || github.event_name == 'pull_request' || startsWith(github.ref, 'refs/tags/v')
7878

79-
- name: Remove preinstalled pixi (if any)
79+
- name: Prepare pixi home
8080
if: (matrix.skip-on-commit != true) || github.event_name == 'pull_request' || startsWith(github.ref, 'refs/tags/v')
81-
run: rm -f "$HOME/.pixi/bin/pixi"
81+
run: |
82+
rm -f "$HOME/.pixi/bin/pixi"
83+
mkdir -p "${HOME}/.pixi/bin"
8284
8385
- uses: prefix-dev/setup-pixi@v0.9.3
8486
if: (matrix.skip-on-commit != true) || github.event_name == 'pull_request' || startsWith(github.ref, 'refs/tags/v')

dart/dynamics/PlanarJoint.cpp

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -115,6 +115,25 @@ const std::string& PlanarJoint::getStaticType()
115115
return name;
116116
}
117117

118+
//==============================================================================
119+
Eigen::Vector3d PlanarJoint::convertToPositions(const Eigen::Isometry2d& tf)
120+
{
121+
Eigen::Vector3d positions;
122+
positions.head<2>() = tf.translation();
123+
positions[2] = Eigen::Rotation2Dd(tf.linear()).angle();
124+
return positions;
125+
}
126+
127+
//==============================================================================
128+
Eigen::Isometry2d PlanarJoint::convertToTransform(
129+
const Eigen::Vector3d& positions)
130+
{
131+
Eigen::Isometry2d tf(Eigen::Isometry2d::Identity());
132+
tf.translation() = positions.head<2>();
133+
tf.linear() = Eigen::Rotation2Dd(positions[2]).toRotationMatrix();
134+
return tf;
135+
}
136+
118137
//==============================================================================
119138
bool PlanarJoint::isCyclic(std::size_t _index) const
120139
{

dart/dynamics/PlanarJoint.hpp

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,6 +37,8 @@
3737

3838
#include <dart/Export.hpp>
3939

40+
#include <Eigen/Geometry>
41+
4042
namespace dart {
4143
namespace dynamics {
4244

@@ -92,6 +94,12 @@ class DART_API PlanarJoint : public detail::PlanarJointBase
9294
// Documentation inherited
9395
bool isCyclic(std::size_t _index) const override;
9496

97+
/// Convert a planar transform into a 3D position vector usable by the joint
98+
static Eigen::Vector3d convertToPositions(const Eigen::Isometry2d& tf);
99+
100+
/// Convert a PlanarJoint-style position vector into a planar transform
101+
static Eigen::Isometry2d convertToTransform(const Eigen::Vector3d& positions);
102+
95103
/// \brief Set plane type as XY-plane
96104
/// \param[in] _renameDofs If true, the names of dofs in this joint will be
97105
/// renmaed according to the plane type.

dart8/io/serializer.hpp

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -227,7 +227,12 @@ class TypedComponentSerializer : public ComponentSerializer
227227
{
228228
ComponentT component;
229229
loadComponent(in, component);
230-
registry.emplace<ComponentT>(entity, std::move(component));
230+
if constexpr (std::is_empty_v<ComponentT>) {
231+
// Tag components in EnTT must be emplaced without constructor args
232+
registry.emplace<ComponentT>(entity);
233+
} else {
234+
registry.emplace<ComponentT>(entity, std::move(component));
235+
}
231236
}
232237

233238
bool hasComponent(

docs/readthedocs/conf.py

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -117,14 +117,18 @@ def _ensure_dartpy_available() -> None:
117117

118118
try:
119119
importlib.import_module("dartpy")
120-
except ModuleNotFoundError:
120+
except (ModuleNotFoundError, ImportError) as exc:
121121
if _prepare_stub_modules("dartpy"):
122122
sys.stderr.write("Using generated dartpy stubs for autodoc.\n")
123123
else:
124124
sys.stderr.write(
125125
"WARNING: dartpy module and stubs are unavailable; "
126126
"dartpy API pages will be empty.\n"
127127
)
128+
if not isinstance(exc, ModuleNotFoundError):
129+
sys.stderr.write(
130+
f"Ignoring installed dartpy due to import failure: {exc}\n"
131+
)
128132

129133

130134
_ensure_dartpy_available()

python/dartpy/dynamics/PlanarJoint.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -245,6 +245,18 @@ void PlanarJoint(py::module& m)
245245
return self->getRelativeJacobianStatic(_positions);
246246
},
247247
::py::arg("positions"))
248+
.def_static(
249+
"convertToPositions",
250+
+[](const Eigen::Isometry2d& tf) {
251+
return dart::dynamics::PlanarJoint::convertToPositions(tf);
252+
},
253+
::py::arg("transform"))
254+
.def_static(
255+
"convertToTransform",
256+
+[](const Eigen::Vector3d& positions) {
257+
return dart::dynamics::PlanarJoint::convertToTransform(positions);
258+
},
259+
::py::arg("positions"))
248260
.def_static(
249261
"getStaticType",
250262
+[]() -> const std::

tests/integration/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@ endif()
1818

1919
if(DART_BUILD_COLLISION_BULLET)
2020
dart_add_test("integration" INTEGRATION_collision_CollisionAccuracy collision/test_CollisionAccuracy.cpp)
21+
dart_add_test("integration" INTEGRATION_collision_BulletBoxStack collision/test_BulletBoxStack.cpp)
2122
endif()
2223

2324
if(DART_BUILD_COLLISION_BULLET AND DART_BUILD_COLLISION_ODE)
Lines changed: 130 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,130 @@
1+
/*
2+
* Copyright (c) 2011-2025, The DART development contributors
3+
* All rights reserved.
4+
*
5+
* The list of contributors can be found at:
6+
* https://github.com/dartsim/dart/blob/main/LICENSE
7+
*
8+
* This file is provided under the following "BSD-style" License:
9+
* Redistribution and use in source and binary forms, with or
10+
* without modification, are permitted provided that the following
11+
* conditions are met:
12+
* * Redistributions of source code must retain the above copyright
13+
* notice, this list of conditions and the following disclaimer.
14+
* * Redistributions in binary form must reproduce the above
15+
* copyright notice, this list of conditions and the following
16+
* disclaimer in the documentation and/or other materials provided
17+
* with the distribution.
18+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
19+
* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES,
20+
* INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21+
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
22+
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
23+
* CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
24+
* SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
25+
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
26+
* USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27+
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30+
* POSSIBILITY OF SUCH DAMAGE.
31+
*/
32+
33+
#include "helpers/dynamics_helpers.hpp"
34+
35+
#include <dart/simulation/World.hpp>
36+
37+
#include <dart/constraint/BoxedLcpConstraintSolver.hpp>
38+
#include <dart/constraint/DantzigBoxedLcpSolver.hpp>
39+
40+
#include <dart/collision/bullet/BulletCollisionDetector.hpp>
41+
42+
#include <dart/dynamics/Skeleton.hpp>
43+
44+
#include <gtest/gtest.h>
45+
46+
#include <limits>
47+
#include <memory>
48+
#include <vector>
49+
50+
using namespace dart;
51+
using dart::simulation::World;
52+
53+
namespace {
54+
55+
constexpr double kBoxSide = 0.4;
56+
constexpr double kBoxHeight = 0.5;
57+
constexpr std::size_t kNumBoxes = 10;
58+
constexpr double kTimeStep = 0.001;
59+
constexpr int kNumSteps = 2000;
60+
61+
//==============================================================================
62+
std::vector<dynamics::SkeletonPtr> createStack(World& world)
63+
{
64+
// Ground
65+
auto ground = createBox({5.0, 5.0, 0.4}, {0.0, 0.0, -0.2});
66+
ground->setMobile(false);
67+
world.addSkeleton(ground);
68+
69+
// Boxes
70+
std::vector<dynamics::SkeletonPtr> boxes;
71+
boxes.reserve(kNumBoxes);
72+
73+
for (std::size_t i = 0; i < kNumBoxes; ++i) {
74+
const double centerZ
75+
= kBoxHeight * 0.5 + static_cast<double>(i) * kBoxHeight;
76+
auto box = createBox({kBoxSide, kBoxSide, kBoxHeight}, {0.0, 0.0, centerZ});
77+
world.addSkeleton(box);
78+
boxes.push_back(std::move(box));
79+
}
80+
81+
return boxes;
82+
}
83+
84+
} // namespace
85+
86+
//==============================================================================
87+
TEST(Issue867, BulletBoxStackingStaysStable)
88+
{
89+
auto world = World::create();
90+
world->setTimeStep(kTimeStep);
91+
92+
auto lcpSolver = std::make_shared<constraint::DantzigBoxedLcpSolver>();
93+
auto solver
94+
= std::make_unique<constraint::BoxedLcpConstraintSolver>(lcpSolver);
95+
solver->setCollisionDetector(collision::BulletCollisionDetector::create());
96+
world->setConstraintSolver(std::move(solver));
97+
98+
auto boxes = createStack(*world);
99+
ASSERT_EQ(boxes.size(), kNumBoxes);
100+
101+
const double expectedTopCenter
102+
= kBoxHeight * (static_cast<double>(kNumBoxes) - 0.5);
103+
double maxObservedTopZ = -std::numeric_limits<double>::infinity();
104+
double finalKineticEnergy = 0.0;
105+
106+
for (int step = 0; step < kNumSteps; ++step) {
107+
world->step();
108+
109+
// Ensure bodies remain finite to catch explosions/NANs early.
110+
for (const auto& box : boxes) {
111+
const auto pos = box->getBodyNode(0)->getWorldTransform().translation();
112+
ASSERT_TRUE(pos.array().allFinite());
113+
}
114+
115+
const auto topPos
116+
= boxes.back()->getBodyNode(0)->getWorldTransform().translation();
117+
maxObservedTopZ = std::max(maxObservedTopZ, topPos.z());
118+
119+
if (step == kNumSteps - 1) {
120+
for (const auto& box : boxes)
121+
finalKineticEnergy += box->computeKineticEnergy();
122+
}
123+
}
124+
125+
EXPECT_LT(maxObservedTopZ, expectedTopCenter + 2.0);
126+
EXPECT_GT(
127+
boxes.back()->getBodyNode(0)->getWorldTransform().translation().z(),
128+
expectedTopCenter - 0.5);
129+
EXPECT_LT(finalKineticEnergy, 5.0);
130+
}

tests/integration/dynamics/test_Joints.cpp

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -410,6 +410,39 @@ TEST_F(Joints, PlanarJoint)
410410
kinematicsTest<PlanarJoint>();
411411
}
412412

413+
//==============================================================================
414+
TEST_F(Joints, PlanarJointIsometry2dHelpers)
415+
{
416+
SkeletonPtr skel = Skeleton::create("planar_helpers");
417+
auto pair = skel->createJointAndBodyNodePair<PlanarJoint>();
418+
auto* joint = pair.first;
419+
420+
const Eigen::Vector3d positions(0.25, -0.15, 0.6);
421+
const Eigen::Isometry2d tf = PlanarJoint::convertToTransform(positions);
422+
EXPECT_TRUE(PlanarJoint::convertToPositions(tf).isApprox(positions, 1e-12));
423+
424+
const auto verifyPlane = [&](auto setPlane) {
425+
setPlane();
426+
joint->setPositions(positions);
427+
428+
const Eigen::Isometry3d expected
429+
= Eigen::Translation3d(joint->getTranslationalAxis1() * positions[0])
430+
* Eigen::Translation3d(joint->getTranslationalAxis2() * positions[1])
431+
* math::expAngular(joint->getRotationalAxis() * positions[2]);
432+
433+
EXPECT_TRUE(joint->getRelativeTransform().isApprox(expected, 1e-12));
434+
};
435+
436+
verifyPlane([&]() { joint->setXYPlane(); });
437+
verifyPlane([&]() { joint->setYZPlane(); });
438+
verifyPlane([&]() { joint->setZXPlane(); });
439+
verifyPlane([&]() {
440+
const Eigen::Vector3d axis1(1.0, 1.0, 0.0);
441+
const Eigen::Vector3d axis2(-1.0, 1.0, 0.0);
442+
joint->setArbitraryPlane(axis1.normalized(), axis2.normalized());
443+
});
444+
}
445+
413446
// 6-dof joint
414447
// TEST_F(Joints, FreeJoint)
415448
//{

0 commit comments

Comments
 (0)