Skip to content

Commit ad3ef0a

Browse files
authored
Merge 8 -> main (#2378)
Signed-off-by: Michael Carroll <mjcarroll@intrinsic.ai>
2 parents 77f4c00 + 098085b commit ad3ef0a

19 files changed

+440
-29
lines changed

.github/ci/packages.apt

-1
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,6 @@ libtinyxml2-dev
2424
libxi-dev
2525
libxmu-dev
2626
libpython3-dev
27-
python3-distutils
2827
python3-gz-math8
2928
python3-gz-msgs11
3029
python3-gz-transport14

CMakeLists.txt

+8-2
Original file line numberDiff line numberDiff line change
@@ -225,11 +225,17 @@ else()
225225
endif()
226226
endif()
227227
# Plugin install dirs
228+
set(GZ_SIM_PLUGIN_RELATIVE_INSTALL_DIR
229+
${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins
230+
)
228231
set(GZ_SIM_PLUGIN_INSTALL_DIR
229-
${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins
232+
${CMAKE_INSTALL_PREFIX}/${GZ_SIM_PLUGIN_RELATIVE_INSTALL_DIR}
233+
)
234+
set(GZ_SIM_GUI_PLUGIN_RELATIVE_INSTALL_DIR
235+
${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui
230236
)
231237
set(GZ_SIM_GUI_PLUGIN_INSTALL_DIR
232-
${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui
238+
${CMAKE_INSTALL_PREFIX}/${GZ_SIM_GUI_PLUGIN_RELATIVE_INSTALL_DIR}
233239
)
234240

235241
#============================================================================

Changelog.md

+32
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,38 @@
44

55
## Gazebo Sim 8.x
66

7+
### Gazebo Sim 8.3.0 (2024-04-11)
8+
9+
1. Use relative install paths for plugin shared libraries and gz-tools data
10+
* [Pull request #2358](https://github.com/gazebosim/gz-sim/pull/2358)
11+
12+
1. Use `steer_p_gain` for UpdateVelocity steer joint speed
13+
* [Pull request #2355](https://github.com/gazebosim/gz-sim/pull/2355)
14+
15+
1. Fix TriggeredPublisher test
16+
* [Pull request #2354](https://github.com/gazebosim/gz-sim/pull/2354)
17+
18+
1. Use SetComponentData to simplify code and improve coverage
19+
* [Pull request #2360](https://github.com/gazebosim/gz-sim/pull/2360)
20+
21+
1. Remove unnecessary sleep
22+
* [Pull request #2357](https://github.com/gazebosim/gz-sim/pull/2357)
23+
24+
1. Fixed undefined behavior in thruster.cc
25+
* [Pull request #2350](https://github.com/gazebosim/gz-sim/pull/2350)
26+
27+
1. Added mutex to protect stored time variables
28+
* [Pull request #2345](https://github.com/gazebosim/gz-sim/pull/2345)
29+
30+
1. Fixed turning error in ackermann steering
31+
* [Pull request #2342](https://github.com/gazebosim/gz-sim/pull/2342)
32+
33+
1. Check null mesh
34+
* [Pull request #2341](https://github.com/gazebosim/gz-sim/pull/2341)
35+
36+
1. Publish step size in world stats topic
37+
* [Pull request #2340](https://github.com/gazebosim/gz-sim/pull/2340)
38+
739
### Gazebo Sim 8.2.0 (2024-03-14)
840

941
1. Add reference to joint_controller.md tutorial.

examples/worlds/dvl_world.sdf

+291
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,291 @@
1+
<?xml version="1.0" ?>
2+
<!--
3+
Example showing the usage of the Doppler Velocity Log (DVL) sensor
4+
on an Autonomous Underwater Vehicle (AUV).
5+
6+
The world contains the MBARI Tethys LRAUV model along with
7+
the following plugins:
8+
9+
* Buoyancy: applies buoyancy forces
10+
* DopplerVelocityLogSystem: sensor to measure doppler velocity
11+
* JointPositionController: controls the vertical and horizontal fins
12+
* LiftDrag: generates forces on the vertical and horizontal fins
13+
* Thruster: propels the vehicle
14+
* Hydrodynamics: applies forces such as added mass, drag and coriolis
15+
16+
The AUV can be controlled using the following commands (to move in a circle):
17+
18+
1. Move the rudder:
19+
20+
gz topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \
21+
-m gz.msgs.Double -p 'data: -0.17'
22+
23+
2. Propel the vehicle:
24+
25+
gz topic -t /model/tethys/joint/propeller_joint/cmd_thrust \
26+
-m gz.msgs.Double -p 'data: -31'
27+
28+
To see the DVL output run the following command:
29+
30+
3. gz topic -t /dvl/velocity -e
31+
32+
-->
33+
<sdf version="1.6">
34+
<world name="dvl_world">
35+
<scene>
36+
<!-- For turquoise ambient to match particle effect -->
37+
<ambient>0.0 1.0 1.0</ambient>
38+
<!-- For default gray ambient -->
39+
<background>0.0 0.7 0.8</background>
40+
41+
<grid>false</grid>
42+
</scene>
43+
44+
<physics name="1ms" type="ode">
45+
<max_step_size>0.001</max_step_size>
46+
<real_time_factor>1.0</real_time_factor>
47+
</physics>
48+
<plugin
49+
filename="gz-sim-physics-system"
50+
name="gz::sim::systems::Physics">
51+
</plugin>
52+
<plugin
53+
filename="gz-sim-sensors-system"
54+
name="gz::sim::systems::Sensors">
55+
</plugin>
56+
<plugin
57+
filename="gz-sim-dvl-system"
58+
name="gz::sim::systems::DopplerVelocityLogSystem">
59+
</plugin>
60+
<plugin
61+
filename="gz-sim-buoyancy-system"
62+
name="gz::sim::systems::Buoyancy">
63+
<uniform_fluid_density>1000</uniform_fluid_density>
64+
</plugin>
65+
<plugin
66+
filename="gz-sim-scene-broadcaster-system"
67+
name="gz::sim::systems::SceneBroadcaster">
68+
</plugin>
69+
<plugin
70+
filename="gz-sim-contact-system"
71+
name="gz::sim::systems::Contact">
72+
</plugin>
73+
<plugin
74+
filename="gz-sim-user-commands-system"
75+
name="gz::sim::systems::UserCommands">
76+
</plugin>
77+
78+
<light type="directional" name="sun">
79+
<cast_shadows>true</cast_shadows>
80+
<pose>0 0 10 0 0 0</pose>
81+
<diffuse>1 1 1 1</diffuse>
82+
<specular>0.5 0.5 0.5 1</specular>
83+
<attenuation>
84+
<range>1000</range>
85+
<constant>0.9</constant>
86+
<linear>0.01</linear>
87+
<quadratic>0.001</quadratic>
88+
</attenuation>
89+
<direction>-0.5 0.1 -0.9</direction>
90+
</light>
91+
92+
<!-- This invisible plane helps with orbiting the camera, especially at large scales -->
93+
<model name="horizontal_plane">
94+
<static>true</static>
95+
<link name="link">
96+
<visual name="visual">
97+
<geometry>
98+
<plane>
99+
<normal>0 0 1</normal>
100+
<!-- 300 km x 300 km -->
101+
<size>300000 300000</size>
102+
</plane>
103+
</geometry>
104+
<transparency>1.0</transparency>
105+
</visual>
106+
</link>
107+
</model>
108+
109+
<model name="sea_bottom">
110+
<static>true</static>
111+
<pose>0 0 -100 0 0 0</pose>
112+
<link name="link">
113+
<collision name="collision">
114+
<geometry>
115+
<plane>
116+
<normal>0 0 1</normal>
117+
<!-- 300 km x 300 km -->
118+
<size>300000 300000</size>
119+
</plane>
120+
</geometry>
121+
</collision>
122+
<visual name="visual">
123+
<material>
124+
<ambient>0.5 0.5 0.5</ambient>
125+
<diffuse>0.5 0.5 0.5</diffuse>
126+
</material>
127+
<geometry>
128+
<plane>
129+
<normal>0 0 1</normal>
130+
<!-- 300 km x 300 km -->
131+
<size>300000 300000</size>
132+
</plane>
133+
</geometry>
134+
</visual>
135+
</link>
136+
</model>
137+
138+
<include>
139+
<pose>0 0 -80 0 0 1.57</pose>
140+
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>
141+
142+
<experimental:params>
143+
<sensor
144+
element_id="base_link" action="add"
145+
name="teledyne_pathfinder_dvl"
146+
type="custom" gz:type="dvl">
147+
<pose degrees="true">-0.60 0 -0.16 0 0 180</pose>
148+
<always_on>1</always_on>
149+
<update_rate>1</update_rate>
150+
<topic>/dvl/velocity</topic>
151+
<gz:dvl>
152+
<type>phased_array</type>
153+
<arrangement degrees="true">
154+
<beam id="1">
155+
<aperture>2</aperture>
156+
<rotation>45</rotation>
157+
<tilt>30</tilt>
158+
</beam>
159+
<beam>
160+
<aperture>2</aperture>
161+
<rotation>135</rotation>
162+
<tilt>30</tilt>
163+
</beam>
164+
<beam>
165+
<aperture>2</aperture>
166+
<rotation>-45</rotation>
167+
<tilt>30</tilt>
168+
</beam>
169+
<beam>
170+
<aperture>2</aperture>
171+
<rotation>-135</rotation>
172+
<tilt>30</tilt>
173+
</beam>
174+
</arrangement>
175+
<tracking>
176+
<bottom_mode>
177+
<when>best</when>
178+
<noise type="gaussian">
179+
<!-- +/- 0.4 cm/s precision at 10 m/s within 2 stddevs -->
180+
<stddev>0.002</stddev>
181+
</noise>
182+
<visualize>false</visualize>
183+
</bottom_mode>
184+
</tracking>
185+
<!-- Roughly 1 m resolution at a 100m -->
186+
<resolution>0.01</resolution>
187+
<maximum_range>100.</maximum_range>
188+
<minimum_range>0.1</minimum_range>
189+
<!-- ENU to SFM -->
190+
<reference_frame>0 0 0 0 0 -1.570796</reference_frame>
191+
</gz:dvl>
192+
</sensor>
193+
</experimental:params>
194+
195+
<!-- Odometry publisher -->
196+
<plugin
197+
filename="gz-sim-odometry-publisher-system"
198+
name="gz::sim::systems::OdometryPublisher">
199+
</plugin>
200+
201+
<!-- Joint controllers -->
202+
<plugin
203+
filename="gz-sim-joint-position-controller-system"
204+
name="gz::sim::systems::JointPositionController">
205+
<joint_name>horizontal_fins_joint</joint_name>
206+
<p_gain>0.1</p_gain>
207+
</plugin>
208+
209+
<plugin
210+
filename="gz-sim-joint-position-controller-system"
211+
name="gz::sim::systems::JointPositionController">
212+
<joint_name>vertical_fins_joint</joint_name>
213+
<p_gain>0.1</p_gain>
214+
</plugin>
215+
216+
<plugin
217+
filename="gz-sim-thruster-system"
218+
name="gz::sim::systems::Thruster">
219+
<namespace>tethys</namespace>
220+
<use_angvel_cmd>0</use_angvel_cmd>
221+
<joint_name>propeller_joint</joint_name>
222+
<thrust_coefficient>0.004422</thrust_coefficient>
223+
<fluid_density>1000</fluid_density>
224+
<propeller_diameter>0.2</propeller_diameter>
225+
</plugin>
226+
227+
<!-- Lift and drag -->
228+
229+
<!-- Vertical fin -->
230+
<plugin
231+
filename="gz-sim-lift-drag-system"
232+
name="gz::sim::systems::LiftDrag">
233+
<air_density>1000</air_density>
234+
<cla>4.13</cla>
235+
<cla_stall>-1.1</cla_stall>
236+
<cda>0.2</cda>
237+
<cda_stall>0.03</cda_stall>
238+
<alpha_stall>0.17</alpha_stall>
239+
<a0>0</a0>
240+
<area>0.0244</area>
241+
<upward>0 1 0</upward>
242+
<forward>1 0 0</forward>
243+
<link_name>vertical_fins</link_name>
244+
<cp>0 0 0</cp>
245+
</plugin>
246+
247+
<!-- Horizontal fin -->
248+
<plugin
249+
filename="gz-sim-lift-drag-system"
250+
name="gz::sim::systems::LiftDrag">
251+
<air_density>1000</air_density>
252+
<cla>4.13</cla>
253+
<cla_stall>-1.1</cla_stall>
254+
<cda>0.2</cda>
255+
<cda_stall>0.03</cda_stall>
256+
<alpha_stall>0.17</alpha_stall>
257+
<a0>0</a0>
258+
<area>0.0244</area>
259+
<upward>0 0 1</upward>
260+
<forward>1 0 0</forward>
261+
<link_name>horizontal_fins</link_name>
262+
<cp>0 0 0</cp>
263+
</plugin>
264+
265+
<!-- Hydrodynamics plugin-->
266+
<plugin
267+
filename="gz-sim-hydrodynamics-system"
268+
name="gz::sim::systems::Hydrodynamics">
269+
<link_name>base_link</link_name>
270+
<xDotU>-4.876161</xDotU>
271+
<yDotV>-126.324739</yDotV>
272+
<zDotW>-126.324739</zDotW>
273+
<kDotP>0</kDotP>
274+
<mDotQ>-33.46</mDotQ>
275+
<nDotR>-33.46</nDotR>
276+
<xUabsU>-6.2282</xUabsU>
277+
<xU>0</xU>
278+
<yVabsV>-601.27</yVabsV>
279+
<yV>0</yV>
280+
<zWabsW>-601.27</zWabsW>
281+
<zW>0</zW>
282+
<kPabsP>-0.1916</kPabsP>
283+
<kP>0</kP>
284+
<mQabsQ>-632.698957</mQabsQ>
285+
<mQ>0</mQ>
286+
<nRabsR>-632.698957</nRabsR>
287+
<nR>0</nR>
288+
</plugin>
289+
</include>
290+
</world>
291+
</sdf>

include/gz/sim/ServerConfig.hh

+19-1
Original file line numberDiff line numberDiff line change
@@ -60,6 +60,14 @@ namespace gz
6060
kSdfString,
6161
};
6262

63+
/// \brief SDF error behavior
64+
public: enum class SdfErrorBehavior
65+
{
66+
/// \brief Exit the server immediately
67+
EXIT_IMMEDIATELY,
68+
/// \brief Continue loading the server if possible
69+
CONTINUE_LOADING
70+
};
6371

6472
class PluginInfoPrivate;
6573
/// \brief Information about a plugin that should be loaded by the
@@ -386,7 +394,17 @@ namespace gz
386394
const std::string &_apiBackend);
387395

388396
/// \return Api backend for gui. See SetRenderEngineGuiApiBackend()
389-
const std::string &RenderEngineGuiApiBackend() const;
397+
public: const std::string &RenderEngineGuiApiBackend() const;
398+
399+
/// \brief Set the server behavior when SDF errors are encountered while
400+
//// loading the server.
401+
/// \param[in] _behavior Server behavior when SDF errors are encounted.
402+
public: void SetBehaviorOnSdfErrors(SdfErrorBehavior _behavior);
403+
404+
/// \brief Get the behavior when SDF errors are encountered while
405+
//// loading the server.
406+
/// \return Server behavior when SDF errors are encounted.
407+
public: SdfErrorBehavior BehaviorOnSdfErrors() const;
390408

391409
/// \brief Instruct simulation to attach a plugin to a specific
392410
/// entity when simulation starts.

0 commit comments

Comments
 (0)