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 non-const overload for Root::Model() getter #1524

Merged
merged 3 commits into from
Jan 6, 2025
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
5 changes: 5 additions & 0 deletions include/sdf/Root.hh
Original file line number Diff line number Diff line change
Expand Up @@ -170,6 +170,11 @@ namespace sdf
/// \return A pointer to the model, nullptr if it doesn't exist
public: const sdf::Model *Model() const;

/// \brief Get a mutable pointer to the model object if it exists.
///
/// \return A pointer to the model; nullptr if it doesn't exist.
public: sdf::Model *Model();

/// \brief Set the model object. This will override any existing model,
/// actor, and light object.
/// \param[in] _model The model to use.
Expand Down
2 changes: 1 addition & 1 deletion python/src/sdf/pyRoot.cc
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,7 @@ void defineRoot(pybind11::object module)
"Get a world based on an index.")
.def("world_name_exists", &sdf::Root::WorldNameExists,
"Get whether a world name exists.")
.def("model", &sdf::Root::Model,
.def("model", pybind11::overload_cast<>(&sdf::Root::Model),
pybind11::return_value_policy::reference_internal,
"Get a model object if it exists.")
.def("set_model", &sdf::Root::SetModel,
Expand Down
6 changes: 6 additions & 0 deletions src/Root.cc
Original file line number Diff line number Diff line change
Expand Up @@ -475,6 +475,12 @@ const Model *Root::Model() const
return std::get_if<sdf::Model>(&this->dataPtr->modelLightOrActor);
}

/////////////////////////////////////////////////
Model *Root::Model()
{
return std::get_if<sdf::Model>(&this->dataPtr->modelLightOrActor);
}

/////////////////////////////////////////////////
void Root::SetModel(const sdf::Model &_model)
{
Expand Down
23 changes: 16 additions & 7 deletions src/Root_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,9 @@ TEST(DOMRoot, Construction)
EXPECT_EQ(nullptr, root.Model());
EXPECT_EQ(nullptr, root.Light());
EXPECT_EQ(nullptr, root.Actor());

const sdf::Root &const_root = root;
EXPECT_EQ(nullptr, const_root.Model());
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -424,6 +427,7 @@ TEST(DOMRoot, ToElementEmpty)
TEST(DOMRoot, ToElementModel)
{
sdf::Root root;
const sdf::Root &const_root = root;

sdf::Actor actor1;
actor1.SetName("actor1");
Expand All @@ -438,6 +442,7 @@ TEST(DOMRoot, ToElementModel)
root.SetModel(model1);

ASSERT_NE(nullptr, root.Model());
ASSERT_NE(nullptr, const_root.Model());
ASSERT_EQ(nullptr, root.Light());
ASSERT_EQ(nullptr, root.Actor());
EXPECT_EQ(0u, root.WorldCount());
Expand All @@ -447,12 +452,15 @@ TEST(DOMRoot, ToElementModel)
ASSERT_NE(nullptr, elem);

sdf::Root root2;
const sdf::Root &const_root2 = root2;
root2.LoadSdfString(elem->ToString(""));

EXPECT_EQ(SDF_VERSION, root2.Version());

ASSERT_NE(nullptr, root2.Model());
ASSERT_NE(nullptr, const_root2.Model());
EXPECT_EQ("model1", root2.Model()->Name());
EXPECT_EQ("model1", const_root2.Model()->Name());

ASSERT_EQ(nullptr, root2.Actor());
ASSERT_EQ(nullptr, root2.Light());
Expand Down Expand Up @@ -651,24 +659,25 @@ TEST(DOMRoot, CopyConstructor)
TEST(DOMRoot, WorldByName)
{
sdf::Root root;
EXPECT_EQ(0u, root.WorldCount());
const sdf::Root &const_root = root;
EXPECT_EQ(0u, const_root.WorldCount());

sdf::World world;
world.SetName("world1");
EXPECT_TRUE(root.AddWorld(world).empty());
EXPECT_EQ(1u, root.WorldCount());
EXPECT_EQ(1u, const_root.WorldCount());

EXPECT_TRUE(root.WorldNameExists("world1"));
const sdf::World *wPtr = root.WorldByName("world1");
EXPECT_NE(nullptr, wPtr);
EXPECT_TRUE(const_root.WorldNameExists("world1"));
EXPECT_NE(nullptr, root.WorldByName("world1"));
EXPECT_NE(nullptr, const_root.WorldByName("world1"));

// Modify the world
sdf::World *w = root.WorldByName("world1");
ASSERT_NE(nullptr, w);
EXPECT_EQ("world1", w->Name());
w->SetName("world2");
ASSERT_TRUE(root.WorldNameExists("world2"));
EXPECT_EQ("world2", root.WorldByName("world2")->Name());
ASSERT_TRUE(const_root.WorldNameExists("world2"));
EXPECT_EQ("world2", const_root.WorldByName("world2")->Name());
}

/////////////////////////////////////////////////
Expand Down
Loading