@@ -104,6 +104,49 @@ constexpr const char * kSphereSdf = R"(<?xml version="1.0"?>
104
104
</sdf>
105
105
)" ;
106
106
107
+ // ///////////////////////////////////////////////
108
+ constexpr const char * kConeSdf = R"( <?xml version="1.0"?>
109
+ <sdf version="1.9">
110
+ <model name="cone">
111
+ <pose>0 0 0.5 0 0 0</pose>
112
+ <link name="cone_link">
113
+ <inertial>
114
+ <inertia>
115
+ <ixx>0.075</ixx>
116
+ <ixy>0</ixy>
117
+ <ixz>0</ixz>
118
+ <iyy>0.075</iyy>
119
+ <iyz>0</iyz>
120
+ <izz>0.075</izz>
121
+ </inertia>
122
+ <mass>1.0</mass>
123
+ </inertial>
124
+ <collision name="cone_collision">
125
+ <geometry>
126
+ <cone>
127
+ <radius>0.5</radius>
128
+ <length>1.0</length>
129
+ </cone>
130
+ </geometry>
131
+ </collision>
132
+ <visual name="cone_visual">
133
+ <geometry>
134
+ <cone>
135
+ <radius>0.5</radius>
136
+ <length>1.0</length>
137
+ </cone>
138
+ </geometry>
139
+ <material>
140
+ <ambient>0.3 0.3 0.3 1</ambient>
141
+ <diffuse>0.7 0.7 0.7 1</diffuse>
142
+ <specular>1 1 1 1</specular>
143
+ </material>
144
+ </visual>
145
+ </link>
146
+ </model>
147
+ </sdf>
148
+ )" ;
149
+
107
150
// ///////////////////////////////////////////////
108
151
constexpr const char * kCylinderSdf = R"( <?xml version="1.0"?>
109
152
<sdf version="1.9">
@@ -301,6 +344,8 @@ std::string gz::sim::getPrimitiveShape(const PrimitiveShape &_type)
301
344
return kBoxSdf ;
302
345
case PrimitiveShape::kSphere :
303
346
return kSphereSdf ;
347
+ case PrimitiveShape::kCone :
348
+ return kConeSdf ;
304
349
case PrimitiveShape::kCylinder :
305
350
return kCylinderSdf ;
306
351
case PrimitiveShape::kCapsule :
@@ -339,6 +384,8 @@ std::string gz::sim::getPrimitive(const std::string &_typeName)
339
384
return getPrimitiveShape (PrimitiveShape::kSphere );
340
385
else if (type == " cylinder" )
341
386
return getPrimitiveShape (PrimitiveShape::kCylinder );
387
+ else if (type == " cone" )
388
+ return getPrimitiveShape (PrimitiveShape::kCone );
342
389
else if (type == " capsule" )
343
390
return getPrimitiveShape (PrimitiveShape::kCapsule );
344
391
else if (type == " ellipsoid" )
@@ -354,6 +401,7 @@ std::string gz::sim::getPrimitive(const std::string &_typeName)
354
401
gzwarn << " The valid options are:\n " ;
355
402
gzwarn << " - box\n " ;
356
403
gzwarn << " - sphere\n " ;
404
+ gzwarn << " - cone\n " ;
357
405
gzwarn << " - cylinder\n " ;
358
406
gzwarn << " - capsule\n " ;
359
407
gzwarn << " - ellipsoid\n " ;
0 commit comments