Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Joint DOM API to access joint sensors #517

Merged
merged 4 commits into from
Mar 24, 2021
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
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
24 changes: 24 additions & 0 deletions include/sdf/Joint.hh
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ namespace sdf
struct FrameAttachedToGraph;
struct PoseRelativeToGraph;
template <typename T> class ScopedGraph;
class Sensor;

/// \enum JointType
/// \brief The set of joint types. INVALID indicates that joint type has
Expand Down Expand Up @@ -201,6 +202,29 @@ namespace sdf
/// \return SemanticPose object for this link.
public: sdf::SemanticPose SemanticPose() const;

/// \brief Get the number of sensors.
/// \return Number of sensors contained in this Joint object.
public: uint64_t SensorCount() const;

/// \brief Get a sensor based on an index.
/// \param[in] _index Index of the sensor. The index should be in the
/// range [0..SensorCount()).
/// \return Pointer to the sensor. Nullptr if the index does not exist.
/// \sa uint64_t SensorCount() const
public: const Sensor *SensorByIndex(const uint64_t _index) const;

/// \brief Get whether a sensor name exists.
/// \param[in] _name Name of the sensor to check.
/// \return True if there exists a sensor with the given name.
public: bool SensorNameExists(const std::string &_name) const;

/// \brief Get a sensor based on a name.
/// \param[in] _name Name of the sensor.
/// \return Pointer to the sensor. Nullptr if a sensor with the given name
/// does not exist.
/// \sa bool SensorNameExists(const std::string &_name) const
public: const Sensor *SensorByName(const std::string &_name) const;

/// \brief Give the scoped FrameAttachedToGraph to be used for resolving
/// parent and child link names. This is private and is intended to be
/// called by Model::Load.
Expand Down
48 changes: 48 additions & 0 deletions src/Joint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include "sdf/Error.hh"
#include "sdf/Joint.hh"
#include "sdf/JointAxis.hh"
#include "sdf/Sensor.hh"
#include "sdf/Types.hh"
#include "FrameSemantics.hh"
#include "ScopedGraph.hh"
Expand Down Expand Up @@ -65,6 +66,9 @@ class sdf::Joint::Implementation

/// \brief Scoped Pose Relative-To graph at the parent model scope.
public: sdf::ScopedGraph<sdf::PoseRelativeToGraph> poseRelativeToGraph;

/// \brief The sensors specified in this joint.
public: std::vector<Sensor> sensors;
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -215,6 +219,10 @@ Errors Joint::Load(ElementPtr _sdf)
"A joint type is required, but is not set."});
}

// Load all the sensors.
Errors sensorLoadErrors = loadUniqueRepeated<Sensor>(_sdf, "sensor",
this->dataPtr->sensors);
errors.insert(errors.end(), sensorLoadErrors.begin(), sensorLoadErrors.end());
return errors;
}

Expand Down Expand Up @@ -405,3 +413,43 @@ sdf::ElementPtr Joint::Element() const
{
return this->dataPtr->sdf;
}

/////////////////////////////////////////////////
uint64_t Joint::SensorCount() const
{
return this->dataPtr->sensors.size();
}

/////////////////////////////////////////////////
const Sensor *Joint::SensorByIndex(const uint64_t _index) const
{
if (_index < this->dataPtr->sensors.size())
return &this->dataPtr->sensors[_index];
return nullptr;
}

/////////////////////////////////////////////////
bool Joint::SensorNameExists(const std::string &_name) const
{
for (auto const &s : this->dataPtr->sensors)
{
if (s.Name() == _name)
{
return true;
}
}
return false;
jennuine marked this conversation as resolved.
Show resolved Hide resolved
}

/////////////////////////////////////////////////
const Sensor *Joint::SensorByName(const std::string &_name) const
{
for (auto const &s : this->dataPtr->sensors)
{
if (s.Name() == _name)
{
return &s;
}
}
return nullptr;
}
7 changes: 7 additions & 0 deletions src/Joint_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,13 @@ TEST(DOMJoint, Construction)
const double threadPitch = 0.1;
joint.SetThreadPitch(threadPitch);
EXPECT_DOUBLE_EQ(threadPitch, joint.ThreadPitch());

EXPECT_EQ(0u, joint.SensorCount());
EXPECT_EQ(nullptr, joint.SensorByIndex(0));
EXPECT_EQ(nullptr, joint.SensorByIndex(1));
EXPECT_EQ(nullptr, joint.SensorByName("empty"));
EXPECT_FALSE(joint.SensorNameExists(""));
EXPECT_FALSE(joint.SensorNameExists("default"));
}

/////////////////////////////////////////////////
Expand Down
42 changes: 42 additions & 0 deletions test/integration/joint_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,13 +20,15 @@

#include "sdf/Element.hh"
#include "sdf/Filesystem.hh"
#include "sdf/ForceTorque.hh"
#include "sdf/Frame.hh"
#include "sdf/Joint.hh"
#include "sdf/JointAxis.hh"
#include "sdf/Link.hh"
#include "sdf/Model.hh"
#include "sdf/Root.hh"
#include "sdf/SDFImpl.hh"
#include "sdf/Sensor.hh"
#include "sdf/Types.hh"
#include "sdf/parser.hh"
#include "test_config.h"
Expand Down Expand Up @@ -857,3 +859,43 @@ TEST(DOMJoint, LoadJointNestedParentChild)
EXPECT_EQ(Pose(0, -1, 1, IGN_PI_2, 0, 0), pose);
}
}


//////////////////////////////////////////////////
TEST(DOMJoint, Sensors)
{
const std::string testFile =
sdf::testing::TestFile("sdf", "joint_sensors.sdf");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this file is missing

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I always forget to add the sdf file 🤦🏾‍♂️ . Added in 8d50882


// Load the SDF file
sdf::Root root;
auto errors = root.Load(testFile);
EXPECT_TRUE(errors.empty()) << errors;

// Get the first model
const sdf::Model *model = root.Model();
ASSERT_NE(nullptr, model);
EXPECT_EQ("model", model->Name());

// Get the first joint
const sdf::Joint *joint = model->JointByIndex(0);
ASSERT_NE(nullptr, joint);
EXPECT_EQ("joint", joint->Name());
EXPECT_EQ(1u, joint->SensorCount());

ignition::math::Pose3d pose;

// Get the force_torque sensor
const sdf::Sensor *forceTorqueSensor =
joint->SensorByName("force_torque_sensor");
ASSERT_NE(nullptr, forceTorqueSensor);
EXPECT_EQ("force_torque_sensor", forceTorqueSensor->Name());
EXPECT_EQ(sdf::SensorType::FORCE_TORQUE, forceTorqueSensor->Type());
EXPECT_EQ(ignition::math::Pose3d(10, 11, 12, 0, 0, 0),
forceTorqueSensor->RawPose());
auto forceTorqueSensorConfig = forceTorqueSensor->ForceTorqueSensor();
ASSERT_NE(nullptr, forceTorqueSensorConfig);
EXPECT_EQ(sdf::ForceTorqueFrame::PARENT, forceTorqueSensorConfig->Frame());
EXPECT_EQ(sdf::ForceTorqueMeasureDirection::PARENT_TO_CHILD,
forceTorqueSensorConfig->MeasureDirection());
}