Skip to content

Commit

Permalink
Merge remote-tracking branch 'origin/gz-sim8' into arjo/refactor/remo…
Browse files Browse the repository at this point in the history
…ve_unused_file
  • Loading branch information
arjo129 committed May 6, 2024
2 parents a221fb0 + 3444847 commit 6429798
Show file tree
Hide file tree
Showing 15 changed files with 467 additions and 20 deletions.
1 change: 0 additions & 1 deletion .github/ci/packages.apt
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,6 @@ libtinyxml2-dev
libxi-dev
libxmu-dev
libpython3-dev
python3-distutils
python3-gz-math7
python3-gz-msgs10
python3-gz-transport13
Expand Down
11 changes: 11 additions & 0 deletions .github/workflows/package_xml.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
name: Validate package.xml

on:
pull_request:

jobs:
package-xml:
runs-on: ubuntu-latest
name: Validate package.xml
steps:
- uses: gazebo-tooling/action-gz-ci/validate_package_xml@jammy
9 changes: 5 additions & 4 deletions examples/plugin/custom_sensor_system/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,10 +27,11 @@ add_subdirectory(${sensors_clone_SOURCE_DIR}/examples/custom_sensor ${sensors_cl

add_library(${PROJECT_NAME} SHARED ${PROJECT_NAME}.cc)
target_link_libraries(${PROJECT_NAME}
PRIVATE gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER}
PRIVATE gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
PRIVATE gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER}
PRIVATE odometer
PRIVATE
gz-plugin${GZ_PLUGIN_VER}::gz-plugin${GZ_PLUGIN_VER}
gz-sim${GZ_SIM_VER}::gz-sim${GZ_SIM_VER}
gz-sensors${GZ_SENSORS_VER}::gz-sensors${GZ_SENSORS_VER}
odometer
)
target_include_directories(${PROJECT_NAME}
PUBLIC ${sensors_clone_SOURCE_DIR}/examples/custom_sensor)
3 changes: 2 additions & 1 deletion examples/standalone/gtest_setup/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,8 @@ set(GZ_SIM_VER ${gz-sim8_VERSION_MAJOR})
include(FetchContent)
FetchContent_Declare(
googletest
URL https://github.com/google/googletest/archive/609281088cfefc76f9d0ce82e1ff6c30cc3591e5.zip
# Version 1.14. Use commit hash to prevent tag relocation
URL https://github.com/google/googletest/archive/f8d7d77c06936315286eb55f8de22cd23c188571.zip
)
set(gtest_force_shared_crt ON CACHE BOOL "" FORCE)
FetchContent_MakeAvailable(googletest)
Expand Down
291 changes: 291 additions & 0 deletions examples/worlds/dvl_world.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,291 @@
<?xml version="1.0" ?>
<!--
Example showing the usage of the Doppler Velocity Log (DVL) sensor
on an Autonomous Underwater Vehicle (AUV).
The world contains the MBARI Tethys LRAUV model along with
the following plugins:
* Buoyancy: applies buoyancy forces
* DopplerVelocityLogSystem: sensor to measure doppler velocity
* JointPositionController: controls the vertical and horizontal fins
* LiftDrag: generates forces on the vertical and horizontal fins
* Thruster: propels the vehicle
* Hydrodynamics: applies forces such as added mass, drag and coriolis
The AUV can be controlled using the following commands (to move in a circle):
1. Move the rudder:
gz topic -t /model/tethys/joint/vertical_fins_joint/0/cmd_pos \
-m gz.msgs.Double -p 'data: -0.17'
2. Propel the vehicle:
gz topic -t /model/tethys/joint/propeller_joint/cmd_thrust \
-m gz.msgs.Double -p 'data: -31'
To see the DVL output run the following command:
3. gz topic -t /dvl/velocity -e
-->
<sdf version="1.6">
<world name="dvl_world">
<scene>
<!-- For turquoise ambient to match particle effect -->
<ambient>0.0 1.0 1.0</ambient>
<!-- For default gray ambient -->
<background>0.0 0.7 0.8</background>

<grid>false</grid>
</scene>

<physics name="1ms" type="ode">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-sensors-system"
name="gz::sim::systems::Sensors">
</plugin>
<plugin
filename="gz-sim-dvl-system"
name="gz::sim::systems::DopplerVelocityLogSystem">
</plugin>
<plugin
filename="gz-sim-buoyancy-system"
name="gz::sim::systems::Buoyancy">
<uniform_fluid_density>1000</uniform_fluid_density>
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin
filename="gz-sim-contact-system"
name="gz::sim::systems::Contact">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<!-- This invisible plane helps with orbiting the camera, especially at large scales -->
<model name="horizontal_plane">
<static>true</static>
<link name="link">
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<!-- 300 km x 300 km -->
<size>300000 300000</size>
</plane>
</geometry>
<transparency>1.0</transparency>
</visual>
</link>
</model>

<model name="sea_bottom">
<static>true</static>
<pose>0 0 -100 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<!-- 300 km x 300 km -->
<size>300000 300000</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<material>
<ambient>0.5 0.5 0.5</ambient>
<diffuse>0.5 0.5 0.5</diffuse>
</material>
<geometry>
<plane>
<normal>0 0 1</normal>
<!-- 300 km x 300 km -->
<size>300000 300000</size>
</plane>
</geometry>
</visual>
</link>
</model>

<include>
<pose>0 0 -80 0 0 1.57</pose>
<uri>https://fuel.gazebosim.org/1.0/accurrent/models/MBARI Tethys LRAUV</uri>

<experimental:params>
<sensor
element_id="base_link" action="add"
name="teledyne_pathfinder_dvl"
type="custom" gz:type="dvl">
<pose degrees="true">-0.60 0 -0.16 0 0 180</pose>
<always_on>1</always_on>
<update_rate>1</update_rate>
<topic>/dvl/velocity</topic>
<gz:dvl>
<type>phased_array</type>
<arrangement degrees="true">
<beam id="1">
<aperture>2</aperture>
<rotation>45</rotation>
<tilt>30</tilt>
</beam>
<beam>
<aperture>2</aperture>
<rotation>135</rotation>
<tilt>30</tilt>
</beam>
<beam>
<aperture>2</aperture>
<rotation>-45</rotation>
<tilt>30</tilt>
</beam>
<beam>
<aperture>2</aperture>
<rotation>-135</rotation>
<tilt>30</tilt>
</beam>
</arrangement>
<tracking>
<bottom_mode>
<when>best</when>
<noise type="gaussian">
<!-- +/- 0.4 cm/s precision at 10 m/s within 2 stddevs -->
<stddev>0.002</stddev>
</noise>
<visualize>false</visualize>
</bottom_mode>
</tracking>
<!-- Roughly 1 m resolution at a 100m -->
<resolution>0.01</resolution>
<maximum_range>100.</maximum_range>
<minimum_range>0.1</minimum_range>
<!-- ENU to SFM -->
<reference_frame>0 0 0 0 0 -1.570796</reference_frame>
</gz:dvl>
</sensor>
</experimental:params>

<!-- Odometry publisher -->
<plugin
filename="gz-sim-odometry-publisher-system"
name="gz::sim::systems::OdometryPublisher">
</plugin>

<!-- Joint controllers -->
<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>horizontal_fins_joint</joint_name>
<p_gain>0.1</p_gain>
</plugin>

<plugin
filename="gz-sim-joint-position-controller-system"
name="gz::sim::systems::JointPositionController">
<joint_name>vertical_fins_joint</joint_name>
<p_gain>0.1</p_gain>
</plugin>

<plugin
filename="gz-sim-thruster-system"
name="gz::sim::systems::Thruster">
<namespace>tethys</namespace>
<use_angvel_cmd>0</use_angvel_cmd>
<joint_name>propeller_joint</joint_name>
<thrust_coefficient>0.004422</thrust_coefficient>
<fluid_density>1000</fluid_density>
<propeller_diameter>0.2</propeller_diameter>
</plugin>

<!-- Lift and drag -->

<!-- Vertical fin -->
<plugin
filename="gz-sim-lift-drag-system"
name="gz::sim::systems::LiftDrag">
<air_density>1000</air_density>
<cla>4.13</cla>
<cla_stall>-1.1</cla_stall>
<cda>0.2</cda>
<cda_stall>0.03</cda_stall>
<alpha_stall>0.17</alpha_stall>
<a0>0</a0>
<area>0.0244</area>
<upward>0 1 0</upward>
<forward>1 0 0</forward>
<link_name>vertical_fins</link_name>
<cp>0 0 0</cp>
</plugin>

<!-- Horizontal fin -->
<plugin
filename="gz-sim-lift-drag-system"
name="gz::sim::systems::LiftDrag">
<air_density>1000</air_density>
<cla>4.13</cla>
<cla_stall>-1.1</cla_stall>
<cda>0.2</cda>
<cda_stall>0.03</cda_stall>
<alpha_stall>0.17</alpha_stall>
<a0>0</a0>
<area>0.0244</area>
<upward>0 0 1</upward>
<forward>1 0 0</forward>
<link_name>horizontal_fins</link_name>
<cp>0 0 0</cp>
</plugin>

<!-- Hydrodynamics plugin-->
<plugin
filename="gz-sim-hydrodynamics-system"
name="gz::sim::systems::Hydrodynamics">
<link_name>base_link</link_name>
<xDotU>-4.876161</xDotU>
<yDotV>-126.324739</yDotV>
<zDotW>-126.324739</zDotW>
<kDotP>0</kDotP>
<mDotQ>-33.46</mDotQ>
<nDotR>-33.46</nDotR>
<xUabsU>-6.2282</xUabsU>
<xU>0</xU>
<yVabsV>-601.27</yVabsV>
<yV>0</yV>
<zWabsW>-601.27</zWabsW>
<zW>0</zW>
<kPabsP>-0.1916</kPabsP>
<kP>0</kP>
<mQabsQ>-632.698957</mQabsQ>
<mQ>0</mQ>
<nRabsR>-632.698957</nRabsR>
<nR>0</nR>
</plugin>
</include>
</world>
</sdf>
20 changes: 19 additions & 1 deletion include/gz/sim/ServerConfig.hh
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,14 @@ namespace gz
kSdfString,
};

/// \brief SDF error behavior
public: enum class SdfErrorBehavior
{
/// \brief Exit the server immediately
EXIT_IMMEDIATELY,
/// \brief Continue loading the server if possible
CONTINUE_LOADING
};

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

/// \return Api backend for gui. See SetRenderEngineGuiApiBackend()
const std::string &RenderEngineGuiApiBackend() const;
public: const std::string &RenderEngineGuiApiBackend() const;

/// \brief Set the server behavior when SDF errors are encountered while
//// loading the server.
/// \param[in] _behavior Server behavior when SDF errors are encounted.
public: void SetBehaviorOnSdfErrors(SdfErrorBehavior _behavior);

/// \brief Get the behavior when SDF errors are encountered while
//// loading the server.
/// \return Server behavior when SDF errors are encounted.
public: SdfErrorBehavior BehaviorOnSdfErrors() const;

/// \brief Instruct simulation to attach a plugin to a specific
/// entity when simulation starts.
Expand Down
Loading

0 comments on commit 6429798

Please sign in to comment.