Skip to content

Commit

Permalink
Merge branch 'arjo/buoyancy_engine' of github.com:ignitionrobotics/ig…
Browse files Browse the repository at this point in the history
…n-gazebo into arjo/buoyancy_engine
  • Loading branch information
arjo129 committed Sep 15, 2021
2 parents bdf5ba8 + 834b2d0 commit baad4ad
Show file tree
Hide file tree
Showing 145 changed files with 2,224 additions and 952 deletions.
5 changes: 3 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ endif()

# This option is needed to use the PROTOBUF_GENERATE_CPP
# in case protobuf is found with the CMake config files
# It needs to be set before any find_package(...) call
# It needs to be set before any find_package(...) call
# as protobuf could be find transitively by any dependency
set(protobuf_MODULE_COMPATIBLE TRUE)

Expand All @@ -65,7 +65,7 @@ set(IGN_MSGS_VER ${ignition-msgs8_VERSION_MAJOR})
#--------------------------------------
# Find ignition-common
# Always use the profiler component to get the headers, regardless of status.
ign_find_package(ignition-common4
ign_find_package(ignition-common4 VERSION 4.2
COMPONENTS
profiler
events
Expand Down Expand Up @@ -192,6 +192,7 @@ if (NOT APPLE)
API_MAINPAGE_MD "${CMAKE_BINARY_DIR}/api.md"
TUTORIALS_MAINPAGE_MD "${CMAKE_BINARY_DIR}/tutorials.md"
ADDITIONAL_INPUT_DIRS "${CMAKE_SOURCE_DIR}/src/systems ${CMAKE_SOURCE_DIR}/src/gui/plugins"
IMAGE_PATH_DIRS "${CMAKE_SOURCE_DIR}/tutorials/files"
TAGFILES
"${IGNITION-MATH_DOXYGEN_TAGFILE} = ${IGNITION-MATH_API_URL}"
"${IGNITION-MSGS_DOXYGEN_TAGFILE} = ${IGNITION-MSGS_API_URL}"
Expand Down
62 changes: 61 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -775,7 +775,67 @@
### Ignition Gazebo 3.X.X (202X-XX-XX)


### Ignition Gazebo 3.9.0 (2021-07-XX)
### Ignition Gazebo 3.9.0 (2021-08-16)

1. Entity tree: prevent creation of repeated entity items
* [Pull request #974](https:/ignitionrobotics/ign-gazebo/pull/974)

1. Don't use $HOME on most tests (InternalFixture)
* [Pull request #971](https:/ignitionrobotics/ign-gazebo/pull/971)

1. Be more specific when looking for physics plugins
* [Pull request #965](https:/ignitionrobotics/ign-gazebo/pull/965)

1. Drag and drop meshes into scene
* [Pull request #939](https:/ignitionrobotics/ign-gazebo/pull/939)

1. Set protobuf_MODULE_COMPATIBLE before any find_package call
* [Pull request #957](https:/ignitionrobotics/ign-gazebo/pull/957)

1. [DiffDrive] add enable/disable
* [Pull request #772](https:/ignitionrobotics/ign-gazebo/pull/772)

1. Fix component inspector shutdown crash
* [Pull request #724](https:/ignitionrobotics/ign-gazebo/pull/724)

1. Add UserCommands Plugin.
* [Pull request #719](https:/ignitionrobotics/ign-gazebo/pull/719)

1. Setting the intiial velocity for a model or joint
* [Pull request #693](https:/ignitionrobotics/ign-gazebo/pull/693)

1. Examples and tutorial on using rendering API from plugins
* [Pull request #596](https:/ignitionrobotics/ign-gazebo/pull/596)

1. Add missing IGNITION_GAZEBO_VISIBLE macros
* [Pull request #563](https:/ignitionrobotics/ign-gazebo/pull/563)

1. Fix visibility macro names when used by a different component (Windows)
* [Pull request #564](https:/ignitionrobotics/ign-gazebo/pull/564)

1. No install apt recommends and clear cache
* [Pull request #423](https:/ignitionrobotics/ign-gazebo/pull/423)

1. Add 25percent darker view angle icons
* [Pull request #426](https:/ignitionrobotics/ign-gazebo/pull/426)

1. Expose a test fixture helper class
* [Pull request #926](https:/ignitionrobotics/ign-gazebo/pull/926)

1. Fix logic to disable server default plugins loading
* [Pull request #953](https:/ignitionrobotics/ign-gazebo/pull/953)

1. removed unneeded plugin update
* [Pull request #944](https:/ignitionrobotics/ign-gazebo/pull/944)

1. Functions to enable velocity and acceleration checks on Link
* [Pull request #935](https:/ignitionrobotics/ign-gazebo/pull/935)

1. Support adding systems that don't come from a plugin
* [Pull request #936](https:/ignitionrobotics/ign-gazebo/pull/936)

1. 3D plot GUI plugin
* [Pull request #917](https:/ignitionrobotics/ign-gazebo/pull/917)

1. Add a convenience function for getting possibly non-existing components.
* [Pull request #629](https:/ignitionrobotics/ign-gazebo/pull/629)
Expand Down
103 changes: 0 additions & 103 deletions bitbucket-pipelines.yml

This file was deleted.

9 changes: 5 additions & 4 deletions docker/scripts/install_ign_deps.sh
Original file line number Diff line number Diff line change
Expand Up @@ -67,10 +67,11 @@ sudo apt-get install --no-install-recommends -y \
# ign-physics dependencies
sudo apt-get install --no-install-recommends -y \
libeigen3-dev \
dart6-data \
libdart6-collision-ode-dev \
libdart6-dev \
libdart6-utils-urdf-dev \
libdart-collision-ode-dev \
libdart-dev \
libdart-external-ikfast-dev \
libdart-external-odelcpsolver-dev \
libdart-utils-urdf-dev \
libbenchmark-dev

# ign-gazebo dependencies
Expand Down
2 changes: 1 addition & 1 deletion examples/standalone/entity_creation/entity_creation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ void createEntityFromStr(const std::string modelStr)
if (executed)
{
if (result)
std::cout << "Sphere was created : [" << res.data() << "]" << std::endl;
std::cout << "Entity was created : [" << res.data() << "]" << std::endl;
else
{
std::cout << "Service call failed" << std::endl;
Expand Down
1 change: 1 addition & 0 deletions examples/worlds/logical_camera_sensor.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -141,6 +141,7 @@
<alwaysOn>1</alwaysOn>
<visualize>true</visualize>
<topic>logical_camera</topic>
<enable_metrics>true</enable_metrics>
</sensor>
</link>
</model>
Expand Down
32 changes: 27 additions & 5 deletions examples/worlds/minimal_scene.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,15 @@ Features:
* Grid config
* Select entities
* Transform controls
* Spawn entities through GUI
* View angles
Missing for parity with GzScene3D:
* Spawn entities through GUI
* Context menu
* Record video
* View angles
* View collisions, wireframe, transparent, CoM, etc
* Drag and drop from Fuel / meshes
* ...
-->
Expand Down Expand Up @@ -131,8 +132,6 @@ Missing for parity with GzScene3D:
<play_pause>true</play_pause>
<step>true</step>
<start_paused>true</start_paused>
<service>/world/buoyancy/control</service>
<stats_topic>/world/buoyancy/stats</stats_topic>

</plugin>

Expand All @@ -157,7 +156,20 @@ Missing for parity with GzScene3D:
<real_time>true</real_time>
<real_time_factor>true</real_time_factor>
<iterations>true</iterations>
<topic>/world/buoyancy/stats</topic>
</plugin>

<plugin filename="Spawn" name="Spawn Entities">
<ignition-gui>
<anchors target="Select entities">
<line own="right" target="right"/>
<line own="top" target="top"/>
</anchors>
<property key="resizable" type="bool">false</property>
<property key="width" type="double">5</property>
<property key="height" type="double">5</property>
<property key="state" type="string">floating</property>
<property key="showTitleBar" type="bool">false</property>
</ignition-gui>
</plugin>

<!-- Insert simple shapes -->
Expand Down Expand Up @@ -235,6 +247,16 @@ Missing for parity with GzScene3D:
</ignition-gui>
</plugin>

<!-- View angle -->
<plugin filename="ViewAngle" name="View angle">
<ignition-gui>
<property type="string" key="state">docked</property>
</ignition-gui>

<!-- disable legacy features used to connect this plugin to GzScene3D -->
<legacy>false</legacy>
</plugin>

</gui>

<light type="directional" name="sun">
Expand Down
1 change: 0 additions & 1 deletion examples/worlds/pendulum_links.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,6 @@
-->

<?xml version="1.0" ?>
<sdf version="1.7">
<world name="double_pendulum">
<physics name="1ms" type="ignored">
Expand Down
4 changes: 4 additions & 0 deletions examples/worlds/sensors.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,7 @@
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>altimeter</topic>
<enable_metrics>true</enable_metrics>
<altimeter>
<vertical_position>
<noise type="gaussian">
Expand All @@ -136,6 +137,7 @@
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>air_pressure</topic>
<enable_metrics>true</enable_metrics>
<air_pressure>
<reference_altitude>123</reference_altitude>
<pressure>
Expand All @@ -152,12 +154,14 @@
<update_rate>100</update_rate>
<visualize>true</visualize>
<topic>imu</topic>
<enable_metrics>true</enable_metrics>
</sensor>
<sensor name="magnetometer" type="magnetometer">
<always_on>1</always_on>
<update_rate>100</update_rate>
<visualize>true</visualize>
<topic>magnetometer</topic>
<enable_metrics>true</enable_metrics>
<magnetometer>
<x>
<noise type="gaussian">
Expand Down
4 changes: 4 additions & 0 deletions examples/worlds/sensors_demo.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -276,10 +276,12 @@
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>camera_alone</topic>
<enable_metrics>true</enable_metrics>
</sensor>
<sensor name="depth_camera1" type="depth_camera">
<update_rate>10</update_rate>
<topic>depth_camera</topic>
<enable_metrics>true</enable_metrics>
<camera>
<horizontal_fov>1.05</horizontal_fov>
<image>
Expand Down Expand Up @@ -344,6 +346,7 @@
<sensor name='gpu_lidar' type='gpu_lidar'>"
<topic>lidar</topic>
<update_rate>10</update_rate>
<enable_metrics>true</enable_metrics>
<ray>
<scan>
<horizontal>
Expand Down Expand Up @@ -415,6 +418,7 @@
<update_rate>30</update_rate>
<visualize>true</visualize>
<topic>rgbd_camera</topic>
<enable_metrics>true</enable_metrics>
</sensor>
</link>
</model>
Expand Down
Loading

0 comments on commit baad4ad

Please sign in to comment.