Skip to content

Commit

Permalink
Support plotting for entities with / in the name (#3187)
Browse files Browse the repository at this point in the history
I noticed while testing the rexrov models from the rexrov
model in Field-Robotics-Lab/dave that the plotting window
does not work properly when elements of a model include
a forward-slash `/` in the entity name. To fix the problem,
the `/` characters are encoded as %2f in physics::Base::URI().
Corresponding decoding is added to the gui/plot/Palette class.

* Escape '%' as "%25" as well

This would prevent a string containing "%2f" from
incorrectly being unescaped to "/".

Signed-off-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
scpeters authored Mar 10, 2022
1 parent ea95601 commit 7fcdc94
Show file tree
Hide file tree
Showing 5 changed files with 172 additions and 2 deletions.
5 changes: 5 additions & 0 deletions gazebo/gui/plot/Palette.cc
Original file line number Diff line number Diff line change
Expand Up @@ -870,6 +870,11 @@ void Palette::IntrospectionUpdateSlot(const std::set<std::string> &_items)

// Process path
auto pathParts = common::split(pathStr, "/");
for (auto & part : pathParts)
{
part = common::replaceAll(part, "%2f", "/");
part = common::replaceAll(part, "%25", "%");
}

QStandardItem *previousItem = nullptr;
unsigned int i = 0;
Expand Down
67 changes: 67 additions & 0 deletions gazebo/gui/plot/Palette_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -112,5 +112,72 @@ void Palette_TEST::ModelsTab()
delete palette;
}

/////////////////////////////////////////////////
void Palette_TEST::ModelsTabNamesWithSlashes()
{
this->resMaxPercentChange = 5.0;
this->shareMaxPercentChange = 2.0;

this->Load("worlds/names_with_slashes.world");

// Get the number of models in the world
auto world = gazebo::physics::get_world("default");
QVERIFY(world != nullptr);

auto count = world->ModelCount();

// Create a new plot window widget
auto palette = new gazebo::gui::Palette(nullptr);
QVERIFY(palette != nullptr);

// Get the models model
auto modelsModel =
palette->findChild<QStandardItemModel *>("plotModelsModel");
QVERIFY(modelsModel != nullptr);

// Check the model has as many rows as there are top level models,
// plus the title
QCOMPARE(modelsModel->rowCount(), static_cast<int>(count + 1));

auto model = modelsModel->item(1);
QCOMPARE(0, model->text().toStdString().compare("double/pendulum_%2f"));
QVERIFY(model->hasChildren());

auto jointsLabel = model->child(3);
QVERIFY(!jointsLabel->hasChildren());

auto joint1 = model->child(4);
QCOMPARE(0, joint1->text().toStdString().compare("lower/joint"));
QCOMPARE(2, joint1->rowCount());

auto joint2 = model->child(5);
QCOMPARE(0, joint2->text().toStdString().compare("upper/joint"));
QCOMPARE(2, joint1->rowCount());

auto linksLabel = model->child(6);
QVERIFY(!linksLabel->hasChildren());

auto link1 = model->child(7);
QCOMPARE(0, link1->text().toStdString().compare("lower/link"));
QCOMPARE(3, link1->rowCount());

auto link2 = model->child(8);
QCOMPARE(0, link2->text().toStdString().compare("upper/link"));
QCOMPARE(3, link2->rowCount());

this->ProcessEventsAndDraw();

// Get the new models model
modelsModel =
palette->findChild<QStandardItemModel *>("plotModelsModel");
QVERIFY(modelsModel != nullptr);

// Check the model has as many rows as there are top level models,
// plus the title
QCOMPARE(modelsModel->rowCount(), static_cast<int>(count + 1));

delete palette;
}

// Generate a main function for the test
QTEST_MAIN(Palette_TEST)
3 changes: 3 additions & 0 deletions gazebo/gui/plot/Palette_TEST.hh
Original file line number Diff line number Diff line change
Expand Up @@ -30,5 +30,8 @@ class Palette_TEST : public QTestFixture

/// \brief Test the models tab.
private slots: void ModelsTab();

/// \brief test that models with slashes in name are handled.
private slots: void ModelsTabNamesWithSlashes();
};
#endif
11 changes: 9 additions & 2 deletions gazebo/physics/Base.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
*
*/
#include "gazebo/common/Assert.hh"
#include "gazebo/common/CommonIface.hh"
#include "gazebo/common/Console.hh"
#include "gazebo/common/Exception.hh"
#include "gazebo/common/SdfFrameSemantics.hh"
Expand Down Expand Up @@ -383,15 +384,21 @@ common::URI Base::URI() const
{
if (p->GetParent())
{
uri.Path().PushFront(p->GetName());
std::string escapedParentName = p->GetName();
escapedParentName = common::replaceAll(escapedParentName, "%", "%25");
escapedParentName = common::replaceAll(escapedParentName, "/", "%2f");
uri.Path().PushFront(escapedParentName);
uri.Path().PushFront(p->TypeStr());
}

p = p->GetParent();
}

uri.Path().PushBack(this->TypeStr());
uri.Path().PushBack(this->GetName());
std::string escapedName = this->GetName();
escapedName = common::replaceAll(escapedName, "%", "%25");
escapedName = common::replaceAll(escapedName, "/", "%2f");
uri.Path().PushBack(escapedName);
uri.Path().PushFront(this->world->Name());
uri.Path().PushFront("world");

Expand Down
88 changes: 88 additions & 0 deletions test/worlds/names_with_slashes.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
<?xml version="1.0" ?>
<sdf version="1.4">
<world name="default">
<physics type="ode">
<gravity>1 0 -9.81</gravity>
<max_step_size>0.00101</max_step_size>
</physics>
<include>
<uri>model://sun</uri>
</include>
<!-- add %2f to ensure it is escaped properly -->
<model name="double/pendulum_%2f">
<pose>0 0 0.9 0.7853981633974483 0 0</pose>
<link name="upper/link">
<pose>0 0 -0.05 0 0 0</pose>
<inertial>
<mass>0.02700000000000001</mass>
<inertia>
<ixx>2.272500000000001e-05</ixx>
<iyy>2.272500000000001e-05</iyy>
<izz>4.5000000000000035e-07</izz>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.010000000000000002 0.010000000000000002 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.010000000000000002 0.010000000000000002 0.1</size>
</box>
</geometry>
</visual>
</link>
<joint name="upper/joint" type="revolute">
<pose>0 0 0.05 0 0 0</pose>
<parent>world</parent>
<child>upper/link</child>
<axis>
<xyz>1 0 0</xyz>
</axis>
</joint>
<link name="lower/link">
<pose>0 0.17677669529663687 -0.2767766952966369 0.7853981633974483 0 0</pose>
<inertial>
<mass>3.375</mass>
<inertia>
<ixx>0.071015625</ixx>
<iyy>0.071015625</iyy>
<izz>0.0014062500000000004</izz>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyz>0.0</iyz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.05 0.05 0.5</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.05 0.05 0.5</size>
</box>
</geometry>
</visual>
</link>
<joint name="lower/joint" type="revolute">
<pose>0 0 0.25 0 0 0</pose>
<parent>upper/link</parent>
<child>lower/link</child>
<axis>
<xyz>1 0 0</xyz>
</axis>
</joint>
</model>
</world>
</sdf>

0 comments on commit 7fcdc94

Please sign in to comment.