diff --git a/CMakeLists.txt b/CMakeLists.txt
index 2b01b31798..322646018d 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -178,6 +178,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}"
diff --git a/Changelog.md b/Changelog.md
index 09a75047c7..6c493720f7 100644
--- a/Changelog.md
+++ b/Changelog.md
@@ -443,7 +443,13 @@
### Ignition Gazebo 3.X.X (202X-XX-XX)
-### Ignition Gazebo 3.9.0 (2021-08-XX)
+### Ignition Gazebo 3.9.0 (2021-08-16)
+
+1. Entity tree: prevent creation of repeated entity items
+ * [Pull request #974](https://github.com/ignitionrobotics/ign-gazebo/pull/974)
+
+1. Don't use $HOME on most tests (InternalFixture)
+ * [Pull request #971](https://github.com/ignitionrobotics/ign-gazebo/pull/971)
1. Be more specific when looking for physics plugins
* [Pull request #965](https://github.com/ignitionrobotics/ign-gazebo/pull/965)
diff --git a/bitbucket-pipelines.yml b/bitbucket-pipelines.yml
deleted file mode 100644
index 1e85154391..0000000000
--- a/bitbucket-pipelines.yml
+++ /dev/null
@@ -1,103 +0,0 @@
-image: ubuntu:bionic
-
-pipelines:
- default:
- - step:
- script:
- - apt-get update
- - apt -y install wget lsb-release gnupg sudo curl
- # Enable relevant package repositories
- - docker/scripts/enable_ign_stable.sh
- - docker/scripts/enable_ign_prerelease.sh
- # Install base dependencies
- - docker/scripts/install_common_deps.sh
- - docker/scripts/enable_gcc8.sh
- - docker/scripts/install_ign_deps.sh
- # There are two methods to install ignition/osrf dependencies.
- # The first method uses debians and the second builds dependencies
- # from source. For each dependency, please use only one method.
- # METHOD 1: Install the following debians
- - apt-get install -y
- libignition-cmake2-dev
- libignition-math6-eigen3-dev
- libignition-msgs5-dev
- libignition-plugin-dev
- libignition-tools-dev
- libignition-transport8-dev
- libsdformat9-dev
- libignition-fuel-tools4-dev
- libignition-physics3-dev
- # libignition-common3-dev
- # libignition-gui3-dev
- # libignition-sensors3-dev
- # libignition-rendering3-dev
- # METHOD 2: Build from source
- # Build dependencies from source using a given branch
- # - docker/scripts/build_ign.sh ignitionrobotics ign-physics default
- # - docker/scripts/build_ign.sh ignitionrobotics ign-fuel-tools default
- - docker/scripts/build_ign.sh ignitionrobotics ign-common ign-common3
- - docker/scripts/build_ign.sh ignitionrobotics ign-rendering default
- - docker/scripts/build_ign.sh ignitionrobotics ign-gui default
- - docker/scripts/build_ign.sh ignitionrobotics ign-sensors default
- # Build Ignition Gazebo
- - ./tools/clang_tidy.sh
- - mkdir build
- - cd build
- - cmake .. -DCMAKE_BUILD_TYPE=coverage
- - make -j1 install
- - export IGN_CONFIG_PATH=/usr/local/share/ignition
- - export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/usr/local/lib
- # run codecheck before tests so flaky tests don't obscure codecheck failures
- - make codecheck
- - export CTEST_OUTPUT_ON_FAILURE=1
- - make test
- - make coverage
- # Use a special version of codecov for handling gcc8 output.
- - bash <(curl -s https://raw.githubusercontent.com/codecov/codecov-bash/4678d212cce2078bbaaf5027af0c0dafaad6a095/codecov) -X gcovout -X gcov
- custom:
- benchmark:
- - step:
- script:
- - apt-get update
- - apt -y install wget lsb-release gnupg sudo curl
- # Enable relevant package repositories
- - docker/scripts/enable_ign_stable.sh
- # Install base dependencies
- - docker/scripts/install_common_deps.sh
- - docker/scripts/enable_gcc8.sh
- - docker/scripts/install_ign_deps.sh
- # There are two methods to install ignition/osrf dependencies.
- # The first method uses debians and the second builds dependencies
- # from source. For each dependency, please use only one method.
- # METHOD 1: Install the following debians
- - apt-get install -y
- libignition-cmake2-dev
- libignition-common3-dev
- libignition-math6-eigen3-dev
- libignition-plugin-dev
- libignition-tools-dev
- # libignition-fuel-tools4-dev
- # libignition-physics2-dev
- # libsdformat9-dev
- # libignition-gui3-dev
- # libignition-msgs5-dev
- # libignition-rendering3-dev
- # libignition-sensors3-dev
- # libignition-transport8-dev
- # Build some Ignition libraries from source.
- # Build ign-rendering from source using the default branch
- - docker/scripts/build_ign.sh osrf sdformat default
- - docker/scripts/build_ign.sh ignitionrobotics ign-msgs default
- - docker/scripts/build_ign.sh ignitionrobotics ign-transport default
- - docker/scripts/build_ign.sh ignitionrobotics ign-rendering default
- - docker/scripts/build_ign.sh ignitionrobotics ign-gui default
- - docker/scripts/build_ign.sh ignitionrobotics ign-sensors default
- - docker/scripts/build_ign.sh ignitionrobotics ign-physics default
- - docker/scripts/build_ign.sh ignitionrobotics ign-fuel-tools default
- # Build Ignition Gazebo
- - mkdir build
- - cd build
- - cmake ..
- - make -j4 install
- - ./bin/BENCHMARK_each --benchmark_out_format=json --benchmark_out=each.json
- - ../docker/scripts/upload_json_benchmark.sh each.json
diff --git a/examples/worlds/logical_camera_sensor.sdf b/examples/worlds/logical_camera_sensor.sdf
index 14d596c8e2..f8eb3cccd0 100644
--- a/examples/worlds/logical_camera_sensor.sdf
+++ b/examples/worlds/logical_camera_sensor.sdf
@@ -141,6 +141,7 @@
1truelogical_camera
+ true
diff --git a/examples/worlds/pendulum_links.sdf b/examples/worlds/pendulum_links.sdf
index 2f62bab25c..1927835b7a 100644
--- a/examples/worlds/pendulum_links.sdf
+++ b/examples/worlds/pendulum_links.sdf
@@ -9,7 +9,6 @@
-->
-
diff --git a/examples/worlds/sensors.sdf b/examples/worlds/sensors.sdf
index 48af629339..eefd6a8ee8 100644
--- a/examples/worlds/sensors.sdf
+++ b/examples/worlds/sensors.sdf
@@ -116,6 +116,7 @@
30truealtimeter
+ true
@@ -136,6 +137,7 @@
30trueair_pressure
+ true123
@@ -152,12 +154,14 @@
100trueimu
+ true1100truemagnetometer
+ true
diff --git a/examples/worlds/sensors_demo.sdf b/examples/worlds/sensors_demo.sdf
index 7bf8790dc9..9e0d2414e3 100644
--- a/examples/worlds/sensors_demo.sdf
+++ b/examples/worlds/sensors_demo.sdf
@@ -276,10 +276,12 @@
30truecamera_alone
+ true10depth_camera
+ true1.05
@@ -344,6 +346,7 @@
"
lidar10
+ true
@@ -415,6 +418,7 @@
30truergbd_camera
+ true
diff --git a/include/ignition/gazebo/Conversions.hh b/include/ignition/gazebo/Conversions.hh
index d1ed7ee41c..15eea67bea 100644
--- a/include/ignition/gazebo/Conversions.hh
+++ b/include/ignition/gazebo/Conversions.hh
@@ -90,8 +90,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Geometry &/*_in*/)
+ Out convert(const sdf::Geometry &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -107,8 +108,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Pose &/*_in*/)
+ Out convert(const msgs::Pose &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -123,8 +125,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Geometry &/*_in*/)
+ Out convert(const msgs::Geometry &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -140,8 +143,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Material &/*_in*/)
+ Out convert(const sdf::Material &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -157,8 +161,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Material &/*_in*/)
+ Out convert(const msgs::Material &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -174,8 +179,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Actor &/*_in*/)
+ Out convert(const sdf::Actor &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -191,8 +197,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Actor& /*_in*/)
+ Out convert(const msgs::Actor& _in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -208,8 +215,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Light &/*_in*/)
+ Out convert(const sdf::Light &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -226,8 +234,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Light& /*_in*/)
+ Out convert(const msgs::Light& _in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -243,8 +252,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Gui &/*_in*/)
+ Out convert(const sdf::Gui &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -259,8 +269,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const std::chrono::steady_clock::duration &/*_in*/)
+ Out convert(const std::chrono::steady_clock::duration &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -276,8 +287,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Time &/*_in*/)
+ Out convert(const msgs::Time &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -293,8 +305,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const math::Inertiald &/*_in*/)
+ Out convert(const math::Inertiald &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -310,8 +323,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Inertial &/*_in*/)
+ Out convert(const msgs::Inertial &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -327,8 +341,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::JointAxis &/*_in*/)
+ Out convert(const sdf::JointAxis &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -344,8 +359,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Axis &/*_in*/)
+ Out convert(const msgs::Axis &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -361,8 +377,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Scene &/*_in*/)
+ Out convert(const sdf::Scene &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -377,8 +394,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Scene &/*_in*/)
+ Out convert(const msgs::Scene &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -394,8 +412,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Atmosphere &/*_in*/)
+ Out convert(const sdf::Atmosphere &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -411,8 +430,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Atmosphere &/*_in*/)
+ Out convert(const msgs::Atmosphere &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -429,8 +449,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Physics &/*_in*/)
+ Out convert(const sdf::Physics &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -446,8 +467,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Physics &/*_in*/)
+ Out convert(const msgs::Physics &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -464,8 +486,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Sensor &/*_in*/)
+ Out convert(const sdf::Sensor &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -481,8 +504,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Sensor &/*_in*/)
+ Out convert(const msgs::Sensor &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -498,8 +522,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::SensorNoise &/*_in*/)
+ Out convert(const msgs::SensorNoise &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -516,8 +541,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::WorldStatistics &/*_in*/)
+ Out convert(const msgs::WorldStatistics &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -533,8 +559,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const UpdateInfo &/*_in*/)
+ Out convert(const UpdateInfo &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -550,8 +577,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const sdf::Collision &/*_in*/)
+ Out convert(const sdf::Collision &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -567,8 +595,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::Collision &/*_in*/)
+ Out convert(const msgs::Collision &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -584,8 +613,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const std::string &/*_in*/)
+ Out convert(const std::string &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -600,8 +630,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const math::AxisAlignedBox &/*_in*/)
+ Out convert(const math::AxisAlignedBox &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
@@ -618,8 +649,9 @@ namespace ignition
/// \return Conversion result.
/// \tparam Out Output type.
template
- Out convert(const msgs::AxisAlignedBox &/*_in*/)
+ Out convert(const msgs::AxisAlignedBox &_in)
{
+ (void)_in;
Out::ConversionNotImplemented;
}
diff --git a/include/ignition/gazebo/EntityComponentManager.hh b/include/ignition/gazebo/EntityComponentManager.hh
index ad28252e65..2df7fc4369 100644
--- a/include/ignition/gazebo/EntityComponentManager.hh
+++ b/include/ignition/gazebo/EntityComponentManager.hh
@@ -81,7 +81,7 @@ namespace ignition
/// into a queue. The queue is processed toward the end of a simulation
/// update step.
///
- /// \detail It is recommended that systems don't call this function
+ /// \details It is recommended that systems don't call this function
/// directly, and instead use the `gazebo::SdfEntityCreator` class to
/// remove entities.
///
@@ -102,7 +102,7 @@ namespace ignition
public: bool HasEntity(const Entity _entity) const;
/// \brief Get the first parent of the given entity.
- /// \detail Entities are not expected to have multiple parents.
+ /// \details Entities are not expected to have multiple parents.
/// TODO(louise) Either prevent multiple parents or provide full support
/// for multiple parents.
/// \param[in] _entity Entity.
@@ -111,11 +111,13 @@ namespace ignition
/// \brief Set the parent of an entity.
///
- /// \detail It is recommended that systems don't call this function
+ /// \details It is recommended that systems don't call this function
/// directly, and instead use the `gazebo::SdfEntityCreator` class to
/// create entities that have the correct parent-child relationship.
///
- /// \param[in] _entity Entity or kNullEntity to remove current parent.
+ /// \param[in] _child Entity to set the parent
+ /// \param[in] _parent Entity which should be an immediate parent _child
+ /// entity.
/// \return True if successful. Will fail if entities don't exist.
public: bool SetParentEntity(const Entity _child, const Entity _parent);
@@ -278,7 +280,7 @@ namespace ignition
/// auto entity = EntityByComponents(components::Name("name"),
/// components::Model());
///
- /// \detail Component type must have inequality operator.
+ /// \details Component type must have inequality operator.
///
/// \param[in] _desiredComponents All the components which must match.
/// \return Entity or kNullEntity if no entity has the exact components.
@@ -293,7 +295,7 @@ namespace ignition
/// auto entities = EntitiesByComponents(components::Name("camera"),
/// components::Sensor());
///
- /// \detail Component type must have inequality operator.
+ /// \details Component type must have inequality operator.
///
/// \param[in] _desiredComponents All the components which must match.
/// \return All matching entities, or an empty vector if no child entity
@@ -310,7 +312,7 @@ namespace ignition
///
/// auto entity = ChildrenByComponents(parent, 123, std::string("name"));
///
- /// \detail Component type must have inequality operator.
+ /// \details Component type must have inequality operator.
///
/// \param[in] _parent Entity which should be an immediate parent of the
/// returned entity.
@@ -465,7 +467,7 @@ namespace ignition
/// \brief Get a message with the serialized state of the given entities
/// and components.
- /// \detail The header of the message will not be populated, it is the
+ /// \details The header of the message will not be populated, it is the
/// responsibility of the caller to timestamp it before use.
/// \param[in] _entities Entities to be serialized. Leave empty to get
/// all entities.
@@ -485,7 +487,7 @@ namespace ignition
/// * Entities which had a component removed
/// * Entities which had a component modified
///
- /// \detail The header of the message will not be populated, it is the
+ /// \details The header of the message will not be populated, it is the
/// responsibility of the caller to timestamp it before use.
public: msgs::SerializedState ChangedState() const;
@@ -513,15 +515,16 @@ namespace ignition
/// one will be created.
/// Entities / components that are marked as removed will be removed, but
/// they won't be removed if they're not present in the state.
- /// \detail The header of the message will not be handled, it is the
+ /// \details The header of the message will not be handled, it is the
/// responsibility of the caller to use the timestamp.
/// \param[in] _stateMsg Message containing state to be set.
public: void SetState(const msgs::SerializedState &_stateMsg);
/// \brief Get a message with the serialized state of the given entities
/// and components.
- /// \detail The header of the message will not be populated, it is the
+ /// \details The header of the message will not be populated, it is the
/// responsibility of the caller to timestamp it before use.
+ /// \param[in] _state serialized state
/// \param[in] _entities Entities to be serialized. Leave empty to get
/// all entities.
/// \param[in] _types Type ID of components to be serialized. Leave empty
@@ -545,7 +548,7 @@ namespace ignition
/// * Entities which had a component modified
///
/// \param[in] _state New serialized state.
- /// \detail The header of the message will not be populated, it is the
+ /// \details The header of the message will not be populated, it is the
/// responsibility of the caller to timestamp it before use.
public: void ChangedState(msgs::SerializedStateMap &_state) const;
@@ -554,7 +557,7 @@ namespace ignition
/// one will be created.
/// Entities / components that are marked as removed will be removed, but
/// they won't be removed if they're not present in the state.
- /// \detail The header of the message will not be handled, it is the
+ /// \details The header of the message will not be handled, it is the
/// responsibility of the caller to use the timestamp.
/// \param[in] _stateMsg Message containing state to be set.
public: void SetState(const msgs::SerializedStateMap &_stateMsg);
diff --git a/include/ignition/gazebo/Events.hh b/include/ignition/gazebo/Events.hh
index 92c04c6e5e..672c264c03 100644
--- a/include/ignition/gazebo/Events.hh
+++ b/include/ignition/gazebo/Events.hh
@@ -55,7 +55,7 @@ namespace ignition
/// \brief Event used to load plugins for an entity into simulation.
/// Pass in the entity which will own the plugins, and an SDF element for
- /// the entity, which may contain multiple tags.
+ /// the entity, which may contain multiple `` tags.
using LoadPlugins = common::EventT;
}
diff --git a/include/ignition/gazebo/Server.hh b/include/ignition/gazebo/Server.hh
index fb2e7a17ef..f67bf6ff1c 100644
--- a/include/ignition/gazebo/Server.hh
+++ b/include/ignition/gazebo/Server.hh
@@ -75,34 +75,34 @@ namespace ignition
/// ## Services
///
/// The following are services provided by the Server.
- /// The in the service list is the name of the
+ /// The `` in the service list is the name of the
/// simulated world.
///
/// List syntax: *service_name(request_msg_type) : response_msg_type*
///
- /// 1. /world//scene/info(none) : ignition::msgs::Scene
+ /// 1. `/world//scene/info(none)` : ignition::msgs::Scene
/// + Returns the current scene information.
///
- /// 2. /gazebo/resource_paths/get : ignition::msgs::StringMsg_V
+ /// 2. `/gazebo/resource_paths/get` : ignition::msgs::StringMsg_V
/// + Get list of resource paths.
///
- /// 3. /gazebo/resource_paths/add : ignition::msgs::Empty
+ /// 3. `/gazebo/resource_paths/add` : ignition::msgs::Empty
/// + Add new resource paths.
///
/// ## Topics
///
/// The following are topics provided by the Server.
- /// The in the service list is the name of the
+ /// The `` in the service list is the name of the
/// simulated world.
///
/// List syntax: *topic_name : published_msg_type*
///
- /// 1. /world//clock : ignition::msgs::Clock
+ /// 1. `/world//clock` : ignition::msgs::Clock
///
- /// 2. /world//stats : ignition::msgs::WorldStatistics
+ /// 2. `/world//stats` : ignition::msgs::WorldStatistics
/// + This topic is throttled to 5Hz.
///
- /// 3. /gazebo/resource_paths : ignition::msgs::StringMsg_V
+ /// 3. `/gazebo/resource_paths` : ignition::msgs::StringMsg_V
/// + Updated list of resource paths.
///
class IGNITION_GAZEBO_VISIBLE Server
diff --git a/include/ignition/gazebo/ServerConfig.hh b/include/ignition/gazebo/ServerConfig.hh
index 199ccdee35..438c716c48 100644
--- a/include/ignition/gazebo/ServerConfig.hh
+++ b/include/ignition/gazebo/ServerConfig.hh
@@ -45,7 +45,7 @@ namespace ignition
class PluginInfoPrivate;
/// \brief Information about a plugin that should be loaded by the
/// server.
- /// \detail Currently supports attaching a plugin to an entity given its
+ /// \details Currently supports attaching a plugin to an entity given its
/// type and name, but it can't tell apart multiple entities with the same
/// name in different parts of the entity tree.
/// \sa const std::list &Plugins() const
@@ -114,7 +114,7 @@ namespace ignition
/// \brief Set the type of the entity which should receive this
/// plugin. The type is used in conjuction with EntityName to
/// uniquely identify an entity.
- /// \param[in] _entityType Entity type string.
+ /// \param[in] _filename Entity type string.
public: void SetFilename(const std::string &_filename);
/// \brief Name of the interface within the plugin library
@@ -166,7 +166,7 @@ namespace ignition
///
/// Setting the SDF string will override any value set by `SetSdfFile`.
///
- /// \param[in] _file Full path to an SDF file.
+ /// \param[in] _sdfString Full path to an SDF file.
/// \return (reserved for future use)
public: bool SetSdfString(const std::string &_sdfString);
@@ -336,12 +336,12 @@ namespace ignition
public: const std::string &RenderEngineGui() const;
/// \brief Set the render engine server plugin library.
- /// \param[in] _renderEngine File containing render engine library.
+ /// \param[in] _renderEngineServer File containing render engine library.
public: void SetRenderEngineServer(
const std::string &_renderEngineServer);
/// \brief Set the render engine gui plugin library.
- /// \param[in] _renderEngine File containing render engine library.
+ /// \param[in] _renderEngineGui File containing render engine library.
public: void SetRenderEngineGui(const std::string &_renderEngineGui);
/// \brief Instruct simulation to attach a plugin to a specific
@@ -350,7 +350,7 @@ namespace ignition
public: void AddPlugin(const PluginInfo &_info);
/// \brief Add multiple plugins to the simulation
- /// \param[in] _info List of Information about the plugin to load.
+ /// \param[in] _plugins List of Information about the plugin to load.
public: void AddPlugins(const std::list &_plugins);
/// \brief Generate PluginInfo for Log recording based on the
diff --git a/include/ignition/gazebo/Util.hh b/include/ignition/gazebo/Util.hh
index 6eba8458ce..1b5a6f73ac 100644
--- a/include/ignition/gazebo/Util.hh
+++ b/include/ignition/gazebo/Util.hh
@@ -244,7 +244,7 @@ namespace ignition
/// ``
const std::string kSdfPathEnv{"SDF_PATH"};
- /// \breif Environment variable holding server config paths.
+ /// \brief Environment variable holding server config paths.
const std::string kServerConfigPathEnv{"IGN_GAZEBO_SERVER_CONFIG_PATH"};
/// \brief Environment variable holding paths to custom rendering engine
diff --git a/include/ignition/gazebo/components/Component.hh b/include/ignition/gazebo/components/Component.hh
index 727c2b48be..bbee6d34c5 100644
--- a/include/ignition/gazebo/components/Component.hh
+++ b/include/ignition/gazebo/components/Component.hh
@@ -240,8 +240,10 @@ namespace components
/// override this function to support serialization.
///
/// \param[in] _out Out stream.
- public: virtual void Serialize(std::ostream &/*_out*/) const
+ public: virtual void Serialize(std::ostream &_out) const
{
+ // This will avoid a doxygen warning
+ (void)_out;
static bool warned{false};
if (!warned)
{
@@ -257,8 +259,10 @@ namespace components
/// override this function to support deserialization.
///
/// \param[in] _in In stream.
- public: virtual void Deserialize(std::istream &/*_in*/)
+ public: virtual void Deserialize(std::istream &_in)
{
+ // This will avoid a doxygen warning
+ (void)_in;
static bool warned{false};
if (!warned)
{
@@ -358,7 +362,6 @@ namespace components
/// \param[in] _data New data for this component.
/// \param[in] _eql Equality comparison function. This function should
/// return true if two instances of DataType are equal.
- /// \param[in} _ecm Pointer to the entity component manager.
/// \return True if the _eql function returns false.
public: bool SetData(const DataType &_data,
const std::function<
@@ -396,14 +399,14 @@ namespace components
/// \param[in] _component Component to compare to
/// \return True.
public: bool operator==(const Component &) const;
+ Serializer> &_component) const;
/// \brief Components with no data are always equal to another instance of
/// the same type.
/// \param[in] _component Component to compare to
/// \return False.
public: bool operator!=(const Component &) const;
+ Serializer> &_component) const;
// Documentation inherited
public: ComponentTypeId TypeId() const override;
diff --git a/include/ignition/gazebo/components/ContactSensor.hh b/include/ignition/gazebo/components/ContactSensor.hh
index 4df9ef12a6..f772101579 100644
--- a/include/ignition/gazebo/components/ContactSensor.hh
+++ b/include/ignition/gazebo/components/ContactSensor.hh
@@ -31,7 +31,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace components
{
/// \brief TODO(anyone) Substitute with sdf::Contact once that exists?
- /// This is currently the whole element.
+ /// This is currently the whole `` element.
using ContactSensor = Component;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ContactSensor",
ContactSensor)
diff --git a/include/ignition/gazebo/components/Factory.hh b/include/ignition/gazebo/components/Factory.hh
index 490d18e813..01ef49694d 100644
--- a/include/ignition/gazebo/components/Factory.hh
+++ b/include/ignition/gazebo/components/Factory.hh
@@ -171,9 +171,9 @@ namespace components
/// \brief Unregister a component so that the factory can't create instances
/// of the component or its storage anymore.
- /// \detail This function will not reset the `typeId` static variable within
- /// the component type itself. Prefer using the templated `Unregister`
- /// function when possible.
+ /// \details This function will not reset the `typeId` static variable
+ /// within the component type itself. Prefer using the templated
+ /// `Unregister` function when possible.
/// \param[in] _typeId Type of component to unregister.
public: void Unregister(ComponentTypeId _typeId)
{
@@ -310,12 +310,12 @@ namespace components
private: std::map storagesById;
/// \brief A list of IDs and their equivalent names.
- /// \detail Make it non-static on version 2.0.
+ /// \details Make it non-static on version 2.0.
public: inline static std::map namesById;
/// \brief Keep track of the runtime names for types and warn the user if
/// they try to register different types with the same typeName.
- /// \detail Make it non-static on version 2.0.
+ /// \details Make it non-static on version 2.0.
public: inline static std::map
runtimeNamesById;
};
@@ -324,7 +324,7 @@ namespace components
///
/// Use this macro to register components.
///
- /// \detail Each time a plugin which uses a component is loaded, it tries to
+ /// \details Each time a plugin which uses a component is loaded, it tries to
/// register the component again, so we prevent that.
/// \param[in] _compType Component type name.
/// \param[in] _classname Class name for component.
diff --git a/include/ignition/gazebo/components/LogicalCamera.hh b/include/ignition/gazebo/components/LogicalCamera.hh
index 8c1daab981..7ed6463163 100644
--- a/include/ignition/gazebo/components/LogicalCamera.hh
+++ b/include/ignition/gazebo/components/LogicalCamera.hh
@@ -31,7 +31,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace components
{
/// \brief TODO(anyone) Substitute with sdf::LogicalCamera once that exists?
- /// This is currently the whole element.
+ /// This is currently the whole `` element.
using LogicalCamera = Component;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.LogicalCamera",
LogicalCamera)
diff --git a/include/ignition/gazebo/components/Serialization.hh b/include/ignition/gazebo/components/Serialization.hh
index 5fe9999dce..7fd3ee7765 100644
--- a/include/ignition/gazebo/components/Serialization.hh
+++ b/include/ignition/gazebo/components/Serialization.hh
@@ -148,7 +148,7 @@ namespace serializers
/// \brief Deserialization
/// \param[in] _in Input stream.
- /// \param[in] _vec Message to populate
+ /// \param[in] _msg Message to populate
/// \return The stream.
public: static std::istream &Deserialize(std::istream &_in,
google::protobuf::Message &_msg)
diff --git a/include/ignition/gazebo/gui/GuiSystem.hh b/include/ignition/gazebo/gui/GuiSystem.hh
index c031101042..1de32584eb 100644
--- a/include/ignition/gazebo/gui/GuiSystem.hh
+++ b/include/ignition/gazebo/gui/GuiSystem.hh
@@ -51,8 +51,13 @@ namespace gazebo
/// \param[in] _info Current simulation information, such as time.
/// \param[in] _ecm Mutable reference to the ECM, so the system can read
/// and write entities and their components.
- public: virtual void Update(const UpdateInfo &/*_info*/,
- EntityComponentManager &/*_ecm*/){}
+ public: virtual void Update(const UpdateInfo &_info,
+ EntityComponentManager &_ecm)
+ {
+ // This will avoid many doxygen warnings
+ (void)_info;
+ (void)_ecm;
+ }
};
}
}
diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh
index efbf91c445..05f64cc9f7 100644
--- a/include/ignition/gazebo/rendering/SceneManager.hh
+++ b/include/ignition/gazebo/rendering/SceneManager.hh
@@ -149,7 +149,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Create an actor
/// \param[in] _id Unique actor id
- /// \param[in] _visual Actor sdf dom
+ /// \param[in] _actor Actor sdf dom
/// \param[in] _parentId Parent id
/// \return Actor object created from the sdf dom
public: rendering::VisualPtr CreateActor(Entity _id,
@@ -183,7 +183,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// the correct parent.
/// \param[in] _gazeboId Entity in Gazebo
/// \param[in] _sensorName Name of sensor node in Ignition Rendering.
- /// \param[in] _parentId Parent Id on Gazebo.
+ /// \param[in] _parentGazeboId Parent Id on Gazebo.
/// \return True if sensor is successfully handled
public: bool AddSensor(Entity _gazeboId, const std::string &_sensorName,
Entity _parentGazeboId = 0);
diff --git a/src/gui/plugins/align_tool/AlignTool.hh b/src/gui/plugins/align_tool/AlignTool.hh
index b18e158564..8b4c0c001c 100644
--- a/src/gui/plugins/align_tool/AlignTool.hh
+++ b/src/gui/plugins/align_tool/AlignTool.hh
@@ -138,7 +138,7 @@ namespace gazebo
/// \brief Returns the top level node of the passed in node within
/// a given scene.
/// \param[in] _scene The scene to check
- /// \param[in] _visual The node to get the top level node for
+ /// \param[in] _node The node to get the top level node for
public: rendering::NodePtr TopLevelNode(rendering::ScenePtr &_scene,
rendering::NodePtr &_node) const;
diff --git a/src/gui/plugins/entity_tree/EntityTree.cc b/src/gui/plugins/entity_tree/EntityTree.cc
index 8a0ae74152..79de5dfb7f 100644
--- a/src/gui/plugins/entity_tree/EntityTree.cc
+++ b/src/gui/plugins/entity_tree/EntityTree.cc
@@ -132,6 +132,13 @@ void TreeModel::AddEntity(unsigned int _entity, const QString &_entityName,
return;
}
+ if (this->entityItems.find(_entity) != this->entityItems.end())
+ {
+ ignwarn << "Internal error: Trying to create item for entity [" << _entity
+ << "], but entity already has an item." << std::endl;
+ return;
+ }
+
// New entity item
auto entityItem = new QStandardItem(_entityName);
entityItem->setData(_entityName, this->roleNames().key("entityName"));
diff --git a/src/gui/plugins/modules/EntityContextMenu.hh b/src/gui/plugins/modules/EntityContextMenu.hh
index 0dd8f567b6..80de797028 100644
--- a/src/gui/plugins/modules/EntityContextMenu.hh
+++ b/src/gui/plugins/modules/EntityContextMenu.hh
@@ -54,7 +54,6 @@ namespace gazebo
public: ~EntityContextMenu() override;
/// \brief Callback when a context menu item is invoked
- /// \param[in] _request Request type
/// \param[in] _data Request data
/// \param[in] _type Entity type
public: Q_INVOKABLE void OnRemove(
diff --git a/src/gui/plugins/resource_spawner/ResourceSpawner.hh b/src/gui/plugins/resource_spawner/ResourceSpawner.hh
index d95e5727cb..377ad95ec5 100644
--- a/src/gui/plugins/resource_spawner/ResourceSpawner.hh
+++ b/src/gui/plugins/resource_spawner/ResourceSpawner.hh
@@ -212,6 +212,8 @@ namespace gazebo
/// \brief Callback when a request is made to download a fuel resource.
/// \param[in] _path URI to the fuel resource
+ /// \param[in] _name Name of the resource
+ /// \param[in] _owner The name of the owner
/// \param[in] index The index of the grid pane to update
public slots: void OnDownloadFuelResource(const QString &_path,
const QString &_name, const QString &_owner, int index);
@@ -231,7 +233,7 @@ namespace gazebo
/// sets the model's thumbnail path attribute to it, no action is
/// taken if no thumbnail is found.
/// \param[in] _thumbnailPath The path to search for a thumbnail
- /// \param[in] _model The model to update with the thumbnail information
+ /// \param[in] _resource The model to update with the thumbnail information
public: void SetThumbnail(const std::string &_thumbnailPath,
Resource &_resource);
diff --git a/src/gui/plugins/scene3d/Scene3D.hh b/src/gui/plugins/scene3d/Scene3D.hh
index be0e257097..e46b19a4a0 100644
--- a/src/gui/plugins/scene3d/Scene3D.hh
+++ b/src/gui/plugins/scene3d/Scene3D.hh
@@ -250,11 +250,11 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
const std::string &_savePath);
/// \brief Set whether to record video using sim time as timestamp
- /// \param[in] _true True record video using sim time
+ /// \param[in] _useSimTime True record video using sim time
public: void SetRecordVideoUseSimTime(bool _useSimTime);
/// \brief Set whether to record video in lockstep mode
- /// \param[in] _true True to record video in lockstep mode
+ /// \param[in] _lockstep True to record video in lockstep mode
public: void SetRecordVideoLockstep(bool _lockstep);
/// \brief Set video recorder bitrate in bps
@@ -293,7 +293,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief True to set the camera to follow the target in world frame,
/// false to follow in target's local frame
- /// \param[in] _gain Camera follow p gain.
+ /// \param[in] _worldFrame True to use the world frame.
public: void SetFollowWorldFrame(bool _worldFrame);
/// \brief Set the camera follow offset position
@@ -433,7 +433,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief Retrieve the point on a plane at z = 0 in the 3D scene hit by a
/// ray cast from the given 2D screen coordinates.
- /// \param[in] _screenPod 2D coordinates on the screen, in pixels.
+ /// \param[in] _screenPos 2D coordinates on the screen, in pixels.
/// \return 3D coordinates of a point in the 3D scene.
public: math::Vector3d ScreenToPlane(const math::Vector2i &_screenPos)
const;
@@ -596,11 +596,11 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
const std::string &_savePath);
/// \brief Set whether to record video using sim time as timestamp
- /// \param[in] _true True record video using sim time
+ /// \param[in] _useSimTime True record video using sim time
public: void SetRecordVideoUseSimTime(bool _useSimTime);
/// \brief Set whether to record video in lockstep mode
- /// \param[in] _true True to record video in lockstep mode
+ /// \param[in] _lockstep True to record video in lockstep mode
public: void SetRecordVideoLockstep(bool _lockstep);
/// \brief Set video recorder bitrate in bps
@@ -639,7 +639,7 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
/// \brief True to set the camera to follow the target in world frame,
/// false to follow in target's local frame
- /// \param[in] _gain Camera follow p gain.
+ /// \param[in] _worldFrame True to use the world frame.
public: void SetFollowWorldFrame(bool _worldFrame);
/// \brief Set the camera follow offset position
diff --git a/src/gui/plugins/shapes/Shapes.cc b/src/gui/plugins/shapes/Shapes.cc
index 3b9165e5e3..dc00229760 100644
--- a/src/gui/plugins/shapes/Shapes.cc
+++ b/src/gui/plugins/shapes/Shapes.cc
@@ -40,9 +40,6 @@ namespace ignition::gazebo
/// \brief Ignition communication node.
public: transport::Node node;
- /// \brief Mutex to protect mode
- public: std::mutex mutex;
-
/// \brief Transform control service name
public: std::string service;
};
diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc
index 06219d9387..82761b4ad9 100644
--- a/src/rendering/SceneManager.cc
+++ b/src/rendering/SceneManager.cc
@@ -334,7 +334,14 @@ rendering::VisualPtr SceneManager::CreateVisual(Entity _id,
double productAlpha = (1.0-_visual.Transparency()) *
(1.0 - submeshMat->Transparency());
submeshMat->SetTransparency(1 - productAlpha);
+
+ // unlike setting transparency above, the parent submesh are not
+ // notified about the the cast shadows changes. So we need to set
+ // the material back to the submesh.
+ // \todo(anyone) find way to propate cast shadows changes tos submesh
+ // in ign-rendering
submeshMat->SetCastShadows(_visual.CastShadows());
+ submesh->SetMaterial(submeshMat);
}
}
}
diff --git a/src/systems/battery_plugin/LinearBatteryPlugin.hh b/src/systems/battery_plugin/LinearBatteryPlugin.hh
index 9e0f243e37..75149eef0f 100644
--- a/src/systems/battery_plugin/LinearBatteryPlugin.hh
+++ b/src/systems/battery_plugin/LinearBatteryPlugin.hh
@@ -40,23 +40,23 @@ namespace systems
/// \brief A plugin for simulating battery usage
///
/// This system processes the following sdf parameters:
- /// name of the battery (required)
- /// Initial voltage of the battery (required)
- /// Voltage at full charge
- /// Amount of voltage decrease when no
+ /// - `` name of the battery (required)
+ /// - `` Initial voltage of the battery (required)
+ /// - `` Voltage at full charge
+ /// - `` Amount of voltage decrease when no
/// charge
- /// Initial charge of the battery (Ah)
- /// Total charge that the battery can hold (Ah)
- /// Internal resistance (Ohm)
- /// coefficient for smoothing current [0, 1].
- /// power load on battery (required) (Watts)
- /// If true, the battery can be recharged
- /// If true, the start/stop signals for recharging the
+ /// - `` Initial charge of the battery (Ah)
+ /// - `` Total charge that the battery can hold (Ah)
+ /// - `` Internal resistance (Ohm)
+ /// - `` coefficient for smoothing current [0, 1].
+ /// - `` power load on battery (required) (Watts)
+ /// - `` If true, the battery can be recharged
+ /// - `` If true, the start/stop signals for recharging the
/// battery will also be available via topics. The
/// regular Ignition services will still be available.
- /// Hours taken to fully charge the battery.
- /// (Required if is set to true)
- /// True to change the battery behavior to fix some issues
+ /// - `` Hours taken to fully charge the battery.
+ /// (Required if `` is set to true)
+ /// - `` True to change the battery behavior to fix some issues
/// described in https://github.com/ignitionrobotics/ign-gazebo/issues/225.
class LinearBatteryPlugin
: public System,
diff --git a/src/systems/breadcrumbs/Breadcrumbs.hh b/src/systems/breadcrumbs/Breadcrumbs.hh
index 9e1fd8f976..6d6270b58d 100644
--- a/src/systems/breadcrumbs/Breadcrumbs.hh
+++ b/src/systems/breadcrumbs/Breadcrumbs.hh
@@ -47,39 +47,40 @@ namespace systems
/// get deployed/spawned at the location of the model to which this system is
/// attached. Each breadcrumb is a complete sdf::Model. When deployed, the
/// pose of the breadcrumb model is offset from the containing model by the
- /// pose specified in the element of the breadcrumb model. A name is
+ /// pose specified in the `` element of the breadcrumb model. A name is
/// generated for the breadcrumb by appending the current count of deployments
- /// to the name specified in the breadcrumb element. The model
- /// specified in the parameter serves as a template for deploying
- /// multiple breadcrumbs of the same type. Including models from Fuel is
- /// accomplished by creating a that includes the Fuel model using the
- /// tag. See the example in examples/worlds/breadcrumbs.sdf.
+ /// to the name specified in the breadcrumb `` element. The model
+ /// specified in the `` parameter serves as a template for
+ /// deploying multiple breadcrumbs of the same type. Including models from
+ /// Fuel is accomplished by creating a `` that includes the Fuel
+ /// model using the `` tag.
+ /// See the example in examples/worlds/breadcrumbs.sdf.
///
/// System Paramters
///
- /// ``: Custom topic to be used to deploy breadcrumbs. If topic is not
- /// set, the default topic with the following pattern would be used
- /// "/model//breadcrumbs//deploy". The topic type
- /// is ignition.msgs.Empty
- /// ``: The maximum number of times this breadcrumb can be
- /// deployed. Once this many are deployed, publishing on the deploy topic will
- /// have no effect. If a negative number is set, the maximum deployment will
- /// be unbounded. If a value of zero is used, then the breadcrumb system will
- /// be disabled. A zero value is useful for situations where SDF files are
- /// programmatically created. The remaining deployment count is available on
- /// the `/remaining` topic.
- /// ``: The time in which the breadcrumb entity's
+ /// - ``: Custom topic to be used to deploy breadcrumbs. If topic is
+ /// not set, the default topic with the following pattern would be used
+ /// `/model//breadcrumbs//deploy`. The topic
+ /// type is ignition.msgs.Empty
+ /// - ``: The maximum number of times this breadcrumb can be
+ /// deployed. Once this many are deployed, publishing on the deploy topic
+ /// will have no effect. If a negative number is set, the maximum deployment
+ /// will be unbounded. If a value of zero is used, then the breadcrumb system
+ /// will be disabled. A zero value is useful for situations where SDF files
+ /// are programmatically created. The remaining deployment count is available
+ /// on the `/remaining` topic.
+ /// - ``: The time in which the breadcrumb entity's
/// dynamics remain enabled. After his specified time, the breadcrumb will
/// be made static. If this value is <= 0 or the param is not specified, the
/// breadcrumb model's dynamics will not be modified.
- /// ``: Geometry that represents the bounding volume of
+ /// - ``: Geometry that represents the bounding volume of
/// the performer. Only `` is supported currently. When this
/// parameter is present, the deployed models will be performers.
- /// ``: If true, the deployed model will be renamed if another
- /// model with the same name already exists in the world. If false and there
- /// is another model with the same name, the breadcrumb will not be deployed.
- /// Defaults to false.
- /// ``: This is the model used as a template for deploying
+ /// - ``: If true, the deployed model will be renamed if
+ /// another model with the same name already exists in the world. If false
+ /// and there is another model with the same name, the breadcrumb will not
+ /// be deployed. Defaults to false.
+ /// - ``: This is the model used as a template for deploying
/// breadcrumbs.
/// ``: If true, then topic statistics are enabled on
/// `` and error messages will be generated when messages are
@@ -181,4 +182,3 @@ namespace systems
}
#endif
-
diff --git a/src/systems/buoyancy/Buoyancy.hh b/src/systems/buoyancy/Buoyancy.hh
index 7d9f1a4ae5..55d040cdb8 100644
--- a/src/systems/buoyancy/Buoyancy.hh
+++ b/src/systems/buoyancy/Buoyancy.hh
@@ -45,7 +45,7 @@ namespace systems
///
/// ## System Parameters
///
- /// * sets the density of the fluid that surrounds
+ /// * `` sets the density of the fluid that surrounds
/// the buoyant object.
///
/// ## Example
diff --git a/src/systems/camera_video_recorder/CameraVideoRecorder.hh b/src/systems/camera_video_recorder/CameraVideoRecorder.hh
index a7204e5a80..90c4dfdb06 100644
--- a/src/systems/camera_video_recorder/CameraVideoRecorder.hh
+++ b/src/systems/camera_video_recorder/CameraVideoRecorder.hh
@@ -36,10 +36,10 @@ namespace systems
**/
/// \brief Record video from a camera sensor
/// The system takes in the following parameter:
- /// Name of topic for the video recorder service. If this is
- /// not specified, the topic defaults to:
- /// /world//link//
- /// sensor//record_video
+ /// - `` Name of topic for the video recorder service. If this is
+ /// not specified, the topic defaults to:
+ /// `/world//link//`
+ /// `sensor//record_video`
class CameraVideoRecorder:
public System,
public ISystemConfigure,
@@ -69,4 +69,3 @@ namespace systems
}
}
#endif
-
diff --git a/src/systems/detachable_joint/DetachableJoint.hh b/src/systems/detachable_joint/DetachableJoint.hh
index 5a1089321a..f52dc9d24a 100644
--- a/src/systems/detachable_joint/DetachableJoint.hh
+++ b/src/systems/detachable_joint/DetachableJoint.hh
@@ -40,17 +40,17 @@ namespace systems
///
/// Parameters:
///
- /// : Name of the link in the parent model to be used in
+ /// - ``: Name of the link in the parent model to be used in
/// creating a fixed joint with a link in the child model.
///
- /// : Name of the model to which this model will be connected
+ /// - ``: Name of the model to which this model will be connected
///
- /// : Name of the link in the child model to be used in
+ /// - ``: Name of the link in the child model to be used in
/// creating a fixed joint with a link in the parent model.
///
- /// (optional): Topic name to be used for detaching connections
+ /// - `` (optional): Topic name to be used for detaching connections
///
- /// (optional): If true, the system
+ /// - `` (optional): If true, the system
/// will not print a warning message if a child model does not exist yet.
/// Otherwise, a warning message is printed. Defaults to false.
diff --git a/src/systems/log_video_recorder/LogVideoRecorder.hh b/src/systems/log_video_recorder/LogVideoRecorder.hh
index 7c2a87fc5e..29d61208d7 100644
--- a/src/systems/log_video_recorder/LogVideoRecorder.hh
+++ b/src/systems/log_video_recorder/LogVideoRecorder.hh
@@ -39,13 +39,14 @@ namespace systems
/// There are two ways to specify what entities in the log playback to follow
/// and record videos for: 1) by entity name and 2) by region. See the
/// following parameters:
- /// Name of entity to record.
- /// Axis-aligned box where entities are at start of log
- /// Min corner position of box region.
- /// Max corner position of box region.
- /// Sim time when recording should start
- /// Sim time when recording should end
- /// Exit ign-gazebo when log playback recording ends
+ /// - `` Name of entity to record.
+ /// - `` Axis-aligned box where entities are at start of log
+ /// + `` Min corner position of box region.
+ /// + `` Max corner position of box region.
+ /// - `` Sim time when recording should start
+ /// - `` Sim time when recording should end
+ /// - `` Exit ign-gazebo when log playback recording ends
+ ///
/// When recording is finished. An `end` string will be published to the
/// `/log_video_recorder/status` topic and the videos are saved to a
/// timestamped directory
@@ -78,4 +79,3 @@ namespace systems
}
}
#endif
-
diff --git a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh
index 6ec0c390ab..3dcaeb67a2 100644
--- a/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh
+++ b/src/systems/logical_audio_sensor_plugin/LogicalAudioSensorPlugin.hh
@@ -34,7 +34,7 @@ namespace systems
/// \brief A plugin for logical audio detection.
///
- /// Each tag can accept multiple sensors (sound sources
+ /// Each `` tag can accept multiple sensors (sound sources
/// and/or microphones).
/// After each simulation step, microphones check if audio
/// was detected by any sources in the world.
@@ -44,90 +44,92 @@ namespace systems
///
/// Secifying an audio source via SDF is done as follows:
///
- ///