Skip to content

Commit

Permalink
parse kinematic property in link
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 committed Mar 29, 2024
1 parent 67ead53 commit 3b09d54
Show file tree
Hide file tree
Showing 5 changed files with 37 additions and 0 deletions.
8 changes: 8 additions & 0 deletions include/sdf/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -414,6 +414,14 @@ namespace sdf
/// \sa Model::SetEnableWind(bool)
public: void SetEnableWind(bool _enableWind);

/// \brief Check if this link is kinematic only
/// \return true if the link is kinematic only, false otherwise.
public: bool Kinematic() const;

/// \brief Set whether this link is kinematic only.
/// \param[in] _enable True to make the link kinematic only,
public: void SetKinematic(bool _kinematic);

/// \brief Check if the automatic calculation for the link inertial
/// is enabled or not.
/// \return True if automatic calculation is enabled. This can be done
Expand Down
21 changes: 21 additions & 0 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,9 @@ class sdf::Link::Implementation
/// \brief True if this link should be subject to wind, false otherwise.
public: bool enableWind = false;

/// \brief True if this link is kinematic only
public: bool kinematic = false;

/// \brief True if automatic caluclation for the link inertial is enabled
public: bool autoInertia = false;

Expand Down Expand Up @@ -313,6 +316,9 @@ Errors Link::Load(ElementPtr _sdf, const ParserConfig &_config)
this->dataPtr->enableWind = _sdf->Get<bool>("enable_wind",
this->dataPtr->enableWind).first;

this->dataPtr->kinematic = _sdf->Get<bool>("kinematic",
this->dataPtr->kinematic).first;

return errors;
}

Expand Down Expand Up @@ -841,6 +847,18 @@ void Link::SetEnableWind(const bool _enableWind)
this->dataPtr->enableWind = _enableWind;
}

/////////////////////////////////////////////////
bool Link::Kinematic() const
{
return this->dataPtr->kinematic;
}

/////////////////////////////////////////////////
void Link::SetKinematic(bool _kinematic)
{
this->dataPtr->kinematic = _kinematic;
}

/////////////////////////////////////////////////
bool Link::AutoInertia() const
{
Expand Down Expand Up @@ -1022,6 +1040,9 @@ sdf::ElementPtr Link::ToElement() const
// wind mode
elem->GetElement("enable_wind")->Set(this->EnableWind());

// kinematic
elem->GetElement("kinematic")->Set(this->Kinematic());

// Collisions
for (const sdf::Collision &collision : this->dataPtr->collisions)
{
Expand Down
6 changes: 6 additions & 0 deletions src/Link_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,10 @@ TEST(DOMLink, Construction)
link.SetEnableWind(true);
EXPECT_TRUE(link.EnableWind());

EXPECT_FALSE(link.Kinematic());
link.SetKinematic(true);
EXPECT_TRUE(link.Kinematic());

EXPECT_FALSE(link.AutoInertiaSaved());
link.SetAutoInertiaSaved(true);
EXPECT_TRUE(link.AutoInertiaSaved());
Expand Down Expand Up @@ -902,6 +906,7 @@ TEST(DOMLink, ToElement)
EXPECT_TRUE(link.SetInertial(inertial));
link.SetRawPose(gz::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3));
link.SetEnableWind(true);
link.SetKinematic(true);

for (int j = 0; j <= 1; ++j)
{
Expand Down Expand Up @@ -998,6 +1003,7 @@ TEST(DOMLink, ToElement)
EXPECT_EQ(link.Density(), link2.Density());
EXPECT_EQ(link.RawPose(), link2.RawPose());
EXPECT_EQ(link.EnableWind(), link2.EnableWind());
EXPECT_EQ(link.Kinematic(), link2.Kinematic());
EXPECT_EQ(link.CollisionCount(), link2.CollisionCount());
for (uint64_t i = 0; i < link2.CollisionCount(); ++i)
EXPECT_NE(nullptr, link2.CollisionByIndex(i));
Expand Down
1 change: 1 addition & 0 deletions test/integration/link_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -147,6 +147,7 @@ TEST(DOMLink, InertialDoublePendulum)
upperLink->RawPose());
EXPECT_EQ("", upperLink->PoseRelativeTo());
EXPECT_TRUE(upperLink->EnableWind());
EXPECT_TRUE(upperLink->Kinematic());

const gz::math::Inertiald inertialUpper = upperLink->Inertial();
EXPECT_DOUBLE_EQ(1.0, inertialUpper.MassMatrix().Mass());
Expand Down
1 change: 1 addition & 0 deletions test/sdf/double_pendulum.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@
<!-- upper link, length 1, IC -90 degrees -->
<link name="upper_link">
<enable_wind>true</enable_wind>
<kinematic>true</kinematic>
<pose>0 0 2.1 -1.5708 0 0</pose>
<self_collide>0</self_collide>
<inertial>
Expand Down

0 comments on commit 3b09d54

Please sign in to comment.