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

Scale mode - Part2 #881

Merged
merged 23 commits into from
Aug 9, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
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
55 changes: 54 additions & 1 deletion include/ignition/gazebo/components/Model.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,10 @@
#ifndef IGNITION_GAZEBO_COMPONENTS_MODEL_HH_
#define IGNITION_GAZEBO_COMPONENTS_MODEL_HH_

#include <string>

#include <sdf/Model.hh>
#include <sdf/Root.hh>

#include <ignition/gazebo/components/Factory.hh>
#include <ignition/gazebo/components/Component.hh>
Expand All @@ -29,14 +32,64 @@ namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace serializers
{
class SdfModelSerializer
jennuine marked this conversation as resolved.
Show resolved Hide resolved
{
/// \brief Serialization for `sdf::Model`.
/// \param[in] _out Output stream.
/// \param[in] _time Model to stream
/// \return The stream.
public: static std::ostream &Serialize(std::ostream &_out,
const sdf::Model &_model)
{
sdf::ElementPtr modelElem = _model.Element();
if (!modelElem)
{
ignerr << "Unable to serialize sdf::Model" << std::endl;
return _out;
}

_out << "<?xml version=\"1.0\" ?>"
<< "<sdf version='" << SDF_PROTOCOL_VERSION << "'>"
<< modelElem->ToString("")
<< "</sdf>";
return _out;
}

/// \brief Deserialization for `sdf::Model`.
/// \param[in] _in Input stream.
/// \param[out] _model Model to populate
/// \return The stream.
public: static std::istream &Deserialize(std::istream &_in,
sdf::Model &_model)
{
sdf::Root root;
std::string sdf(std::istreambuf_iterator<char>(_in), {});

sdf::Errors errors = root.LoadSdfString(sdf);
if (!root.Element()->HasElement("model"))
{
ignerr << "Unable to unserialize sdf::Model" << std::endl;
return _in;
}

_model.Load(root.Element()->GetElement("model"));
return _in;
}
};
}

namespace components
{
/// \brief A component that identifies an entity as being a model.
using Model = Component<NoData, class ModelTag>;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.Model", Model)

/// \brief A component that holds the model's SDF DOM
using ModelSdf = Component<sdf::Model, class ModelTag>;
using ModelSdf = Component<sdf::Model,
class ModelTag,
serializers::SdfModelSerializer>;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ModelSdf", ModelSdf)
}
}
Expand Down
61 changes: 61 additions & 0 deletions test/integration/components.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,7 @@
#include <sdf/Material.hh>
#include <sdf/Noise.hh>
#include <sdf/Pbr.hh>
#include <sdf/sdf.hh>
#include <sdf/Sensor.hh>

#include "ignition/gazebo/components/Actor.hh"
Expand Down Expand Up @@ -1098,6 +1099,66 @@ TEST_F(ComponentsTest, Model)
comp3.Deserialize(istr);
}

/////////////////////////////////////////////////
TEST_F(ComponentsTest, ModelSdf)
{
std::ostringstream stream;
std::string version = SDF_VERSION;
stream
<< "<?xml version=\"1.0\" ?>"
<< "<sdf version='" << version << "'>"
<< " <world name=\"modelSDF\">"
<< " <physics name=\"1ms\" type=\"ode\">"
<< " <max_step_size>0.001</max_step_size>"
<< " <real_time_factor>1.0</real_time_factor>"
<< " </physics>"
<< " <plugin"
<< " filename=\"ignition-gazebo-physics-system\""
<< " name=\"ignition::gazebo::systems::Physics\">"
<< " </plugin>"
<< " <model name='my_model'>"
<< " <link name='link'>"
<< " <light type= 'point' name='my_light'>"
<< " <pose>0.1 0 0 0 0 0</pose>"
<< " <diffuse>0.2 0.3 0.4 1</diffuse>"
<< " <specular>0.3 0.4 0.5 1</specular>"
<< " </light>"
<< " </link>"
<< " </model>"
<< " </world>"
<< "</sdf>";

sdf::SDFPtr sdfParsed(new sdf::SDF());
sdf::init(sdfParsed);
ASSERT_TRUE(sdf::readString(stream.str(), sdfParsed));

// model
EXPECT_TRUE(sdfParsed->Root()->HasElement("world"));
sdf::ElementPtr worldElem = sdfParsed->Root()->GetElement("world");
EXPECT_TRUE(worldElem->HasElement("model"));
sdf::ElementPtr modelElem = worldElem->GetElement("model");
EXPECT_TRUE(modelElem->HasAttribute("name"));
EXPECT_EQ(modelElem->Get<std::string>("name"), "my_model");

sdf::Model model;
model.Load(modelElem);
EXPECT_EQ("my_model", model.Name());

// Create components
auto comp1 = components::ModelSdf(model);
components::ModelSdf comp2;

// Stream operators
std::ostringstream ostr;
comp1.Serialize(ostr);

std::istringstream istr(ostr.str());
comp2.Deserialize(istr);

EXPECT_EQ("my_model", comp2.Data().Name());
EXPECT_EQ(1u, comp2.Data().LinkCount());
}

/////////////////////////////////////////////////
TEST_F(ComponentsTest, Name)
{
Expand Down