Skip to content

Commit

Permalink
Address reviewer feedback
Browse files Browse the repository at this point in the history
Signed-off-by: Addisu Z. Taddese <addisu@openrobotics.org>
  • Loading branch information
azeey committed Feb 2, 2022
1 parent 74f06b7 commit 60708f0
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 6 deletions.
2 changes: 1 addition & 1 deletion src/Model.cc
Expand Up @@ -84,7 +84,7 @@ class sdf::Model::Implementation
public: std::vector<std::pair<std::optional<sdf::NestedInclude>,
sdf::InterfaceModelConstPtr>> interfaceModels;

/// \brief The interface models specified in this model.
/// \brief The interface models added into in this model via merge include.
public: std::vector<std::pair<std::optional<sdf::NestedInclude>,
sdf::InterfaceModelConstPtr>> mergedInterfaceModels;

Expand Down
7 changes: 3 additions & 4 deletions test/integration/interface_api.cc
Expand Up @@ -934,8 +934,7 @@ TEST_F(InterfaceAPIMergeInclude, Reposturing)
std::unordered_map<std::string, std::vector<std::string>> elementsToReposture;

// Create a resposture callback function for a given absolute model name. The
// name is used to store poses in `posesAfterReposture` as well as to lookup
// interface models in `models`
// name is used to store poses in `posesAfterReposture`.
auto makeRepostureFunc = [&](const std::string &_absoluteName)
{
auto repostureFunc =
Expand Down Expand Up @@ -1222,12 +1221,12 @@ R"(<include>
/////////////////////////////////////////////////
TEST_F(InterfaceAPIMergeInclude, JointModelChild)
{
const std::string testSdf = R"(
const std::string testSdf = R"(
<sdf version="1.9">
<model name="parent_model">
<link name="L1"/>
<include merge="true">
<uri>joint_model_parent_or_child.toml</uri>
<uri>joint_child_model_frame.toml</uri>
</include>
<frame name="frame_1" attached_to="joint_model_child"/>
</model>
Expand Down
Expand Up @@ -8,7 +8,7 @@ canonical_link = "base"
[links.base]
pose = "0 0 0 0 0 0"

# Test use of __model__ in joint parent or child
# Test use of __model__ in joint child
[links.parent_link]
pose = "0 0 0 0 0 0"

Expand Down

0 comments on commit 60708f0

Please sign in to comment.