Skip to content

Commit

Permalink
Add more link APIs, with tutorial (gazebosim#375)
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
  • Loading branch information
chapulina authored and Guillaume Doisy committed Dec 13, 2020
1 parent c1f3f40 commit f834169
Show file tree
Hide file tree
Showing 8 changed files with 544 additions and 104 deletions.
51 changes: 51 additions & 0 deletions include/ignition/gazebo/Link.hh
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <memory>
#include <optional>
#include <string>
#include <vector>

#include <ignition/math/Pose3.hh>
#include <ignition/math/Quaternion.hh>
Expand Down Expand Up @@ -114,6 +115,56 @@ namespace ignition
public: std::optional<Model> ParentModel(
const EntityComponentManager &_ecm) const;

/// \brief Check if this is the canonical link.
/// \param[in] _ecm Entity-component manager.
/// \return True if it is the canonical link.
public: bool IsCanonical(const EntityComponentManager &_ecm) const;

/// \brief Get whether this link has wind enabled.
/// \param[in] _ecm Entity-component manager.
/// \return True if wind mode is on.
public: bool WindMode(const EntityComponentManager &_ecm) const;

/// \brief Get the ID of a collision entity which is an immediate child of
/// this link.
/// \param[in] _ecm Entity-component manager.
/// \param[in] _name Collision name.
/// \return Collision entity.
public: gazebo::Entity CollisionByName(const EntityComponentManager &_ecm,
const std::string &_name) const;

/// \brief Get the ID of a visual entity which is an immediate child of
/// this link.
/// \param[in] _ecm Entity-component manager.
/// \param[in] _name Visual name.
/// \return Visual entity.
public: gazebo::Entity VisualByName(const EntityComponentManager &_ecm,
const std::string &_name) const;

/// \brief Get all collisions which are immediate children of this link.
/// \param[in] _ecm Entity-component manager.
/// \return All collisions in this link.
public: std::vector<gazebo::Entity> Collisions(
const EntityComponentManager &_ecm) const;

/// \brief Get all visuals which are immediate children of this link.
/// \param[in] _ecm Entity-component manager.
/// \return All visuals in this link.
public: std::vector<gazebo::Entity> Visuals(
const EntityComponentManager &_ecm) const;

/// \brief Get the number of collisions which are immediate children of
/// this link.
/// \param[in] _ecm Entity-component manager.
/// \return Number of collisions in this link.
public: uint64_t CollisionCount(const EntityComponentManager &_ecm) const;

/// \brief Get the number of visuals which are immediate children of this
/// link.
/// \param[in] _ecm Entity-component manager.
/// \return Number of visuals in this link.
public: uint64_t VisualCount(const EntityComponentManager &_ecm) const;

/// \brief Get the pose of the link frame in the world coordinate frame.
/// \param[in] _ecm Entity-component manager.
/// \return Absolute Pose of the link or nullopt if the entity does not
Expand Down
6 changes: 0 additions & 6 deletions include/ignition/gazebo/Model.hh
Original file line number Diff line number Diff line change
Expand Up @@ -98,12 +98,6 @@ namespace ignition
/// \return Model's name.
public: std::string Name(const EntityComponentManager &_ecm) const;

/// \brief Get the ID of the entity which is the immediate parent of this
/// model.
/// \param[in] _ecm Entity-component manager.
/// \return Parent entity ID.
public: gazebo::Entity Parent(const EntityComponentManager &_ecm) const;

/// \brief Get whether this model is static.
/// \param[in] _ecm Entity-component manager.
/// \return True if static.
Expand Down
69 changes: 69 additions & 0 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@
#include <ignition/msgs/Utility.hh>

#include "ignition/gazebo/components/AngularVelocity.hh"
#include "ignition/gazebo/components/CanonicalLink.hh"
#include "ignition/gazebo/components/Collision.hh"
#include "ignition/gazebo/components/ExternalWorldWrenchCmd.hh"
#include "ignition/gazebo/components/Inertial.hh"
#include "ignition/gazebo/components/Joint.hh"
Expand All @@ -28,6 +30,8 @@
#include "ignition/gazebo/components/Name.hh"
#include "ignition/gazebo/components/ParentEntity.hh"
#include "ignition/gazebo/components/Pose.hh"
#include "ignition/gazebo/components/Visual.hh"
#include "ignition/gazebo/components/WindMode.hh"

#include "ignition/gazebo/Link.hh"

Expand Down Expand Up @@ -108,6 +112,71 @@ std::optional<Model> Link::ParentModel(const EntityComponentManager &_ecm) const
return std::optional<Model>(parent->Data());
}

//////////////////////////////////////////////////
Entity Link::CollisionByName(const EntityComponentManager &_ecm,
const std::string &_name) const
{
return _ecm.EntityByComponents(
components::ParentEntity(this->dataPtr->id),
components::Name(_name),
components::Collision());
}

//////////////////////////////////////////////////
Entity Link::VisualByName(const EntityComponentManager &_ecm,
const std::string &_name) const
{
return _ecm.EntityByComponents(
components::ParentEntity(this->dataPtr->id),
components::Name(_name),
components::Visual());
}

//////////////////////////////////////////////////
std::vector<Entity> Link::Collisions(const EntityComponentManager &_ecm) const
{
return _ecm.EntitiesByComponents(
components::ParentEntity(this->dataPtr->id),
components::Collision());
}

//////////////////////////////////////////////////
std::vector<Entity> Link::Visuals(const EntityComponentManager &_ecm) const
{
return _ecm.EntitiesByComponents(
components::ParentEntity(this->dataPtr->id),
components::Visual());
}

//////////////////////////////////////////////////
uint64_t Link::CollisionCount(const EntityComponentManager &_ecm) const
{
return this->Collisions(_ecm).size();
}

//////////////////////////////////////////////////
uint64_t Link::VisualCount(const EntityComponentManager &_ecm) const
{
return this->Visuals(_ecm).size();
}

//////////////////////////////////////////////////
bool Link::IsCanonical(const EntityComponentManager &_ecm) const
{
auto comp = _ecm.Component<components::CanonicalLink>(this->dataPtr->id);
return comp != nullptr;
}

//////////////////////////////////////////////////
bool Link::WindMode(const EntityComponentManager &_ecm) const
{
auto comp = _ecm.Component<components::WindMode>(this->dataPtr->id);
if (comp)
return comp->Data();

return false;
}

//////////////////////////////////////////////////
std::optional<math::Pose3d> Link::WorldPose(
const EntityComponentManager &_ecm) const
Expand Down
10 changes: 0 additions & 10 deletions src/Model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -86,16 +86,6 @@ std::string Model::Name(const EntityComponentManager &_ecm) const
return "";
}

//////////////////////////////////////////////////
Entity Model::Parent(const EntityComponentManager &_ecm) const
{
auto comp = _ecm.Component<components::ParentEntity>(this->dataPtr->id);
if (comp)
return comp->Data();

return kNullEntity;
}

//////////////////////////////////////////////////
bool Model::Static(const EntityComponentManager &_ecm) const
{
Expand Down
69 changes: 69 additions & 0 deletions test/integration/link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include <ignition/common/Console.hh>

#include <ignition/gazebo/components/AngularVelocity.hh>
#include <ignition/gazebo/components/CanonicalLink.hh>
#include <ignition/gazebo/components/Collision.hh>
#include <ignition/gazebo/components/Inertial.hh>
#include <ignition/gazebo/components/Joint.hh>
#include <ignition/gazebo/components/LinearAcceleration.hh>
Expand All @@ -29,6 +31,7 @@
#include <ignition/gazebo/components/Name.hh>
#include <ignition/gazebo/components/ParentEntity.hh>
#include <ignition/gazebo/components/Pose.hh>
#include <ignition/gazebo/components/Visual.hh>

#include <ignition/gazebo/EntityComponentManager.hh>
#include <ignition/gazebo/SdfEntityCreator.hh>
Expand Down Expand Up @@ -135,6 +138,72 @@ TEST_F(LinkIntegrationTest, ParentModel)
EXPECT_EQ(eModel, parentModel->Entity());
}

//////////////////////////////////////////////////
TEST_F(LinkIntegrationTest, VisualByName)
{
EntityComponentManager ecm;

// Link
auto eLink = ecm.CreateEntity();
Link link(eLink);
EXPECT_EQ(eLink, link.Entity());
EXPECT_EQ(0u, link.VisualCount(ecm));

// Visual
auto eVisual = ecm.CreateEntity();
ecm.CreateComponent<components::Visual>(eVisual, components::Visual());
ecm.CreateComponent<components::ParentEntity>(eVisual,
components::ParentEntity(eLink));
ecm.CreateComponent<components::Name>(eVisual,
components::Name("visual_name"));

// Check link
EXPECT_EQ(eVisual, link.VisualByName(ecm, "visual_name"));
EXPECT_EQ(1u, link.VisualCount(ecm));
}

//////////////////////////////////////////////////
TEST_F(LinkIntegrationTest, CollisionByName)
{
EntityComponentManager ecm;

// Link
auto eLink = ecm.CreateEntity();
Link link(eLink);
EXPECT_EQ(eLink, link.Entity());
EXPECT_EQ(0u, link.CollisionCount(ecm));

// Collision
auto eCollision = ecm.CreateEntity();
ecm.CreateComponent<components::Collision>(eCollision,
components::Collision());
ecm.CreateComponent<components::ParentEntity>(eCollision,
components::ParentEntity(eLink));
ecm.CreateComponent<components::Name>(eCollision,
components::Name("collision_name"));

// Check link
EXPECT_EQ(eCollision, link.CollisionByName(ecm, "collision_name"));
EXPECT_EQ(1u, link.CollisionCount(ecm));
}

//////////////////////////////////////////////////
TEST_F(LinkIntegrationTest, IsCanonical)
{
EntityComponentManager ecm;

auto id = ecm.CreateEntity();
ecm.CreateComponent<components::Link>(id, components::Link());

Link link(id);

EXPECT_FALSE(link.IsCanonical(ecm));

ecm.CreateComponent<components::CanonicalLink>(id,
components::CanonicalLink());
EXPECT_TRUE(link.IsCanonical(ecm));
}

//////////////////////////////////////////////////
TEST_F(LinkIntegrationTest, LinkPoses)
{
Expand Down
19 changes: 0 additions & 19 deletions test/integration/model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -90,25 +90,6 @@ TEST_F(ModelIntegrationTest, Name)
EXPECT_EQ("model_name", model.Name(ecm));
}

//////////////////////////////////////////////////
TEST_F(ModelIntegrationTest, Parent)
{
EntityComponentManager ecm;

auto id = ecm.CreateEntity();
ecm.CreateComponent<components::Model>(id, components::Model());

Model model(id);

// No parent
EXPECT_EQ(kNullEntity, model.Parent(ecm));

// Add parent
ecm.CreateComponent<components::ParentEntity>(id,
components::ParentEntity(100u));
EXPECT_EQ(100u, model.Parent(ecm));
}

//////////////////////////////////////////////////
TEST_F(ModelIntegrationTest, Static)
{
Expand Down
Loading

0 comments on commit f834169

Please sign in to comment.