Skip to content

Commit

Permalink
Backport: Adding cone primitives. (#2410)
Browse files Browse the repository at this point in the history
Signed-off-by: Benjamin Perseghetti <bperseghetti@rudislabs.com>
  • Loading branch information
bperseghetti committed Jun 26, 2024
1 parent cd9a855 commit 80faf44
Show file tree
Hide file tree
Showing 15 changed files with 173 additions and 10 deletions.
48 changes: 40 additions & 8 deletions examples/worlds/shapes.sdf
Original file line number Diff line number Diff line change
@@ -1,12 +1,13 @@
<?xml version="1.0" ?>
<!--
Try moving a model:
gz service -s /world/shapes/set_pose --reqtype gz.msgs.Pose --reptype gz.msgs.Boolean --timeout 300 --req 'name: "box", position: {z: 5.0}'
-->
<sdf version="1.6">
<sdf version="1.12">
<!--
Try moving a model using the command in the following CDATA block::
-->
<![CDATA[
gz service -s /world/shapes/set_pose \
--reqtype gz.msgs.Pose --reptype gz.msgs.Boolean \
--timeout 300 --req 'name: "box", position: {z: 5.0}'
]]>
<world name="shapes">
<scene>
<ambient>1.0 1.0 1.0</ambient>
Expand Down Expand Up @@ -240,5 +241,36 @@ Try moving a model:
</visual>
</link>
</model>

<model name="cone">
<pose>0 4.5 0.5 0 0 0</pose>
<link name="cone_link">
<inertial auto="true">
<density>1</density>
</inertial>
<collision name="cone_collision">
<geometry>
<cone>
<radius>0.5</radius>
<length>1.0</length>
</cone>
</geometry>
</collision>

<visual name="cone_visual">
<geometry>
<cone>
<radius>0.5</radius>
<length>1.0</length>
</cone>
</geometry>
<material>
<ambient>1 0.47 0 1</ambient>
<diffuse>1 0.47 0 1</diffuse>
<specular>1 0.47 0 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>
5 changes: 3 additions & 2 deletions include/gz/sim/Primitives.hh
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ namespace gz
{
kBox,
kCapsule,
kCone,
kCylinder,
kEllipsoid,
kSphere,
Expand Down Expand Up @@ -67,8 +68,8 @@ namespace gz
/// \brief Return an SDF string of one of the available primitive shape or
/// light types.
/// \param[in] _typeName Type name of the of shape or light to retrieve.
/// Must be one of: box, sphere, cylinder, capsule, ellipsoid, directional,
/// point, or spot.
/// Must be one of: box, sphere, cylinder, cone, capsule, ellipsoid,
/// directional, point, or spot.
/// \return String containing SDF description of primitive shape or light.
/// Empty string if the _typeName is invalid.
std::string GZ_SIM_VISIBLE
Expand Down
18 changes: 18 additions & 0 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <gz/msgs/axis_aligned_box.pb.h>
#include <gz/msgs/boxgeom.pb.h>
#include <gz/msgs/capsulegeom.pb.h>
#include <gz/msgs/conegeom.pb.h>
#include <gz/msgs/cylindergeom.pb.h>
#include <gz/msgs/ellipsoidgeom.pb.h>
#include <gz/msgs/entity.pb.h>
Expand Down Expand Up @@ -53,6 +54,7 @@
#include <sdf/Box.hh>
#include <sdf/Camera.hh>
#include <sdf/Capsule.hh>
#include <sdf/Cone.hh>
#include <sdf/Cylinder.hh>
#include <sdf/Ellipsoid.hh>
#include <sdf/Geometry.hh>
Expand Down Expand Up @@ -176,6 +178,12 @@ msgs::Geometry gz::sim::convert(const sdf::Geometry &_in)
out.mutable_capsule()->set_radius(_in.CapsuleShape()->Radius());
out.mutable_capsule()->set_length(_in.CapsuleShape()->Length());
}
else if (_in.Type() == sdf::GeometryType::CONE && _in.ConeShape())
{
out.set_type(msgs::Geometry::CONE);
out.mutable_cone()->set_radius(_in.ConeShape()->Radius());
out.mutable_cone()->set_length(_in.ConeShape()->Length());
}
else if (_in.Type() == sdf::GeometryType::CYLINDER && _in.CylinderShape())
{
out.set_type(msgs::Geometry::CYLINDER);
Expand Down Expand Up @@ -293,6 +301,16 @@ sdf::Geometry gz::sim::convert(const msgs::Geometry &_in)

out.SetCapsuleShape(capsuleShape);
}
else if (_in.type() == msgs::Geometry::CONE && _in.has_cone())
{
out.SetType(sdf::GeometryType::CONE);

sdf::Cone coneShape;
coneShape.SetRadius(_in.cone().radius());
coneShape.SetLength(_in.cone().length());

out.SetConeShape(coneShape);
}
else if (_in.type() == msgs::Geometry::CYLINDER && _in.has_cylinder())
{
out.SetType(sdf::GeometryType::CYLINDER);
Expand Down
48 changes: 48 additions & 0 deletions src/Primitives.cc
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,49 @@ constexpr const char * kSphereSdf = R"(<?xml version="1.0"?>
</sdf>
)";

/////////////////////////////////////////////////
constexpr const char * kConeSdf = R"(<?xml version="1.0"?>
<sdf version="1.9">
<model name="cone">
<pose>0 0 0.5 0 0 0</pose>
<link name="cone_link">
<inertial>
<inertia>
<ixx>0.075</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.075</iyy>
<iyz>0</iyz>
<izz>0.075</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="cone_collision">
<geometry>
<cone>
<radius>0.5</radius>
<length>1.0</length>
</cone>
</geometry>
</collision>
<visual name="cone_visual">
<geometry>
<cone>
<radius>0.5</radius>
<length>1.0</length>
</cone>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1</ambient>
<diffuse>0.7 0.7 0.7 1</diffuse>
<specular>1 1 1 1</specular>
</material>
</visual>
</link>
</model>
</sdf>
)";

/////////////////////////////////////////////////
constexpr const char * kCylinderSdf = R"(<?xml version="1.0"?>
<sdf version="1.9">
Expand Down Expand Up @@ -301,6 +344,8 @@ std::string gz::sim::getPrimitiveShape(const PrimitiveShape &_type)
return kBoxSdf;
case PrimitiveShape::kSphere:
return kSphereSdf;
case PrimitiveShape::kCone:
return kConeSdf;
case PrimitiveShape::kCylinder:
return kCylinderSdf;
case PrimitiveShape::kCapsule:
Expand Down Expand Up @@ -339,6 +384,8 @@ std::string gz::sim::getPrimitive(const std::string &_typeName)
return getPrimitiveShape(PrimitiveShape::kSphere);
else if (type == "cylinder")
return getPrimitiveShape(PrimitiveShape::kCylinder);
else if (type == "cone")
return getPrimitiveShape(PrimitiveShape::kCone);
else if (type == "capsule")
return getPrimitiveShape(PrimitiveShape::kCapsule);
else if (type == "ellipsoid")
Expand All @@ -354,6 +401,7 @@ std::string gz::sim::getPrimitive(const std::string &_typeName)
gzwarn << "The valid options are:\n";
gzwarn << " - box\n";
gzwarn << " - sphere\n";
gzwarn << " - cone\n";
gzwarn << " - cylinder\n";
gzwarn << " - capsule\n";
gzwarn << " - ellipsoid\n";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -373,6 +373,14 @@ Rectangle {
}
}

MenuItem {
id: coneLink
text: "Cone"
onClicked: {
ComponentInspectorEditor.OnAddEntity("cone", "link");
}
}

MenuItem {
id: cylinderLink
text: "Cylinder"
Expand Down
9 changes: 9 additions & 0 deletions src/gui/plugins/component_inspector_editor/ModelEditor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
#include <sdf/Box.hh>
#include <sdf/Ellipsoid.hh>
#include <sdf/Capsule.hh>
#include <sdf/Cone.hh>
#include <sdf/Cylinder.hh>
#include <sdf/Mesh.hh>
#include <sdf/Sphere.hh>
Expand Down Expand Up @@ -330,6 +331,14 @@ std::optional<sdf::Geometry> ModelEditorPrivate::CreateGeom(
geom.SetSphereShape(shape);
geom.SetType(sdf::GeometryType::SPHERE);
}
else if (_eta.geomOrLightType == "cone")
{
sdf::Cone shape;
shape.SetRadius(size.X() * 0.5);
shape.SetLength(size.Z());
geom.SetConeShape(shape);
geom.SetType(sdf::GeometryType::CONE);
}
else if (_eta.geomOrLightType == "cylinder")
{
sdf::Cylinder shape;
Expand Down
9 changes: 9 additions & 0 deletions src/gui/plugins/entity_tree/EntityTree.qml
Original file line number Diff line number Diff line change
Expand Up @@ -202,6 +202,15 @@ Rectangle {
}
}

MenuItem
{
id: cone
text: "Cone"
onClicked: {
EntityTree.OnInsertEntity("cone")
}
}

MenuItem
{
id: cylinder
Expand Down
17 changes: 17 additions & 0 deletions src/gui/plugins/shapes/Shapes.qml
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,23 @@ ToolBar {
Shapes.OnMode("sphere")
}
}
ToolButton {
id: cone
ToolTip.text: "Cone"
ToolTip.visible: hovered
ToolTip.delay: Qt.styleHints.mousePressAndHoldInterval
contentItem: Image {
fillMode: Image.Pad
horizontalAlignment: Image.AlignHCenter
verticalAlignment: Image.AlignVCenter
source: "cone.png"
sourceSize.width: 24;
sourceSize.height: 24;
}
onClicked: {
Shapes.OnMode("cone")
}
}
ToolButton {
id: cylinder
ToolTip.text: "Cylinder"
Expand Down
1 change: 1 addition & 0 deletions src/gui/plugins/shapes/Shapes.qrc
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
<file>Shapes.qml</file>
<file>box.png</file>
<file>sphere.png</file>
<file>cone.png</file>
<file>cylinder.png</file>
<file>capsule.png</file>
<file>ellipsoid.png</file>
Expand Down
Binary file added src/gui/plugins/shapes/cone.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@
#include <gz/transport/Node.hh>

#include <sdf/Capsule.hh>
#include <sdf/Cone.hh>
#include <sdf/Ellipsoid.hh>
#include <sdf/Joint.hh>
#include <sdf/Heightmap.hh>
Expand Down Expand Up @@ -1191,6 +1192,13 @@ rendering::GeometryPtr VisualizationCapabilitiesPrivate::CreateGeometry(
capsule->SetLength(_geom.CapsuleShape()->Length());
geom = capsule;
}
else if (_geom.Type() == sdf::GeometryType::CONE)
{
geom = this->scene->CreateCone();
scale.X() = _geom.ConeShape()->Radius() * 2;
scale.Y() = scale.X();
scale.Z() = _geom.ConeShape()->Length();
}
else if (_geom.Type() == sdf::GeometryType::CYLINDER)
{
geom = this->scene->CreateCylinder();
Expand Down
2 changes: 2 additions & 0 deletions src/rendering/MarkerManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -387,6 +387,8 @@ rendering::MarkerType MarkerManagerPrivate::MsgToType(
return rendering::MarkerType::MT_BOX;
case msgs::Marker::CAPSULE:
return rendering::MarkerType::MT_CAPSULE;
case msgs::Marker::CONE:
return rendering::MarkerType::MT_CONE;
case msgs::Marker::CYLINDER:
return rendering::MarkerType::MT_CYLINDER;
case msgs::Marker::LINE_STRIP:
Expand Down
8 changes: 8 additions & 0 deletions src/rendering/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include <sdf/Box.hh>
#include <sdf/Capsule.hh>
#include <sdf/Collision.hh>
#include <sdf/Cone.hh>
#include <sdf/Cylinder.hh>
#include <sdf/Ellipsoid.hh>
#include <sdf/Heightmap.hh>
Expand Down Expand Up @@ -667,6 +668,13 @@ rendering::GeometryPtr SceneManager::LoadGeometry(const sdf::Geometry &_geom,
capsule->SetLength(_geom.CapsuleShape()->Length());
geom = capsule;
}
else if (_geom.Type() == sdf::GeometryType::CONE)
{
geom = this->dataPtr->scene->CreateCone();
scale.X() = _geom.ConeShape()->Radius() * 2;
scale.Y() = scale.X();
scale.Z() = _geom.ConeShape()->Length();
}
else if (_geom.Type() == sdf::GeometryType::CYLINDER)
{
geom = this->dataPtr->scene->CreateCylinder();
Expand Down
1 change: 1 addition & 0 deletions src/systems/physics/Physics.cc
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@
#include <gz/physics/RequestEngine.hh>

#include <gz/physics/BoxShape.hh>
#include <gz/physics/ConeShape.hh>
#include <gz/physics/ContactProperties.hh>
#include <gz/physics/CylinderShape.hh>
#include <gz/physics/ForwardStep.hh>
Expand Down
1 change: 1 addition & 0 deletions src/systems/physics/Physics.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
// Features need to be defined ahead of entityCast
#include <gz/physics/BoxShape.hh>
#include <gz/physics/CapsuleShape.hh>
#include <gz/physics/ConeShape.hh>
#include <gz/physics/CylinderShape.hh>
#include <gz/physics/EllipsoidShape.hh>
#include <gz/physics/ForwardStep.hh>
Expand Down

0 comments on commit 80faf44

Please sign in to comment.