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

Inspect more components #1090

Closed
wants to merge 3 commits into from
Closed
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
68 changes: 68 additions & 0 deletions src/gui/plugins/component_inspector/ComponentInspector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,11 +28,14 @@
#include "ignition/gazebo/components/AngularAcceleration.hh"
#include "ignition/gazebo/components/AngularVelocity.hh"
#include "ignition/gazebo/components/CastShadows.hh"
#include "ignition/gazebo/components/CenterOfVolume.hh"
#include "ignition/gazebo/components/ChildLinkName.hh"
#include "ignition/gazebo/components/Collision.hh"
#include "ignition/gazebo/components/ExternalWorldWrenchCmd.hh"
#include "ignition/gazebo/components/Factory.hh"
#include "ignition/gazebo/components/Gravity.hh"
#include "ignition/gazebo/components/Joint.hh"
#include "ignition/gazebo/components/JointPosition.hh"
#include "ignition/gazebo/components/Level.hh"
#include "ignition/gazebo/components/Light.hh"
#include "ignition/gazebo/components/LightCmd.hh"
Expand Down Expand Up @@ -60,6 +63,7 @@
#include "ignition/gazebo/components/SphericalCoordinates.hh"
#include "ignition/gazebo/components/Static.hh"
#include "ignition/gazebo/components/Visual.hh"
#include "ignition/gazebo/components/Volume.hh"
#include "ignition/gazebo/components/WindMode.hh"
#include "ignition/gazebo/components/World.hh"
#include "ignition/gazebo/EntityComponentManager.hh"
Expand Down Expand Up @@ -288,6 +292,25 @@ void ignition::gazebo::setData(QStandardItem *_item,
}), ComponentsModel::RoleNames().key("data"));
}

//////////////////////////////////////////////////
template<>
void ignition::gazebo::setData(QStandardItem *_item, const msgs::Wrench &_data)
{
if (nullptr == _item)
return;

_item->setData(QString("Wrench"),
ComponentsModel::RoleNames().key("dataType"));
_item->setData(QList({
QVariant(_data.force().x()),
QVariant(_data.force().y()),
QVariant(_data.force().z()),
QVariant(_data.torque().x()),
QVariant(_data.torque().y()),
QVariant(_data.torque().z())
}), ComponentsModel::RoleNames().key("data"));
}

//////////////////////////////////////////////////
void ignition::gazebo::setUnit(QStandardItem *_item, const std::string &_unit)
{
Expand Down Expand Up @@ -551,13 +574,27 @@ void ComponentInspector::Update(const UpdateInfo &,
if (comp)
setData(item, comp->Data());
}
else if (typeId == components::CenterOfVolume::typeId)
{
auto comp = _ecm.Component<components::CenterOfVolume>(
this->dataPtr->entity);
if (comp)
setData(item, comp->Data());
}
else if (typeId == components::ChildLinkName::typeId)
{
auto comp = _ecm.Component<components::ChildLinkName>(
this->dataPtr->entity);
if (comp)
setData(item, comp->Data());
}
else if (typeId == components::ExternalWorldWrenchCmd::typeId)
{
auto comp = _ecm.Component<components::ExternalWorldWrenchCmd>(
this->dataPtr->entity);
if (comp)
setData(item, comp->Data());
}
else if (typeId == components::Gravity::typeId)
{
auto comp = _ecm.Component<components::Gravity>(this->dataPtr->entity);
Expand All @@ -567,6 +604,17 @@ void ComponentInspector::Update(const UpdateInfo &,
setUnit(item, "m/s\u00B2");
}
}
else if (typeId == components::JointPosition::typeId)
{
auto comp = _ecm.Component<components::JointPosition>(this->dataPtr->entity);
if (comp)
{
// TODO(louise) support any number of axes
setData(item, comp->Data()[0]);
// TODO(louise) choose unit based on joint type
// setUnit(item, "rad");
}
}
else if (typeId == components::LinearAcceleration::typeId)
{
auto comp = _ecm.Component<components::LinearAcceleration>(
Expand Down Expand Up @@ -718,6 +766,16 @@ void ComponentInspector::Update(const UpdateInfo &,
if (comp)
setData(item, comp->Data());
}
else if (typeId == components::Volume::typeId)
{
auto comp = _ecm.Component<components::Volume>(
this->dataPtr->entity);
if (comp)
{
setData(item, comp->Data());
setUnit(item, "m\u00B3");
}
}
else if (typeId == components::WindMode::typeId)
{
auto comp = _ecm.Component<components::WindMode>(this->dataPtr->entity);
Expand All @@ -734,6 +792,16 @@ void ComponentInspector::Update(const UpdateInfo &,
setUnit(item, "rad/s\u00B2");
}
}
else if (typeId == components::WorldAngularVelocity::typeId)
{
auto comp = _ecm.Component<components::WorldAngularVelocity>(
this->dataPtr->entity);
if (comp)
{
setData(item, comp->Data());
setUnit(item, "rad/s");
}
}
else if (typeId == components::WorldLinearVelocity::typeId)
{
auto comp = _ecm.Component<components::WorldLinearVelocity>(
Expand Down
2 changes: 2 additions & 0 deletions src/gui/plugins/component_inspector/ComponentInspector.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
<qresource prefix="ComponentInspector/">
<file>Boolean.qml</file>
<file>ComponentInspector.qml</file>
<file>Float.qml</file>
<file>Light.qml</file>
<file>NoData.qml</file>
<file>Physics.qml</file>
Expand All @@ -10,6 +11,7 @@
<file>String.qml</file>
<file>TypeHeader.qml</file>
<file>Vector3d.qml</file>
<file>Wrench.qml</file>
<file>plottable_icon.svg</file>
</qresource>
</RCC>
2 changes: 1 addition & 1 deletion src/gui/plugins/component_inspector/Float.qml
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ Rectangle {
value: model.data
minimumValue: -spinMax
maximumValue: spinMax
decimals: xSpin.width < 100 ? 2 : 6
decimals: content.width < 100 ? 2 : 6
Layout.fillWidth: true
}

Expand Down
Loading