Skip to content

Commit

Permalink
6 ➡️ 7 (main) - part 3
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Aug 8, 2022
2 parents ee48126 + 8c9489d commit 30a312f
Show file tree
Hide file tree
Showing 70 changed files with 3,296 additions and 827 deletions.
3 changes: 3 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -12,3 +12,6 @@ build_*

.ycm_extra_conf.py
*.orig

# clangd index
.cache
6 changes: 3 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,12 @@

Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-sim/branch/main/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-sim)
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-sim/branch/main/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-sim/branch/main)
Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_gazebo-ci-main-focal-amd64)](https://build.osrfoundation.org/job/ignition_gazebo-ci-main-focal-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_gazebo-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_gazebo-ci-main-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/job/ign_gazebo-ci-win/badge/icon)](https://build.osrfoundation.org/job/ign_gazebo-ci-win/)

Gazebo Sim is an open source robotics simulator. Through Gazebo, users have access to high fidelity physics, rendering, and sensor models. Additionally, users and developers have multiple points of entry to simulation including a graphical user interface, plugins, and asynchronous message passing and services.
Gazebo Sim is an open source robotics simulator. Through Gazebo Sim, users have access to high fidelity physics, rendering, and sensor models. Additionally, users and developers have multiple points of entry to simulation including a graphical user interface, plugins, and asynchronous message passing and services.

Gazebo Sim is derived from [Gazebo Classic](http://classic.gazebosim.org) and represents over 16 years of development and experience in robotics and simulation. This library is part of the [Gazebo](https://gazebosim.org) project.

Expand Down Expand Up @@ -59,7 +59,7 @@ force-torque, IMU, GPS, and more, all powered by
* **Plugins**: Develop custom plugins for robot, sensor, and
environment control.

* **Graphical interface**: Create, instrospect and interact with your simulations
* **Graphical interface**: Create, introspect and interact with your simulations
through plugin-based graphical interfaces powered by
[Gazebo GUI](https://github.com/gazebosim/gz-gui).

Expand Down
2 changes: 2 additions & 0 deletions examples/worlds/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@
file(GLOB files "*.sdf")
install(FILES ${files}
DESTINATION ${GZ_DATA_INSTALL_DIR}/worlds)

add_subdirectory(thumbnails)
163 changes: 163 additions & 0 deletions examples/worlds/apply_link_wrench.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,163 @@
<?xml version="1.0" ?>
<!--
Demostrates the ApplyLinkWrench plugin.
When simulation starts, the box model starts moving due to the persistent force defined in this file.
Wrenches can also be applied through transport.
For example, apply a force to the cylinder model (i.e. its canonical link) with:
gz topic -t "/world/apply_link_wrench/wrench" -m gz.msgs.EntityWrench -p "entity: {name: 'cylinder', type: MODEL}, wrench: {force: {y: 1000, z: 10000}}"
Apply a wrench to the cylinder link with:
gz topic -t "/world/apply_link_wrench/wrench" -m gz.msgs.EntityWrench -p "entity: {name: 'cylinder::link', type: LINK}, wrench: {force: {y: -1000, z: 10000}, torque: {x: -1000}}"
Apply a persistent force to the cylinder with:
gz topic -t "/world/apply_link_wrench/wrench/persistent" -m gz.msgs.EntityWrench -p "entity: {name: 'cylinder', type: MODEL}, wrench: {force: {x: -20}}"
Clear the persistent force from the box with:
gz topic -t "/world/apply_link_wrench/wrench/clear" -m gz.msgs.Entity -p "name: 'box', type: MODEL"
-->
<sdf version="1.6">
<world name="apply_link_wrench">
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin
filename="gz-sim-apply-link-wrench-system"
name="gz::sim::systems::ApplyLinkWrench">
<persistent>
<entity_name>box</entity_name>
<entity_type>model</entity_type>
<force>-10 0 0</force>
<torque>0 0 0.1</torque>
</persistent>
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 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>
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name="box">
<pose>0 -2 0.5 0 0 0</pose>
<link name="link">
<inertial>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>
</model>

<model name="cylinder">
<pose>0 2 0.5 0 0 0</pose>
<link name="link">
<inertial>
<inertia>
<ixx>2</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2</iyy>
<iyz>0</iyz>
<izz>2</izz>
</inertia>
<mass>2.0</mass>
</inertial>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1.0</length>
</cylinder>
</geometry>
</collision>

<visual name="visual">
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1.0</length>
</cylinder>
</geometry>
<material>
<ambient>0 1 0 1</ambient>
<diffuse>0 1 0 1</diffuse>
<specular>0 1 0 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>
3 changes: 3 additions & 0 deletions examples/worlds/thumbnails/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
file(GLOB files "*.png")
install(FILES ${files}
DESTINATION ${GZ_DATA_INSTALL_DIR}/worlds/thumbnails)
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
6 changes: 6 additions & 0 deletions include/gz/sim/Model.hh
Original file line number Diff line number Diff line change
Expand Up @@ -175,6 +175,12 @@ namespace gz
public: void SetWorldPoseCmd(EntityComponentManager &_ecm,
const math::Pose3d &_pose);

/// \brief Get the model's canonical link entity.
/// \param[in] _ecm Entity-component manager.
/// \return Link entity.
public: sim::Entity CanonicalLink(
const EntityComponentManager &_ecm) const;

/// \brief Pointer to private data.
private: std::unique_ptr<ModelPrivate> dataPtr;
};
Expand Down
22 changes: 22 additions & 0 deletions include/gz/sim/Util.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,8 @@
#ifndef GZ_SIM_UTIL_HH_
#define GZ_SIM_UTIL_HH_

#include <gz/msgs/entity.pb.h>

#include <string>
#include <unordered_set>
#include <vector>
Expand Down Expand Up @@ -257,6 +259,26 @@ namespace gz
return changed;
}

/// \brief Helper function to get an entity from an entity message.
/// The returned entity is not guaranteed to exist.
///
/// The message is used as follows:
///
/// if id not null
/// use id
/// else if name not null and type not null
/// use name + type
/// else
/// error
/// end
///
/// \param[in] _ecm Entity component manager
/// \param[in] _msg Entity message
/// \return Entity ID, or kNullEntity if a matching entity couldn't be
/// found.
Entity GZ_SIM_VISIBLE entityFromMsg(
const EntityComponentManager &_ecm, const msgs::Entity &_msg);

/// \brief Get the spherical coordinates for an entity.
/// \param[in] _entity Entity whose coordinates we want.
/// \param[in] _ecm Entity component manager
Expand Down
1 change: 1 addition & 0 deletions include/gz/sim/config.hh.in
Original file line number Diff line number Diff line change
Expand Up @@ -39,5 +39,6 @@
#define GZ_SIM_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins"
#define GZ_SIM_GUI_PLUGIN_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_LIB_INSTALL_DIR}/gz-${GZ_DESIGNATION}-${PROJECT_VERSION_MAJOR}/plugins/gui"
#define GZ_SIM_WORLD_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/${GZ_DATA_INSTALL_DIR}/worlds"
#define GZ_DISTRIBUTION "${GZ_DISTRIBUTION}"

#endif
52 changes: 49 additions & 3 deletions include/gz/sim/gui/Gui.hh
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#define GZ_SIM_GUI_GUI_HH_

#include <memory>
#include <string>
#include <gz/gui/Application.hh>

#include "gz/sim/config.hh"
Expand All @@ -41,10 +42,29 @@ namespace gui
/// gz-tools. Set to the name of the application if using gz-tools)
/// \param[in] _guiConfig The GUI configuration file. If nullptr, the default
/// configuration from GZ_HOMEDIR/.gz/sim/gui.config will be used.
/// \param[in] _renderEngineGui --render-engine-gui option
/// \param[in] _renderEngine --render-engine-gui option
/// \return -1 on failure, 0 on success
GZ_SIM_GUI_VISIBLE int runGui(int &_argc,
char **_argv, const char *_guiConfig, const char * _renderEngine = nullptr);
char **_argv, const char *_guiConfig, const char *_renderEngine = nullptr);

/// \brief Run GUI application
/// \param[in] _argc Number of command line arguments (Used when running
/// without gz-tools. Set to 1 if using gz-tools). Note: The object
/// referenced by this variable must continue to exist for the lifetime of the
/// application.
/// \param[in] _argv Command line arguments (Used when running without
/// gz-tools. Set to the name of the application if using gz-tools)
/// \param[in] _guiConfig The GUI configuration file. If nullptr, the default
/// configuration from GZ_HOMEDIR/.gz/sim/gui.config will be used.
/// \param[in] _sdfFile The world file path passed as a command line argument.
/// If set, QuickStart Dialog will not be shown.
/// \param[in] _waitGui Flag indicating whether the server waits until
/// it receives a world path from GUI.
/// \param[in] _renderEngine --render-engine-gui option
/// \return -1 on failure, 0 on success
GZ_SIM_GUI_VISIBLE int runGui(int &_argc, char **_argv,
const char *_guiConfig, const char *_sdfFile, int _waitGui,
const char *_renderEngine = nullptr);

/// \brief Create a Gazebo GUI application
/// \param[in] _argc Number of command line arguments (Used when running
Expand All @@ -62,14 +82,40 @@ namespace gui
/// GZ_HOMEDIR/.gz/sim/gui.config will be used.
/// \param[in] _loadPluginsFromSdf If true, plugins specified in the world
/// SDFormat file will get loaded.
/// \param[in] _renderEngineGui --render-engine-gui option
/// \param[in] _renderEngine --render-engine-gui option
/// \return Newly created application.
GZ_SIM_GUI_VISIBLE
std::unique_ptr<gz::gui::Application> createGui(
int &_argc, char **_argv, const char *_guiConfig,
const char *_defaultGuiConfig = nullptr, bool _loadPluginsFromSdf = true,
const char *_renderEngine = nullptr);

/// \brief Create a Gazebo GUI application
/// \param[in] _argc Number of command line arguments (Used when running
/// without gz-tools. Set to 1 if using gz-tools). Note: The object
/// referenced by this variable must continue to exist for the lifetime of the
/// application.
/// \param[in] _argv Command line arguments (Used when running without
/// gz-tools. Set to the name of the application if using gz-tools)
/// \param[in] _guiConfig The GUI configuration file. If nullptr, the default
/// configuration from GZ_HOMEDIR/.gz/sim/gui.config will be used.
/// \param[in] _defaultGuiConfig The default GUI configuration file. If no
/// plugins were added from a world file or from _guiConfig, this
/// configuration file will be loaded. If this argument is a nullptr or if the
/// file does not exist, the default configuration from
/// GZ_HOMEDIR/.gz/sim/gui.config will be used.
/// \param[in] _loadPluginsFromSdf If true, plugins specified in the world
/// SDFormat file will get loaded.
/// \param[in] _sdfFile SDF world file, or nullptr if not set.
/// \param[in] _waitGui True if the server is waiting for the GUI to decide on
/// a starting world.
/// \param[in] _renderEngine --render-engine-gui option
/// \return Newly created application.
GZ_SIM_GUI_VISIBLE
std::unique_ptr<gz::gui::Application> createGui(
int &_argc, char **_argv, const char *_guiConfig,
const char *_defaultGuiConfig, bool _loadPluginsFromSdf,
const char *_sdfFile, int _waitGui, const char *_renderEngine = nullptr);
} // namespace gui
} // namespace GZ_SIM_VERSION_NAMESPACE
} // namespace sim
Expand Down
Loading

0 comments on commit 30a312f

Please sign in to comment.