Skip to content

Commit e01fa3a

Browse files
authored
Merge 3386838 into 5d3970a
2 parents 5d3970a + 3386838 commit e01fa3a

23 files changed

+830
-108
lines changed

examples/standalone/marker/marker.cc

+11-9
Original file line numberDiff line numberDiff line change
@@ -70,19 +70,19 @@ int main(int _argc, char **_argv)
7070
markerMsg.mutable_lifetime()->set_sec(0);
7171
node.Request("/marker", markerMsg);
7272

73-
std::cout << "Moving the sphere to x=0, y=1, z=1\n";
73+
std::cout << "Moving the black sphere to x=0, y=1, z=1\n";
7474
std::this_thread::sleep_for(std::chrono::seconds(4));
7575
ignition::msgs::Set(markerMsg.mutable_pose(),
7676
ignition::math::Pose3d(0, 1, 1, 0, 0, 0));
7777
node.Request("/marker", markerMsg);
7878

79-
std::cout << "Shrinking the sphere\n";
79+
std::cout << "Shrinking the black sphere\n";
8080
std::this_thread::sleep_for(std::chrono::seconds(4));
8181
ignition::msgs::Set(markerMsg.mutable_scale(),
8282
ignition::math::Vector3d(0.2, 0.2, 0.2));
8383
node.Request("/marker", markerMsg);
8484

85-
std::cout << "Changing the sphere to red\n";
85+
std::cout << "Changing the black sphere to red\n";
8686
markerMsg.mutable_material()->mutable_ambient()->set_r(1);
8787
markerMsg.mutable_material()->mutable_ambient()->set_g(0);
8888
markerMsg.mutable_material()->mutable_ambient()->set_b(0);
@@ -92,7 +92,7 @@ int main(int _argc, char **_argv)
9292
std::this_thread::sleep_for(std::chrono::seconds(4));
9393
node.Request("/marker", markerMsg);
9494

95-
std::cout << "Adding a green box\n";
95+
std::cout << "Adding a green ellipsoid\n";
9696
markerMsg.mutable_material()->mutable_ambient()->set_r(0);
9797
markerMsg.mutable_material()->mutable_ambient()->set_g(1);
9898
markerMsg.mutable_material()->mutable_ambient()->set_b(0);
@@ -102,16 +102,18 @@ int main(int _argc, char **_argv)
102102
std::this_thread::sleep_for(std::chrono::seconds(4));
103103
markerMsg.set_id(2);
104104
markerMsg.set_action(ignition::msgs::Marker::ADD_MODIFY);
105-
markerMsg.set_type(ignition::msgs::Marker::BOX);
105+
markerMsg.set_type(ignition::msgs::Marker::SPHERE);
106106
ignition::msgs::Set(markerMsg.mutable_scale(),
107-
ignition::math::Vector3d(1.0, 1.0, 1.0));
107+
ignition::math::Vector3d(0.5, 1.0, 1.5));
108108
ignition::msgs::Set(markerMsg.mutable_pose(),
109109
ignition::math::Pose3d(2, 0, .5, 0, 0, 0));
110110
node.Request("/marker", markerMsg);
111111

112-
std::cout << "Changing the green box to a cylinder\n";
112+
std::cout << "Changing the green ellipsoid to a cylinder\n";
113113
std::this_thread::sleep_for(std::chrono::seconds(4));
114114
markerMsg.set_type(ignition::msgs::Marker::CYLINDER);
115+
ignition::msgs::Set(markerMsg.mutable_scale(),
116+
ignition::math::Vector3d(0.5, 0.5, 1.5));
115117
node.Request("/marker", markerMsg);
116118

117119
std::cout << "Connecting the sphere and cylinder with a line\n";
@@ -279,12 +281,12 @@ int main(int _argc, char **_argv)
279281
ignition::msgs::Set(markerMsg2->mutable_pose(),
280282
ignition::math::Pose3d(3, 3, 2, 0, 0, 0));
281283

282-
// Create third green cylinder marker
284+
// Create green capsule marker
283285
auto markerMsg3 = markerMsgs.add_marker();
284286
markerMsg3->set_ns("default");
285287
markerMsg3->set_id(0);
286288
markerMsg3->set_action(ignition::msgs::Marker::ADD_MODIFY);
287-
markerMsg3->set_type(ignition::msgs::Marker::CYLINDER);
289+
markerMsg3->set_type(ignition::msgs::Marker::CAPSULE);
288290
markerMsg3->set_visibility(ignition::msgs::Marker::GUI);
289291

290292
// Set color to Green

examples/worlds/rolling_shapes.sdf

+86-12
Original file line numberDiff line numberDiff line change
@@ -64,16 +64,16 @@
6464
</model>
6565

6666
<model name="box">
67-
<pose>0 0 0.5 0 0 0</pose>
67+
<pose>0 0 0.5 0 0.4 0</pose>
6868
<link name="box_link">
6969
<inertial>
7070
<inertia>
71-
<ixx>1</ixx>
71+
<ixx>0.16666</ixx>
7272
<ixy>0</ixy>
7373
<ixz>0</ixz>
74-
<iyy>1</iyy>
74+
<iyy>0.16666</iyy>
7575
<iyz>0</iyz>
76-
<izz>1</izz>
76+
<izz>0.16666</izz>
7777
</inertia>
7878
<mass>1.0</mass>
7979
</inertial>
@@ -105,14 +105,14 @@
105105
<link name="cylinder_link">
106106
<inertial>
107107
<inertia>
108-
<ixx>2</ixx>
108+
<ixx>0.0938</ixx>
109109
<ixy>0</ixy>
110110
<ixz>0</ixz>
111-
<iyy>2</iyy>
111+
<iyy>0.0938</iyy>
112112
<iyz>0</iyz>
113-
<izz>2</izz>
113+
<izz>0.125</izz>
114114
</inertia>
115-
<mass>2.0</mass>
115+
<mass>1.0</mass>
116116
</inertial>
117117
<collision name="cylinder_collision">
118118
<geometry>
@@ -144,14 +144,14 @@
144144
<link name="sphere_link">
145145
<inertial>
146146
<inertia>
147-
<ixx>3</ixx>
147+
<ixx>0.1</ixx>
148148
<ixy>0</ixy>
149149
<ixz>0</ixz>
150-
<iyy>3</iyy>
150+
<iyy>0.1</iyy>
151151
<iyz>0</iyz>
152-
<izz>3</izz>
152+
<izz>0.1</izz>
153153
</inertia>
154-
<mass>3.0</mass>
154+
<mass>1.0</mass>
155155
</inertial>
156156
<collision name="sphere_collision">
157157
<geometry>
@@ -175,5 +175,79 @@
175175
</visual>
176176
</link>
177177
</model>
178+
179+
<model name="capsule">
180+
<pose>0 -3.0 0.5 1.57079632679 0 0</pose>
181+
<link name="capsule_link">
182+
<inertial>
183+
<inertia>
184+
<ixx>0.074154</ixx>
185+
<ixy>0</ixy>
186+
<ixz>0</ixz>
187+
<iyy>0.074154</iyy>
188+
<iyz>0</iyz>
189+
<izz>0.018769</izz>
190+
</inertia>
191+
<mass>1.0</mass>
192+
</inertial>
193+
<collision name="capsule_collision">
194+
<geometry>
195+
<capsule>
196+
<radius>0.2</radius>
197+
<length>0.6</length>
198+
</capsule>
199+
</geometry>
200+
</collision>
201+
<visual name="capsule_visual">
202+
<geometry>
203+
<capsule>
204+
<radius>0.2</radius>
205+
<length>0.6</length>
206+
</capsule>
207+
</geometry>
208+
<material>
209+
<ambient>1 1 0 1</ambient>
210+
<diffuse>1 1 0 1</diffuse>
211+
<specular>1 1 0 1</specular>
212+
</material>
213+
</visual>
214+
</link>
215+
</model>
216+
217+
<model name="ellipsoid">
218+
<pose>0 3.0 0.5 1.57079632679 0 0</pose>
219+
<link name="ellipsoid_link">
220+
<inertial>
221+
<inertia>
222+
<ixx>0.068</ixx>
223+
<ixy>0</ixy>
224+
<ixz>0</ixz>
225+
<iyy>0.058</iyy>
226+
<iyz>0</iyz>
227+
<izz>0.026</izz>
228+
</inertia>
229+
<mass>1.0</mass>
230+
</inertial>
231+
<collision name="ellipsoid_collision">
232+
<geometry>
233+
<ellipsoid>
234+
<radii>0.2 0.3 0.5</radii>
235+
</ellipsoid>
236+
</geometry>
237+
</collision>
238+
<visual name="ellipsoid_visual">
239+
<geometry>
240+
<ellipsoid>
241+
<radii>0.2 0.3 0.5</radii>
242+
</ellipsoid>
243+
</geometry>
244+
<material>
245+
<ambient>1 0 1 1</ambient>
246+
<diffuse>1 0 1 1</diffuse>
247+
<specular>1 0 1 1</specular>
248+
</material>
249+
</visual>
250+
</link>
251+
</model>
178252
</world>
179253
</sdf>

examples/worlds/shapes.sdf

+86-12
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,7 @@ Try moving a model:
1717
<cast_shadows>true</cast_shadows>
1818
<pose>0 0 10 0 0 0</pose>
1919
<diffuse>0.8 0.8 0.8 1</diffuse>
20-
<specular>0.8 0.8 0.8 1</specular>
20+
<specular>0.2 0.2 0.2 1</specular>
2121
<attenuation>
2222
<range>1000</range>
2323
<constant>0.9</constant>
@@ -59,12 +59,12 @@ Try moving a model:
5959
<link name="box_link">
6060
<inertial>
6161
<inertia>
62-
<ixx>1</ixx>
62+
<ixx>0.16666</ixx>
6363
<ixy>0</ixy>
6464
<ixz>0</ixz>
65-
<iyy>1</iyy>
65+
<iyy>0.16666</iyy>
6666
<iyz>0</iyz>
67-
<izz>1</izz>
67+
<izz>0.16666</izz>
6868
</inertia>
6969
<mass>1.0</mass>
7070
</inertial>
@@ -96,14 +96,14 @@ Try moving a model:
9696
<link name="cylinder_link">
9797
<inertial>
9898
<inertia>
99-
<ixx>2</ixx>
99+
<ixx>0.1458</ixx>
100100
<ixy>0</ixy>
101101
<ixz>0</ixz>
102-
<iyy>2</iyy>
102+
<iyy>0.1458</iyy>
103103
<iyz>0</iyz>
104-
<izz>2</izz>
104+
<izz>0.125</izz>
105105
</inertia>
106-
<mass>2.0</mass>
106+
<mass>1.0</mass>
107107
</inertial>
108108
<collision name="cylinder_collision">
109109
<geometry>
@@ -135,14 +135,14 @@ Try moving a model:
135135
<link name="sphere_link">
136136
<inertial>
137137
<inertia>
138-
<ixx>3</ixx>
138+
<ixx>0.1</ixx>
139139
<ixy>0</ixy>
140140
<ixz>0</ixz>
141-
<iyy>3</iyy>
141+
<iyy>0.1</iyy>
142142
<iyz>0</iyz>
143-
<izz>3</izz>
143+
<izz>0.1</izz>
144144
</inertia>
145-
<mass>3.0</mass>
145+
<mass>1.0</mass>
146146
</inertial>
147147
<collision name="sphere_collision">
148148
<geometry>
@@ -166,5 +166,79 @@ Try moving a model:
166166
</visual>
167167
</link>
168168
</model>
169+
170+
<model name="capsule">
171+
<pose>0 -3.0 0.5 0 0 0</pose>
172+
<link name="capsule_link">
173+
<inertial>
174+
<inertia>
175+
<ixx>0.074154</ixx>
176+
<ixy>0</ixy>
177+
<ixz>0</ixz>
178+
<iyy>0.074154</iyy>
179+
<iyz>0</iyz>
180+
<izz>0.018769</izz>
181+
</inertia>
182+
<mass>1.0</mass>
183+
</inertial>
184+
<collision name="capsule_collision">
185+
<geometry>
186+
<capsule>
187+
<radius>0.2</radius>
188+
<length>0.6</length>
189+
</capsule>
190+
</geometry>
191+
</collision>
192+
<visual name="capsule_visual">
193+
<geometry>
194+
<capsule>
195+
<radius>0.2</radius>
196+
<length>0.6</length>
197+
</capsule>
198+
</geometry>
199+
<material>
200+
<ambient>1 1 0 1</ambient>
201+
<diffuse>1 1 0 1</diffuse>
202+
<specular>1 1 0 1</specular>
203+
</material>
204+
</visual>
205+
</link>
206+
</model>
207+
208+
<model name="ellipsoid">
209+
<pose>0 3.0 0.5 0 0 0</pose>
210+
<link name="ellipsoid_link">
211+
<inertial>
212+
<inertia>
213+
<ixx>0.068</ixx>
214+
<ixy>0</ixy>
215+
<ixz>0</ixz>
216+
<iyy>0.058</iyy>
217+
<iyz>0</iyz>
218+
<izz>0.026</izz>
219+
</inertia>
220+
<mass>1.0</mass>
221+
</inertial>
222+
<collision name="ellipsoid_collision">
223+
<geometry>
224+
<ellipsoid>
225+
<radii>0.2 0.3 0.5</radii>
226+
</ellipsoid>
227+
</geometry>
228+
</collision>
229+
<visual name="ellipsoid_visual">
230+
<geometry>
231+
<ellipsoid>
232+
<radii>0.2 0.3 0.5</radii>
233+
</ellipsoid>
234+
</geometry>
235+
<material>
236+
<ambient>1 0 1 1</ambient>
237+
<diffuse>1 0 1 1</diffuse>
238+
<specular>1 0 1 1</specular>
239+
</material>
240+
</visual>
241+
</link>
242+
</model>
169243
</world>
170244
</sdf>

0 commit comments

Comments
 (0)